From 4f67e05b4c54ad61dae7bd3afff342b0412784e0 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 1 Sep 2025 22:40:14 +0200 Subject: [PATCH 1/3] fix(new project): vehicle names can contain . characters --- .../backend_filesystem_program_settings.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ardupilot_methodic_configurator/backend_filesystem_program_settings.py b/ardupilot_methodic_configurator/backend_filesystem_program_settings.py index 27350b6ab..bf7203498 100644 --- a/ardupilot_methodic_configurator/backend_filesystem_program_settings.py +++ b/ardupilot_methodic_configurator/backend_filesystem_program_settings.py @@ -128,7 +128,7 @@ def create_new_vehicle_dir(new_vehicle_dir: str) -> str: @staticmethod def valid_directory_name(dir_name: str) -> bool: """ - Check if a name contains only alphanumeric characters, underscores, hyphens and the OS directory separator. + Check if a name contains only alphanumeric characters, underscores, hyphens, dots and the OS directory separator. This function is designed to ensure that the directory name does not contain characters that are invalid for directory names in many operating systems. It does not guarantee that the name @@ -141,8 +141,8 @@ def valid_directory_name(dir_name: str) -> bool: bool: True if the directory name matches the allowed pattern, False otherwise. """ - # Include os.sep in the pattern - pattern = r"^[\w" + re_escape(os_sep) + "-]+$" + # Include os.sep and dot in the pattern + pattern = r"^[\w" + re_escape(os_sep) + ".-]+$" return re_match(pattern, dir_name) is not None @staticmethod From 5dedc94a282c19e707260014f7eea672f3ec1389 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 1 Sep 2025 22:52:36 +0200 Subject: [PATCH 2/3] fix(images in Linux): Images in Linux were not being correctly rendered The test was failing with a "bad argument type for built-in operation" error when trying to create ImageTk.PhotoImage objects. Through debugging, I discovered that this was a compatibility issue with the current Pillow version (11.3.0) and Tkinter when using ImageTk.PhotoImage directly. Solution Implemented Replaced ImageTk.PhotoImage with tk.PhotoImage: Instead of using ImageTk.PhotoImage(resized_image), I changed the implementation to use tk.PhotoImage(data=buffer.getvalue()) where the image is first saved to a BytesIO buffer as PNG data. Enhanced Error Handling: Added validation for image dimensions to prevent division by zero errors and ensure minimum dimensions of 1 pixel. Added Context Manager: Used with Image.open(filepath) as image: for proper resource management. Improved Image Format Compatibility: Added checks to ensure the image is in a compatible format for tk.PhotoImage. --- .../frontend_tkinter_base_window.py | 62 ++++++++++++------- tests/test_frontend_tkinter_base_window.py | 20 +++++- 2 files changed, 58 insertions(+), 24 deletions(-) diff --git a/ardupilot_methodic_configurator/frontend_tkinter_base_window.py b/ardupilot_methodic_configurator/frontend_tkinter_base_window.py index b1a6a6b73..1e2cec10d 100644 --- a/ardupilot_methodic_configurator/frontend_tkinter_base_window.py +++ b/ardupilot_methodic_configurator/frontend_tkinter_base_window.py @@ -20,6 +20,7 @@ # https://wiki.tcl-lang.org/page/Changing+Widget+Colors +import io import os import tkinter as tk import tkinter.font as tkfont @@ -30,7 +31,7 @@ from tkinter import ttk from typing import Optional, Union -from PIL import Image, ImageTk +from PIL import Image from ardupilot_methodic_configurator import _ from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem @@ -262,7 +263,7 @@ def center_window(window: Union[tk.Toplevel, tk.Tk], parent: Union[tk.Toplevel, y = parent.winfo_y() + (parent_height // 2) - (window_height // 2) window.geometry(f"+{x}+{y}") - def put_image_in_label( + def put_image_in_label( # pylint: disable=too-many-locals self, parent: ttk.Frame, filepath: str, @@ -320,25 +321,44 @@ def put_image_in_label( raise FileNotFoundError(msg) # Load and validate the image - image = Image.open(filepath) - if image is None: - msg = _("Failed to load image from %s") % filepath - raise ValueError(msg) - - # Calculate new dimensions while preserving aspect ratio - width, height = image.size - if height == 0: - msg = _("Image has zero height") - raise ValueError(msg) - - aspect_ratio = width / height - dpi_scaled_height = int(image_height * self.dpi_scaling_factor) - - # Resize the image - resized_image = image.resize((int(dpi_scaled_height * aspect_ratio), dpi_scaled_height), Image.Resampling.LANCZOS) - - # Convert to PhotoImage for Tkinter - photo = ImageTk.PhotoImage(resized_image) + with Image.open(filepath) as image: + if image is None: + msg = _("Failed to load image from %s") % filepath + raise ValueError(msg) + + # Calculate new dimensions while preserving aspect ratio + width, height = image.size + if height == 0: + msg = _("Image has zero height") + raise ValueError(msg) + if width == 0: + msg = _("Image has zero width") + raise ValueError(msg) + + aspect_ratio = width / height + dpi_scaled_height = int(image_height * self.dpi_scaling_factor) + + # Ensure minimum dimensions to prevent resize errors + dpi_scaled_height = max(dpi_scaled_height, 1) + + calculated_width = int(dpi_scaled_height * aspect_ratio) + calculated_width = max(calculated_width, 1) + + # Resize the image + resized_image = image.resize((calculated_width, dpi_scaled_height), Image.Resampling.LANCZOS) + + # Convert to PhotoImage for Tkinter using a buffer approach + buffer = io.BytesIO() + # Ensure the image is in a format that tk.PhotoImage can handle + if resized_image.mode not in ("RGB", "RGBA"): + resized_image = resized_image.convert("RGB") + + # Save as PNG to buffer + resized_image.save(buffer, format="PNG") + buffer.seek(0) + + # Create PhotoImage from buffer + photo = tk.PhotoImage(data=buffer.getvalue()) # Create the label with the image image_label = ttk.Label(parent, image=photo) diff --git a/tests/test_frontend_tkinter_base_window.py b/tests/test_frontend_tkinter_base_window.py index b8798248c..a8a71a022 100755 --- a/tests/test_frontend_tkinter_base_window.py +++ b/tests/test_frontend_tkinter_base_window.py @@ -67,16 +67,28 @@ def _image_context(image_size: tuple[int, int] = (100, 50), file_exists: bool = with ( patch("os.path.isfile", return_value=file_exists), patch("PIL.Image.open") as mock_open, - patch("PIL.ImageTk.PhotoImage") as mock_photo, + patch("tkinter.PhotoImage") as mock_photo, patch("tkinter.ttk.Label") as mock_label, + patch("io.BytesIO") as mock_buffer, ): - # Setup image mocks + # Setup image mocks to work with context manager mock_image = MagicMock() mock_image.size = image_size + mock_image.mode = "RGB" mock_resized_image = MagicMock() + mock_resized_image.mode = "RGB" mock_image.resize.return_value = mock_resized_image + + # Mock image to work as context manager + mock_image.__enter__ = MagicMock(return_value=mock_image) + mock_image.__exit__ = MagicMock(return_value=None) mock_open.return_value = mock_image + # Setup buffer mock + mock_buffer_instance = MagicMock() + mock_buffer.return_value = mock_buffer_instance + mock_buffer_instance.getvalue.return_value = b"fake_png_data" + # Setup photo and label mocks mock_photo_instance = MagicMock() mock_photo.return_value = mock_photo_instance @@ -91,6 +103,7 @@ def _image_context(image_size: tuple[int, int] = (100, 50), file_exists: bool = "open_mock": mock_open, "photo_mock": mock_photo, "label_mock": mock_label, + "buffer": mock_buffer_instance, } return _image_context @@ -272,7 +285,8 @@ def test_user_sees_properly_sized_images(self, image_test_context, sample_image_ assert result == mocks["label"] mocks["open_mock"].assert_called_once_with(sample_image_file) mocks["image"].resize.assert_called_once() - mocks["photo_mock"].assert_called_once_with(mocks["resized_image"]) + # Check that PhotoImage was called with data parameter (our new implementation) + mocks["photo_mock"].assert_called_once_with(data=b"fake_png_data") def test_user_sees_fallback_when_image_unavailable(self, image_test_context, mocked_base_window) -> None: """ From 02411d81757595ebd5b7d2a048aa4143477d56d1 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 1 Sep 2025 23:22:47 +0200 Subject: [PATCH 3/3] feat(empty templates): Add empty templates These templates have no opinions nor recomendations --- .../ArduCopter/empty_4.5.x/00_default.param | 999 ++++++++++++++++ ...02_imu_temperature_calibration_setup.param | 8 + .../empty_4.5.x/04_board_orientation.param | 4 + .../empty_4.5.x/05_remote_controller.param | 10 + .../ArduCopter/empty_4.5.x/06_telemetry.param | 2 + .../ArduCopter/empty_4.5.x/07_esc.param | 28 + .../ArduCopter/empty_4.5.x/08_batt1.param | 15 + .../ArduCopter/empty_4.5.x/10_gnss.param | 16 + .../empty_4.5.x/11_initial_atc.param | 18 + .../12_mp_setup_mandatory_hardware.param | 82 ++ .../13_general_configuration.param | 18 + .../ArduCopter/empty_4.5.x/14_logging.param | 6 + .../ArduCopter/empty_4.5.x/15_motor.param | 4 + .../empty_4.5.x/16_pid_adjustment.param | 15 + .../ArduCopter/empty_4.5.x/17_remote_id.param | 4 + .../empty_4.5.x/18_notch_filter_setup.param | 10 + .../empty_4.5.x/19_notch_filter_results.param | 8 + .../empty_4.5.x/20_throttle_controller.param | 3 + .../empty_4.5.x/21_ekf_config.param | 2 + .../empty_4.5.x/22_quick_tune_setup.param | 14 + .../empty_4.5.x/23_quick_tune_results.param | 10 + .../24_inflight_magnetometer_fit_setup.param | 8 + ...4_inflight_magnetometer_fit_setup.pdef.xml | 57 + ...25_inflight_magnetometer_fit_results.param | 43 + .../empty_4.5.x/26_quick_tune_setup.param | 16 + .../empty_4.5.x/27_quick_tune_results.param | 10 + ...valuate_the_aircraft_tune_ff_disable.param | 4 + ...evaluate_the_aircraft_tune_ff_enable.param | 1 + .../empty_4.5.x/30_autotune_roll_setup.param | 2 + .../31_autotune_roll_results.param | 5 + .../empty_4.5.x/32_autotune_pitch_setup.param | 2 + .../33_autotune_pitch_results.param | 5 + .../empty_4.5.x/34_autotune_yaw_setup.param | 3 + .../empty_4.5.x/35_autotune_yaw_results.param | 5 + .../empty_4.5.x/36_autotune_yawd_setup.param | 3 + .../37_autotune_yawd_results.param | 5 + .../38_autotune_roll_pitch_retune_setup.param | 2 + ...9_autotune_roll_pitch_retune_results.param | 10 + .../empty_4.5.x/40_windspeed_estimation.param | 5 + .../41_barometer_compensation.param | 7 + .../empty_4.5.x/42_system_id_roll.param | 21 + .../empty_4.5.x/43_system_id_pitch.param | 10 + .../empty_4.5.x/44_system_id_yaw.param | 10 + .../empty_4.5.x/45_system_id_thrust.param | 10 + .../46_analytical_pid_optimization.param | 4 + .../empty_4.5.x/47_position_controller.param | 13 + .../empty_4.5.x/48_guided_operation.param | 4 + .../empty_4.5.x/49_precision_land.param | 27 + .../empty_4.5.x/50_optical_flow_setup.param | 19 + .../empty_4.5.x/51_optical_flow_results.param | 3 + .../52_use_optical_flow_instead_of_gnss.param | 8 + .../empty_4.5.x/53_everyday_use.param | 7 + .../empty_4.5.x/vehicle_components.json | 187 +++ .../ArduCopter/empty_4.6.x/00_default.param | 1019 +++++++++++++++++ ...02_imu_temperature_calibration_setup.param | 8 + .../empty_4.6.x/04_board_orientation.param | 4 + .../empty_4.6.x/05_remote_controller.param | 10 + .../ArduCopter/empty_4.6.x/06_telemetry.param | 2 + .../ArduCopter/empty_4.6.x/07_esc.param | 28 + .../ArduCopter/empty_4.6.x/08_batt1.param | 15 + .../ArduCopter/empty_4.6.x/10_gnss.param | 16 + .../empty_4.6.x/11_initial_atc.param | 18 + .../12_mp_setup_mandatory_hardware.param | 82 ++ .../13_general_configuration.param | 18 + .../ArduCopter/empty_4.6.x/14_logging.param | 6 + .../ArduCopter/empty_4.6.x/15_motor.param | 4 + .../empty_4.6.x/16_pid_adjustment.param | 15 + .../ArduCopter/empty_4.6.x/17_remote_id.param | 4 + .../empty_4.6.x/18_notch_filter_setup.param | 10 + .../empty_4.6.x/19_notch_filter_results.param | 8 + .../empty_4.6.x/20_throttle_controller.param | 3 + .../empty_4.6.x/21_ekf_config.param | 2 + .../empty_4.6.x/22_quick_tune_setup.param | 14 + .../empty_4.6.x/23_quick_tune_results.param | 10 + .../24_inflight_magnetometer_fit_setup.param | 8 + ...4_inflight_magnetometer_fit_setup.pdef.xml | 57 + ...25_inflight_magnetometer_fit_results.param | 43 + .../empty_4.6.x/26_quick_tune_setup.param | 16 + .../empty_4.6.x/27_quick_tune_results.param | 10 + ...valuate_the_aircraft_tune_ff_disable.param | 4 + ...evaluate_the_aircraft_tune_ff_enable.param | 1 + .../empty_4.6.x/30_autotune_roll_setup.param | 2 + .../31_autotune_roll_results.param | 5 + .../empty_4.6.x/32_autotune_pitch_setup.param | 2 + .../33_autotune_pitch_results.param | 5 + .../empty_4.6.x/34_autotune_yaw_setup.param | 3 + .../empty_4.6.x/35_autotune_yaw_results.param | 5 + .../empty_4.6.x/36_autotune_yawd_setup.param | 3 + .../37_autotune_yawd_results.param | 5 + .../38_autotune_roll_pitch_retune_setup.param | 2 + ...9_autotune_roll_pitch_retune_results.param | 10 + .../empty_4.6.x/40_windspeed_estimation.param | 5 + .../41_barometer_compensation.param | 7 + .../empty_4.6.x/42_system_id_roll.param | 21 + .../empty_4.6.x/43_system_id_pitch.param | 10 + .../empty_4.6.x/44_system_id_yaw.param | 10 + .../empty_4.6.x/45_system_id_thrust.param | 10 + .../46_analytical_pid_optimization.param | 4 + .../empty_4.6.x/47_position_controller.param | 13 + .../empty_4.6.x/48_guided_operation.param | 4 + .../empty_4.6.x/49_precision_land.param | 27 + .../empty_4.6.x/50_optical_flow_setup.param | 19 + .../empty_4.6.x/51_optical_flow_results.param | 3 + .../52_use_optical_flow_instead_of_gnss.param | 8 + .../empty_4.6.x/53_everyday_use.param | 7 + .../empty_4.6.x/vehicle_components.json | 187 +++ 106 files changed, 3604 insertions(+) create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/00_default.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/02_imu_temperature_calibration_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/04_board_orientation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/05_remote_controller.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/06_telemetry.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/07_esc.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/08_batt1.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/10_gnss.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/11_initial_atc.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/12_mp_setup_mandatory_hardware.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/13_general_configuration.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/14_logging.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/15_motor.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/16_pid_adjustment.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/17_remote_id.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/18_notch_filter_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/19_notch_filter_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/20_throttle_controller.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/21_ekf_config.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/22_quick_tune_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/23_quick_tune_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.pdef.xml create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/25_inflight_magnetometer_fit_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/26_quick_tune_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/27_quick_tune_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/28_evaluate_the_aircraft_tune_ff_disable.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/29_evaluate_the_aircraft_tune_ff_enable.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/30_autotune_roll_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/31_autotune_roll_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/32_autotune_pitch_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/33_autotune_pitch_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/34_autotune_yaw_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/35_autotune_yaw_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/36_autotune_yawd_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/37_autotune_yawd_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/38_autotune_roll_pitch_retune_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/39_autotune_roll_pitch_retune_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/40_windspeed_estimation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/41_barometer_compensation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/42_system_id_roll.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/43_system_id_pitch.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/44_system_id_yaw.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/45_system_id_thrust.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/46_analytical_pid_optimization.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/47_position_controller.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/48_guided_operation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/49_precision_land.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/50_optical_flow_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/51_optical_flow_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/52_use_optical_flow_instead_of_gnss.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/53_everyday_use.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/vehicle_components.json create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/00_default.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/02_imu_temperature_calibration_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/04_board_orientation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/05_remote_controller.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/06_telemetry.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/07_esc.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/08_batt1.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/10_gnss.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/11_initial_atc.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/12_mp_setup_mandatory_hardware.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/13_general_configuration.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/14_logging.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/15_motor.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/16_pid_adjustment.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/17_remote_id.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/18_notch_filter_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/19_notch_filter_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/20_throttle_controller.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/21_ekf_config.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/22_quick_tune_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/23_quick_tune_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.pdef.xml create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/25_inflight_magnetometer_fit_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/26_quick_tune_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/27_quick_tune_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/28_evaluate_the_aircraft_tune_ff_disable.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/29_evaluate_the_aircraft_tune_ff_enable.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/30_autotune_roll_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/31_autotune_roll_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/32_autotune_pitch_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/33_autotune_pitch_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/34_autotune_yaw_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/35_autotune_yaw_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/36_autotune_yawd_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/37_autotune_yawd_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/38_autotune_roll_pitch_retune_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/39_autotune_roll_pitch_retune_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/40_windspeed_estimation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/41_barometer_compensation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/42_system_id_roll.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/43_system_id_pitch.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/44_system_id_yaw.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/45_system_id_thrust.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/46_analytical_pid_optimization.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/47_position_controller.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/48_guided_operation.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/49_precision_land.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/50_optical_flow_setup.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/51_optical_flow_results.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/52_use_optical_flow_instead_of_gnss.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/53_everyday_use.param create mode 100644 ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/vehicle_components.json diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/00_default.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/00_default.param new file mode 100644 index 000000000..db76d60ee --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/00_default.param @@ -0,0 +1,999 @@ +ACRO_BAL_PITCH,1 +ACRO_BAL_ROLL,1 +ACRO_OPTIONS,0 +ACRO_RP_EXPO,0.3 +ACRO_RP_RATE,360 +ACRO_RP_RATE_TC,0 +ACRO_THR_MID,0 +ACRO_TRAINER,2 +ACRO_Y_EXPO,0 +ACRO_Y_RATE,202.5 +ACRO_Y_RATE_TC,0 +ADSB_TYPE,0 +AHRS_COMP_BETA,0.1 +AHRS_EKF_TYPE,3 +AHRS_GPS_GAIN,1 +AHRS_GPS_MINSATS,6 +AHRS_GPS_USE,1 +AHRS_OPTIONS,0 +AHRS_ORIENTATION,0 +AHRS_RP_P,0.2 +AHRS_TRIM_X,0 +AHRS_TRIM_Y,0 +AHRS_TRIM_Z,0 +AHRS_WIND_MAX,0 +AHRS_YAW_P,0.2 +ANGLE_MAX,3000 +ARMING_ACCTHRESH,0.75 +ARMING_CHECK,1 +ARMING_CRSDP_IGN,0 +ARMING_MAGTHRESH,100 +ARMING_MIS_ITEMS,0 +ARMING_OPTIONS,0 +ARMING_RUDDER,2 +ARSPD_ENABLE,0 +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ACCEL_Y_MAX,27000 +ATC_ANG_LIM_TC,1 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_ANGLE_BOOST,1 +ATC_INPUT_TC,0.15 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_D_FF,0 +ATC_RAT_PIT_FF,0 +ATC_RAT_PIT_FLTD,20 +ATC_RAT_PIT_FLTE,0 +ATC_RAT_PIT_FLTT,20 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_IMAX,0.5 +ATC_RAT_PIT_NEF,0 +ATC_RAT_PIT_NTF,0 +ATC_RAT_PIT_P,0.135 +ATC_RAT_PIT_PDMX,0 +ATC_RAT_PIT_SMAX,0 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_D_FF,0 +ATC_RAT_RLL_FF,0 +ATC_RAT_RLL_FLTD,20 +ATC_RAT_RLL_FLTE,0 +ATC_RAT_RLL_FLTT,20 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_IMAX,0.5 +ATC_RAT_RLL_NEF,0 +ATC_RAT_RLL_NTF,0 +ATC_RAT_RLL_P,0.135 +ATC_RAT_RLL_PDMX,0 +ATC_RAT_RLL_SMAX,0 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_D_FF,0 +ATC_RAT_YAW_FF,0 +ATC_RAT_YAW_FLTD,20 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_FLTT,20 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_IMAX,0.5 +ATC_RAT_YAW_NEF,0 +ATC_RAT_YAW_NTF,0 +ATC_RAT_YAW_P,0.18 +ATC_RAT_YAW_PDMX,0 +ATC_RAT_YAW_SMAX,0 +ATC_RATE_FF_ENAB,1 +ATC_RATE_P_MAX,0 +ATC_RATE_R_MAX,0 +ATC_RATE_Y_MAX,0 +ATC_SLEW_YAW,6000 +ATC_THR_G_BOOST,0 +ATC_THR_MIX_MAN,0.1 +ATC_THR_MIX_MAX,0.5 +ATC_THR_MIX_MIN,0.1 +AUTO_OPTIONS,0 +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,7 +AUTOTUNE_MIN_D,0.001 +AVD_ENABLE,0 +AVOID_ACCEL_MAX,3 +AVOID_ALT_MIN,0 +AVOID_ANGLE_MAX,1000 +AVOID_BACKUP_DZ,0.1 +AVOID_BACKUP_SPD,0.75 +AVOID_BACKZ_SPD,0.75 +AVOID_BEHAVE,0 +AVOID_DIST_MAX,5 +AVOID_ENABLE,3 +AVOID_MARGIN,2 +BARO_ALT_OFFSET,0 +BARO_ALTERR_MAX,2000 +BARO_EXT_BUS,-1 +BARO_FIELD_ELV,0 +BARO_FLTR_RNG,0 +BARO_GND_TEMP,0 +BARO_OPTIONS,0 +BARO_PRIMARY,0 +BARO_PROBE_EXT,0 +BARO1_DEVID,0 +BARO1_GND_PRESS,0 +BARO1_WCF_ENABLE,0 +BARO2_DEVID,0 +BARO2_GND_PRESS,0 +BARO2_WCF_ENABLE,0 +BARO3_DEVID,0 +BARO3_GND_PRESS,0 +BARO3_WCF_ENABLE,0 +BATT_MONITOR,0 +BATT2_MONITOR,0 +BATT3_MONITOR,0 +BATT4_MONITOR,0 +BATT5_MONITOR,0 +BATT6_MONITOR,0 +BATT7_MONITOR,0 +BATT8_MONITOR,0 +BATT9_MONITOR,0 +BCN_TYPE,0 +BRD_BOOT_DELAY,0 +BRD_HEAT_I,0.3 +BRD_HEAT_IMAX,70 +BRD_HEAT_LOWMGN,5 +BRD_HEAT_P,200 +BRD_HEAT_TARG,-1 +BRD_IO_DSHOT,0 +BRD_IO_ENABLE,1 +BRD_OPTIONS,1 +BRD_RTC_TYPES,1 +BRD_RTC_TZ_MIN,0 +BRD_SAFETY_DEFLT,1 +BRD_SAFETY_MASK,16383 +BRD_SAFETYOPTION,3 +BRD_SBUS_OUT,0 +BRD_SD_SLOWDOWN,0 +BRD_SER1_RTSCTS,2 +BRD_SER2_RTSCTS,2 +BRD_SERIAL_NUM,0 +BRD_TYPE,3 +BRD_VBUS_MIN,4.3 +BRD_VSERVO_MIN,0 +BTN_ENABLE,0 +CAM_AUTO_ONLY,0 +CAM_MAX_ROLL,0 +CAM_RC_TYPE,0 +CAM1_TYPE,0 +CAM2_TYPE,0 +CAN_D1_PROTOCOL,1 +CAN_D1_PROTOCOL2,0 +CAN_D2_PROTOCOL,1 +CAN_D2_PROTOCOL2,0 +CAN_LOGLEVEL,0 +CAN_P1_DRIVER,0 +CAN_P2_DRIVER,0 +CAN_SLCAN_CPORT,0 +CAN_SLCAN_SDELAY,1 +CAN_SLCAN_SERNUM,-1 +CAN_SLCAN_TIMOUT,0 +CHUTE_ENABLED,0 +CIRCLE_OPTIONS,1 +CIRCLE_RADIUS,1000 +CIRCLE_RATE,20 +COMPASS_AUTO_ROT,2 +COMPASS_AUTODEC,1 +COMPASS_CAL_FIT,16 +COMPASS_DEC,0 +COMPASS_DEV_ID,0 +COMPASS_DEV_ID2,0 +COMPASS_DEV_ID3,0 +COMPASS_DEV_ID4,0 +COMPASS_DEV_ID5,0 +COMPASS_DEV_ID6,0 +COMPASS_DEV_ID7,0 +COMPASS_DEV_ID8,0 +COMPASS_DIA_X,1 +COMPASS_DIA_Y,1 +COMPASS_DIA_Z,1 +COMPASS_DIA2_X,1 +COMPASS_DIA2_Y,1 +COMPASS_DIA2_Z,1 +COMPASS_DIA3_X,1 +COMPASS_DIA3_Y,1 +COMPASS_DIA3_Z,1 +COMPASS_DISBLMSK,32 +COMPASS_ENABLE,1 +COMPASS_EXTERN2,0 +COMPASS_EXTERN3,0 +COMPASS_EXTERNAL,0 +COMPASS_FLTR_RNG,0 +COMPASS_LEARN,0 +COMPASS_MOT_X,0 +COMPASS_MOT_Y,0 +COMPASS_MOT_Z,0 +COMPASS_MOT2_X,0 +COMPASS_MOT2_Y,0 +COMPASS_MOT2_Z,0 +COMPASS_MOT3_X,0 +COMPASS_MOT3_Y,0 +COMPASS_MOT3_Z,0 +COMPASS_MOTCT,0 +COMPASS_ODI_X,0 +COMPASS_ODI_Y,0 +COMPASS_ODI_Z,0 +COMPASS_ODI2_X,0 +COMPASS_ODI2_Y,0 +COMPASS_ODI2_Z,0 +COMPASS_ODI3_X,0 +COMPASS_ODI3_Y,0 +COMPASS_ODI3_Z,0 +COMPASS_OFFS_MAX,1800 +COMPASS_OFS_X,0 +COMPASS_OFS_Y,0 +COMPASS_OFS_Z,0 +COMPASS_OFS2_X,0 +COMPASS_OFS2_Y,0 +COMPASS_OFS2_Z,0 +COMPASS_OFS3_X,0 +COMPASS_OFS3_Y,0 +COMPASS_OFS3_Z,0 +COMPASS_OPTIONS,0 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +COMPASS_ORIENT3,0 +COMPASS_PMOT_EN,0 +COMPASS_PRIO1_ID,0 +COMPASS_PRIO2_ID,0 +COMPASS_PRIO3_ID,0 +COMPASS_SCALE,0 +COMPASS_SCALE2,0 +COMPASS_SCALE3,0 +COMPASS_USE,1 +COMPASS_USE2,1 +COMPASS_USE3,1 +CUST_ROT_ENABLE,0 +DEV_OPTIONS,0 +DISARM_DELAY,10 +EAHRS_TYPE,0 +EFI_TYPE,0 +EK3_ABIAS_P_NSE,0.02 +EK3_ACC_BIAS_LIM,1 +EK3_ACC_P_NSE,0.35 +EK3_AFFINITY,0 +EK3_ALT_M_NSE,2 +EK3_BCN_DELAY,50 +EK3_BCN_I_GTE,500 +EK3_BCN_M_NSE,1 +EK3_BETA_MASK,0 +EK3_CHECK_SCALE,100 +EK3_DRAG_BCOEF_X,0 +EK3_DRAG_BCOEF_Y,0 +EK3_DRAG_M_NSE,0.5 +EK3_DRAG_MCOEF,0 +EK3_EAS_I_GATE,400 +EK3_EAS_M_NSE,1.4 +EK3_ENABLE,1 +EK3_ERR_THRESH,0.2 +EK3_FLOW_DELAY,10 +EK3_FLOW_I_GATE,300 +EK3_FLOW_M_NSE,0.25 +EK3_FLOW_USE,1 +EK3_GBIAS_P_NSE,0.001 +EK3_GLITCH_RAD,25 +EK3_GND_EFF_DZ,4 +EK3_GPS_CHECK,31 +EK3_GPS_VACC_MAX,0 +EK3_GSF_RST_MAX,2 +EK3_GSF_RUN_MASK,3 +EK3_GSF_USE_MASK,3 +EK3_GYRO_P_NSE,0.015 +EK3_HGT_DELAY,60 +EK3_HGT_I_GATE,500 +EK3_HRT_FILT,2 +EK3_IMU_MASK,3 +EK3_LOG_LEVEL,0 +EK3_MAG_CAL,3 +EK3_MAG_EF_LIM,50 +EK3_MAG_I_GATE,300 +EK3_MAG_M_NSE,0.05 +EK3_MAG_MASK,0 +EK3_MAGB_P_NSE,0.0001 +EK3_MAGE_P_NSE,0.001 +EK3_MAX_FLOW,2.5 +EK3_NOAID_M_NSE,10 +EK3_OGN_HGT_MASK,0 +EK3_OGNM_TEST_SF,2 +EK3_POS_I_GATE,500 +EK3_POSNE_M_NSE,0.5 +EK3_PRIMARY,0 +EK3_RNG_I_GATE,500 +EK3_RNG_M_NSE,0.5 +EK3_RNG_USE_HGT,-1 +EK3_RNG_USE_SPD,2 +EK3_SRC_OPTIONS,1 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +EK3_SRC2_POSXY,0 +EK3_SRC2_POSZ,1 +EK3_SRC2_VELXY,0 +EK3_SRC2_VELZ,0 +EK3_SRC2_YAW,0 +EK3_SRC3_POSXY,0 +EK3_SRC3_POSZ,1 +EK3_SRC3_VELXY,0 +EK3_SRC3_VELZ,0 +EK3_SRC3_YAW,0 +EK3_TAU_OUTPUT,25 +EK3_TERR_GRAD,0.1 +EK3_VEL_I_GATE,500 +EK3_VELD_M_NSE,0.5 +EK3_VELNE_M_NSE,0.3 +EK3_VIS_VERR_MAX,0.9 +EK3_VIS_VERR_MIN,0.1 +EK3_WENC_VERR,0.1 +EK3_WIND_P_NSE,0.2 +EK3_WIND_PSCALE,1 +EK3_YAW_I_GATE,300 +EK3_YAW_M_NSE,0.5 +ESC_CALIBRATION,0 +ESC_TLM_MAV_OFS,0 +FENCE_ACTION,1 +FENCE_ALT_MAX,100 +FENCE_ALT_MIN,-10 +FENCE_ENABLE,0 +FENCE_MARGIN,2 +FENCE_RADIUS,300 +FENCE_TOTAL,0 +FENCE_TYPE,7 +FFT_ENABLE,0 +FHLD_BRAKE_RATE,8 +FHLD_FILT_HZ,5 +FHLD_FLOW_MAX,0.6 +FHLD_QUAL_MIN,10 +FHLD_XY_FILT_HZ,5 +FHLD_XY_I,0.3 +FHLD_XY_IMAX,3000 +FHLD_XY_P,0.2 +FILT1_TYPE,0 +FILT2_TYPE,0 +FILT3_TYPE,0 +FILT4_TYPE,0 +FILT5_TYPE,0 +FILT6_TYPE,0 +FILT7_TYPE,0 +FILT8_TYPE,0 +FLIGHT_OPTIONS,0 +FLOW_TYPE,0 +FLTMODE_CH,5 +FLTMODE_GCSBLOCK,0 +FLTMODE1,0 +FLTMODE2,0 +FLTMODE3,0 +FLTMODE4,0 +FLTMODE5,0 +FLTMODE6,0 +FOLL_ENABLE,0 +FORMAT_VERSION,120 +FRAME_CLASS,0 +FRAME_TYPE,1 +FRSKY_DNLINK_ID,27 +FRSKY_DNLINK1_ID,20 +FRSKY_DNLINK2_ID,7 +FRSKY_OPTIONS,0 +FRSKY_UPLINK_ID,13 +FS_CRASH_CHECK,1 +FS_DR_ENABLE,2 +FS_DR_TIMEOUT,30 +FS_EKF_ACTION,1 +FS_EKF_FILT,5 +FS_EKF_THRESH,0.8 +FS_GCS_ENABLE,0 +FS_GCS_TIMEOUT,5 +FS_OPTIONS,16 +FS_THR_ENABLE,1 +FS_THR_VALUE,975 +FS_VIBE_ENABLE,1 +GCS_PID_MASK,0 +GEN_TYPE,0 +GND_EFFECT_COMP,1 +GPS_AUTO_CONFIG,1 +GPS_AUTO_SWITCH,1 +GPS_BLEND_MASK,5 +GPS_CAN_NODEID1,0 +GPS_CAN_NODEID2,0 +GPS_COM_PORT,1 +GPS_COM_PORT2,1 +GPS_DELAY_MS,0 +GPS_DELAY_MS2,0 +GPS_DRV_OPTIONS,0 +GPS_GNSS_MODE,0 +GPS_GNSS_MODE2,0 +GPS_HDOP_GOOD,140 +GPS_INJECT_TO,127 +GPS_MB1_TYPE,0 +GPS_MB2_TYPE,0 +GPS_MIN_DGPS,100 +GPS_MIN_ELEV,-100 +GPS_NAVFILTER,8 +GPS_POS1_X,0 +GPS_POS1_Y,0 +GPS_POS1_Z,0 +GPS_POS2_X,0 +GPS_POS2_Y,0 +GPS_POS2_Z,0 +GPS_PRIMARY,0 +GPS_RATE_MS,200 +GPS_RATE_MS2,200 +GPS_RAW_DATA,0 +GPS_SAVE_CFG,2 +GPS_SBAS_MODE,2 +GPS_SBP_LOGMASK,-256 +GPS_TYPE,1 +GPS_TYPE2,0 +GPS1_CAN_OVRIDE,0 +GPS2_CAN_OVRIDE,0 +GRIP_ENABLE,0 +GUID_OPTIONS,0 +GUID_TIMEOUT,3 +INITIAL_MODE,0 +INS_ACC_BODYFIX,2 +INS_ACC_ID,0 +INS_ACC1_CALTEMP,-300 +INS_ACC2_CALTEMP,-300 +INS_ACC2_ID,0 +INS_ACC2OFFS_X,0 +INS_ACC2OFFS_Y,0 +INS_ACC2OFFS_Z,0 +INS_ACC2SCAL_X,1 +INS_ACC2SCAL_Y,1 +INS_ACC2SCAL_Z,1 +INS_ACC3_CALTEMP,-300 +INS_ACC3_ID,0 +INS_ACC3OFFS_X,0 +INS_ACC3OFFS_Y,0 +INS_ACC3OFFS_Z,0 +INS_ACC3SCAL_X,1 +INS_ACC3SCAL_Y,1 +INS_ACC3SCAL_Z,1 +INS_ACCEL_FILTER,20 +INS_ACCOFFS_X,0 +INS_ACCOFFS_Y,0 +INS_ACCOFFS_Z,0 +INS_ACCSCAL_X,1 +INS_ACCSCAL_Y,1 +INS_ACCSCAL_Z,1 +INS_ENABLE_MASK,127 +INS_FAST_SAMPLE,5 +INS_GYR_CAL,1 +INS_GYR_ID,0 +INS_GYR1_CALTEMP,-300 +INS_GYR2_CALTEMP,-300 +INS_GYR2_ID,0 +INS_GYR2OFFS_X,0 +INS_GYR2OFFS_Y,0 +INS_GYR2OFFS_Z,0 +INS_GYR3_CALTEMP,-300 +INS_GYR3_ID,0 +INS_GYR3OFFS_X,0 +INS_GYR3OFFS_Y,0 +INS_GYR3OFFS_Z,0 +INS_GYRO_FILTER,20 +INS_GYRO_RATE,0 +INS_GYROFFS_X,0 +INS_GYROFFS_Y,0 +INS_GYROFFS_Z,0 +INS_HNTC2_ENABLE,0 +INS_HNTCH_ENABLE,0 +INS_LOG_BAT_CNT,1024 +INS_LOG_BAT_LGCT,32 +INS_LOG_BAT_LGIN,20 +INS_LOG_BAT_MASK,0 +INS_LOG_BAT_OPT,0 +INS_POS1_X,0 +INS_POS1_Y,0 +INS_POS1_Z,0 +INS_POS2_X,0 +INS_POS2_Y,0 +INS_POS2_Z,0 +INS_POS3_X,0 +INS_POS3_Y,0 +INS_POS3_Z,0 +INS_RAW_LOG_OPT,0 +INS_STILL_THRESH,2.5 +INS_TCAL_OPTIONS,0 +INS_TCAL1_ENABLE,0 +INS_TCAL2_ENABLE,0 +INS_TCAL3_ENABLE,0 +INS_TRIM_OPTION,1 +INS_USE,1 +INS_USE2,1 +INS_USE3,1 +KDE_NPOLE,14 +LAND_ALT_LOW,1000 +LAND_REPOSITION,1 +LAND_SPEED,50 +LAND_SPEED_HIGH,0 +LGR_ENABLE,0 +LOG_BACKEND_TYPE,1 +LOG_BITMASK,176126 +LOG_DARM_RATEMAX,0 +LOG_DISARMED,0 +LOG_FILE_BUFSIZE,16 +LOG_FILE_DSRMROT,0 +LOG_FILE_MB_FREE,500 +LOG_FILE_RATEMAX,0 +LOG_FILE_TIMEOUT,5 +LOG_MAV_BUFSIZE,8 +LOG_MAV_RATEMAX,0 +LOG_MAX_FILES,500 +LOG_REPLAY,0 +LOIT_ACC_MAX,500 +LOIT_ANG_MAX,0 +LOIT_BRK_ACCEL,250 +LOIT_BRK_DELAY,1 +LOIT_BRK_JERK,500 +LOIT_SPEED,1250 +MIS_OPTIONS,0 +MIS_RESTART,0 +MIS_TOTAL,0 +MNT1_TYPE,0 +MNT2_TYPE,0 +MOT_BAT_CURR_MAX,0 +MOT_BAT_CURR_TC,5 +MOT_BAT_IDX,0 +MOT_BAT_VOLT_MAX,0 +MOT_BAT_VOLT_MIN,0 +MOT_BOOST_SCALE,0 +MOT_HOVER_LEARN,2 +MOT_OPTIONS,0 +MOT_PWM_MAX,2000 +MOT_PWM_MIN,1000 +MOT_PWM_TYPE,0 +MOT_SAFE_DISARM,0 +MOT_SAFE_TIME,1 +MOT_SLEW_DN_TIME,0 +MOT_SLEW_UP_TIME,0 +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_SPOOL_TIM_DN,0 +MOT_SPOOL_TIME,0.5 +MOT_THST_EXPO,0.65 +MOT_THST_HOVER,0.35 +MOT_YAW_HEADROOM,200 +MSP_OPTIONS,0 +MSP_OSD_NCELLS,0 +NMEA_MSG_EN,3 +NMEA_RATE_MS,100 +NTF_BUZZ_ON_LVL,1 +NTF_BUZZ_PIN,-1 +NTF_BUZZ_TYPES,5 +NTF_BUZZ_VOLUME,100 +NTF_DISPLAY_TYPE,0 +NTF_LED_BRIGHT,3 +NTF_LED_LEN,1 +NTF_LED_OVERRIDE,0 +NTF_LED_TYPES,123079 +NTF_OREO_THEME,0 +OA_TYPE,0 +OSD_TYPE,0 +PHLD_BRAKE_ANGLE,3000 +PHLD_BRAKE_RATE,8 +PILOT_ACCEL_Z,250 +PILOT_SPEED_DN,0 +PILOT_SPEED_UP,250 +PILOT_THR_BHV,0 +PILOT_THR_FILT,0 +PILOT_TKOFF_ALT,0 +PILOT_Y_EXPO,0 +PILOT_Y_RATE,202.5 +PILOT_Y_RATE_TC,0 +PLDP_DELAY,0 +PLDP_RNG_MIN,0 +PLDP_SPEED_DN,0 +PLDP_THRESH,0.9 +PLND_ENABLED,0 +PRX_ALT_MIN,1 +PRX_FILT,0.25 +PRX_IGN_GND,0 +PRX_LOG_RAW,0 +PRX1_TYPE,0 +PRX2_TYPE,0 +PRX3_TYPE,0 +PSC_ACCZ_D,0 +PSC_ACCZ_D_FF,0 +PSC_ACCZ_FF,0 +PSC_ACCZ_FLTD,0 +PSC_ACCZ_FLTE,20 +PSC_ACCZ_FLTT,0 +PSC_ACCZ_I,1 +PSC_ACCZ_IMAX,800 +PSC_ACCZ_NEF,0 +PSC_ACCZ_NTF,0 +PSC_ACCZ_P,0.5 +PSC_ACCZ_PDMX,0 +PSC_ACCZ_SMAX,0 +PSC_ANGLE_MAX,0 +PSC_JERK_XY,5 +PSC_JERK_Z,5 +PSC_POSXY_P,1 +PSC_POSZ_P,1 +PSC_VELXY_D,0.5 +PSC_VELXY_FF,0 +PSC_VELXY_FLTD,5 +PSC_VELXY_FLTE,5 +PSC_VELXY_I,1 +PSC_VELXY_IMAX,1000 +PSC_VELXY_P,2 +PSC_VELZ_D,0 +PSC_VELZ_FF,0 +PSC_VELZ_FLTD,5 +PSC_VELZ_FLTE,5 +PSC_VELZ_I,0 +PSC_VELZ_IMAX,1000 +PSC_VELZ_P,5 +RALLY_INCL_HOME,1 +RALLY_LIMIT_KM,0.3 +RALLY_TOTAL,0 +RC_FS_TIMEOUT,1 +RC_OPTIONS,32 +RC_OVERRIDE_TIME,3 +RC_PROTOCOLS,1 +RC_SPEED,490 +RC1_DZ,20 +RC1_MAX,1900 +RC1_MIN,1100 +RC1_OPTION,0 +RC1_REVERSED,0 +RC1_TRIM,1500 +RC10_DZ,0 +RC10_MAX,1900 +RC10_MIN,1100 +RC10_OPTION,0 +RC10_REVERSED,0 +RC10_TRIM,1500 +RC11_DZ,0 +RC11_MAX,1900 +RC11_MIN,1100 +RC11_OPTION,0 +RC11_REVERSED,0 +RC11_TRIM,1500 +RC12_DZ,0 +RC12_MAX,1900 +RC12_MIN,1100 +RC12_OPTION,0 +RC12_REVERSED,0 +RC12_TRIM,1500 +RC13_DZ,0 +RC13_MAX,1900 +RC13_MIN,1100 +RC13_OPTION,0 +RC13_REVERSED,0 +RC13_TRIM,1500 +RC14_DZ,0 +RC14_MAX,1900 +RC14_MIN,1100 +RC14_OPTION,0 +RC14_REVERSED,0 +RC14_TRIM,1500 +RC15_DZ,0 +RC15_MAX,1900 +RC15_MIN,1100 +RC15_OPTION,0 +RC15_REVERSED,0 +RC15_TRIM,1500 +RC16_DZ,0 +RC16_MAX,1900 +RC16_MIN,1100 +RC16_OPTION,0 +RC16_REVERSED,0 +RC16_TRIM,1500 +RC2_DZ,20 +RC2_MAX,1900 +RC2_MIN,1100 +RC2_OPTION,0 +RC2_REVERSED,0 +RC2_TRIM,1500 +RC3_DZ,30 +RC3_MAX,1900 +RC3_MIN,1100 +RC3_OPTION,0 +RC3_REVERSED,0 +RC3_TRIM,1500 +RC4_DZ,20 +RC4_MAX,1900 +RC4_MIN,1100 +RC4_OPTION,0 +RC4_REVERSED,0 +RC4_TRIM,1500 +RC5_DZ,0 +RC5_MAX,1900 +RC5_MIN,1100 +RC5_OPTION,0 +RC5_REVERSED,0 +RC5_TRIM,1500 +RC6_DZ,0 +RC6_MAX,1900 +RC6_MIN,1100 +RC6_OPTION,0 +RC6_REVERSED,0 +RC6_TRIM,1500 +RC7_DZ,0 +RC7_MAX,1900 +RC7_MIN,1100 +RC7_OPTION,0 +RC7_REVERSED,0 +RC7_TRIM,1500 +RC8_DZ,0 +RC8_MAX,1900 +RC8_MIN,1100 +RC8_OPTION,0 +RC8_REVERSED,0 +RC8_TRIM,1500 +RC9_DZ,0 +RC9_MAX,1900 +RC9_MIN,1100 +RC9_OPTION,0 +RC9_REVERSED,0 +RC9_TRIM,1500 +RCMAP_PITCH,2 +RCMAP_ROLL,1 +RCMAP_THROTTLE,3 +RCMAP_YAW,4 +RELAY1_FUNCTION,0 +RELAY2_FUNCTION,0 +RELAY3_FUNCTION,0 +RELAY4_FUNCTION,0 +RELAY5_FUNCTION,0 +RELAY6_FUNCTION,0 +RNGFND_FILT,0.5 +RNGFND1_TYPE,0 +RNGFND2_TYPE,0 +RNGFND3_TYPE,0 +RNGFND4_TYPE,0 +RNGFND5_TYPE,0 +RNGFND6_TYPE,0 +RNGFND7_TYPE,0 +RNGFND8_TYPE,0 +RNGFND9_TYPE,0 +RNGFNDA_TYPE,0 +RPM1_TYPE,0 +RPM2_TYPE,0 +RSSI_TYPE,0 +RTL_ALT,1500 +RTL_ALT_FINAL,0 +RTL_ALT_TYPE,0 +RTL_CLIMB_MIN,0 +RTL_CONE_SLOPE,3 +RTL_LOIT_TIME,5000 +RTL_OPTIONS,0 +RTL_SPEED,0 +SCHED_DEBUG,0 +SCHED_LOOP_RATE,400 +SCHED_OPTIONS,0 +SCR_ENABLE,0 +SERIAL_PASS1,0 +SERIAL_PASS2,-1 +SERIAL_PASSTIMO,15 +SERIAL0_BAUD,115 +SERIAL0_PROTOCOL,2 +SERIAL1_BAUD,57 +SERIAL1_OPTIONS,0 +SERIAL1_PROTOCOL,2 +SERIAL2_BAUD,57 +SERIAL2_OPTIONS,0 +SERIAL2_PROTOCOL,2 +SERIAL3_BAUD,230 +SERIAL3_OPTIONS,0 +SERIAL3_PROTOCOL,5 +SERIAL4_BAUD,230 +SERIAL4_OPTIONS,0 +SERIAL4_PROTOCOL,5 +SERIAL5_BAUD,57 +SERIAL5_OPTIONS,0 +SERIAL5_PROTOCOL,-1 +SERVO_32_ENABLE,0 +SERVO_BLH_3DMASK,0 +SERVO_BLH_AUTO,0 +SERVO_BLH_DEBUG,0 +SERVO_BLH_MASK,0 +SERVO_BLH_OTYPE,0 +SERVO_BLH_POLES,14 +SERVO_BLH_PORT,0 +SERVO_BLH_RVMASK,0 +SERVO_BLH_TEST,0 +SERVO_BLH_TMOUT,0 +SERVO_BLH_TRATE,10 +SERVO_DSHOT_ESC,0 +SERVO_DSHOT_RATE,0 +SERVO_FTW_MASK,0 +SERVO_FTW_POLES,14 +SERVO_FTW_RVMASK,0 +SERVO_GPIO_MASK,0 +SERVO_RATE,50 +SERVO_RC_FS_MSK,0 +SERVO_ROB_POSMAX,4095 +SERVO_ROB_POSMIN,0 +SERVO_SBUS_RATE,50 +SERVO_VOLZ_MASK,0 +SERVO1_FUNCTION,0 +SERVO1_MAX,1900 +SERVO1_MIN,1100 +SERVO1_REVERSED,0 +SERVO1_TRIM,1500 +SERVO10_FUNCTION,0 +SERVO10_MAX,1900 +SERVO10_MIN,1100 +SERVO10_REVERSED,0 +SERVO10_TRIM,1500 +SERVO11_FUNCTION,0 +SERVO11_MAX,1900 +SERVO11_MIN,1100 +SERVO11_REVERSED,0 +SERVO11_TRIM,1500 +SERVO12_FUNCTION,0 +SERVO12_MAX,1900 +SERVO12_MIN,1100 +SERVO12_REVERSED,0 +SERVO12_TRIM,1500 +SERVO13_FUNCTION,0 +SERVO13_MAX,1900 +SERVO13_MIN,1100 +SERVO13_REVERSED,0 +SERVO13_TRIM,1500 +SERVO14_FUNCTION,0 +SERVO14_MAX,1900 +SERVO14_MIN,1100 +SERVO14_REVERSED,0 +SERVO14_TRIM,1500 +SERVO15_FUNCTION,0 +SERVO15_MAX,1900 +SERVO15_MIN,1100 +SERVO15_REVERSED,0 +SERVO15_TRIM,1500 +SERVO16_FUNCTION,0 +SERVO16_MAX,1900 +SERVO16_MIN,1100 +SERVO16_REVERSED,0 +SERVO16_TRIM,1500 +SERVO2_FUNCTION,0 +SERVO2_MAX,1900 +SERVO2_MIN,1100 +SERVO2_REVERSED,0 +SERVO2_TRIM,1500 +SERVO3_FUNCTION,0 +SERVO3_MAX,1900 +SERVO3_MIN,1100 +SERVO3_REVERSED,0 +SERVO3_TRIM,1500 +SERVO4_FUNCTION,0 +SERVO4_MAX,1900 +SERVO4_MIN,1100 +SERVO4_REVERSED,0 +SERVO4_TRIM,1500 +SERVO5_FUNCTION,0 +SERVO5_MAX,1900 +SERVO5_MIN,1100 +SERVO5_REVERSED,0 +SERVO5_TRIM,1500 +SERVO6_FUNCTION,0 +SERVO6_MAX,1900 +SERVO6_MIN,1100 +SERVO6_REVERSED,0 +SERVO6_TRIM,1500 +SERVO7_FUNCTION,0 +SERVO7_MAX,1900 +SERVO7_MIN,1100 +SERVO7_REVERSED,0 +SERVO7_TRIM,1500 +SERVO8_FUNCTION,0 +SERVO8_MAX,1900 +SERVO8_MIN,1100 +SERVO8_REVERSED,0 +SERVO8_TRIM,1500 +SERVO9_FUNCTION,0 +SERVO9_MAX,1900 +SERVO9_MIN,1100 +SERVO9_REVERSED,0 +SERVO9_TRIM,1500 +SID_AXIS,0 +SIMPLE,0 +SPRAY_ENABLE,0 +SR0_ADSB,0 +SR0_EXT_STAT,0 +SR0_EXTRA1,0 +SR0_EXTRA2,0 +SR0_EXTRA3,0 +SR0_PARAMS,0 +SR0_POSITION,0 +SR0_RAW_CTRL,0 +SR0_RAW_SENS,0 +SR0_RC_CHAN,0 +SR1_ADSB,0 +SR1_EXT_STAT,0 +SR1_EXTRA1,0 +SR1_EXTRA2,0 +SR1_EXTRA3,0 +SR1_PARAMS,0 +SR1_POSITION,0 +SR1_RAW_CTRL,0 +SR1_RAW_SENS,0 +SR1_RC_CHAN,0 +SR2_ADSB,0 +SR2_EXT_STAT,0 +SR2_EXTRA1,0 +SR2_EXTRA2,0 +SR2_EXTRA3,0 +SR2_PARAMS,0 +SR2_POSITION,0 +SR2_RAW_CTRL,0 +SR2_RAW_SENS,0 +SR2_RC_CHAN,0 +SR3_ADSB,0 +SR3_EXT_STAT,0 +SR3_EXTRA1,0 +SR3_EXTRA2,0 +SR3_EXTRA3,0 +SR3_PARAMS,0 +SR3_POSITION,0 +SR3_RAW_CTRL,0 +SR3_RAW_SENS,0 +SR3_RC_CHAN,0 +SR4_ADSB,0 +SR4_EXT_STAT,0 +SR4_EXTRA1,0 +SR4_EXTRA2,0 +SR4_EXTRA3,0 +SR4_PARAMS,0 +SR4_POSITION,0 +SR4_RAW_CTRL,0 +SR4_RAW_SENS,0 +SR4_RC_CHAN,0 +SRTL_ACCURACY,2 +SRTL_OPTIONS,0 +SRTL_POINTS,300 +STAT_BOOTCNT,0 +STAT_FLTTIME,0 +STAT_RESET,1 +STAT_RUNTIME,0 +SUPER_SIMPLE,0 +SURFTRAK_MODE,1 +SURFTRAK_TC,1 +SYSID_ENFORCE,0 +SYSID_MYGCS,255 +SYSID_THISMAV,1 +TCAL_ENABLED,0 +TELEM_DELAY,0 +TERRAIN_ENABLE,1 +TERRAIN_MARGIN,0.05 +TERRAIN_OFS_MAX,30 +TERRAIN_OPTIONS,0 +TERRAIN_SPACING,100 +THR_DZ,100 +THROW_ALT_MAX,0 +THROW_ALT_MIN,0 +THROW_MOT_START,0 +THROW_NEXTMODE,18 +THROW_TYPE,0 +TKOFF_RPM_MAX,0 +TKOFF_RPM_MIN,0 +TKOFF_SLEW_TIME,2 +TKOFF_THR_MAX,0.9 +TUNE,0 +TUNE_MAX,0 +TUNE_MIN,0 +VISO_TYPE,0 +VTX_ENABLE,0 +WINCH_TYPE,0 +WP_NAVALT_MIN,0 +WP_YAW_BEHAVIOR,2 +WPNAV_ACCEL,250 +WPNAV_ACCEL_C,0 +WPNAV_ACCEL_Z,100 +WPNAV_JERK,1 +WPNAV_RADIUS,200 +WPNAV_RFND_USE,1 +WPNAV_SPEED,1000 +WPNAV_SPEED_DN,150 +WPNAV_SPEED_UP,250 +WPNAV_TER_MARGIN,10 +WVANE_ENABLE,0 +ZIGZ_AUTO_ENABLE,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/02_imu_temperature_calibration_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/02_imu_temperature_calibration_setup.param new file mode 100644 index 000000000..0f3298701 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/02_imu_temperature_calibration_setup.param @@ -0,0 +1,8 @@ +BRD_HEAT_TARG,65 # Reasonable for most places on this planet +INS_TCAL1_ENABLE,2 # Activates the temperature calibration for IMU 1 at the next start +INS_TCAL1_TMAX,70 +INS_TCAL2_ENABLE,2 # Activates the temperature calibration for IMU 2 at the next start +INS_TCAL2_TMAX,70 +INS_TCAL3_ENABLE,2 # Activates the temperature calibration for IMU 3 at the next start +LOG_BITMASK,524416 # Only for IMU and Raw-IMU +LOG_DISARMED,1 # Gather data for the offline IMU temperature calibration while the FC is disarmed diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/04_board_orientation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/04_board_orientation.param new file mode 100644 index 000000000..73fe42d6d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/04_board_orientation.param @@ -0,0 +1,4 @@ +AHRS_ORIENTATION,0 +BRD_HEAT_TARG,45 # Reset to default after offline IMU temperature calibration +LOG_BITMASK,145118 # Log all but fast att, Nav, Mission, OF, camera, fast IMU, raw, IMU, video stabilization. These are not needed now +LOG_DISARMED,0 # Log disarmed was only required for offline IMU temperature calibration diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/05_remote_controller.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/05_remote_controller.param new file mode 100644 index 000000000..b3eea7662 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/05_remote_controller.param @@ -0,0 +1,10 @@ +ARMING_RUDDER,2 +BRD_ALT_CONFIG,0 +RC_OPTIONS,32 +RC_PROTOCOLS,1 # Selected in the component editor +RC10_OPTION,0 +RC6_OPTION,0 +RC7_OPTION,0 +RC8_OPTION,0 +RC9_OPTION,0 +RSSI_TYPE,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/06_telemetry.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/06_telemetry.param new file mode 100644 index 000000000..81d9af398 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/06_telemetry.param @@ -0,0 +1,2 @@ +BRD_SER1_RTSCTS,2 +SERIAL1_BAUD,57 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/07_esc.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/07_esc.param new file mode 100644 index 000000000..846ee29b5 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/07_esc.param @@ -0,0 +1,28 @@ +ATC_RAT_PIT_SMAX,0 +ATC_RAT_RLL_SMAX,0 +ATC_RAT_YAW_SMAX,0 +ESC_HW_POLES,14 +MOT_HOVER_LEARN,2 # So that it can tune the throttle controller on 20_throttle_controller.param file +MOT_PWM_MAX,2000 +MOT_PWM_MIN,1000 +MOT_PWM_TYPE,0 # Specified in component editor window +MOT_SPOOL_TIME,0.5 +NTF_BUZZ_TYPES,5 +NTF_LED_TYPES,123079 +PSC_ACCZ_SMAX,0 +SERVO_BLH_POLES,14 # Specified in component editor window +SERVO_FTW_POLES,14 # Specified in component editor window +SERVO1_MAX,1900 +SERVO1_MIN,1100 +SERVO1_TRIM,1500 +SERVO2_MAX,1900 +SERVO2_MIN,1100 +SERVO2_TRIM,1500 +SERVO3_MAX,1900 +SERVO3_MIN,1100 +SERVO3_TRIM,1500 +SERVO4_MAX,1900 +SERVO4_MIN,1100 +SERVO4_TRIM,1500 +TKOFF_RPM_MIN,0 +TKOFF_SLEW_TIME,2 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/08_batt1.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/08_batt1.param new file mode 100644 index 000000000..8ee59c72f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/08_batt1.param @@ -0,0 +1,15 @@ +BATT_AMP_PERVLT,0 +BATT_ARM_VOLT,55.2 +BATT_CAPACITY,160000 +BATT_CRT_MAH,0 +BATT_CRT_VOLT,49.7 +BATT_FS_CRT_ACT,1 +BATT_FS_LOW_ACT,2 +BATT_FS_VOLTSRC,0 +BATT_I2C_BUS,4 +BATT_LOW_MAH,0 +BATT_LOW_VOLT,50.4 +BATT_MONITOR,0 +BATT_VOLT_MULT,0 +MOT_BAT_VOLT_MAX,0 # (Max voltage + 0.0) x no. of cells +MOT_BAT_VOLT_MIN,0 # (Critical voltage + 0.0) x no. of cells diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/10_gnss.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/10_gnss.param new file mode 100644 index 000000000..d1513dfb7 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/10_gnss.param @@ -0,0 +1,16 @@ +BRD_SAFETY_DEFLT,1 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +GPS_AUTO_SWITCH,1 +GPS_GNSS_MODE,0 +GPS_POS1_X,0 +GPS_POS1_Y,0 +GPS_POS1_Z,0 +GPS_POS2_X,0 +GPS_POS2_Y,0 +GPS_POS2_Z,0 +GPS_TYPE,1 +NTF_LED_TYPES,123079 +SERIAL3_PROTOCOL,5 +SERIAL4_PROTOCOL,5 +WPNAV_RADIUS,200 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/11_initial_atc.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/11_initial_atc.param new file mode 100644 index 000000000..39997ba2f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/11_initial_atc.param @@ -0,0 +1,18 @@ +ATC_ACCEL_P_MAX,221000 # Derived from vehicle component editor propeller size +ATC_ACCEL_R_MAX,221000 # Derived from vehicle component editor propeller size +ATC_ACCEL_Y_MAX,35100 # Derived from vehicle component editor propeller size +ATC_ANG_YAW_P,5.8 # Derived from vehicle component editor propeller size +ATC_RAT_PIT_FLTD,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_PIT_FLTE,0 # Initial value, will be improved at a later step +ATC_RAT_PIT_FLTT,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_RLL_FLTD,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_RLL_FLTE,0 # Initial value, will be improved at a later step +ATC_RAT_RLL_FLTT,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_YAW_FLTD,0 # Initial value, will be improved at a later step +ATC_RAT_YAW_FLTE,2 # Initial value, will be improved at a later step +ATC_RAT_YAW_FLTT,144.5 # INS_GYRO_FILTER / 2 +ATC_THR_MIX_MAN,0.1 # Value for the first couple of flights will be changed later once MOT_THST_HOVER is learned +INS_ACCEL_FILTER,10 # The default is 20Hz but that is too high in most situations +INS_GYRO_FILTER,289 # Derived from vehicle component editor propeller size +MOT_THST_EXPO,0.24 # Derived from vehicle component editor propeller size +MOT_THST_HOVER,0.2 # Hover learn will improve this initial guess diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/12_mp_setup_mandatory_hardware.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/12_mp_setup_mandatory_hardware.param new file mode 100644 index 000000000..219207364 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/12_mp_setup_mandatory_hardware.param @@ -0,0 +1,82 @@ +AHRS_TRIM_X,0 +AHRS_TRIM_Y,0 +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ACCEL_Y_MAX,27000 +ATC_RAT_PIT_FLTD,20 +ATC_RAT_PIT_FLTT,20 +ATC_RAT_RLL_FLTD,20 +ATC_RAT_RLL_FLTT,20 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_FLTT,20 +COMPASS_EXTERNAL,0 +COMPASS_ORIENT,0 +COMPASS_PRIO1_ID,131874 +COMPASS_USE2,1 +COMPASS_USE3,1 +FENCE_ACTION,1 +FENCE_ALT_MAX,100 +FENCE_ENABLE,0 +FENCE_RADIUS,300 +FLTMODE1,0 +FLTMODE2,0 +FLTMODE3,0 +FLTMODE4,0 +FLTMODE5,0 +FLTMODE6,0 +FRAME_CLASS,0 +FRAME_TYPE,1 +INS_ACC1_CALTEMP,-300 +INS_ACC2_CALTEMP,-300 +INS_ACC2SCAL_X,1 +INS_ACC2SCAL_Y,1 +INS_ACC2SCAL_Z,1 +INS_ACC3SCAL_X,1 +INS_ACC3SCAL_Y,1 +INS_ACC3SCAL_Z,1 +INS_ACCSCAL_X,1 +INS_ACCSCAL_Y,1 +INS_ACCSCAL_Z,1 +INS_GYRO_FILTER,20 +INS_USE3,1 +MOT_BAT_VOLT_MAX,0 +MOT_BAT_VOLT_MIN,0 +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_THST_EXPO,0.65 +MOT_THST_HOVER,0.35 +RC1_MAX,1900 +RC1_MIN,1100 +RC1_TRIM,1500 +RC10_MAX,1900 +RC10_MIN,1100 +RC10_TRIM,1500 +RC2_MAX,1900 +RC2_MIN,1100 +RC2_TRIM,1500 +RC3_MAX,1900 +RC3_MIN,1100 +RC3_TRIM,1500 +RC4_MAX,1900 +RC4_MIN,1100 +RC4_TRIM,1500 +RC5_MAX,1900 +RC5_MIN,1100 +RC5_TRIM,1500 +RC6_MAX,1900 +RC6_MIN,1100 +RC6_TRIM,1500 +RC7_MAX,1900 +RC7_MIN,1100 +RC7_TRIM,1500 +RC8_MAX,1900 +RC8_MIN,1100 +RC8_TRIM,1500 +RC9_MAX,1900 +RC9_MIN,1100 +RC9_TRIM,1500 +SERVO1_FUNCTION,0 +SERVO2_FUNCTION,0 +SERVO3_FUNCTION,0 +SERVO4_FUNCTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/13_general_configuration.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/13_general_configuration.param new file mode 100644 index 000000000..2ab591b4d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/13_general_configuration.param @@ -0,0 +1,18 @@ +ARMING_CHECK,1 # Perform all arming checks. If you have a problem fix its source. Do NOT change this +AUTO_OPTIONS,0 +BRD_HEAT_TARG,-1 +BRD_RTC_TZ_MIN,0 +EK3_SRC1_POSZ,1 +FENCE_TYPE,7 +FS_EKF_ACTION,1 +INS_ACCEL_FILTER,20 +INS_POS1_X,0 +INS_POS1_Y,0 +INS_POS2_X,0 +INS_POS2_Y,0 +LAND_ALT_LOW,1000 +RTL_ALT,1500 +RTL_LOIT_TIME,5000 +SCHED_LOOP_RATE,400 +SCR_ENABLE,1 # Use lua scripting for VTOL-Quicktune, MagFit automation and wind speed estimation automation +SERIAL7_PROTOCOL,-1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/14_logging.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/14_logging.param new file mode 100644 index 000000000..1cd3fedf3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/14_logging.param @@ -0,0 +1,6 @@ +INS_LOG_BAT_CNT,1024 +INS_LOG_BAT_MASK,1 # Use acc and gyro batch logging on F4 processors, gyro raw logging on others +INS_LOG_BAT_OPT,4 # Use pre and post filters acc and gyro batch logging on F4 processors, pre-post gyro raw logging on others +INS_RAW_LOG_OPT,0 # Use pre and post filters acc and gyro batch logging on F4 processors, pre-post gyro raw logging on others +LOG_BITMASK,145118 # Log all but fast att, Nav, Mission, OF, camera, fast IMU, raw, IMU, video stabilization. These are not needed now +LOG_FILE_DSRMROT,1 # One .bin log file per flight, not per battery/reboot diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/15_motor.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/15_motor.param new file mode 100644 index 000000000..14d698a75 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/15_motor.param @@ -0,0 +1,4 @@ +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_THST_EXPO,0.65 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/16_pid_adjustment.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/16_pid_adjustment.param new file mode 100644 index 000000000..f606f619b --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/16_pid_adjustment.param @@ -0,0 +1,15 @@ +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_INPUT_TC,0.15 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 +PSC_POSXY_P,1 +PSC_POSZ_P,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/17_remote_id.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/17_remote_id.param new file mode 100644 index 000000000..966271913 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/17_remote_id.param @@ -0,0 +1,4 @@ +DID_CANDRIVER,0 +DID_ENABLE,0 +DID_MAVPORT,2 +DID_OPTIONS,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/18_notch_filter_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/18_notch_filter_setup.param new file mode 100644 index 000000000..36fd0114f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/18_notch_filter_setup.param @@ -0,0 +1,10 @@ +INS_FAST_SAMPLE,5 +INS_GYRO_RATE,0 +INS_HNTCH_ATT,40 +INS_HNTCH_BW,22 +INS_HNTCH_ENABLE,1 # Use the first notch filter to filter the noise created by the motors/propellers +INS_HNTCH_FREQ,28 +INS_HNTCH_HMNCS,3 +INS_HNTCH_MODE,3 +INS_HNTCH_OPTS,2 +INS_HNTCH_REF,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/19_notch_filter_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/19_notch_filter_results.param new file mode 100644 index 000000000..aa4e78e30 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/19_notch_filter_results.param @@ -0,0 +1,8 @@ +INS_GYRO_FILTER,20 +INS_HNTCH_ATT,30 +INS_HNTCH_BW,11 +INS_HNTCH_FM_RAT,0.7 +INS_HNTCH_FREQ,43 +INS_HNTCH_HMNCS,3 +INS_HNTCH_OPTS,2 +INS_HNTCH_REF,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/20_throttle_controller.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/20_throttle_controller.param new file mode 100644 index 000000000..0cf81f627 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/20_throttle_controller.param @@ -0,0 +1,3 @@ +ATC_THR_MIX_MAN,0.1 +PSC_ACCZ_I,1 +PSC_ACCZ_P,0.5 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/21_ekf_config.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/21_ekf_config.param new file mode 100644 index 000000000..e937e5ee2 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/21_ekf_config.param @@ -0,0 +1,2 @@ +EK3_ACC_P_NSE,0.35 +EK3_ALT_M_NSE,2 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/22_quick_tune_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/22_quick_tune_setup.param new file mode 100644 index 000000000..cffbe6056 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/22_quick_tune_setup.param @@ -0,0 +1,14 @@ +QUIK_AUTO_FILTER,1 +QUIK_AUTO_SAVE,0 +QUIK_AXES,7 +QUIK_DOUBLE_TIME,10 +QUIK_ENABLE,1 +QUIK_GAIN_MARGIN,70 +QUIK_MAX_REDUCE,25 +QUIK_OPTIONS,0 +QUIK_OSC_SMAX,3 +QUIK_RC_FUNC,300 +QUIK_RP_PI_RATIO,1 +QUIK_Y_PI_RATIO,10 +QUIK_YAW_D_MAX,0.01 +QUIK_YAW_P_MAX,0.5 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/23_quick_tune_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/23_quick_tune_results.param new file mode 100644 index 000000000..df52dd073 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/23_quick_tune_results.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_FLTD,20 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.param new file mode 100644 index 000000000..4bc63ead8 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.param @@ -0,0 +1,8 @@ +MAGH_ALT_DELTA,20 +MAGH_B,1.4 +MAGH_CMD,117 +MAGH_COUNT,6 +MAGH_LOG_ENABLE,1 +MAGH_MIN_SPEED,6 +MAGH_NUM_WP,18 +MAGH_USE_LOITER,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.pdef.xml b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.pdef.xml new file mode 100644 index 000000000..aa2f497ab --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/24_inflight_magnetometer_fit_setup.pdef.xml @@ -0,0 +1,57 @@ + + + + + + + m + 0 100 + 10 + + + 1.2 1.5 + 1.2 + + + 0 255 + 117 + + + 1 20 + 6 + + + 0 1 + 1 + + + m/s + 1/2 of WPNAV_SPEED + + + 16 24 + 18 + + + 0 1 + 1 + + + 300 307 + 300 + + + 300 307 + 301 + + + 0 3600 + 0 + + + 0 1 + 0 + + + + diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/25_inflight_magnetometer_fit_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/25_inflight_magnetometer_fit_results.param new file mode 100644 index 000000000..1e91cd573 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/25_inflight_magnetometer_fit_results.param @@ -0,0 +1,43 @@ +COMPASS_DIA_X,1 +COMPASS_DIA_Y,1 +COMPASS_DIA_Z,1 +COMPASS_DIA2_X,1 +COMPASS_DIA2_Y,1 +COMPASS_DIA2_Z,1 +COMPASS_DIA3_X,1 +COMPASS_DIA3_Y,1 +COMPASS_DIA3_Z,1 +COMPASS_MOT_X,0 +COMPASS_MOT_Y,0 +COMPASS_MOT_Z,0 +COMPASS_MOT2_X,0 +COMPASS_MOT2_Y,0 +COMPASS_MOT2_Z,0 +COMPASS_MOT3_X,0 +COMPASS_MOT3_Y,0 +COMPASS_MOT3_Z,0 +COMPASS_MOTCT,0 +COMPASS_ODI_X,0 +COMPASS_ODI_Y,0 +COMPASS_ODI_Z,0 +COMPASS_ODI2_X,0 +COMPASS_ODI2_Y,0 +COMPASS_ODI2_Z,0 +COMPASS_ODI3_X,0 +COMPASS_ODI3_Y,0 +COMPASS_ODI3_Z,0 +COMPASS_OFS_X,0 +COMPASS_OFS_Y,0 +COMPASS_OFS_Z,0 +COMPASS_OFS2_X,0 +COMPASS_OFS2_Y,0 +COMPASS_OFS2_Z,0 +COMPASS_OFS3_X,0 +COMPASS_OFS3_Y,0 +COMPASS_OFS3_Z,0 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +COMPASS_ORIENT3,0 +COMPASS_SCALE,0 +COMPASS_SCALE2,0 +COMPASS_SCALE3,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/26_quick_tune_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/26_quick_tune_setup.param new file mode 100644 index 000000000..961400f78 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/26_quick_tune_setup.param @@ -0,0 +1,16 @@ +INS_RAW_LOG_OPT,0 +LOG_BITMASK,176126 +QUIK_AUTO_FILTER,1 +QUIK_AUTO_SAVE,0 +QUIK_AXES,7 +QUIK_DOUBLE_TIME,10 +QUIK_ENABLE,1 +QUIK_GAIN_MARGIN,70 +QUIK_MAX_REDUCE,25 +QUIK_OPTIONS,0 +QUIK_OSC_SMAX,3 +QUIK_RC_FUNC,300 +QUIK_RP_PI_RATIO,1 +QUIK_Y_PI_RATIO,10 +QUIK_YAW_D_MAX,0.01 +QUIK_YAW_P_MAX,0.5 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/27_quick_tune_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/27_quick_tune_results.param new file mode 100644 index 000000000..df52dd073 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/27_quick_tune_results.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_FLTD,20 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/28_evaluate_the_aircraft_tune_ff_disable.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/28_evaluate_the_aircraft_tune_ff_disable.param new file mode 100644 index 000000000..92e512243 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/28_evaluate_the_aircraft_tune_ff_disable.param @@ -0,0 +1,4 @@ +ATC_RATE_FF_ENAB,0 # test the stabilization loops independent of the input shaping +INS_LOG_BAT_MASK,0 # IMU batch logging no longer required, notch filter setup is complete, this reduces processor load and log file size +INS_RAW_LOG_OPT,0 # Gyro raw logging no longer required, notch filter setup is complete, this reduces processor load and log file size +LOG_BITMASK,145118 # Disable fast harmonic notch logging diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/29_evaluate_the_aircraft_tune_ff_enable.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/29_evaluate_the_aircraft_tune_ff_enable.param new file mode 100644 index 000000000..77242b284 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/29_evaluate_the_aircraft_tune_ff_enable.param @@ -0,0 +1 @@ +ATC_RATE_FF_ENAB,1 # re-enable normal operation, activate input shaping diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/30_autotune_roll_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/30_autotune_roll_setup.param new file mode 100644 index 000000000..eab08f0ff --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/30_autotune_roll_setup.param @@ -0,0 +1,2 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,1 # Autotune roll axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/31_autotune_roll_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/31_autotune_roll_results.param new file mode 100644 index 000000000..8c0d08ace --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/31_autotune_roll_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_R_MAX,110000 +ATC_ANG_RLL_P,4.5 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/32_autotune_pitch_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/32_autotune_pitch_setup.param new file mode 100644 index 000000000..741334b72 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/32_autotune_pitch_setup.param @@ -0,0 +1,2 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,2 # Autotune pitch axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/33_autotune_pitch_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/33_autotune_pitch_results.param new file mode 100644 index 000000000..e3b36741a --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/33_autotune_pitch_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_P_MAX,110000 +ATC_ANG_PIT_P,4.5 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/34_autotune_yaw_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/34_autotune_yaw_setup.param new file mode 100644 index 000000000..569a03736 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/34_autotune_yaw_setup.param @@ -0,0 +1,3 @@ +ATC_RAT_YAW_FLTD,20 +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,4 # Autotune yaw axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/35_autotune_yaw_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/35_autotune_yaw_results.param new file mode 100644 index 000000000..73a09d4e3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/35_autotune_yaw_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_Y_MAX,27000 +ATC_ANG_YAW_P,4.5 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/36_autotune_yawd_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/36_autotune_yawd_setup.param new file mode 100644 index 000000000..0f02e68c9 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/36_autotune_yawd_setup.param @@ -0,0 +1,3 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,8 # Autotune yaw D axis +AUTOTUNE_MIN_D,0.001 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/37_autotune_yawd_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/37_autotune_yawd_results.param new file mode 100644 index 000000000..452105da9 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/37_autotune_yawd_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_Y_MAX,27000 +ATC_ANG_YAW_P,4.5 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/38_autotune_roll_pitch_retune_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/38_autotune_roll_pitch_retune_setup.param new file mode 100644 index 000000000..2a1d17c2f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/38_autotune_roll_pitch_retune_setup.param @@ -0,0 +1,2 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,3 # Autotune roll and pitch axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/39_autotune_roll_pitch_retune_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/39_autotune_roll_pitch_retune_results.param new file mode 100644 index 000000000..fc82ea31d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/39_autotune_roll_pitch_retune_results.param @@ -0,0 +1,10 @@ +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/40_windspeed_estimation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/40_windspeed_estimation.param new file mode 100644 index 000000000..dcb80529d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/40_windspeed_estimation.param @@ -0,0 +1,5 @@ +EK3_DRAG_BCOEF_X,0 +EK3_DRAG_BCOEF_Y,0 +EK3_DRAG_MCOEF,0 +LOG_DISARMED,1 # allow post flight tuning with Replay +LOG_REPLAY,1 # allow post flight tuning with Replay diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/41_barometer_compensation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/41_barometer_compensation.param new file mode 100644 index 000000000..e8d825caf --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/41_barometer_compensation.param @@ -0,0 +1,7 @@ +BARO1_WCF_BCK,0 +BARO1_WCF_DN,0 +BARO1_WCF_ENABLE,0 +BARO1_WCF_FWD,0 +BARO1_WCF_LFT,0 +BARO1_WCF_RGT,0 +BARO1_WCF_UP,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/42_system_id_roll.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/42_system_id_roll.param new file mode 100644 index 000000000..b12b1aaaa --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/42_system_id_roll.param @@ -0,0 +1,21 @@ +ANGLE_MAX,3000 +ARMING_CHECK,1 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_RAT_RLL_I,0.135 +ATC_RATE_FF_ENAB,1 +FLTMODE5,0 +LOG_BITMASK,176126 +LOG_DISARMED,0 # was only needed for wind speed estimation +LOG_REPLAY,0 # was only needed for wind speed estimation +SID_AXIS,10 # Inject chip on the mixer roll signal +SID_F_START_HZ,0.05 +SID_F_STOP_HZ,5 +SID_MAGNITUDE,0.15 +SID_T_FADE_IN,5 +SID_T_FADE_OUT,5 +SID_T_REC,130 +TUNE,0 +TUNE_MAX,0 +TUNE_MIN,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/43_system_id_pitch.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/43_system_id_pitch.param new file mode 100644 index 000000000..e5c17d70b --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/43_system_id_pitch.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_I,0.135 +ATC_RAT_RLL_I,0.135 +ATC_RATE_FF_ENAB,1 +SID_AXIS,11 # Inject chip on the mixer pitch signal +SID_F_START_HZ,0.05 +SID_F_STOP_HZ,5 +SID_MAGNITUDE,0.15 +SID_T_FADE_IN,5 +SID_T_FADE_OUT,5 +SID_T_REC,130 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/44_system_id_yaw.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/44_system_id_yaw.param new file mode 100644 index 000000000..e4469d36a --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/44_system_id_yaw.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_I,0.135 +ATC_RAT_YAW_I,0.018 +ATC_RATE_FF_ENAB,1 +SID_AXIS,12 # Inject chip on the mixer yaw signal +SID_F_START_HZ,0.05 +SID_F_STOP_HZ,5 +SID_MAGNITUDE,0.55 +SID_T_FADE_IN,5 +SID_T_FADE_OUT,5 +SID_T_REC,130 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/45_system_id_thrust.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/45_system_id_thrust.param new file mode 100644 index 000000000..09c52e3de --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/45_system_id_thrust.param @@ -0,0 +1,10 @@ +ATC_RAT_YAW_I,0.018 +ATC_RATE_FF_ENAB,1 +PSC_ACCZ_I,1 +SID_AXIS,13 # Inject chip on the mixer thrust signal +SID_F_START_HZ,0.2 +SID_F_STOP_HZ,10 +SID_MAGNITUDE,0.12 +SID_T_FADE_IN,10 +SID_T_FADE_OUT,5 +SID_T_REC,100 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/46_analytical_pid_optimization.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/46_analytical_pid_optimization.param new file mode 100644 index 000000000..f76d7d5a3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/46_analytical_pid_optimization.param @@ -0,0 +1,4 @@ +ARMING_CHECK,1 # Normal state for everyday use +ATC_RATE_FF_ENAB,1 # Restore value now that system identification is done +PSC_ACCZ_I,1 +SID_AXIS,0 # No more system identification chip injections diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/47_position_controller.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/47_position_controller.param new file mode 100644 index 000000000..4b0e39a6c --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/47_position_controller.param @@ -0,0 +1,13 @@ +ANGLE_MAX,3000 +LOG_BITMASK,145150 # Add Navigation logging +LOIT_ACC_MAX,500 +LOIT_BRK_ACCEL,250 +LOIT_BRK_DELAY,1 +LOIT_BRK_JERK,500 +PSC_VELXY_FF,0 +WPNAV_ACCEL,250 +WPNAV_ACCEL_C,0 +WPNAV_ACCEL_Z,100 +WPNAV_JERK,1 +WPNAV_SPEED,1000 +WPNAV_SPEED_DN,150 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/48_guided_operation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/48_guided_operation.param new file mode 100644 index 000000000..a1aed6e17 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/48_guided_operation.param @@ -0,0 +1,4 @@ +FS_GCS_ENABLE,0 +RALLY_INCL_HOME,1 +RALLY_TOTAL,0 +SYSID_MYGCS,255 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/49_precision_land.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/49_precision_land.param new file mode 100644 index 000000000..d6ec9fba0 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/49_precision_land.param @@ -0,0 +1,27 @@ +EK3_RNG_M_NSE,0.5 +EK3_RNG_USE_HGT,-1 +LAND_ALT_LOW,1000 +LAND_SPEED,50 +PLND_ACC_P_NSE,2.5 +PLND_ALT_MAX,8 +PLND_ALT_MIN,0.75 +PLND_BUS,-1 +PLND_CAM_POS_X,0.14 +PLND_CAM_POS_Y,0 +PLND_CAM_POS_Z,0.05 +PLND_ENABLED,0 +PLND_EST_TYPE,0 +PLND_LAG,0.24 +PLND_LAND_OFS_X,0 +PLND_LAND_OFS_Y,0 +PLND_OPTIONS,0 +PLND_RET_BEHAVE,0 +PLND_RET_MAX,4 +PLND_STRICT,1 +PLND_TIMEOUT,4 +PLND_TYPE,1 +PLND_XY_DIST_MAX,0 +PLND_YAW_ALIGN,0 +PSC_POSXY_P,1 +RC10_OPTION,0 +RC11_OPTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/50_optical_flow_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/50_optical_flow_setup.param new file mode 100644 index 000000000..32883e818 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/50_optical_flow_setup.param @@ -0,0 +1,19 @@ +EK3_FLOW_DELAY,10 +EK3_SRC_OPTIONS,1 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +EK3_SRC2_POSXY,0 +EK3_SRC2_POSZ,1 +EK3_SRC2_VELXY,0 +EK3_SRC2_VELZ,0 +EK3_SRC2_YAW,0 +FLOW_ORIENT_YAW,0 +FLOW_POS_X,0 +FLOW_POS_Y,0 +FLOW_POS_Z,0 +FLOW_TYPE,0 +RC8_OPTION,0 +RC9_OPTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/51_optical_flow_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/51_optical_flow_results.param new file mode 100644 index 000000000..8afd7781c --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/51_optical_flow_results.param @@ -0,0 +1,3 @@ +FLOW_FXSCALER,0 +FLOW_FYSCALER,0 +FLOW_ORIENT_YAW,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/52_use_optical_flow_instead_of_gnss.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/52_use_optical_flow_instead_of_gnss.param new file mode 100644 index 000000000..35d946303 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/52_use_optical_flow_instead_of_gnss.param @@ -0,0 +1,8 @@ +EK3_SRC_OPTIONS,1 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +RC8_OPTION,0 +RC9_OPTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/53_everyday_use.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/53_everyday_use.param new file mode 100644 index 000000000..ba44f1aa3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/53_everyday_use.param @@ -0,0 +1,7 @@ +ATC_THR_MIX_MAX,0.5 +BATT_FS_LOW_ACT,2 +BATT2_FS_LOW_ACT,2 +LOG_BITMASK,176126 +MIS_OPTIONS,0 +RTL_ALT,1500 +RTL_CLIMB_MIN,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/vehicle_components.json b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/vehicle_components.json new file mode 100644 index 000000000..36f78f5e5 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.5.x/vehicle_components.json @@ -0,0 +1,187 @@ +{ + "Format version": 0, + "Components": { + "Flight Controller": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "ArduCopter", + "Version": "4.5.x" + }, + "Specifications": { + "MCU Series": "" + }, + "Notes": "" + }, + "Frame": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "TOW min Kg": 0.1, + "TOW max Kg": 0.1 + }, + "Notes": "" + }, + "RC Controller": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "Notes": "" + }, + "RC Transmitter": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "Notes": "" + }, + "RC Receiver": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "RCin/SBUS", + "Protocol": "All" + }, + "Notes": "" + }, + "Telemetry": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "SERIAL1", + "Protocol": "MAVLink2" + }, + "Notes": "" + }, + "Battery Monitor": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "None", + "Protocol": "None" + }, + "Notes": "" + }, + "Battery": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "Chemistry": "Lipo", + "Volt per cell max": 4.2, + "Volt per cell low": 3.6, + "Volt per cell crit": 3.55, + "Number of cells": 0, + "Capacity mAh": 0 + }, + "Notes": "" + }, + "ESC": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "Main Out", + "Protocol": "Normal" + }, + "Notes": "" + }, + "Motors": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "Poles": 14 + }, + "Notes": "" + }, + "Propellers": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "Diameter_inches": 0 + }, + "Notes": "" + }, + "GNSS Receiver": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "SERIAL3", + "Protocol": "AUTO" + }, + "Notes": "" + } + }, + "Program version": "2.0.6" +} diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/00_default.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/00_default.param new file mode 100644 index 000000000..592a00bf3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/00_default.param @@ -0,0 +1,1019 @@ +ACRO_BAL_PITCH,1 +ACRO_BAL_ROLL,1 +ACRO_OPTIONS,0 +ACRO_RP_EXPO,0.3 +ACRO_RP_RATE,360 +ACRO_RP_RATE_TC,0 +ACRO_THR_MID,0 +ACRO_TRAINER,2 +ACRO_Y_EXPO,0 +ACRO_Y_RATE,202.5 +ACRO_Y_RATE_TC,0 +ADSB_TYPE,0 +AHRS_COMP_BETA,0.1 +AHRS_EKF_TYPE,3 +AHRS_GPS_GAIN,1 +AHRS_GPS_MINSATS,6 +AHRS_GPS_USE,1 +AHRS_OPTIONS,0 +AHRS_ORIENTATION,0 +AHRS_RP_P,0.2 +AHRS_TRIM_X,0 +AHRS_TRIM_Y,0 +AHRS_TRIM_Z,0 +AHRS_WIND_MAX,0 +AHRS_YAW_P,0.2 +ANGLE_MAX,3000 +ARMING_ACCTHRESH,0.75 +ARMING_CHECK,1 +ARMING_CRSDP_IGN,0 +ARMING_MAGTHRESH,100 +ARMING_MIS_ITEMS,0 +ARMING_NEED_LOC,0 +ARMING_OPTIONS,0 +ARMING_RUDDER,2 +ARSPD_ENABLE,0 +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ACCEL_Y_MAX,27000 +ATC_ANG_LIM_TC,1 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_ANGLE_BOOST,1 +ATC_INPUT_TC,0.15 +ATC_LAND_P_MULT,1 +ATC_LAND_R_MULT,1 +ATC_LAND_Y_MULT,1 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_D_FF,0 +ATC_RAT_PIT_FF,0 +ATC_RAT_PIT_FLTD,20 +ATC_RAT_PIT_FLTE,0 +ATC_RAT_PIT_FLTT,20 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_IMAX,0.5 +ATC_RAT_PIT_NEF,0 +ATC_RAT_PIT_NTF,0 +ATC_RAT_PIT_P,0.135 +ATC_RAT_PIT_PDMX,0 +ATC_RAT_PIT_SMAX,0 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_D_FF,0 +ATC_RAT_RLL_FF,0 +ATC_RAT_RLL_FLTD,20 +ATC_RAT_RLL_FLTE,0 +ATC_RAT_RLL_FLTT,20 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_IMAX,0.5 +ATC_RAT_RLL_NEF,0 +ATC_RAT_RLL_NTF,0 +ATC_RAT_RLL_P,0.135 +ATC_RAT_RLL_PDMX,0 +ATC_RAT_RLL_SMAX,0 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_D_FF,0 +ATC_RAT_YAW_FF,0 +ATC_RAT_YAW_FLTD,20 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_FLTT,20 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_IMAX,0.5 +ATC_RAT_YAW_NEF,0 +ATC_RAT_YAW_NTF,0 +ATC_RAT_YAW_P,0.18 +ATC_RAT_YAW_PDMX,0 +ATC_RAT_YAW_SMAX,0 +ATC_RATE_FF_ENAB,1 +ATC_RATE_P_MAX,0 +ATC_RATE_R_MAX,0 +ATC_RATE_Y_MAX,0 +ATC_SLEW_YAW,6000 +ATC_THR_G_BOOST,0 +ATC_THR_MIX_MAN,0.1 +ATC_THR_MIX_MAX,0.5 +ATC_THR_MIX_MIN,0.1 +AUTO_OPTIONS,0 +AUTOTUNE_AGGR,0.075 +AUTOTUNE_AXES,7 +AUTOTUNE_MIN_D,0.0005 +AVD_ENABLE,0 +AVOID_ACCEL_MAX,3 +AVOID_ALT_MIN,0 +AVOID_ANGLE_MAX,1000 +AVOID_BACKUP_DZ,0.1 +AVOID_BACKUP_SPD,0.75 +AVOID_BACKZ_SPD,0.75 +AVOID_BEHAVE,0 +AVOID_DIST_MAX,5 +AVOID_ENABLE,3 +AVOID_MARGIN,2 +BARO_ALT_OFFSET,0 +BARO_ALTERR_MAX,2000 +BARO_EXT_BUS,-1 +BARO_FIELD_ELV,0 +BARO_FLTR_RNG,0 +BARO_GND_TEMP,0 +BARO_OPTIONS,0 +BARO_PRIMARY,0 +BARO_PROBE_EXT,0 +BARO1_DEVID,0 +BARO1_GND_PRESS,0 +BARO1_WCF_ENABLE,0 +BARO2_DEVID,0 +BARO2_GND_PRESS,0 +BARO2_WCF_ENABLE,0 +BARO3_DEVID,0 +BARO3_GND_PRESS,0 +BARO3_WCF_ENABLE,0 +BATT_MONITOR,0 +BATT2_MONITOR,0 +BATT3_MONITOR,0 +BATT4_MONITOR,0 +BATT5_MONITOR,0 +BATT6_MONITOR,0 +BATT7_MONITOR,0 +BATT8_MONITOR,0 +BATT9_MONITOR,0 +BCN_TYPE,0 +BRD_BOOT_DELAY,0 +BRD_HEAT_I,0.3 +BRD_HEAT_IMAX,70 +BRD_HEAT_LOWMGN,5 +BRD_HEAT_P,200 +BRD_HEAT_TARG,-1 +BRD_IO_DSHOT,0 +BRD_IO_ENABLE,1 +BRD_OPTIONS,1 +BRD_RTC_TYPES,1 +BRD_RTC_TZ_MIN,0 +BRD_SAFETY_DEFLT,1 +BRD_SAFETY_MASK,16383 +BRD_SAFETYOPTION,3 +BRD_SBUS_OUT,0 +BRD_SD_SLOWDOWN,0 +BRD_SER1_RTSCTS,2 +BRD_SER2_RTSCTS,2 +BRD_SERIAL_NUM,0 +BRD_TYPE,3 +BRD_VBUS_MIN,4.3 +BRD_VSERVO_MIN,0 +BTN_ENABLE,0 +CAM_AUTO_ONLY,0 +CAM_MAX_ROLL,0 +CAM_RC_TYPE,0 +CAM1_TYPE,0 +CAM2_TYPE,0 +CAN_D1_PROTOCOL,1 +CAN_D1_PROTOCOL2,0 +CAN_D2_PROTOCOL,1 +CAN_D2_PROTOCOL2,0 +CAN_LOGLEVEL,0 +CAN_P1_DRIVER,0 +CAN_P2_DRIVER,0 +CAN_SLCAN_CPORT,0 +CAN_SLCAN_SDELAY,1 +CAN_SLCAN_SERNUM,-1 +CAN_SLCAN_TIMOUT,0 +CHUTE_ENABLED,0 +CIRCLE_OPTIONS,1 +CIRCLE_RADIUS,1000 +CIRCLE_RATE,20 +COMPASS_AUTO_ROT,2 +COMPASS_AUTODEC,1 +COMPASS_CAL_FIT,16 +COMPASS_DEC,0 +COMPASS_DEV_ID,0 +COMPASS_DEV_ID2,0 +COMPASS_DEV_ID3,0 +COMPASS_DEV_ID4,0 +COMPASS_DEV_ID5,0 +COMPASS_DEV_ID6,0 +COMPASS_DEV_ID7,0 +COMPASS_DEV_ID8,0 +COMPASS_DIA_X,1 +COMPASS_DIA_Y,1 +COMPASS_DIA_Z,1 +COMPASS_DIA2_X,1 +COMPASS_DIA2_Y,1 +COMPASS_DIA2_Z,1 +COMPASS_DIA3_X,1 +COMPASS_DIA3_Y,1 +COMPASS_DIA3_Z,1 +COMPASS_DISBLMSK,32 +COMPASS_ENABLE,1 +COMPASS_EXTERN2,0 +COMPASS_EXTERN3,0 +COMPASS_EXTERNAL,0 +COMPASS_FLTR_RNG,0 +COMPASS_LEARN,0 +COMPASS_MOT_X,0 +COMPASS_MOT_Y,0 +COMPASS_MOT_Z,0 +COMPASS_MOT2_X,0 +COMPASS_MOT2_Y,0 +COMPASS_MOT2_Z,0 +COMPASS_MOT3_X,0 +COMPASS_MOT3_Y,0 +COMPASS_MOT3_Z,0 +COMPASS_MOTCT,0 +COMPASS_ODI_X,0 +COMPASS_ODI_Y,0 +COMPASS_ODI_Z,0 +COMPASS_ODI2_X,0 +COMPASS_ODI2_Y,0 +COMPASS_ODI2_Z,0 +COMPASS_ODI3_X,0 +COMPASS_ODI3_Y,0 +COMPASS_ODI3_Z,0 +COMPASS_OFFS_MAX,1800 +COMPASS_OFS_X,0 +COMPASS_OFS_Y,0 +COMPASS_OFS_Z,0 +COMPASS_OFS2_X,0 +COMPASS_OFS2_Y,0 +COMPASS_OFS2_Z,0 +COMPASS_OFS3_X,0 +COMPASS_OFS3_Y,0 +COMPASS_OFS3_Z,0 +COMPASS_OPTIONS,0 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +COMPASS_ORIENT3,0 +COMPASS_PMOT_EN,0 +COMPASS_PRIO1_ID,0 +COMPASS_PRIO2_ID,0 +COMPASS_PRIO3_ID,0 +COMPASS_SCALE,0 +COMPASS_SCALE2,0 +COMPASS_SCALE3,0 +COMPASS_USE,1 +COMPASS_USE2,1 +COMPASS_USE3,1 +CUST_ROT_ENABLE,0 +DEV_OPTIONS,0 +DISARM_DELAY,10 +EAHRS_TYPE,0 +EFI_TYPE,0 +EK3_ABIAS_P_NSE,0.02 +EK3_ACC_BIAS_LIM,1 +EK3_ACC_P_NSE,0.35 +EK3_AFFINITY,0 +EK3_ALT_M_NSE,2 +EK3_BCN_DELAY,50 +EK3_BCN_I_GTE,500 +EK3_BCN_M_NSE,1 +EK3_BETA_MASK,0 +EK3_CHECK_SCALE,100 +EK3_DRAG_BCOEF_X,0 +EK3_DRAG_BCOEF_Y,0 +EK3_DRAG_M_NSE,0.5 +EK3_DRAG_MCOEF,0 +EK3_EAS_I_GATE,400 +EK3_EAS_M_NSE,1.4 +EK3_ENABLE,1 +EK3_ERR_THRESH,0.2 +EK3_FLOW_DELAY,10 +EK3_FLOW_I_GATE,300 +EK3_FLOW_M_NSE,0.25 +EK3_FLOW_USE,1 +EK3_GBIAS_P_NSE,0.001 +EK3_GLITCH_RAD,25 +EK3_GND_EFF_DZ,4 +EK3_GPS_CHECK,31 +EK3_GPS_VACC_MAX,0 +EK3_GSF_RST_MAX,2 +EK3_GSF_RUN_MASK,3 +EK3_GSF_USE_MASK,3 +EK3_GYRO_P_NSE,0.015 +EK3_HGT_DELAY,60 +EK3_HGT_I_GATE,500 +EK3_HRT_FILT,2 +EK3_IMU_MASK,3 +EK3_LOG_LEVEL,0 +EK3_MAG_CAL,3 +EK3_MAG_EF_LIM,50 +EK3_MAG_I_GATE,300 +EK3_MAG_M_NSE,0.05 +EK3_MAG_MASK,0 +EK3_MAGB_P_NSE,0.0001 +EK3_MAGE_P_NSE,0.001 +EK3_MAX_FLOW,2.5 +EK3_NOAID_M_NSE,10 +EK3_OGN_HGT_MASK,0 +EK3_OGNM_TEST_SF,2 +EK3_OPTIONS,0 +EK3_POS_I_GATE,500 +EK3_POSNE_M_NSE,0.5 +EK3_PRIMARY,0 +EK3_RNG_I_GATE,500 +EK3_RNG_M_NSE,0.5 +EK3_RNG_USE_HGT,-1 +EK3_RNG_USE_SPD,2 +EK3_SRC_OPTIONS,1 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +EK3_SRC2_POSXY,0 +EK3_SRC2_POSZ,1 +EK3_SRC2_VELXY,0 +EK3_SRC2_VELZ,0 +EK3_SRC2_YAW,0 +EK3_SRC3_POSXY,0 +EK3_SRC3_POSZ,1 +EK3_SRC3_VELXY,0 +EK3_SRC3_VELZ,0 +EK3_SRC3_YAW,0 +EK3_TAU_OUTPUT,25 +EK3_TERR_GRAD,0.1 +EK3_VEL_I_GATE,500 +EK3_VELD_M_NSE,0.5 +EK3_VELNE_M_NSE,0.3 +EK3_VIS_VERR_MAX,0.9 +EK3_VIS_VERR_MIN,0.1 +EK3_WENC_VERR,0.1 +EK3_WIND_P_NSE,0.2 +EK3_WIND_PSCALE,1 +EK3_YAW_I_GATE,300 +EK3_YAW_M_NSE,0.5 +ESC_CALIBRATION,0 +ESC_TLM_MAV_OFS,0 +FENCE_ACTION,1 +FENCE_ALT_MAX,100 +FENCE_ALT_MIN,-10 +FENCE_AUTOENABLE,0 +FENCE_ENABLE,0 +FENCE_MARGIN,2 +FENCE_OPTIONS,0 +FENCE_RADIUS,300 +FENCE_TOTAL,0 +FENCE_TYPE,7 +FFT_ENABLE,0 +FHLD_BRAKE_RATE,8 +FHLD_FILT_HZ,5 +FHLD_FLOW_MAX,0.6 +FHLD_QUAL_MIN,10 +FHLD_XY_FILT_HZ,5 +FHLD_XY_I,0.3 +FHLD_XY_IMAX,3000 +FHLD_XY_P,0.2 +FILT1_TYPE,0 +FILT2_TYPE,0 +FILT3_TYPE,0 +FILT4_TYPE,0 +FILT5_TYPE,0 +FILT6_TYPE,0 +FILT7_TYPE,0 +FILT8_TYPE,0 +FLIGHT_OPTIONS,0 +FLOW_TYPE,0 +FLTMODE_CH,5 +FLTMODE_GCSBLOCK,0 +FLTMODE1,0 +FLTMODE2,0 +FLTMODE3,0 +FLTMODE4,0 +FLTMODE5,0 +FLTMODE6,0 +FOLL_ENABLE,0 +FORMAT_VERSION,120 +FRAME_CLASS,0 +FRAME_TYPE,1 +FRSKY_DNLINK_ID,27 +FRSKY_DNLINK1_ID,20 +FRSKY_DNLINK2_ID,7 +FRSKY_OPTIONS,0 +FRSKY_UPLINK_ID,13 +FS_CRASH_CHECK,1 +FS_DR_ENABLE,2 +FS_DR_TIMEOUT,30 +FS_EKF_ACTION,1 +FS_EKF_FILT,5 +FS_EKF_THRESH,0.8 +FS_GCS_ENABLE,0 +FS_GCS_TIMEOUT,5 +FS_OPTIONS,16 +FS_THR_ENABLE,1 +FS_THR_VALUE,975 +FS_VIBE_ENABLE,1 +GCS_PID_MASK,0 +GEN_TYPE,0 +GND_EFFECT_COMP,1 +GPS_AUTO_CONFIG,1 +GPS_AUTO_SWITCH,1 +GPS_BLEND_MASK,5 +GPS_DRV_OPTIONS,0 +GPS_HDOP_GOOD,140 +GPS_INJECT_TO,127 +GPS_MIN_ELEV,-100 +GPS_NAVFILTER,8 +GPS_PRIMARY,0 +GPS_RAW_DATA,0 +GPS_SAVE_CFG,2 +GPS_SBAS_MODE,2 +GPS_SBP_LOGMASK,-256 +GPS1_CAN_NODEID,0 +GPS1_CAN_OVRIDE,0 +GPS1_COM_PORT,1 +GPS1_DELAY_MS,0 +GPS1_GNSS_MODE,0 +GPS1_MB_TYPE,0 +GPS1_POS_X,0 +GPS1_POS_Y,0 +GPS1_POS_Z,0 +GPS1_RATE_MS,200 +GPS1_TYPE,1 +GPS2_TYPE,0 +GRIP_ENABLE,0 +GUID_OPTIONS,0 +GUID_TIMEOUT,3 +INITIAL_MODE,0 +INS_ACC_BODYFIX,2 +INS_ACC_ID,0 +INS_ACC1_CALTEMP,-300 +INS_ACC2_CALTEMP,-300 +INS_ACC2_ID,0 +INS_ACC2OFFS_X,0 +INS_ACC2OFFS_Y,0 +INS_ACC2OFFS_Z,0 +INS_ACC2SCAL_X,1 +INS_ACC2SCAL_Y,1 +INS_ACC2SCAL_Z,1 +INS_ACC3_CALTEMP,-300 +INS_ACC3_ID,0 +INS_ACC3OFFS_X,0 +INS_ACC3OFFS_Y,0 +INS_ACC3OFFS_Z,0 +INS_ACC3SCAL_X,1 +INS_ACC3SCAL_Y,1 +INS_ACC3SCAL_Z,1 +INS_ACCEL_FILTER,20 +INS_ACCOFFS_X,0 +INS_ACCOFFS_Y,0 +INS_ACCOFFS_Z,0 +INS_ACCSCAL_X,1 +INS_ACCSCAL_Y,1 +INS_ACCSCAL_Z,1 +INS_ENABLE_MASK,127 +INS_FAST_SAMPLE,5 +INS_GYR_CAL,1 +INS_GYR_ID,0 +INS_GYR1_CALTEMP,-300 +INS_GYR2_CALTEMP,-300 +INS_GYR2_ID,0 +INS_GYR2OFFS_X,0 +INS_GYR2OFFS_Y,0 +INS_GYR2OFFS_Z,0 +INS_GYR3_CALTEMP,-300 +INS_GYR3_ID,0 +INS_GYR3OFFS_X,0 +INS_GYR3OFFS_Y,0 +INS_GYR3OFFS_Z,0 +INS_GYRO_FILTER,20 +INS_GYRO_RATE,0 +INS_GYROFFS_X,0 +INS_GYROFFS_Y,0 +INS_GYROFFS_Z,0 +INS_HNTC2_ENABLE,0 +INS_HNTCH_ENABLE,0 +INS_LOG_BAT_CNT,1024 +INS_LOG_BAT_LGCT,32 +INS_LOG_BAT_LGIN,20 +INS_LOG_BAT_MASK,0 +INS_LOG_BAT_OPT,0 +INS_POS1_X,0 +INS_POS1_Y,0 +INS_POS1_Z,0 +INS_POS2_X,0 +INS_POS2_Y,0 +INS_POS2_Z,0 +INS_POS3_X,0 +INS_POS3_Y,0 +INS_POS3_Z,0 +INS_RAW_LOG_OPT,0 +INS_STILL_THRESH,2.5 +INS_TCAL_OPTIONS,0 +INS_TCAL1_ENABLE,0 +INS_TCAL2_ENABLE,0 +INS_TCAL3_ENABLE,0 +INS_TRIM_OPTION,1 +INS_USE,1 +INS_USE2,1 +INS_USE3,1 +KDE_NPOLE,14 +LAND_ALT_LOW,1000 +LAND_REPOSITION,1 +LAND_SPEED,50 +LAND_SPEED_HIGH,0 +LGR_ENABLE,0 +LOG_BACKEND_TYPE,1 +LOG_BITMASK,180222 +LOG_DARM_RATEMAX,0 +LOG_DISARMED,0 +LOG_FILE_BUFSIZE,16 +LOG_FILE_DSRMROT,0 +LOG_FILE_MB_FREE,500 +LOG_FILE_RATEMAX,0 +LOG_FILE_TIMEOUT,5 +LOG_MAV_BUFSIZE,8 +LOG_MAV_RATEMAX,0 +LOG_MAX_FILES,500 +LOG_REPLAY,0 +LOIT_ACC_MAX,500 +LOIT_ANG_MAX,0 +LOIT_BRK_ACCEL,250 +LOIT_BRK_DELAY,1 +LOIT_BRK_JERK,500 +LOIT_SPEED,1250 +MIS_OPTIONS,0 +MIS_RESTART,0 +MIS_TOTAL,0 +MNT1_TYPE,0 +MNT2_TYPE,0 +MOT_BAT_CURR_MAX,0 +MOT_BAT_CURR_TC,5 +MOT_BAT_IDX,0 +MOT_BAT_VOLT_MAX,0 +MOT_BAT_VOLT_MIN,0 +MOT_BOOST_SCALE,0 +MOT_HOVER_LEARN,2 +MOT_OPTIONS,0 +MOT_PWM_MAX,2000 +MOT_PWM_MIN,1000 +MOT_PWM_TYPE,0 +MOT_SAFE_DISARM,0 +MOT_SAFE_TIME,1 +MOT_SLEW_DN_TIME,0 +MOT_SLEW_UP_TIME,0 +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_SPOOL_TIM_DN,0 +MOT_SPOOL_TIME,0.5 +MOT_THST_EXPO,0.65 +MOT_THST_HOVER,0.35 +MOT_YAW_HEADROOM,200 +MSP_OPTIONS,0 +MSP_OSD_NCELLS,0 +NMEA_MSG_EN,3 +NMEA_RATE_MS,100 +NTF_BUZZ_ON_LVL,1 +NTF_BUZZ_PIN,-1 +NTF_BUZZ_TYPES,5 +NTF_BUZZ_VOLUME,100 +NTF_DISPLAY_TYPE,0 +NTF_LED_BRIGHT,3 +NTF_LED_LEN,1 +NTF_LED_OVERRIDE,0 +NTF_LED_TYPES,123079 +NTF_OREO_THEME,0 +OA_TYPE,0 +OSD_TYPE,0 +PHLD_BRAKE_ANGLE,3000 +PHLD_BRAKE_RATE,8 +PILOT_ACCEL_Z,250 +PILOT_SPEED_DN,0 +PILOT_SPEED_UP,250 +PILOT_THR_BHV,0 +PILOT_THR_FILT,0 +PILOT_TKOFF_ALT,0 +PILOT_Y_EXPO,0 +PILOT_Y_RATE,202.5 +PILOT_Y_RATE_TC,0 +PLDP_DELAY,0 +PLDP_RNG_MAX,0 +PLDP_SPEED_DN,0 +PLDP_THRESH,0.9 +PLND_ENABLED,0 +PRX_ALT_MIN,1 +PRX_FILT,0.25 +PRX_IGN_GND,0 +PRX_LOG_RAW,0 +PRX1_TYPE,0 +PRX2_TYPE,0 +PRX3_TYPE,0 +PRX4_TYPE,0 +PRX5_TYPE,0 +PSC_ACCZ_D,0 +PSC_ACCZ_D_FF,0 +PSC_ACCZ_FF,0 +PSC_ACCZ_FLTD,0 +PSC_ACCZ_FLTE,20 +PSC_ACCZ_FLTT,0 +PSC_ACCZ_I,1 +PSC_ACCZ_IMAX,800 +PSC_ACCZ_NEF,0 +PSC_ACCZ_NTF,0 +PSC_ACCZ_P,0.5 +PSC_ACCZ_PDMX,0 +PSC_ACCZ_SMAX,0 +PSC_ANGLE_MAX,0 +PSC_JERK_XY,5 +PSC_JERK_Z,5 +PSC_POSXY_P,1 +PSC_POSZ_P,1 +PSC_VELXY_D,0.25 +PSC_VELXY_FF,0 +PSC_VELXY_FLTD,5 +PSC_VELXY_FLTE,5 +PSC_VELXY_I,1 +PSC_VELXY_IMAX,1000 +PSC_VELXY_P,2 +PSC_VELZ_D,0 +PSC_VELZ_FF,0 +PSC_VELZ_FLTD,5 +PSC_VELZ_FLTE,5 +PSC_VELZ_I,0 +PSC_VELZ_IMAX,1000 +PSC_VELZ_P,5 +RALLY_INCL_HOME,1 +RALLY_LIMIT_KM,0.3 +RALLY_TOTAL,0 +RC_FS_TIMEOUT,1 +RC_OPTIONS,32 +RC_OVERRIDE_TIME,3 +RC_PROTOCOLS,1 +RC_SPEED,490 +RC1_DZ,20 +RC1_MAX,1900 +RC1_MIN,1100 +RC1_OPTION,0 +RC1_REVERSED,0 +RC1_TRIM,1500 +RC10_DZ,0 +RC10_MAX,1900 +RC10_MIN,1100 +RC10_OPTION,0 +RC10_REVERSED,0 +RC10_TRIM,1500 +RC11_DZ,0 +RC11_MAX,1900 +RC11_MIN,1100 +RC11_OPTION,0 +RC11_REVERSED,0 +RC11_TRIM,1500 +RC12_DZ,0 +RC12_MAX,1900 +RC12_MIN,1100 +RC12_OPTION,0 +RC12_REVERSED,0 +RC12_TRIM,1500 +RC13_DZ,0 +RC13_MAX,1900 +RC13_MIN,1100 +RC13_OPTION,0 +RC13_REVERSED,0 +RC13_TRIM,1500 +RC14_DZ,0 +RC14_MAX,1900 +RC14_MIN,1100 +RC14_OPTION,0 +RC14_REVERSED,0 +RC14_TRIM,1500 +RC15_DZ,0 +RC15_MAX,1900 +RC15_MIN,1100 +RC15_OPTION,0 +RC15_REVERSED,0 +RC15_TRIM,1500 +RC16_DZ,0 +RC16_MAX,1900 +RC16_MIN,1100 +RC16_OPTION,0 +RC16_REVERSED,0 +RC16_TRIM,1500 +RC2_DZ,20 +RC2_MAX,1900 +RC2_MIN,1100 +RC2_OPTION,0 +RC2_REVERSED,0 +RC2_TRIM,1500 +RC3_DZ,30 +RC3_MAX,1900 +RC3_MIN,1100 +RC3_OPTION,0 +RC3_REVERSED,0 +RC3_TRIM,1500 +RC4_DZ,20 +RC4_MAX,1900 +RC4_MIN,1100 +RC4_OPTION,0 +RC4_REVERSED,0 +RC4_TRIM,1500 +RC5_DZ,0 +RC5_MAX,1900 +RC5_MIN,1100 +RC5_OPTION,0 +RC5_REVERSED,0 +RC5_TRIM,1500 +RC6_DZ,0 +RC6_MAX,1900 +RC6_MIN,1100 +RC6_OPTION,0 +RC6_REVERSED,0 +RC6_TRIM,1500 +RC7_DZ,0 +RC7_MAX,1900 +RC7_MIN,1100 +RC7_OPTION,0 +RC7_REVERSED,0 +RC7_TRIM,1500 +RC8_DZ,0 +RC8_MAX,1900 +RC8_MIN,1100 +RC8_OPTION,0 +RC8_REVERSED,0 +RC8_TRIM,1500 +RC9_DZ,0 +RC9_MAX,1900 +RC9_MIN,1100 +RC9_OPTION,0 +RC9_REVERSED,0 +RC9_TRIM,1500 +RCMAP_PITCH,2 +RCMAP_ROLL,1 +RCMAP_THROTTLE,3 +RCMAP_YAW,4 +RELAY1_FUNCTION,0 +RELAY2_FUNCTION,0 +RELAY3_FUNCTION,0 +RELAY4_FUNCTION,0 +RELAY5_FUNCTION,0 +RELAY6_FUNCTION,0 +RNGFND_FILT,0.5 +RNGFND1_TYPE,0 +RNGFND2_TYPE,0 +RNGFND3_TYPE,0 +RNGFND4_TYPE,0 +RNGFND5_TYPE,0 +RNGFND6_TYPE,0 +RNGFND7_TYPE,0 +RNGFND8_TYPE,0 +RNGFND9_TYPE,0 +RNGFNDA_TYPE,0 +RPM1_TYPE,0 +RPM2_TYPE,0 +RSSI_TYPE,0 +RTL_ALT,1500 +RTL_ALT_FINAL,0 +RTL_ALT_TYPE,0 +RTL_CLIMB_MIN,0 +RTL_CONE_SLOPE,3 +RTL_LOIT_TIME,5000 +RTL_OPTIONS,0 +RTL_SPEED,0 +SCHED_DEBUG,0 +SCHED_LOOP_RATE,400 +SCHED_OPTIONS,0 +SCR_ENABLE,0 +SERIAL_PASS1,0 +SERIAL_PASS2,-1 +SERIAL_PASSTIMO,15 +SERIAL0_BAUD,115 +SERIAL0_PROTOCOL,2 +SERIAL1_BAUD,57 +SERIAL1_OPTIONS,0 +SERIAL1_PROTOCOL,2 +SERIAL2_BAUD,57 +SERIAL2_OPTIONS,0 +SERIAL2_PROTOCOL,2 +SERIAL3_BAUD,230 +SERIAL3_OPTIONS,0 +SERIAL3_PROTOCOL,5 +SERIAL4_BAUD,230 +SERIAL4_OPTIONS,0 +SERIAL4_PROTOCOL,5 +SERIAL5_BAUD,57 +SERIAL5_OPTIONS,0 +SERIAL5_PROTOCOL,-1 +SERVO_32_ENABLE,0 +SERVO_BLH_3DMASK,0 +SERVO_BLH_AUTO,0 +SERVO_BLH_DEBUG,0 +SERVO_BLH_MASK,0 +SERVO_BLH_OTYPE,0 +SERVO_BLH_POLES,14 +SERVO_BLH_PORT,0 +SERVO_BLH_RVMASK,0 +SERVO_BLH_TEST,0 +SERVO_BLH_TMOUT,0 +SERVO_BLH_TRATE,10 +SERVO_DSHOT_ESC,0 +SERVO_DSHOT_RATE,0 +SERVO_FTW_MASK,0 +SERVO_FTW_POLES,14 +SERVO_FTW_RVMASK,0 +SERVO_GPIO_MASK,0 +SERVO_RATE,50 +SERVO_RC_FS_MSK,0 +SERVO_ROB_POSMAX,4095 +SERVO_ROB_POSMIN,0 +SERVO_SBUS_RATE,50 +SERVO_VOLZ_MASK,0 +SERVO_VOLZ_RANGE,200 +SERVO1_FUNCTION,0 +SERVO1_MAX,1900 +SERVO1_MIN,1100 +SERVO1_REVERSED,0 +SERVO1_TRIM,1500 +SERVO10_FUNCTION,0 +SERVO10_MAX,1900 +SERVO10_MIN,1100 +SERVO10_REVERSED,0 +SERVO10_TRIM,1500 +SERVO11_FUNCTION,0 +SERVO11_MAX,1900 +SERVO11_MIN,1100 +SERVO11_REVERSED,0 +SERVO11_TRIM,1500 +SERVO12_FUNCTION,0 +SERVO12_MAX,1900 +SERVO12_MIN,1100 +SERVO12_REVERSED,0 +SERVO12_TRIM,1500 +SERVO13_FUNCTION,0 +SERVO13_MAX,1900 +SERVO13_MIN,1100 +SERVO13_REVERSED,0 +SERVO13_TRIM,1500 +SERVO14_FUNCTION,0 +SERVO14_MAX,1900 +SERVO14_MIN,1100 +SERVO14_REVERSED,0 +SERVO14_TRIM,1500 +SERVO15_FUNCTION,0 +SERVO15_MAX,1900 +SERVO15_MIN,1100 +SERVO15_REVERSED,0 +SERVO15_TRIM,1500 +SERVO16_FUNCTION,0 +SERVO16_MAX,1900 +SERVO16_MIN,1100 +SERVO16_REVERSED,0 +SERVO16_TRIM,1500 +SERVO2_FUNCTION,0 +SERVO2_MAX,1900 +SERVO2_MIN,1100 +SERVO2_REVERSED,0 +SERVO2_TRIM,1500 +SERVO3_FUNCTION,0 +SERVO3_MAX,1900 +SERVO3_MIN,1100 +SERVO3_REVERSED,0 +SERVO3_TRIM,1500 +SERVO4_FUNCTION,0 +SERVO4_MAX,1900 +SERVO4_MIN,1100 +SERVO4_REVERSED,0 +SERVO4_TRIM,1500 +SERVO5_FUNCTION,0 +SERVO5_MAX,1900 +SERVO5_MIN,1100 +SERVO5_REVERSED,0 +SERVO5_TRIM,1500 +SERVO6_FUNCTION,0 +SERVO6_MAX,1900 +SERVO6_MIN,1100 +SERVO6_REVERSED,0 +SERVO6_TRIM,1500 +SERVO7_FUNCTION,0 +SERVO7_MAX,1900 +SERVO7_MIN,1100 +SERVO7_REVERSED,0 +SERVO7_TRIM,1500 +SERVO8_FUNCTION,0 +SERVO8_MAX,1900 +SERVO8_MIN,1100 +SERVO8_REVERSED,0 +SERVO8_TRIM,1500 +SERVO9_FUNCTION,0 +SERVO9_MAX,1900 +SERVO9_MIN,1100 +SERVO9_REVERSED,0 +SERVO9_TRIM,1500 +SID_AXIS,0 +SIMPLE,0 +SPRAY_ENABLE,0 +SR0_ADSB,0 +SR0_EXT_STAT,0 +SR0_EXTRA1,0 +SR0_EXTRA2,0 +SR0_EXTRA3,0 +SR0_PARAMS,0 +SR0_POSITION,0 +SR0_RAW_CTRL,0 +SR0_RAW_SENS,0 +SR0_RC_CHAN,0 +SR1_ADSB,0 +SR1_EXT_STAT,0 +SR1_EXTRA1,0 +SR1_EXTRA2,0 +SR1_EXTRA3,0 +SR1_PARAMS,0 +SR1_POSITION,0 +SR1_RAW_CTRL,0 +SR1_RAW_SENS,0 +SR1_RC_CHAN,0 +SR2_ADSB,0 +SR2_EXT_STAT,0 +SR2_EXTRA1,0 +SR2_EXTRA2,0 +SR2_EXTRA3,0 +SR2_PARAMS,0 +SR2_POSITION,0 +SR2_RAW_CTRL,0 +SR2_RAW_SENS,0 +SR2_RC_CHAN,0 +SR3_ADSB,0 +SR3_EXT_STAT,0 +SR3_EXTRA1,0 +SR3_EXTRA2,0 +SR3_EXTRA3,0 +SR3_PARAMS,0 +SR3_POSITION,0 +SR3_RAW_CTRL,0 +SR3_RAW_SENS,0 +SR3_RC_CHAN,0 +SR4_ADSB,0 +SR4_EXT_STAT,0 +SR4_EXTRA1,0 +SR4_EXTRA2,0 +SR4_EXTRA3,0 +SR4_PARAMS,0 +SR4_POSITION,0 +SR4_RAW_CTRL,0 +SR4_RAW_SENS,0 +SR4_RC_CHAN,0 +SR5_ADSB,0 +SR5_EXT_STAT,0 +SR5_EXTRA1,0 +SR5_EXTRA2,0 +SR5_EXTRA3,0 +SR5_PARAMS,0 +SR5_POSITION,0 +SR5_RAW_CTRL,0 +SR5_RAW_SENS,0 +SR5_RC_CHAN,0 +SR6_ADSB,0 +SR6_EXT_STAT,0 +SR6_EXTRA1,0 +SR6_EXTRA2,0 +SR6_EXTRA3,0 +SR6_PARAMS,0 +SR6_POSITION,0 +SR6_RAW_CTRL,0 +SR6_RAW_SENS,0 +SR6_RC_CHAN,0 +SRTL_ACCURACY,2 +SRTL_OPTIONS,0 +SRTL_POINTS,300 +STAT_BOOTCNT,0 +STAT_FLTTIME,0 +STAT_RESET,1 +STAT_RUNTIME,0 +SUPER_SIMPLE,0 +SURFTRAK_MODE,1 +SURFTRAK_TC,1 +SYSID_ENFORCE,0 +SYSID_MYGCS,255 +SYSID_THISMAV,1 +TCAL_ENABLED,0 +TELEM_DELAY,0 +TERRAIN_CACHE_SZ,12 +TERRAIN_ENABLE,1 +TERRAIN_MARGIN,0.05 +TERRAIN_OFS_MAX,30 +TERRAIN_OPTIONS,0 +TERRAIN_SPACING,100 +THR_DZ,100 +THROW_ALT_MAX,0 +THROW_ALT_MIN,0 +THROW_MOT_START,0 +THROW_NEXTMODE,18 +THROW_TYPE,0 +TKOFF_RPM_MAX,0 +TKOFF_RPM_MIN,0 +TKOFF_SLEW_TIME,2 +TKOFF_THR_MAX,0.9 +TUNE,0 +TUNE_MAX,0 +TUNE_MIN,0 +VISO_TYPE,0 +VTX_ENABLE,0 +WINCH_TYPE,0 +WP_NAVALT_MIN,0 +WP_YAW_BEHAVIOR,2 +WPNAV_ACCEL,250 +WPNAV_ACCEL_C,0 +WPNAV_ACCEL_Z,100 +WPNAV_JERK,1 +WPNAV_RADIUS,200 +WPNAV_RFND_USE,1 +WPNAV_SPEED,1000 +WPNAV_SPEED_DN,150 +WPNAV_SPEED_UP,250 +WPNAV_TER_MARGIN,10 +WVANE_ENABLE,0 +ZIGZ_AUTO_ENABLE,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/02_imu_temperature_calibration_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/02_imu_temperature_calibration_setup.param new file mode 100644 index 000000000..0f3298701 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/02_imu_temperature_calibration_setup.param @@ -0,0 +1,8 @@ +BRD_HEAT_TARG,65 # Reasonable for most places on this planet +INS_TCAL1_ENABLE,2 # Activates the temperature calibration for IMU 1 at the next start +INS_TCAL1_TMAX,70 +INS_TCAL2_ENABLE,2 # Activates the temperature calibration for IMU 2 at the next start +INS_TCAL2_TMAX,70 +INS_TCAL3_ENABLE,2 # Activates the temperature calibration for IMU 3 at the next start +LOG_BITMASK,524416 # Only for IMU and Raw-IMU +LOG_DISARMED,1 # Gather data for the offline IMU temperature calibration while the FC is disarmed diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/04_board_orientation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/04_board_orientation.param new file mode 100644 index 000000000..73fe42d6d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/04_board_orientation.param @@ -0,0 +1,4 @@ +AHRS_ORIENTATION,0 +BRD_HEAT_TARG,45 # Reset to default after offline IMU temperature calibration +LOG_BITMASK,145118 # Log all but fast att, Nav, Mission, OF, camera, fast IMU, raw, IMU, video stabilization. These are not needed now +LOG_DISARMED,0 # Log disarmed was only required for offline IMU temperature calibration diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/05_remote_controller.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/05_remote_controller.param new file mode 100644 index 000000000..b3eea7662 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/05_remote_controller.param @@ -0,0 +1,10 @@ +ARMING_RUDDER,2 +BRD_ALT_CONFIG,0 +RC_OPTIONS,32 +RC_PROTOCOLS,1 # Selected in the component editor +RC10_OPTION,0 +RC6_OPTION,0 +RC7_OPTION,0 +RC8_OPTION,0 +RC9_OPTION,0 +RSSI_TYPE,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/06_telemetry.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/06_telemetry.param new file mode 100644 index 000000000..81d9af398 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/06_telemetry.param @@ -0,0 +1,2 @@ +BRD_SER1_RTSCTS,2 +SERIAL1_BAUD,57 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/07_esc.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/07_esc.param new file mode 100644 index 000000000..846ee29b5 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/07_esc.param @@ -0,0 +1,28 @@ +ATC_RAT_PIT_SMAX,0 +ATC_RAT_RLL_SMAX,0 +ATC_RAT_YAW_SMAX,0 +ESC_HW_POLES,14 +MOT_HOVER_LEARN,2 # So that it can tune the throttle controller on 20_throttle_controller.param file +MOT_PWM_MAX,2000 +MOT_PWM_MIN,1000 +MOT_PWM_TYPE,0 # Specified in component editor window +MOT_SPOOL_TIME,0.5 +NTF_BUZZ_TYPES,5 +NTF_LED_TYPES,123079 +PSC_ACCZ_SMAX,0 +SERVO_BLH_POLES,14 # Specified in component editor window +SERVO_FTW_POLES,14 # Specified in component editor window +SERVO1_MAX,1900 +SERVO1_MIN,1100 +SERVO1_TRIM,1500 +SERVO2_MAX,1900 +SERVO2_MIN,1100 +SERVO2_TRIM,1500 +SERVO3_MAX,1900 +SERVO3_MIN,1100 +SERVO3_TRIM,1500 +SERVO4_MAX,1900 +SERVO4_MIN,1100 +SERVO4_TRIM,1500 +TKOFF_RPM_MIN,0 +TKOFF_SLEW_TIME,2 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/08_batt1.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/08_batt1.param new file mode 100644 index 000000000..8ee59c72f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/08_batt1.param @@ -0,0 +1,15 @@ +BATT_AMP_PERVLT,0 +BATT_ARM_VOLT,55.2 +BATT_CAPACITY,160000 +BATT_CRT_MAH,0 +BATT_CRT_VOLT,49.7 +BATT_FS_CRT_ACT,1 +BATT_FS_LOW_ACT,2 +BATT_FS_VOLTSRC,0 +BATT_I2C_BUS,4 +BATT_LOW_MAH,0 +BATT_LOW_VOLT,50.4 +BATT_MONITOR,0 +BATT_VOLT_MULT,0 +MOT_BAT_VOLT_MAX,0 # (Max voltage + 0.0) x no. of cells +MOT_BAT_VOLT_MIN,0 # (Critical voltage + 0.0) x no. of cells diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/10_gnss.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/10_gnss.param new file mode 100644 index 000000000..96202797c --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/10_gnss.param @@ -0,0 +1,16 @@ +BRD_SAFETY_DEFLT,1 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +GPS_AUTO_SWITCH,1 +GPS1_GNSS_MODE,0 +GPS1_POS_X,0 +GPS1_POS_Y,0 +GPS1_POS_Z,0 +GPS2_POS_X,0 +GPS2_POS_Y,0 +GPS2_POS_Z,0 +GPS1_TYPE,1 +NTF_LED_TYPES,123079 +SERIAL3_PROTOCOL,5 +SERIAL4_PROTOCOL,5 +WPNAV_RADIUS,200 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/11_initial_atc.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/11_initial_atc.param new file mode 100644 index 000000000..39997ba2f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/11_initial_atc.param @@ -0,0 +1,18 @@ +ATC_ACCEL_P_MAX,221000 # Derived from vehicle component editor propeller size +ATC_ACCEL_R_MAX,221000 # Derived from vehicle component editor propeller size +ATC_ACCEL_Y_MAX,35100 # Derived from vehicle component editor propeller size +ATC_ANG_YAW_P,5.8 # Derived from vehicle component editor propeller size +ATC_RAT_PIT_FLTD,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_PIT_FLTE,0 # Initial value, will be improved at a later step +ATC_RAT_PIT_FLTT,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_RLL_FLTD,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_RLL_FLTE,0 # Initial value, will be improved at a later step +ATC_RAT_RLL_FLTT,144.5 # INS_GYRO_FILTER / 2 +ATC_RAT_YAW_FLTD,0 # Initial value, will be improved at a later step +ATC_RAT_YAW_FLTE,2 # Initial value, will be improved at a later step +ATC_RAT_YAW_FLTT,144.5 # INS_GYRO_FILTER / 2 +ATC_THR_MIX_MAN,0.1 # Value for the first couple of flights will be changed later once MOT_THST_HOVER is learned +INS_ACCEL_FILTER,10 # The default is 20Hz but that is too high in most situations +INS_GYRO_FILTER,289 # Derived from vehicle component editor propeller size +MOT_THST_EXPO,0.24 # Derived from vehicle component editor propeller size +MOT_THST_HOVER,0.2 # Hover learn will improve this initial guess diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/12_mp_setup_mandatory_hardware.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/12_mp_setup_mandatory_hardware.param new file mode 100644 index 000000000..219207364 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/12_mp_setup_mandatory_hardware.param @@ -0,0 +1,82 @@ +AHRS_TRIM_X,0 +AHRS_TRIM_Y,0 +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ACCEL_Y_MAX,27000 +ATC_RAT_PIT_FLTD,20 +ATC_RAT_PIT_FLTT,20 +ATC_RAT_RLL_FLTD,20 +ATC_RAT_RLL_FLTT,20 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_FLTT,20 +COMPASS_EXTERNAL,0 +COMPASS_ORIENT,0 +COMPASS_PRIO1_ID,131874 +COMPASS_USE2,1 +COMPASS_USE3,1 +FENCE_ACTION,1 +FENCE_ALT_MAX,100 +FENCE_ENABLE,0 +FENCE_RADIUS,300 +FLTMODE1,0 +FLTMODE2,0 +FLTMODE3,0 +FLTMODE4,0 +FLTMODE5,0 +FLTMODE6,0 +FRAME_CLASS,0 +FRAME_TYPE,1 +INS_ACC1_CALTEMP,-300 +INS_ACC2_CALTEMP,-300 +INS_ACC2SCAL_X,1 +INS_ACC2SCAL_Y,1 +INS_ACC2SCAL_Z,1 +INS_ACC3SCAL_X,1 +INS_ACC3SCAL_Y,1 +INS_ACC3SCAL_Z,1 +INS_ACCSCAL_X,1 +INS_ACCSCAL_Y,1 +INS_ACCSCAL_Z,1 +INS_GYRO_FILTER,20 +INS_USE3,1 +MOT_BAT_VOLT_MAX,0 +MOT_BAT_VOLT_MIN,0 +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_THST_EXPO,0.65 +MOT_THST_HOVER,0.35 +RC1_MAX,1900 +RC1_MIN,1100 +RC1_TRIM,1500 +RC10_MAX,1900 +RC10_MIN,1100 +RC10_TRIM,1500 +RC2_MAX,1900 +RC2_MIN,1100 +RC2_TRIM,1500 +RC3_MAX,1900 +RC3_MIN,1100 +RC3_TRIM,1500 +RC4_MAX,1900 +RC4_MIN,1100 +RC4_TRIM,1500 +RC5_MAX,1900 +RC5_MIN,1100 +RC5_TRIM,1500 +RC6_MAX,1900 +RC6_MIN,1100 +RC6_TRIM,1500 +RC7_MAX,1900 +RC7_MIN,1100 +RC7_TRIM,1500 +RC8_MAX,1900 +RC8_MIN,1100 +RC8_TRIM,1500 +RC9_MAX,1900 +RC9_MIN,1100 +RC9_TRIM,1500 +SERVO1_FUNCTION,0 +SERVO2_FUNCTION,0 +SERVO3_FUNCTION,0 +SERVO4_FUNCTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/13_general_configuration.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/13_general_configuration.param new file mode 100644 index 000000000..2ab591b4d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/13_general_configuration.param @@ -0,0 +1,18 @@ +ARMING_CHECK,1 # Perform all arming checks. If you have a problem fix its source. Do NOT change this +AUTO_OPTIONS,0 +BRD_HEAT_TARG,-1 +BRD_RTC_TZ_MIN,0 +EK3_SRC1_POSZ,1 +FENCE_TYPE,7 +FS_EKF_ACTION,1 +INS_ACCEL_FILTER,20 +INS_POS1_X,0 +INS_POS1_Y,0 +INS_POS2_X,0 +INS_POS2_Y,0 +LAND_ALT_LOW,1000 +RTL_ALT,1500 +RTL_LOIT_TIME,5000 +SCHED_LOOP_RATE,400 +SCR_ENABLE,1 # Use lua scripting for VTOL-Quicktune, MagFit automation and wind speed estimation automation +SERIAL7_PROTOCOL,-1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/14_logging.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/14_logging.param new file mode 100644 index 000000000..1cd3fedf3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/14_logging.param @@ -0,0 +1,6 @@ +INS_LOG_BAT_CNT,1024 +INS_LOG_BAT_MASK,1 # Use acc and gyro batch logging on F4 processors, gyro raw logging on others +INS_LOG_BAT_OPT,4 # Use pre and post filters acc and gyro batch logging on F4 processors, pre-post gyro raw logging on others +INS_RAW_LOG_OPT,0 # Use pre and post filters acc and gyro batch logging on F4 processors, pre-post gyro raw logging on others +LOG_BITMASK,145118 # Log all but fast att, Nav, Mission, OF, camera, fast IMU, raw, IMU, video stabilization. These are not needed now +LOG_FILE_DSRMROT,1 # One .bin log file per flight, not per battery/reboot diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/15_motor.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/15_motor.param new file mode 100644 index 000000000..14d698a75 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/15_motor.param @@ -0,0 +1,4 @@ +MOT_SPIN_ARM,0.1 +MOT_SPIN_MAX,0.95 +MOT_SPIN_MIN,0.15 +MOT_THST_EXPO,0.65 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/16_pid_adjustment.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/16_pid_adjustment.param new file mode 100644 index 000000000..f606f619b --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/16_pid_adjustment.param @@ -0,0 +1,15 @@ +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_INPUT_TC,0.15 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 +PSC_POSXY_P,1 +PSC_POSZ_P,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/17_remote_id.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/17_remote_id.param new file mode 100644 index 000000000..966271913 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/17_remote_id.param @@ -0,0 +1,4 @@ +DID_CANDRIVER,0 +DID_ENABLE,0 +DID_MAVPORT,2 +DID_OPTIONS,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/18_notch_filter_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/18_notch_filter_setup.param new file mode 100644 index 000000000..36fd0114f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/18_notch_filter_setup.param @@ -0,0 +1,10 @@ +INS_FAST_SAMPLE,5 +INS_GYRO_RATE,0 +INS_HNTCH_ATT,40 +INS_HNTCH_BW,22 +INS_HNTCH_ENABLE,1 # Use the first notch filter to filter the noise created by the motors/propellers +INS_HNTCH_FREQ,28 +INS_HNTCH_HMNCS,3 +INS_HNTCH_MODE,3 +INS_HNTCH_OPTS,2 +INS_HNTCH_REF,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/19_notch_filter_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/19_notch_filter_results.param new file mode 100644 index 000000000..aa4e78e30 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/19_notch_filter_results.param @@ -0,0 +1,8 @@ +INS_GYRO_FILTER,20 +INS_HNTCH_ATT,30 +INS_HNTCH_BW,11 +INS_HNTCH_FM_RAT,0.7 +INS_HNTCH_FREQ,43 +INS_HNTCH_HMNCS,3 +INS_HNTCH_OPTS,2 +INS_HNTCH_REF,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/20_throttle_controller.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/20_throttle_controller.param new file mode 100644 index 000000000..0cf81f627 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/20_throttle_controller.param @@ -0,0 +1,3 @@ +ATC_THR_MIX_MAN,0.1 +PSC_ACCZ_I,1 +PSC_ACCZ_P,0.5 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/21_ekf_config.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/21_ekf_config.param new file mode 100644 index 000000000..e937e5ee2 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/21_ekf_config.param @@ -0,0 +1,2 @@ +EK3_ACC_P_NSE,0.35 +EK3_ALT_M_NSE,2 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/22_quick_tune_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/22_quick_tune_setup.param new file mode 100644 index 000000000..cffbe6056 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/22_quick_tune_setup.param @@ -0,0 +1,14 @@ +QUIK_AUTO_FILTER,1 +QUIK_AUTO_SAVE,0 +QUIK_AXES,7 +QUIK_DOUBLE_TIME,10 +QUIK_ENABLE,1 +QUIK_GAIN_MARGIN,70 +QUIK_MAX_REDUCE,25 +QUIK_OPTIONS,0 +QUIK_OSC_SMAX,3 +QUIK_RC_FUNC,300 +QUIK_RP_PI_RATIO,1 +QUIK_Y_PI_RATIO,10 +QUIK_YAW_D_MAX,0.01 +QUIK_YAW_P_MAX,0.5 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/23_quick_tune_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/23_quick_tune_results.param new file mode 100644 index 000000000..df52dd073 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/23_quick_tune_results.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_FLTD,20 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.param new file mode 100644 index 000000000..4bc63ead8 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.param @@ -0,0 +1,8 @@ +MAGH_ALT_DELTA,20 +MAGH_B,1.4 +MAGH_CMD,117 +MAGH_COUNT,6 +MAGH_LOG_ENABLE,1 +MAGH_MIN_SPEED,6 +MAGH_NUM_WP,18 +MAGH_USE_LOITER,1 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.pdef.xml b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.pdef.xml new file mode 100644 index 000000000..aa2f497ab --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/24_inflight_magnetometer_fit_setup.pdef.xml @@ -0,0 +1,57 @@ + + + + + + + m + 0 100 + 10 + + + 1.2 1.5 + 1.2 + + + 0 255 + 117 + + + 1 20 + 6 + + + 0 1 + 1 + + + m/s + 1/2 of WPNAV_SPEED + + + 16 24 + 18 + + + 0 1 + 1 + + + 300 307 + 300 + + + 300 307 + 301 + + + 0 3600 + 0 + + + 0 1 + 0 + + + + diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/25_inflight_magnetometer_fit_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/25_inflight_magnetometer_fit_results.param new file mode 100644 index 000000000..1e91cd573 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/25_inflight_magnetometer_fit_results.param @@ -0,0 +1,43 @@ +COMPASS_DIA_X,1 +COMPASS_DIA_Y,1 +COMPASS_DIA_Z,1 +COMPASS_DIA2_X,1 +COMPASS_DIA2_Y,1 +COMPASS_DIA2_Z,1 +COMPASS_DIA3_X,1 +COMPASS_DIA3_Y,1 +COMPASS_DIA3_Z,1 +COMPASS_MOT_X,0 +COMPASS_MOT_Y,0 +COMPASS_MOT_Z,0 +COMPASS_MOT2_X,0 +COMPASS_MOT2_Y,0 +COMPASS_MOT2_Z,0 +COMPASS_MOT3_X,0 +COMPASS_MOT3_Y,0 +COMPASS_MOT3_Z,0 +COMPASS_MOTCT,0 +COMPASS_ODI_X,0 +COMPASS_ODI_Y,0 +COMPASS_ODI_Z,0 +COMPASS_ODI2_X,0 +COMPASS_ODI2_Y,0 +COMPASS_ODI2_Z,0 +COMPASS_ODI3_X,0 +COMPASS_ODI3_Y,0 +COMPASS_ODI3_Z,0 +COMPASS_OFS_X,0 +COMPASS_OFS_Y,0 +COMPASS_OFS_Z,0 +COMPASS_OFS2_X,0 +COMPASS_OFS2_Y,0 +COMPASS_OFS2_Z,0 +COMPASS_OFS3_X,0 +COMPASS_OFS3_Y,0 +COMPASS_OFS3_Z,0 +COMPASS_ORIENT,0 +COMPASS_ORIENT2,0 +COMPASS_ORIENT3,0 +COMPASS_SCALE,0 +COMPASS_SCALE2,0 +COMPASS_SCALE3,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/26_quick_tune_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/26_quick_tune_setup.param new file mode 100644 index 000000000..961400f78 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/26_quick_tune_setup.param @@ -0,0 +1,16 @@ +INS_RAW_LOG_OPT,0 +LOG_BITMASK,176126 +QUIK_AUTO_FILTER,1 +QUIK_AUTO_SAVE,0 +QUIK_AXES,7 +QUIK_DOUBLE_TIME,10 +QUIK_ENABLE,1 +QUIK_GAIN_MARGIN,70 +QUIK_MAX_REDUCE,25 +QUIK_OPTIONS,0 +QUIK_OSC_SMAX,3 +QUIK_RC_FUNC,300 +QUIK_RP_PI_RATIO,1 +QUIK_Y_PI_RATIO,10 +QUIK_YAW_D_MAX,0.01 +QUIK_YAW_P_MAX,0.5 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/27_quick_tune_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/27_quick_tune_results.param new file mode 100644 index 000000000..df52dd073 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/27_quick_tune_results.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_FLTD,20 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/28_evaluate_the_aircraft_tune_ff_disable.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/28_evaluate_the_aircraft_tune_ff_disable.param new file mode 100644 index 000000000..92e512243 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/28_evaluate_the_aircraft_tune_ff_disable.param @@ -0,0 +1,4 @@ +ATC_RATE_FF_ENAB,0 # test the stabilization loops independent of the input shaping +INS_LOG_BAT_MASK,0 # IMU batch logging no longer required, notch filter setup is complete, this reduces processor load and log file size +INS_RAW_LOG_OPT,0 # Gyro raw logging no longer required, notch filter setup is complete, this reduces processor load and log file size +LOG_BITMASK,145118 # Disable fast harmonic notch logging diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/29_evaluate_the_aircraft_tune_ff_enable.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/29_evaluate_the_aircraft_tune_ff_enable.param new file mode 100644 index 000000000..77242b284 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/29_evaluate_the_aircraft_tune_ff_enable.param @@ -0,0 +1 @@ +ATC_RATE_FF_ENAB,1 # re-enable normal operation, activate input shaping diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/30_autotune_roll_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/30_autotune_roll_setup.param new file mode 100644 index 000000000..eab08f0ff --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/30_autotune_roll_setup.param @@ -0,0 +1,2 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,1 # Autotune roll axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/31_autotune_roll_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/31_autotune_roll_results.param new file mode 100644 index 000000000..8c0d08ace --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/31_autotune_roll_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_R_MAX,110000 +ATC_ANG_RLL_P,4.5 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/32_autotune_pitch_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/32_autotune_pitch_setup.param new file mode 100644 index 000000000..741334b72 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/32_autotune_pitch_setup.param @@ -0,0 +1,2 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,2 # Autotune pitch axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/33_autotune_pitch_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/33_autotune_pitch_results.param new file mode 100644 index 000000000..e3b36741a --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/33_autotune_pitch_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_P_MAX,110000 +ATC_ANG_PIT_P,4.5 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/34_autotune_yaw_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/34_autotune_yaw_setup.param new file mode 100644 index 000000000..569a03736 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/34_autotune_yaw_setup.param @@ -0,0 +1,3 @@ +ATC_RAT_YAW_FLTD,20 +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,4 # Autotune yaw axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/35_autotune_yaw_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/35_autotune_yaw_results.param new file mode 100644 index 000000000..73a09d4e3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/35_autotune_yaw_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_Y_MAX,27000 +ATC_ANG_YAW_P,4.5 +ATC_RAT_YAW_FLTE,2.5 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/36_autotune_yawd_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/36_autotune_yawd_setup.param new file mode 100644 index 000000000..0f02e68c9 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/36_autotune_yawd_setup.param @@ -0,0 +1,3 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,8 # Autotune yaw D axis +AUTOTUNE_MIN_D,0.001 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/37_autotune_yawd_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/37_autotune_yawd_results.param new file mode 100644 index 000000000..452105da9 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/37_autotune_yawd_results.param @@ -0,0 +1,5 @@ +ATC_ACCEL_Y_MAX,27000 +ATC_ANG_YAW_P,4.5 +ATC_RAT_YAW_D,0 +ATC_RAT_YAW_I,0.018 +ATC_RAT_YAW_P,0.18 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/38_autotune_roll_pitch_retune_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/38_autotune_roll_pitch_retune_setup.param new file mode 100644 index 000000000..2a1d17c2f --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/38_autotune_roll_pitch_retune_setup.param @@ -0,0 +1,2 @@ +AUTOTUNE_AGGR,0.1 +AUTOTUNE_AXES,3 # Autotune roll and pitch axis diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/39_autotune_roll_pitch_retune_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/39_autotune_roll_pitch_retune_results.param new file mode 100644 index 000000000..fc82ea31d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/39_autotune_roll_pitch_retune_results.param @@ -0,0 +1,10 @@ +ATC_ACCEL_P_MAX,110000 +ATC_ACCEL_R_MAX,110000 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_RAT_PIT_D,0.0036 +ATC_RAT_PIT_I,0.135 +ATC_RAT_PIT_P,0.135 +ATC_RAT_RLL_D,0.0036 +ATC_RAT_RLL_I,0.135 +ATC_RAT_RLL_P,0.135 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/40_windspeed_estimation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/40_windspeed_estimation.param new file mode 100644 index 000000000..dcb80529d --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/40_windspeed_estimation.param @@ -0,0 +1,5 @@ +EK3_DRAG_BCOEF_X,0 +EK3_DRAG_BCOEF_Y,0 +EK3_DRAG_MCOEF,0 +LOG_DISARMED,1 # allow post flight tuning with Replay +LOG_REPLAY,1 # allow post flight tuning with Replay diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/41_barometer_compensation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/41_barometer_compensation.param new file mode 100644 index 000000000..e8d825caf --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/41_barometer_compensation.param @@ -0,0 +1,7 @@ +BARO1_WCF_BCK,0 +BARO1_WCF_DN,0 +BARO1_WCF_ENABLE,0 +BARO1_WCF_FWD,0 +BARO1_WCF_LFT,0 +BARO1_WCF_RGT,0 +BARO1_WCF_UP,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/42_system_id_roll.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/42_system_id_roll.param new file mode 100644 index 000000000..b12b1aaaa --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/42_system_id_roll.param @@ -0,0 +1,21 @@ +ANGLE_MAX,3000 +ARMING_CHECK,1 +ATC_ANG_PIT_P,4.5 +ATC_ANG_RLL_P,4.5 +ATC_ANG_YAW_P,4.5 +ATC_RAT_RLL_I,0.135 +ATC_RATE_FF_ENAB,1 +FLTMODE5,0 +LOG_BITMASK,176126 +LOG_DISARMED,0 # was only needed for wind speed estimation +LOG_REPLAY,0 # was only needed for wind speed estimation +SID_AXIS,10 # Inject chip on the mixer roll signal +SID_F_START_HZ,0.05 +SID_F_STOP_HZ,5 +SID_MAGNITUDE,0.15 +SID_T_FADE_IN,5 +SID_T_FADE_OUT,5 +SID_T_REC,130 +TUNE,0 +TUNE_MAX,0 +TUNE_MIN,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/43_system_id_pitch.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/43_system_id_pitch.param new file mode 100644 index 000000000..e5c17d70b --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/43_system_id_pitch.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_I,0.135 +ATC_RAT_RLL_I,0.135 +ATC_RATE_FF_ENAB,1 +SID_AXIS,11 # Inject chip on the mixer pitch signal +SID_F_START_HZ,0.05 +SID_F_STOP_HZ,5 +SID_MAGNITUDE,0.15 +SID_T_FADE_IN,5 +SID_T_FADE_OUT,5 +SID_T_REC,130 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/44_system_id_yaw.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/44_system_id_yaw.param new file mode 100644 index 000000000..e4469d36a --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/44_system_id_yaw.param @@ -0,0 +1,10 @@ +ATC_RAT_PIT_I,0.135 +ATC_RAT_YAW_I,0.018 +ATC_RATE_FF_ENAB,1 +SID_AXIS,12 # Inject chip on the mixer yaw signal +SID_F_START_HZ,0.05 +SID_F_STOP_HZ,5 +SID_MAGNITUDE,0.55 +SID_T_FADE_IN,5 +SID_T_FADE_OUT,5 +SID_T_REC,130 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/45_system_id_thrust.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/45_system_id_thrust.param new file mode 100644 index 000000000..09c52e3de --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/45_system_id_thrust.param @@ -0,0 +1,10 @@ +ATC_RAT_YAW_I,0.018 +ATC_RATE_FF_ENAB,1 +PSC_ACCZ_I,1 +SID_AXIS,13 # Inject chip on the mixer thrust signal +SID_F_START_HZ,0.2 +SID_F_STOP_HZ,10 +SID_MAGNITUDE,0.12 +SID_T_FADE_IN,10 +SID_T_FADE_OUT,5 +SID_T_REC,100 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/46_analytical_pid_optimization.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/46_analytical_pid_optimization.param new file mode 100644 index 000000000..f76d7d5a3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/46_analytical_pid_optimization.param @@ -0,0 +1,4 @@ +ARMING_CHECK,1 # Normal state for everyday use +ATC_RATE_FF_ENAB,1 # Restore value now that system identification is done +PSC_ACCZ_I,1 +SID_AXIS,0 # No more system identification chip injections diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/47_position_controller.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/47_position_controller.param new file mode 100644 index 000000000..4b0e39a6c --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/47_position_controller.param @@ -0,0 +1,13 @@ +ANGLE_MAX,3000 +LOG_BITMASK,145150 # Add Navigation logging +LOIT_ACC_MAX,500 +LOIT_BRK_ACCEL,250 +LOIT_BRK_DELAY,1 +LOIT_BRK_JERK,500 +PSC_VELXY_FF,0 +WPNAV_ACCEL,250 +WPNAV_ACCEL_C,0 +WPNAV_ACCEL_Z,100 +WPNAV_JERK,1 +WPNAV_SPEED,1000 +WPNAV_SPEED_DN,150 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/48_guided_operation.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/48_guided_operation.param new file mode 100644 index 000000000..a1aed6e17 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/48_guided_operation.param @@ -0,0 +1,4 @@ +FS_GCS_ENABLE,0 +RALLY_INCL_HOME,1 +RALLY_TOTAL,0 +SYSID_MYGCS,255 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/49_precision_land.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/49_precision_land.param new file mode 100644 index 000000000..d6ec9fba0 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/49_precision_land.param @@ -0,0 +1,27 @@ +EK3_RNG_M_NSE,0.5 +EK3_RNG_USE_HGT,-1 +LAND_ALT_LOW,1000 +LAND_SPEED,50 +PLND_ACC_P_NSE,2.5 +PLND_ALT_MAX,8 +PLND_ALT_MIN,0.75 +PLND_BUS,-1 +PLND_CAM_POS_X,0.14 +PLND_CAM_POS_Y,0 +PLND_CAM_POS_Z,0.05 +PLND_ENABLED,0 +PLND_EST_TYPE,0 +PLND_LAG,0.24 +PLND_LAND_OFS_X,0 +PLND_LAND_OFS_Y,0 +PLND_OPTIONS,0 +PLND_RET_BEHAVE,0 +PLND_RET_MAX,4 +PLND_STRICT,1 +PLND_TIMEOUT,4 +PLND_TYPE,1 +PLND_XY_DIST_MAX,0 +PLND_YAW_ALIGN,0 +PSC_POSXY_P,1 +RC10_OPTION,0 +RC11_OPTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/50_optical_flow_setup.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/50_optical_flow_setup.param new file mode 100644 index 000000000..32883e818 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/50_optical_flow_setup.param @@ -0,0 +1,19 @@ +EK3_FLOW_DELAY,10 +EK3_SRC_OPTIONS,1 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +EK3_SRC2_POSXY,0 +EK3_SRC2_POSZ,1 +EK3_SRC2_VELXY,0 +EK3_SRC2_VELZ,0 +EK3_SRC2_YAW,0 +FLOW_ORIENT_YAW,0 +FLOW_POS_X,0 +FLOW_POS_Y,0 +FLOW_POS_Z,0 +FLOW_TYPE,0 +RC8_OPTION,0 +RC9_OPTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/51_optical_flow_results.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/51_optical_flow_results.param new file mode 100644 index 000000000..8afd7781c --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/51_optical_flow_results.param @@ -0,0 +1,3 @@ +FLOW_FXSCALER,0 +FLOW_FYSCALER,0 +FLOW_ORIENT_YAW,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/52_use_optical_flow_instead_of_gnss.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/52_use_optical_flow_instead_of_gnss.param new file mode 100644 index 000000000..35d946303 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/52_use_optical_flow_instead_of_gnss.param @@ -0,0 +1,8 @@ +EK3_SRC_OPTIONS,1 +EK3_SRC1_POSXY,3 +EK3_SRC1_POSZ,1 +EK3_SRC1_VELXY,3 +EK3_SRC1_VELZ,3 +EK3_SRC1_YAW,1 +RC8_OPTION,0 +RC9_OPTION,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/53_everyday_use.param b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/53_everyday_use.param new file mode 100644 index 000000000..ba44f1aa3 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/53_everyday_use.param @@ -0,0 +1,7 @@ +ATC_THR_MIX_MAX,0.5 +BATT_FS_LOW_ACT,2 +BATT2_FS_LOW_ACT,2 +LOG_BITMASK,176126 +MIS_OPTIONS,0 +RTL_ALT,1500 +RTL_CLIMB_MIN,0 diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/vehicle_components.json b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/vehicle_components.json new file mode 100644 index 000000000..624ce7d65 --- /dev/null +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduCopter/empty_4.6.x/vehicle_components.json @@ -0,0 +1,187 @@ +{ + "Format version": 0, + "Components": { + "Flight Controller": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "ArduCopter", + "Version": "4.6.x" + }, + "Specifications": { + "MCU Series": "" + }, + "Notes": "" + }, + "Frame": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "TOW min Kg": 0.1, + "TOW max Kg": 0.1 + }, + "Notes": "" + }, + "RC Controller": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "Notes": "" + }, + "RC Transmitter": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "Notes": "" + }, + "RC Receiver": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "RCin/SBUS", + "Protocol": "All" + }, + "Notes": "" + }, + "Telemetry": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "SERIAL1", + "Protocol": "MAVLink2" + }, + "Notes": "" + }, + "Battery Monitor": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "None", + "Protocol": "None" + }, + "Notes": "" + }, + "Battery": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "Chemistry": "Lipo", + "Volt per cell max": 4.2, + "Volt per cell low": 3.6, + "Volt per cell crit": 3.55, + "Number of cells": 0, + "Capacity mAh": 0 + }, + "Notes": "" + }, + "ESC": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "Main Out", + "Protocol": "Normal" + }, + "Notes": "" + }, + "Motors": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "Poles": 14 + }, + "Notes": "" + }, + "Propellers": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Specifications": { + "Diameter_inches": 0 + }, + "Notes": "" + }, + "GNSS Receiver": { + "Product": { + "Manufacturer": "", + "Model": "", + "URL": "", + "Version": "" + }, + "Firmware": { + "Type": "", + "Version": "" + }, + "FC Connection": { + "Type": "SERIAL3", + "Protocol": "AUTO" + }, + "Notes": "" + } + }, + "Program version": "2.0.6" +}