Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -97,12 +97,12 @@ def set_board_version(self, board_version: int) -> None:
self.board_version = str(board_version & 0x0FFFF)
apj_board_id = board_version >> 16
self.apj_board_id = str(apj_board_id)
self.firmware_type = str(",".join(APJ_BOARD_ID_NAME_DICT.get(apj_board_id, _("Unknown"))))
self.firmware_type = str(",".join(APJ_BOARD_ID_NAME_DICT.get(apj_board_id, [_("Unknown")])))

vendor_derived_from_apj_board_id = str(",".join(APJ_BOARD_ID_VENDOR_DICT.get(apj_board_id, "ArduPilot")))
vendor_derived_from_apj_board_id = str(",".join(APJ_BOARD_ID_VENDOR_DICT.get(apj_board_id, ["ArduPilot"])))
if vendor_derived_from_apj_board_id != "ArduPilot" and self.vendor in ["ArduPilot", _("Unknown")]:
self.vendor = vendor_derived_from_apj_board_id
self.mcu_series = str(",".join(APJ_BOARD_ID_MCU_SERIES_DICT.get(apj_board_id, _("Unknown"))))
self.mcu_series = str(",".join(APJ_BOARD_ID_MCU_SERIES_DICT.get(apj_board_id, [_("Unknown")])))

def set_flight_custom_version(self, flight_custom_version: Sequence[int]) -> None:
self.flight_custom_version = "".join(chr(c) for c in flight_custom_version)
Expand All @@ -112,11 +112,11 @@ def set_os_custom_version(self, os_custom_version: Sequence[int]) -> None:

def set_usb_vendor_and_product_ids(self, vendor_id: int, product_id: int) -> None:
self.vendor_id = f"0x{vendor_id:04X}" if vendor_id else _("Unknown")
self.vendor = str(",".join(VID_VENDOR_DICT.get(vendor_id, _("Unknown"))))
self.vendor = str(",".join(VID_VENDOR_DICT.get(vendor_id, [_("Unknown")])))
self.vendor_and_vendor_id = f"{self.vendor} ({self.vendor_id})"

self.product_id = f"0x{product_id:04X}" if product_id else _("Unknown")
self.product = str(",".join(VID_PID_PRODUCT_DICT.get((vendor_id, product_id), _("Unknown"))))
self.product = str(",".join(VID_PID_PRODUCT_DICT.get((vendor_id, product_id), [_("Unknown")])))
self.product_and_product_id = f"{self.product} ({self.product_id})"

def set_capabilities(self, capabilities: int) -> None:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -883,7 +883,7 @@
"start": 50
},
"Everyday use": {
"description": "Everyday use",
"description": "Switch tests off, configure for productive work",
"start": 53
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -826,5 +826,65 @@
"auto_changed_by": "",
"old_filenames": ["45_everyday_use.param", "47_everyday_use.param", "50_everyday_use.param"]
}
},
"phases": {
"IMU temperature calibration": {
"description": "Calibrate the IMU sensors for at different temperatures",
"optional": true,
"start": 2
},
"Assemble all components except the propellers": {
"description": "Assemble all components except the propellers"
},
"Basic mandatory configuration": {
"description": "Set up the basic parameters for the vehicle",
"start": 4
},
"Assemble the propellers and perform the first flight": {
"description": "Assemble the propellers and perform the first flight"
},
"Minimalistic mandatory tuning": {
"description": "Minimalistic mandatory tuning using test flight data",
"start": 19
},
"Standard tuning": {
"description": "Improve tuning with more test flight data",
"optional": true,
"start": 24
},
"Improve altitude control": {
"description": "Improve altitude under windy conditions",
"optional": true,
"start": 40
},
"Analytical PID optimization": {
"description": "System identification and analytical PID optimization",
"optional": true,
"start": 42
},
"Position controller tuning": {
"description": "Position controller tuning",
"optional": true,
"start": 47
},
"Guided operation": {
"description": "Guided operation",
"optional": true,
"start": 48
},
"Precision landing": {
"description": "Precision landing",
"optional": true,
"start": 49
},
"Optical flow calibration": {
"description": "Optical flow sensor calibration",
"optional": true,
"start": 50
},
"Everyday use": {
"description": "Switch tests off, configure for productive work",
"start": 53
}
}
}
82 changes: 71 additions & 11 deletions ardupilot_methodic_configurator/configuration_steps_Heli.json
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,7 @@
"wiki_text": "Manual tuning of Roll and Pitch",
"wiki_url": "https://ardupilot.org/copter/docs/ac_rollpitchtuning.html",
"external_tool_text": "param_pid_adjustment_update.py",
"external_tool_url": "https://github.com/ArduPilot/MethodicConfigurator/blob/master/ardupilot_methodic_configuratoronfigurator/param_pid_adjustment_update.py",
"external_tool_url": "https://github.com/ArduPilot/MethodicConfigurator/blob/master/ardupilot_methodic_configurator/param_pid_adjustment_update.py",
"mandatory_text": "20% mandatory (80% optional)",
"auto_changed_by": "",
"old_filenames": ["15_pid_adjustment.param"]
Expand Down Expand Up @@ -494,8 +494,8 @@
"blog_url": "https://ardupilot.github.io/MethodicConfigurator/TUNING_GUIDE_Heli#951-roll-axis-autotune",
"wiki_text": "AutoTune",
"wiki_url": "https://ardupilot.org/copter/docs/autotune.html",
"external_tool_text": "",
"external_tool_url": "",
"external_tool_text": "ArduPilot PID Review Tool",
"external_tool_url": "https://firmware.ardupilot.org/Tools/WebTools/PIDReview/",
"mandatory_text": "80% mandatory (20% optional)",
"auto_changed_by": "ArduPilot autotune",
"old_filenames": ["29_autotune_roll_results.param"]
Expand Down Expand Up @@ -523,8 +523,8 @@
"blog_url": "https://ardupilot.github.io/MethodicConfigurator/TUNING_GUIDE_Heli#952-pitch-axis-autotune",
"wiki_text": "AutoTune",
"wiki_url": "https://ardupilot.org/copter/docs/autotune.html",
"external_tool_text": "",
"external_tool_url": "",
"external_tool_text": "ArduPilot PID Review Tool",
"external_tool_url": "https://firmware.ardupilot.org/Tools/WebTools/PIDReview/",
"mandatory_text": "80% mandatory (20% optional)",
"auto_changed_by": "ArduPilot autotune",
"old_filenames": ["31_autotune_pitch_results.param"]
Expand Down Expand Up @@ -555,8 +555,8 @@
"blog_url": "https://ardupilot.github.io/MethodicConfigurator/TUNING_GUIDE_Heli#953-yaw-axis-autotune",
"wiki_text": "AutoTune",
"wiki_url": "https://ardupilot.org/copter/docs/autotune.html",
"external_tool_text": "",
"external_tool_url": "",
"external_tool_text": "ArduPilot PID Review Tool",
"external_tool_url": "https://firmware.ardupilot.org/Tools/WebTools/PIDReview/",
"mandatory_text": "80% mandatory (20% optional)",
"auto_changed_by": "ArduPilot autotune",
"old_filenames": ["33_autotune_yaw_results.param"]
Expand Down Expand Up @@ -584,8 +584,8 @@
"blog_url": "https://ardupilot.github.io/MethodicConfigurator/TUNING_GUIDE_Heli#954-yaw-d-axis-autotune-optional",
"wiki_text": "AutoTune",
"wiki_url": "https://ardupilot.org/copter/docs/autotune.html",
"external_tool_text": "",
"external_tool_url": "",
"external_tool_text": "ArduPilot PID Review Tool",
"external_tool_url": "https://firmware.ardupilot.org/Tools/WebTools/PIDReview/",
"mandatory_text": "80% mandatory (20% optional)",
"auto_changed_by": "ArduPilot autotune",
"old_filenames": ["35_autotune_yawd_results.param"]
Expand Down Expand Up @@ -613,8 +613,8 @@
"blog_url": "https://ardupilot.github.io/MethodicConfigurator/TUNING_GUIDE_Heli#955-roll-and-pitch-axis-re-autotune",
"wiki_text": "AutoTune",
"wiki_url": "https://ardupilot.org/copter/docs/autotune.html",
"external_tool_text": "",
"external_tool_url": "",
"external_tool_text": "ArduPilot PID Review Tool",
"external_tool_url": "https://firmware.ardupilot.org/Tools/WebTools/PIDReview/",
"mandatory_text": "80% mandatory (20% optional)",
"auto_changed_by": "ArduPilot autotune",
"old_filenames": ["37_autotune_roll_pitch_retune_results.param"]
Expand Down Expand Up @@ -823,5 +823,65 @@
"auto_changed_by": "",
"old_filenames": ["45_everyday_use.param", "47_everyday_use.param", "50_everyday_use.param"]
}
},
"phases": {
"IMU temperature calibration": {
"description": "Calibrate the IMU sensors for at different temperatures",
"optional": true,
"start": 2
},
"Assemble all components except the propellers": {
"description": "Assemble all components except the propellers"
},
"Basic mandatory configuration": {
"description": "Set up the basic parameters for the vehicle",
"start": 4
},
"Assemble the propellers and perform the first flight": {
"description": "Assemble the propellers and perform the first flight"
},
"Minimalistic mandatory tuning": {
"description": "Minimalistic mandatory tuning using test flight data",
"start": 19
},
"Standard tuning": {
"description": "Improve tuning with more test flight data",
"optional": true,
"start": 24
},
"Improve altitude control": {
"description": "Improve altitude under windy conditions",
"optional": true,
"start": 40
},
"Analytical PID optimization": {
"description": "System identification and analytical PID optimization",
"optional": true,
"start": 42
},
"Position controller tuning": {
"description": "Position controller tuning",
"optional": true,
"start": 47
},
"Guided operation": {
"description": "Guided operation",
"optional": true,
"start": 48
},
"Precision landing": {
"description": "Precision landing",
"optional": true,
"start": 49
},
"Optical flow calibration": {
"description": "Optical flow sensor calibration",
"optional": true,
"start": 50
},
"Everyday use": {
"description": "Switch tests off, configure for productive work",
"start": 53
}
}
}
60 changes: 60 additions & 0 deletions ardupilot_methodic_configurator/configuration_steps_Rover.json
Original file line number Diff line number Diff line change
Expand Up @@ -826,5 +826,65 @@
"auto_changed_by": "",
"old_filenames": ["45_everyday_use.param", "47_everyday_use.param", "50_everyday_use.param"]
}
},
"phases": {
"IMU temperature calibration": {
"description": "Calibrate the IMU sensors for at different temperatures",
"optional": true,
"start": 2
},
"Assemble all components except the propellers": {
"description": "Assemble all components except the propellers"
},
"Basic mandatory configuration": {
"description": "Set up the basic parameters for the vehicle",
"start": 4
},
"Assemble the propellers and perform the first flight": {
"description": "Assemble the propellers and perform the first flight"
},
"Minimalistic mandatory tuning": {
"description": "Minimalistic mandatory tuning using test flight data",
"start": 19
},
"Standard tuning": {
"description": "Improve tuning with more test flight data",
"optional": true,
"start": 24
},
"Improve altitude control": {
"description": "Improve altitude under windy conditions",
"optional": true,
"start": 40
},
"Analytical PID optimization": {
"description": "System identification and analytical PID optimization",
"optional": true,
"start": 42
},
"Position controller tuning": {
"description": "Position controller tuning",
"optional": true,
"start": 47
},
"Guided operation": {
"description": "Guided operation",
"optional": true,
"start": 48
},
"Precision landing": {
"description": "Precision landing",
"optional": true,
"start": 49
},
"Optical flow calibration": {
"description": "Optical flow sensor calibration",
"optional": true,
"start": 50
},
"Everyday use": {
"description": "Switch tests off, configure for productive work",
"start": 53
}
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"type": "object",
"required": ["steps", "phases"],
"required": ["steps"],
"properties": {
"steps": {
"type": "object",
Expand Down
Loading
Loading