ardupilot-methodic-configurator 2.5.0__py3-none-any.whl → 2.6.1__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- ardupilot_methodic_configurator/__init__.py +1 -1
- ardupilot_methodic_configurator/backend_filesystem_program_settings.py +15 -20
- ardupilot_methodic_configurator/configuration_manager.py +113 -1
- ardupilot_methodic_configurator/data_model_configuration_step.py +40 -3
- ardupilot_methodic_configurator/frontend_tkinter_base_window.py +4 -0
- ardupilot_methodic_configurator/frontend_tkinter_component_editor_base.py +1 -1
- ardupilot_methodic_configurator/frontend_tkinter_motor_test.py +853 -0
- ardupilot_methodic_configurator/frontend_tkinter_parameter_editor.py +8 -12
- ardupilot_methodic_configurator/frontend_tkinter_parameter_editor_table.py +78 -108
- ardupilot_methodic_configurator/frontend_tkinter_usage_popup_window.py +11 -6
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/07_esc.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/42_system_id_roll.param +5 -3
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/43_system_id_pitch.param +3 -3
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/44_system_id_yaw.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/vehicle.jpg +0 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/vehicle_components.json +3 -4
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/05_remote_controller.param +7 -7
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/06_telemetry.param +2 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/07_esc.param +6 -6
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/10_gnss.param +4 -4
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/13_general_configuration.param +5 -5
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/15_motor.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/16_pid_adjustment.param +10 -10
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/18_notch_filter_setup.param +3 -3
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/20_throttle_controller.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/22_quick_tune_setup.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/26_quick_tune_setup.param +2 -2
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/30_autotune_roll_setup.param +1 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/34_autotune_yaw_setup.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/37_autotune_yawd_results.param +1 -1
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500_V2/vehicle.jpg +0 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/00_default.param +1352 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/02_imu_temperature_calibration_setup.param +8 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/03_imu_temperature_calibration_results.param +42 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/04_board_orientation.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/05_remote_controller.param +13 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/06_telemetry.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/07_esc.param +43 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/08_batt1.param +15 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/10_gnss.param +11 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/11_initial_atc.param +18 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/12_mp_setup_mandatory_hardware.param +99 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/13_general_configuration.param +17 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/14_logging.param +6 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/15_motor.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/16_pid_adjustment.param +13 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/17_remote_id.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/18_notch_filter_setup.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/19_notch_filter_results.param +7 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/20_throttle_controller.param +5 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/21_ekf_config.param +2 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/22_quick_tune_setup.param +14 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/23_quick_tune_results.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/24_inflight_magnetometer_fit_setup.param +8 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/24_inflight_magnetometer_fit_setup.pdef.xml +57 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/25_inflight_magnetometer_fit_results.param +15 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/26_quick_tune_setup.param +14 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/27_quick_tune_results.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/28_evaluate_the_aircraft_tune_ff_disable.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/29_evaluate_the_aircraft_tune_ff_enable.param +1 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/30_autotune_roll_setup.param +2 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/31_autotune_roll_results.param +5 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/32_autotune_pitch_setup.param +2 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/33_autotune_pitch_results.param +5 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/34_autotune_yaw_setup.param +3 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/35_autotune_yaw_results.param +5 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/36_autotune_yawd_setup.param +3 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/37_autotune_yawd_results.param +5 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/38_autotune_roll_pitch_retune_setup.param +2 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/39_autotune_roll_pitch_retune_results.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/40_windspeed_estimation.param +5 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/41_barometer_compensation.param +7 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/42_system_id_roll.param +21 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/43_system_id_pitch.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/44_system_id_yaw.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/45_system_id_thrust.param +10 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/46_analytical_pid_optimization.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/47_position_controller.param +13 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/48_guided_operation.param +4 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/49_precision_land.param +27 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/50_optical_flow_setup.param +19 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/51_optical_flow_results.param +3 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/52_use_optical_flow_instead_of_gnss.param +8 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/53_everyday_use.param +7 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/vehicle.jpg +0 -0
- ardupilot_methodic_configurator/vehicle_templates/ArduCopter/TarotFY680Hexacopter/vehicle_components.json +188 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/METADATA +74 -134
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/RECORD +101 -43
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/WHEEL +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/entry_points.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSE.md +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/Apache-2.0.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/BSD-3-Clause.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/GPL-3.0-or-later.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/LGPL-3.0-or-later.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/MIT-CMU.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/MIT.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/MPL-2.0.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/LICENSES/PSF-2.0.txt +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/licenses/credits/CREDITS.md +0 -0
- {ardupilot_methodic_configurator-2.5.0.dist-info → ardupilot_methodic_configurator-2.6.1.dist-info}/top_level.txt +0 -0
|
@@ -325,8 +325,8 @@ class ParameterEditorWindow(BaseWindow): # pylint: disable=too-many-instance-at
|
|
|
325
325
|
)
|
|
326
326
|
|
|
327
327
|
# Create a Scrollable parameter editor table
|
|
328
|
-
self.parameter_editor_table = ParameterEditorTable(self.main_frame, self.
|
|
329
|
-
self.repopulate_parameter_table(
|
|
328
|
+
self.parameter_editor_table = ParameterEditorTable(self.main_frame, self.configuration_manager, self)
|
|
329
|
+
self.repopulate_parameter_table()
|
|
330
330
|
self.parameter_editor_table.pack(side="top", fill="both", expand=True)
|
|
331
331
|
|
|
332
332
|
# Create a frame for the buttons
|
|
@@ -668,7 +668,7 @@ class ParameterEditorWindow(BaseWindow): # pylint: disable=too-many-instance-at
|
|
|
668
668
|
self.at_least_one_changed_parameter_written = False
|
|
669
669
|
self.documentation_frame.refresh_documentation_labels(selected_file)
|
|
670
670
|
self.documentation_frame.update_why_why_now_tooltip(selected_file)
|
|
671
|
-
self.repopulate_parameter_table(
|
|
671
|
+
self.repopulate_parameter_table()
|
|
672
672
|
self._update_skip_button_state()
|
|
673
673
|
|
|
674
674
|
def _update_progress_bar_from_file(self, selected_file: str) -> None:
|
|
@@ -690,16 +690,14 @@ class ParameterEditorWindow(BaseWindow): # pylint: disable=too-many-instance-at
|
|
|
690
690
|
if not redownload:
|
|
691
691
|
self.on_param_file_combobox_change(None, forced=True) # the initial param read will trigger a table update
|
|
692
692
|
|
|
693
|
-
def repopulate_parameter_table(self
|
|
694
|
-
if not
|
|
693
|
+
def repopulate_parameter_table(self) -> None:
|
|
694
|
+
if not self.configuration_manager.current_file:
|
|
695
695
|
return # no file was yet selected, so skip it
|
|
696
696
|
# Re-populate the table with the new parameters
|
|
697
|
-
self.parameter_editor_table.repopulate(
|
|
698
|
-
selected_file, self.configuration_manager.fc_parameters, self.show_only_differences.get(), self.gui_complexity
|
|
699
|
-
)
|
|
697
|
+
self.parameter_editor_table.repopulate(self.show_only_differences.get(), self.gui_complexity)
|
|
700
698
|
|
|
701
699
|
def on_show_only_changed_checkbox_change(self) -> None:
|
|
702
|
-
self.repopulate_parameter_table(
|
|
700
|
+
self.repopulate_parameter_table()
|
|
703
701
|
|
|
704
702
|
def upload_params_that_require_reset(self, selected_params: dict) -> None:
|
|
705
703
|
"""
|
|
@@ -726,9 +724,7 @@ class ParameterEditorWindow(BaseWindow): # pylint: disable=too-many-instance-at
|
|
|
726
724
|
|
|
727
725
|
def on_upload_selected_click(self) -> None:
|
|
728
726
|
self.write_changes_to_intermediate_parameter_file()
|
|
729
|
-
selected_params = self.parameter_editor_table.get_upload_selected_params(
|
|
730
|
-
self.configuration_manager.current_file, str(self.gui_complexity)
|
|
731
|
-
)
|
|
727
|
+
selected_params = self.parameter_editor_table.get_upload_selected_params(str(self.gui_complexity))
|
|
732
728
|
if selected_params:
|
|
733
729
|
if self.configuration_manager.fc_parameters:
|
|
734
730
|
self.upload_selected_params(selected_params)
|
|
@@ -19,15 +19,18 @@ from tkinter import messagebox, ttk
|
|
|
19
19
|
from typing import Union
|
|
20
20
|
|
|
21
21
|
from ardupilot_methodic_configurator import _
|
|
22
|
-
from ardupilot_methodic_configurator.
|
|
22
|
+
from ardupilot_methodic_configurator.configuration_manager import (
|
|
23
|
+
ConfigurationManager,
|
|
24
|
+
InvalidParameterNameError,
|
|
25
|
+
OperationNotPossibleError,
|
|
26
|
+
)
|
|
23
27
|
from ardupilot_methodic_configurator.data_model_ardupilot_parameter import (
|
|
24
28
|
ArduPilotParameter,
|
|
25
29
|
BitmaskHelper,
|
|
26
30
|
ParameterOutOfRangeError,
|
|
27
31
|
ParameterUnchangedError,
|
|
28
32
|
)
|
|
29
|
-
from ardupilot_methodic_configurator.
|
|
30
|
-
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict
|
|
33
|
+
from ardupilot_methodic_configurator.data_model_par_dict import ParDict
|
|
31
34
|
from ardupilot_methodic_configurator.frontend_tkinter_base_window import BaseWindow
|
|
32
35
|
from ardupilot_methodic_configurator.frontend_tkinter_entry_dynamic import EntryWithDynamicalyFilteredListbox
|
|
33
36
|
from ardupilot_methodic_configurator.frontend_tkinter_pair_tuple_combobox import (
|
|
@@ -42,7 +45,7 @@ NEW_VALUE_WIDGET_WIDTH = 9
|
|
|
42
45
|
NEW_VALUE_DIFFERENT_STR = "\u2260" if platform_system() == "Windows" else "!="
|
|
43
46
|
|
|
44
47
|
|
|
45
|
-
class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors
|
|
48
|
+
class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors
|
|
46
49
|
"""
|
|
47
50
|
A class to manage and display the parameter editor table within the GUI.
|
|
48
51
|
|
|
@@ -51,26 +54,21 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
51
54
|
It uses the ArduPilotParameter domain model to handle parameter operations.
|
|
52
55
|
"""
|
|
53
56
|
|
|
54
|
-
def __init__(self, master,
|
|
57
|
+
def __init__(self, master, configuration_manager: ConfigurationManager, parameter_editor) -> None: # noqa: ANN001
|
|
55
58
|
super().__init__(master)
|
|
56
59
|
self.main_frame = master
|
|
57
|
-
self.
|
|
60
|
+
self.configuration_manager = configuration_manager
|
|
58
61
|
self.parameter_editor = parameter_editor # the parent window that contains this table
|
|
59
|
-
self.current_file = ""
|
|
60
62
|
self.upload_checkbutton_var: dict[str, tk.BooleanVar] = {}
|
|
61
63
|
self.at_least_one_param_edited = False
|
|
62
|
-
|
|
63
|
-
self.config_step_processor = ConfigurationStepProcessor(local_filesystem)
|
|
64
|
+
|
|
64
65
|
# Track last return values to prevent duplicate event processing
|
|
65
66
|
self._last_return_values: dict[tk.Misc, str] = {}
|
|
67
|
+
self._pending_scroll_to_bottom = False
|
|
66
68
|
|
|
67
69
|
style = ttk.Style()
|
|
68
70
|
style.configure("narrow.TButton", padding=0, width=4, border=(0, 0, 0, 0))
|
|
69
71
|
|
|
70
|
-
# Prepare a dictionary that maps variable names to their values
|
|
71
|
-
# These variables are used by the forced_parameters and derived_parameters in configuration_steps_*.json files
|
|
72
|
-
self.variables = local_filesystem.get_eval_variables()
|
|
73
|
-
|
|
74
72
|
def _should_show_upload_column(self, gui_complexity: Union[str, None] = None) -> bool:
|
|
75
73
|
"""
|
|
76
74
|
Determine if the upload column should be shown based on UI complexity.
|
|
@@ -130,13 +128,14 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
130
128
|
return tuple(base_headers), tuple(base_tooltips)
|
|
131
129
|
|
|
132
130
|
def repopulate( # pylint: disable=too-many-locals
|
|
133
|
-
self,
|
|
131
|
+
self, show_only_differences: bool, gui_complexity: str
|
|
134
132
|
) -> None:
|
|
135
133
|
for widget in self.view_port.winfo_children():
|
|
136
134
|
widget.destroy()
|
|
137
|
-
self.current_file = selected_file
|
|
138
135
|
# Clear the last return values tracking dictionary when repopulating
|
|
139
136
|
self._last_return_values.clear()
|
|
137
|
+
scroll_to_bottom = self._pending_scroll_to_bottom
|
|
138
|
+
self._pending_scroll_to_bottom = False
|
|
140
139
|
|
|
141
140
|
# Check if upload column should be shown based on UI complexity
|
|
142
141
|
show_upload_column = self._should_show_upload_column(gui_complexity)
|
|
@@ -152,9 +151,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
152
151
|
self.upload_checkbutton_var = {}
|
|
153
152
|
|
|
154
153
|
# Process configuration step and create domain model parameters
|
|
155
|
-
|
|
156
|
-
selected_file, fc_parameters, self.variables
|
|
157
|
-
)
|
|
154
|
+
(config_step_edited, ui_errors, ui_infos) = self.configuration_manager.repopulate_configuration_step_parameters()
|
|
158
155
|
if config_step_edited:
|
|
159
156
|
self.at_least_one_param_edited = True
|
|
160
157
|
|
|
@@ -165,53 +162,57 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
165
162
|
|
|
166
163
|
if show_only_differences:
|
|
167
164
|
# Filter to show only different parameters
|
|
168
|
-
different_params = self.
|
|
169
|
-
self._update_table(different_params,
|
|
165
|
+
different_params = self.configuration_manager.get_different_parameters()
|
|
166
|
+
self._update_table(different_params, self.parameter_editor.gui_complexity)
|
|
170
167
|
if not different_params:
|
|
171
|
-
info_msg = _("No different parameters found in {selected_file}. Skipping...").format(
|
|
168
|
+
info_msg = _("No different parameters found in {selected_file}. Skipping...").format(
|
|
169
|
+
selected_file=self.configuration_manager.current_file
|
|
170
|
+
)
|
|
172
171
|
logging_info(info_msg)
|
|
173
172
|
messagebox.showinfo(_("ArduPilot methodic configurator"), info_msg)
|
|
174
173
|
self.parameter_editor.on_skip_click()
|
|
175
174
|
return
|
|
176
175
|
else:
|
|
177
|
-
self._update_table(self.parameters,
|
|
178
|
-
|
|
179
|
-
self.canvas.yview("moveto", 0)
|
|
176
|
+
self._update_table(self.configuration_manager.parameters, self.parameter_editor.gui_complexity)
|
|
177
|
+
self._apply_scroll_position(scroll_to_bottom)
|
|
180
178
|
|
|
181
|
-
def
|
|
182
|
-
|
|
183
|
-
|
|
179
|
+
def _apply_scroll_position(self, scroll_to_bottom: bool) -> None:
|
|
180
|
+
"""Apply the requested scroll position to the canvas."""
|
|
181
|
+
self.update_idletasks()
|
|
182
|
+
position = 1.0 if scroll_to_bottom else 0.0
|
|
183
|
+
self.canvas.yview_moveto(position)
|
|
184
|
+
|
|
185
|
+
def _update_table(self, params: dict[str, ArduPilotParameter], gui_complexity: str) -> None:
|
|
184
186
|
"""Update the parameter table with the given parameters."""
|
|
185
187
|
current_param_name: str = ""
|
|
186
188
|
show_upload_column = self._should_show_upload_column(gui_complexity)
|
|
187
|
-
fc_connected = bool(fc_parameters)
|
|
188
189
|
|
|
189
190
|
try:
|
|
190
191
|
for i, (param_name, param) in enumerate(params.items(), 1):
|
|
191
192
|
current_param_name = param_name
|
|
192
193
|
|
|
193
|
-
column: list[tk.Widget] = self._create_column_widgets(param_name, param, show_upload_column
|
|
194
|
+
column: list[tk.Widget] = self._create_column_widgets(param_name, param, show_upload_column)
|
|
194
195
|
self._grid_column_widgets(column, i, show_upload_column)
|
|
195
196
|
|
|
196
197
|
# Add the "Add" button at the bottom of the table
|
|
197
|
-
add_button = ttk.Button(
|
|
198
|
-
|
|
199
|
-
)
|
|
200
|
-
tooltip_msg = _("Add a parameter to the {self.current_file} file")
|
|
198
|
+
add_button = ttk.Button(self.view_port, text=_("Add"), style="narrow.TButton", command=self._on_parameter_add)
|
|
199
|
+
tooltip_msg = _("Add a parameter to the {self.configuration_manager.current_file} file")
|
|
201
200
|
show_tooltip(add_button, tooltip_msg.format(**locals()))
|
|
202
201
|
add_button.grid(row=len(params) + 2, column=0, sticky="w", padx=0)
|
|
203
202
|
|
|
204
203
|
except KeyError as e:
|
|
205
204
|
logging_critical(
|
|
206
|
-
_("Parameter %s not found in the %s file: %s"),
|
|
205
|
+
_("Parameter %s not found in the %s file: %s"),
|
|
206
|
+
current_param_name,
|
|
207
|
+
self.configuration_manager.current_file,
|
|
208
|
+
e,
|
|
209
|
+
exc_info=True,
|
|
207
210
|
)
|
|
208
211
|
sys_exit(1)
|
|
209
212
|
|
|
210
213
|
self._configure_table_columns(show_upload_column)
|
|
211
214
|
|
|
212
|
-
def _create_column_widgets(
|
|
213
|
-
self, param_name: str, param: ArduPilotParameter, show_upload_column: bool, fc_connected: bool
|
|
214
|
-
) -> list[tk.Widget]:
|
|
215
|
+
def _create_column_widgets(self, param_name: str, param: ArduPilotParameter, show_upload_column: bool) -> list[tk.Widget]:
|
|
215
216
|
"""Create all column widgets for a parameter row."""
|
|
216
217
|
column: list[tk.Widget] = []
|
|
217
218
|
change_reason_widget = self._create_change_reason_entry(param)
|
|
@@ -225,7 +226,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
225
226
|
column.append(self._create_unit_label(param))
|
|
226
227
|
|
|
227
228
|
if show_upload_column:
|
|
228
|
-
column.append(self._create_upload_checkbutton(param_name
|
|
229
|
+
column.append(self._create_upload_checkbutton(param_name))
|
|
229
230
|
|
|
230
231
|
column.append(change_reason_widget)
|
|
231
232
|
|
|
@@ -282,7 +283,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
282
283
|
delete_button = ttk.Button(
|
|
283
284
|
self.view_port, text=_("Del"), style="narrow.TButton", command=lambda: self._on_parameter_delete(param_name)
|
|
284
285
|
)
|
|
285
|
-
tooltip_msg = _("Delete {param_name} from the {self.current_file} file")
|
|
286
|
+
tooltip_msg = _("Delete {param_name} from the {self.configuration_manager.current_file} file")
|
|
286
287
|
show_tooltip(delete_button, tooltip_msg.format(**locals()))
|
|
287
288
|
return delete_button
|
|
288
289
|
|
|
@@ -352,7 +353,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
352
353
|
# Success: mark edited and update the stored file parameter value
|
|
353
354
|
show_tooltip(change_reason_widget, param.tooltip_change_reason)
|
|
354
355
|
self.at_least_one_param_edited = True
|
|
355
|
-
self.
|
|
356
|
+
self.configuration_manager.current_file_parameters[param.name].value = new_value
|
|
356
357
|
value_is_different.config(text=NEW_VALUE_DIFFERENT_STR if param.is_different_from_fc else " ")
|
|
357
358
|
|
|
358
359
|
combobox_widget.configure(
|
|
@@ -383,8 +384,6 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
383
384
|
self, param: ArduPilotParameter, change_reason_widget: ttk.Entry, value_is_different: ttk.Label
|
|
384
385
|
) -> Union[PairTupleCombobox, ttk.Entry]:
|
|
385
386
|
"""Create an entry widget for editing the parameter value."""
|
|
386
|
-
# if param.is_dirty:
|
|
387
|
-
# self.at_least_one_param_edited = True
|
|
388
387
|
new_value_entry: Union[PairTupleCombobox, ttk.Entry]
|
|
389
388
|
|
|
390
389
|
# Check if parameter has values dictionary
|
|
@@ -498,7 +497,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
498
497
|
self.at_least_one_param_edited = True
|
|
499
498
|
# Update the corresponding file parameter with the model-returned value
|
|
500
499
|
# (model returns the canonical numeric/string representation)
|
|
501
|
-
self.
|
|
500
|
+
self.configuration_manager.current_file_parameters[param.name].value = new_value_result
|
|
502
501
|
value_is_different.config(text=NEW_VALUE_DIFFERENT_STR if param.is_different_from_fc else " ")
|
|
503
502
|
|
|
504
503
|
# Update the displayed value in the Entry or Combobox
|
|
@@ -574,7 +573,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
574
573
|
show_tooltip(change_reason_widget, param.tooltip_change_reason)
|
|
575
574
|
self.at_least_one_param_edited = True
|
|
576
575
|
# Update the corresponding file parameter
|
|
577
|
-
self.
|
|
576
|
+
self.configuration_manager.current_file_parameters[param.name].value = new_value_result
|
|
578
577
|
value_is_different.config(text=NEW_VALUE_DIFFERENT_STR if param.is_different_from_fc else " ")
|
|
579
578
|
|
|
580
579
|
# Update new_value_entry with the new decimal value
|
|
@@ -673,8 +672,9 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
673
672
|
show_tooltip(unit_label, unit_tooltip)
|
|
674
673
|
return unit_label
|
|
675
674
|
|
|
676
|
-
def _create_upload_checkbutton(self, param_name: str
|
|
675
|
+
def _create_upload_checkbutton(self, param_name: str) -> ttk.Checkbutton:
|
|
677
676
|
"""Create a checkbutton for upload selection."""
|
|
677
|
+
fc_connected: bool = self.configuration_manager.is_fc_connected
|
|
678
678
|
self.upload_checkbutton_var[param_name] = tk.BooleanVar(value=fc_connected)
|
|
679
679
|
upload_checkbutton = ttk.Checkbutton(self.view_port, variable=self.upload_checkbutton_var[param_name])
|
|
680
680
|
upload_checkbutton.configure(state="normal" if fc_connected else "disabled")
|
|
@@ -719,7 +719,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
719
719
|
)
|
|
720
720
|
self.at_least_one_param_edited = True
|
|
721
721
|
# Update the corresponding file parameter comment
|
|
722
|
-
self.
|
|
722
|
+
self.configuration_manager.current_file_parameters[param.name].comment = new_comment
|
|
723
723
|
|
|
724
724
|
change_reason_entry.bind("<FocusOut>", _on_change_reason_change)
|
|
725
725
|
change_reason_entry.bind("<Return>", _on_change_reason_change)
|
|
@@ -731,48 +731,34 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
731
731
|
def _on_parameter_delete(self, param_name: str) -> None:
|
|
732
732
|
"""Handle parameter deletion."""
|
|
733
733
|
msg = _("Are you sure you want to delete the {param_name} parameter?")
|
|
734
|
-
if messagebox.askyesno(f"{self.current_file}", msg.format(**locals())):
|
|
734
|
+
if messagebox.askyesno(f"{self.configuration_manager.current_file}", msg.format(**locals())):
|
|
735
735
|
# Capture current vertical scroll position
|
|
736
736
|
current_scroll_position = self.canvas.yview()[0]
|
|
737
737
|
|
|
738
738
|
# Delete the parameter
|
|
739
|
-
|
|
740
|
-
if param_name in self.parameters:
|
|
741
|
-
del self.parameters[param_name]
|
|
739
|
+
self.configuration_manager.delete_parameter_from_current_file(param_name)
|
|
742
740
|
self.at_least_one_param_edited = True
|
|
743
|
-
self.parameter_editor.repopulate_parameter_table(
|
|
741
|
+
self.parameter_editor.repopulate_parameter_table()
|
|
744
742
|
|
|
745
743
|
# Restore the scroll position
|
|
746
744
|
self.canvas.yview_moveto(current_scroll_position)
|
|
747
745
|
|
|
748
|
-
def _on_parameter_add(self
|
|
746
|
+
def _on_parameter_add(self) -> None:
|
|
749
747
|
"""Handle parameter addition."""
|
|
750
748
|
add_parameter_window = BaseWindow(self.main_frame.master)
|
|
751
|
-
add_parameter_window.root.title(_("Add Parameter to ") + self.current_file)
|
|
749
|
+
add_parameter_window.root.title(_("Add Parameter to ") + self.configuration_manager.current_file)
|
|
752
750
|
add_parameter_window.root.geometry("450x300")
|
|
753
751
|
|
|
754
752
|
# Label for instruction
|
|
755
753
|
instruction_label = ttk.Label(add_parameter_window.main_frame, text=_("Enter the parameter name to add:"))
|
|
756
754
|
instruction_label.pack(pady=5)
|
|
757
755
|
|
|
758
|
-
|
|
759
|
-
|
|
760
|
-
|
|
761
|
-
messagebox.showerror(
|
|
762
|
-
_("Operation not possible"),
|
|
763
|
-
_("No apm.pdef.xml file and no FC connected. Not possible autocomplete parameter names."),
|
|
764
|
-
)
|
|
756
|
+
try:
|
|
757
|
+
possible_add_param_names = self.configuration_manager.get_possible_add_param_names()
|
|
758
|
+
except OperationNotPossibleError as e:
|
|
759
|
+
messagebox.showerror(_("Operation not possible"), str(e))
|
|
765
760
|
return
|
|
766
761
|
|
|
767
|
-
# Remove the parameters that are already displayed in this configuration step
|
|
768
|
-
possible_add_param_names = [
|
|
769
|
-
param_name
|
|
770
|
-
for param_name in param_dict
|
|
771
|
-
if param_name not in self.local_filesystem.file_parameters[self.current_file]
|
|
772
|
-
]
|
|
773
|
-
|
|
774
|
-
possible_add_param_names.sort()
|
|
775
|
-
|
|
776
762
|
# Prompt the user for a parameter name
|
|
777
763
|
parameter_name_combobox = EntryWithDynamicalyFilteredListbox(
|
|
778
764
|
add_parameter_window.main_frame,
|
|
@@ -789,7 +775,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
789
775
|
def custom_selection_handler(event: tk.Event) -> None:
|
|
790
776
|
parameter_name_combobox.update_entry_from_listbox(event)
|
|
791
777
|
param_name = parameter_name_combobox.get().upper()
|
|
792
|
-
if self._confirm_parameter_addition(param_name
|
|
778
|
+
if self._confirm_parameter_addition(param_name):
|
|
793
779
|
add_parameter_window.root.destroy()
|
|
794
780
|
else:
|
|
795
781
|
add_parameter_window.root.focus()
|
|
@@ -798,52 +784,36 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors,
|
|
|
798
784
|
parameter_name_combobox.bind("<Return>", custom_selection_handler)
|
|
799
785
|
parameter_name_combobox.bind("<<ComboboxSelected>>", custom_selection_handler)
|
|
800
786
|
|
|
801
|
-
def _confirm_parameter_addition(self, param_name: str
|
|
802
|
-
"""Confirm and process parameter addition."""
|
|
803
|
-
|
|
804
|
-
|
|
805
|
-
return False
|
|
806
|
-
|
|
807
|
-
if param_name in self.local_filesystem.file_parameters[self.current_file]:
|
|
808
|
-
messagebox.showerror(_("Invalid parameter name."), _("Parameter already exists, edit it instead"))
|
|
809
|
-
return False
|
|
810
|
-
|
|
811
|
-
if fc_parameters:
|
|
812
|
-
if param_name in fc_parameters:
|
|
813
|
-
self.local_filesystem.file_parameters[self.current_file][param_name] = Par(fc_parameters[param_name], "")
|
|
814
|
-
self.at_least_one_param_edited = True
|
|
815
|
-
self.parameter_editor.repopulate_parameter_table(self.current_file)
|
|
816
|
-
return True
|
|
817
|
-
messagebox.showerror(_("Invalid parameter name."), _("Parameter name not found in the flight controller."))
|
|
818
|
-
if self.local_filesystem.doc_dict:
|
|
819
|
-
if param_name in self.local_filesystem.doc_dict:
|
|
820
|
-
self.local_filesystem.file_parameters[self.current_file][param_name] = Par(
|
|
821
|
-
self.local_filesystem.param_default_dict.get(param_name, Par(0, "")).value, ""
|
|
822
|
-
)
|
|
787
|
+
def _confirm_parameter_addition(self, param_name: str) -> bool:
|
|
788
|
+
"""Confirm and process parameter addition using ConfigurationManager."""
|
|
789
|
+
try:
|
|
790
|
+
if self.configuration_manager.add_parameter_to_current_file(param_name):
|
|
823
791
|
self.at_least_one_param_edited = True
|
|
824
|
-
self.
|
|
792
|
+
self._pending_scroll_to_bottom = True
|
|
793
|
+
self.parameter_editor.repopulate_parameter_table()
|
|
825
794
|
return True
|
|
826
|
-
|
|
827
|
-
messagebox.showerror(_("Invalid parameter name."),
|
|
828
|
-
|
|
829
|
-
|
|
830
|
-
|
|
831
|
-
|
|
832
|
-
)
|
|
795
|
+
except InvalidParameterNameError as exc:
|
|
796
|
+
messagebox.showerror(_("Invalid parameter name."), str(exc))
|
|
797
|
+
return False
|
|
798
|
+
except OperationNotPossibleError as exc:
|
|
799
|
+
messagebox.showerror(_("Operation not possible"), str(exc))
|
|
800
|
+
return False
|
|
833
801
|
return False
|
|
834
802
|
|
|
835
|
-
def get_upload_selected_params(self,
|
|
803
|
+
def get_upload_selected_params(self, gui_complexity: str) -> ParDict:
|
|
836
804
|
"""Get the parameters selected for upload."""
|
|
837
805
|
# Check if we should show upload column based on GUI complexity
|
|
838
806
|
if not self._should_show_upload_column(gui_complexity):
|
|
839
807
|
# all parameters are selected for upload in simple mode
|
|
840
|
-
return self.
|
|
841
|
-
|
|
842
|
-
|
|
843
|
-
|
|
844
|
-
|
|
845
|
-
|
|
846
|
-
|
|
808
|
+
return self.configuration_manager.current_file_parameters
|
|
809
|
+
|
|
810
|
+
return ParDict(
|
|
811
|
+
{
|
|
812
|
+
param_name: self.configuration_manager.current_file_parameters[param_name]
|
|
813
|
+
for param_name, checkbutton_state in self.upload_checkbutton_var.items()
|
|
814
|
+
if checkbutton_state.get()
|
|
815
|
+
}
|
|
816
|
+
)
|
|
847
817
|
|
|
848
818
|
def get_at_least_one_param_edited(self) -> bool:
|
|
849
819
|
"""Get whether at least one parameter has been edited."""
|
|
@@ -14,7 +14,6 @@ import tkinter as tk
|
|
|
14
14
|
|
|
15
15
|
# from logging import debug as logging_debug
|
|
16
16
|
# from logging import info as logging_info
|
|
17
|
-
from platform import system as platform_system
|
|
18
17
|
from tkinter import BooleanVar, ttk
|
|
19
18
|
from typing import Callable
|
|
20
19
|
|
|
@@ -53,6 +52,7 @@ class PopupWindow:
|
|
|
53
52
|
"""Set up the basic window properties and add the instructions text."""
|
|
54
53
|
popup_window.root.title(title)
|
|
55
54
|
popup_window.root.geometry(geometry)
|
|
55
|
+
instructions_text.config(borderwidth=0, relief="flat")
|
|
56
56
|
instructions_text.pack(padx=6, pady=10)
|
|
57
57
|
|
|
58
58
|
@staticmethod
|
|
@@ -80,20 +80,19 @@ class PopupWindow:
|
|
|
80
80
|
def finalize_window_setup(popup_window: BaseWindow, parent: tk.Tk, close_callback: Callable[[], None]) -> None:
|
|
81
81
|
"""Finalize window setup: center, make topmost, disable parent, set close handler."""
|
|
82
82
|
BaseWindow.center_window(popup_window.root, parent)
|
|
83
|
+
popup_window.root.deiconify() # Show the window now that it's positioned
|
|
83
84
|
popup_window.root.attributes("-topmost", True) # noqa: FBT003
|
|
84
|
-
|
|
85
|
-
if platform_system() == "Windows":
|
|
86
|
-
parent.attributes("-disabled", True) # noqa: FBT003 # Disable parent window input
|
|
85
|
+
popup_window.root.grab_set() # Make the popup modal
|
|
87
86
|
|
|
88
87
|
popup_window.root.protocol("WM_DELETE_WINDOW", close_callback)
|
|
89
88
|
|
|
90
89
|
@staticmethod
|
|
91
90
|
def close(popup_window: BaseWindow, parent: tk.Tk) -> None:
|
|
92
91
|
"""Close the popup window and re-enable the parent window."""
|
|
92
|
+
popup_window.root.grab_release() # Release the modal grab
|
|
93
93
|
popup_window.root.destroy()
|
|
94
|
-
if platform_system() == "Windows":
|
|
95
|
-
parent.attributes("-disabled", False) # noqa: FBT003 # Re-enable the parent window
|
|
96
94
|
parent.focus_set()
|
|
95
|
+
parent.lift()
|
|
97
96
|
|
|
98
97
|
|
|
99
98
|
class UsagePopupWindow(PopupWindow):
|
|
@@ -114,6 +113,9 @@ class UsagePopupWindow(PopupWindow):
|
|
|
114
113
|
instructions_text: RichText,
|
|
115
114
|
) -> None:
|
|
116
115
|
"""Display a usage popup with a Dismiss button."""
|
|
116
|
+
# Hide the window until it's properly positioned
|
|
117
|
+
usage_popup_window.root.withdraw()
|
|
118
|
+
|
|
117
119
|
# Set up the window
|
|
118
120
|
PopupWindow.setup_window(usage_popup_window, title, geometry, instructions_text)
|
|
119
121
|
|
|
@@ -164,6 +166,9 @@ class ConfirmationPopupWindow(PopupWindow):
|
|
|
164
166
|
bool: True if user clicked Yes, False if user clicked No
|
|
165
167
|
|
|
166
168
|
"""
|
|
169
|
+
# Hide the window until it's properly positioned
|
|
170
|
+
usage_popup_window.root.withdraw()
|
|
171
|
+
|
|
167
172
|
# Set up the window
|
|
168
173
|
PopupWindow.setup_window(usage_popup_window, title, geometry, instructions_text)
|
|
169
174
|
|
|
@@ -6,7 +6,7 @@ MOT_PWM_MAX,1920
|
|
|
6
6
|
MOT_PWM_MIN,1120
|
|
7
7
|
MOT_PWM_TYPE,0 # Specified in component editor window
|
|
8
8
|
MOT_SPOOL_TIME,0.5
|
|
9
|
-
NTF_BUZZ_TYPES,5 # Our
|
|
9
|
+
NTF_BUZZ_TYPES,5 # Our FC has a buzzer.
|
|
10
10
|
NTF_LED_TYPES,123079
|
|
11
11
|
PSC_ACCZ_SMAX,1000 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
|
|
12
12
|
SERVO_BLH_POLES,14 # Specified in component editor window
|
ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/42_system_id_roll.param
CHANGED
|
@@ -3,18 +3,20 @@ ARMING_CHECK,30174 # disable Parameter check because we need to set ATC_RAT_RLL
|
|
|
3
3
|
ATC_ANG_PIT_P,4.5 # reset to default to not interfere with sysID
|
|
4
4
|
ATC_ANG_RLL_P,4.5 # reset to default to not interfere with sysID
|
|
5
5
|
ATC_ANG_YAW_P,4.5 # reset to default to not interfere with sysID
|
|
6
|
+
ATC_RAT_PIT_I,0.180513
|
|
6
7
|
ATC_RAT_RLL_I,0 # prevent the rate controllers from compensating too much of the frequency-sweep signal
|
|
8
|
+
ATC_RAT_YAW_I,0.099616
|
|
7
9
|
ATC_RATE_FF_ENAB,0 # prevent the rate controllers from compensating too much of the frequency-sweep signal
|
|
8
10
|
FLTMODE6,25 # Activate sysid instead of loiter
|
|
9
11
|
LOG_BITMASK,704510 # attitude sample rate at loop rate
|
|
10
12
|
LOG_DISARMED,0 # was only needed for wind speed estimation
|
|
11
13
|
LOG_REPLAY,0 # was only needed for wind speed estimation
|
|
12
14
|
SID_AXIS,10 # Inject chip on the mixer roll signal
|
|
13
|
-
SID_F_START_HZ,0.
|
|
14
|
-
SID_F_STOP_HZ,
|
|
15
|
+
SID_F_START_HZ,0.08
|
|
16
|
+
SID_F_STOP_HZ,11
|
|
15
17
|
SID_MAGNITUDE,0.15
|
|
16
18
|
SID_T_FADE_IN,5
|
|
17
|
-
SID_T_FADE_OUT,
|
|
19
|
+
SID_T_FADE_OUT,1
|
|
18
20
|
SID_T_REC,130
|
|
19
21
|
TUNE,0 # System identification magnitude
|
|
20
22
|
TUNE_MAX,0.3 # System identification max magnitude
|
ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/43_system_id_pitch.param
CHANGED
|
@@ -2,9 +2,9 @@ ATC_RAT_PIT_I,0 # prevent the rate controllers from compensating too much of th
|
|
|
2
2
|
ATC_RAT_RLL_I,0.155054 # we are not performing system identification on the roll axis, so restore it to the autotuned value
|
|
3
3
|
ATC_RATE_FF_ENAB,0 # prevent the rate controllers from compensating too much of the frequency-sweep signal
|
|
4
4
|
SID_AXIS,11 # Inject chip on the mixer pitch signal
|
|
5
|
-
SID_F_START_HZ,0.
|
|
6
|
-
SID_F_STOP_HZ,
|
|
5
|
+
SID_F_START_HZ,0.08
|
|
6
|
+
SID_F_STOP_HZ,11
|
|
7
7
|
SID_MAGNITUDE,0.15
|
|
8
8
|
SID_T_FADE_IN,5
|
|
9
|
-
SID_T_FADE_OUT,
|
|
9
|
+
SID_T_FADE_OUT,1
|
|
10
10
|
SID_T_REC,130
|
|
Binary file
|
ardupilot_methodic_configurator/vehicle_templates/ArduCopter/Holybro_X500/vehicle_components.json
CHANGED
|
@@ -3,9 +3,9 @@
|
|
|
3
3
|
"Components": {
|
|
4
4
|
"Flight Controller": {
|
|
5
5
|
"Product": {
|
|
6
|
-
"Manufacturer": "
|
|
6
|
+
"Manufacturer": "Holybro",
|
|
7
7
|
"Model": "Pixhawk4",
|
|
8
|
-
"URL": "https://holybro.com/products/pixhawk-
|
|
8
|
+
"URL": "https://holybro.com/products/pixhawk-4?srsltid=AfmBOooNvEAR2_85PybTqRHhojmQW-aMW8TY-iQfI1v2qUU50AfxmCYg",
|
|
9
9
|
"Version": "1.0"
|
|
10
10
|
},
|
|
11
11
|
"Firmware": {
|
|
@@ -183,6 +183,5 @@
|
|
|
183
183
|
"Notes": ""
|
|
184
184
|
}
|
|
185
185
|
},
|
|
186
|
-
"Program version": "2.
|
|
187
|
-
"Configuration template": "Holybro_X500_V2"
|
|
186
|
+
"Program version": "2.5.0"
|
|
188
187
|
}
|
|
@@ -1,10 +1,10 @@
|
|
|
1
|
-
ARMING_RUDDER,2
|
|
1
|
+
ARMING_RUDDER,2
|
|
2
2
|
BRD_ALT_CONFIG,0
|
|
3
3
|
RC_OPTIONS,32
|
|
4
4
|
RC_PROTOCOLS,2 # Selected in the component editor
|
|
5
|
-
RC10_OPTION,0
|
|
6
|
-
RC6_OPTION,0
|
|
7
|
-
RC7_OPTION,0
|
|
8
|
-
RC8_OPTION,0
|
|
9
|
-
RC9_OPTION,0
|
|
10
|
-
RSSI_TYPE,0
|
|
5
|
+
RC10_OPTION,0
|
|
6
|
+
RC6_OPTION,0
|
|
7
|
+
RC7_OPTION,0
|
|
8
|
+
RC8_OPTION,0
|
|
9
|
+
RC9_OPTION,0
|
|
10
|
+
RSSI_TYPE,0
|
|
@@ -1,14 +1,14 @@
|
|
|
1
|
-
ATC_RAT_PIT_SMAX,
|
|
2
|
-
ATC_RAT_RLL_SMAX,
|
|
3
|
-
ATC_RAT_YAW_SMAX,
|
|
1
|
+
ATC_RAT_PIT_SMAX,25 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
|
|
2
|
+
ATC_RAT_RLL_SMAX,25 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
|
|
3
|
+
ATC_RAT_YAW_SMAX,25 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
|
|
4
4
|
MOT_HOVER_LEARN,2 # So that it can tune the throttle controller on 20_throttle_controller.param file
|
|
5
5
|
MOT_PWM_MAX,1900
|
|
6
6
|
MOT_PWM_MIN,1100
|
|
7
7
|
MOT_PWM_TYPE,0 # Specified in component editor window
|
|
8
8
|
MOT_SPOOL_TIME,0.5
|
|
9
|
-
NTF_BUZZ_TYPES,5 # Our
|
|
9
|
+
NTF_BUZZ_TYPES,5 # Our FC has a buzzer.
|
|
10
10
|
NTF_LED_TYPES,123079
|
|
11
|
-
PSC_ACCZ_SMAX,
|
|
11
|
+
PSC_ACCZ_SMAX,1000 # limit the slew rate to prevent possible ESC desync - https://ardupilot.org/copter/docs/common-servo-limit-cycle-detection.html
|
|
12
12
|
SERVO_BLH_POLES,14 # Specified in component editor window
|
|
13
13
|
SERVO_FTW_POLES,14 # Specified in component editor window
|
|
14
14
|
SERVO1_MAX,1900 # Operating Pulse Width:1100-1900us(Fixed or cannot be Programmed)
|
|
@@ -23,5 +23,5 @@ SERVO3_TRIM,1500 # Operating Pulse Width:1100-1900us(Fixed or cannot be Program
|
|
|
23
23
|
SERVO4_MAX,1900 # Operating Pulse Width:1100-1900us(Fixed or cannot be Programmed)
|
|
24
24
|
SERVO4_MIN,1100 # Operating Pulse Width:1100-1900us(Fixed or cannot be Programmed)
|
|
25
25
|
SERVO4_TRIM,1500 # Operating Pulse Width:1100-1900us(Fixed or cannot be Programmed)
|
|
26
|
-
TKOFF_RPM_MIN,0 #
|
|
26
|
+
TKOFF_RPM_MIN,0 # No ESC telemetry available, so no way to measure RPM
|
|
27
27
|
TKOFF_SLEW_TIME,2
|
|
@@ -1,10 +1,10 @@
|
|
|
1
1
|
BRD_SAFETY_DEFLT,0 # Safety switch gets disabled.
|
|
2
2
|
CAN_D1_PROTOCOL,0 # Enable this when a CAN gps will be used in the future.
|
|
3
3
|
CAN_P1_DRIVER,0 # No CAN drivers are required for now
|
|
4
|
-
GPS_GNSS_MODE,0
|
|
5
|
-
GPS_POS1_X
|
|
6
|
-
GPS_POS1_Y,0
|
|
7
|
-
GPS_POS1_Z
|
|
4
|
+
GPS_GNSS_MODE,0
|
|
5
|
+
GPS_POS1_X,0
|
|
6
|
+
GPS_POS1_Y,0
|
|
7
|
+
GPS_POS1_Z,0
|
|
8
8
|
GPS_TYPE,2 # Defined in component editor
|
|
9
9
|
NTF_LED_TYPES,123079 # Enable DRONECAN LED
|
|
10
10
|
SERIAL3_PROTOCOL,5 # GPS will be used.
|