diff --git a/TUNING_GUIDE_ArduCopter.md b/TUNING_GUIDE_ArduCopter.md index 87d5da5f2..91ecb8c20 100644 --- a/TUNING_GUIDE_ArduCopter.md +++ b/TUNING_GUIDE_ArduCopter.md @@ -140,9 +140,231 @@ So, [start the ArduPilot Methodic Configurator and select a vehicle that resembl 1. select the destination directory, give it a name and press `Create a vehicle configuration directory from template` 1. On the component editor window, **add all the details of the components of your system** as we did in [Section 1.2](#12-our-example-vehicle): ![Component editor window](images/App_screenshot_Component_Editor.png) -1. Make sure to **scroll all the way down and enter all the information requested**, even if it does not seem important to you. -1. Click the `Save data and start configuration` button on the bottom -1. You now have a vehicle configuration directory with the name that you selected. But the files are just templates, you need to edit them in the next steps. + +Most optional information fields are only visible in `normal` GUI complexity mode. + +All components have **optional** information about the product itself: + +![product](images/blog/component_editor_product.png) + +The URL can be used to store a link to a datasheet or a link to a shop product page. + +Some components have **optional** information about their firmware: + +![firmware](images/blog/component_editor_firmware.png) + +All components have an **optional** notes field. + +## Flight Controller + +![flight controller](images/blog/component_editor_flight_controller.png) + +Some information, if available, is automatically filed in by the software as seen in the example above. + +## Frame + +![frame](images/blog/component_editor_frame.png) + +The minimum take off weight and the maximum take off weight in Kilo are entered here. +If you have variable payload configure the vehicle at the minimum take off weight. +Only after completely tuned can you add the additional payload. + +## Battery Monitor + +All supported connection types and their corresponding protocols are: + +| Connection Type | Protocol | +| --------------- | -------- | +| `None` | `Disabled` | +| `Analog` | `Analog Voltage Only` | +| `Analog` | `Analog Voltage and Current` | +| `Analog` | `FuelLevelAnalog` | +| `Analog` | `Synthetic Current and Analog Voltage` | +| `I2C1`–`I2C4` | `Solo` | +| `I2C1`–`I2C4` | `Bebop` | +| `I2C1`–`I2C4` | `SMBus-Generic` | +| `I2C1`–`I2C4` | `FuelFlow` | +| `I2C1`–`I2C4` | `SMBUS-SUI3` | +| `I2C1`–`I2C4` | `SMBUS-SUI6` | +| `I2C1`–`I2C4` | `NeoDesign` | +| `I2C1`–`I2C4` | `SMBus-Maxell` | +| `I2C1`–`I2C4` | `Generator-Elec` | +| `I2C1`–`I2C4` | `Generator-Fuel` | +| `I2C1`–`I2C4` | `Rotoye` | +| `I2C1`–`I2C4` | `MPPT` | +| `I2C1`–`I2C4` | `INA2XX` | +| `I2C1`–`I2C4` | `LTC2946` | +| `I2C1`–`I2C4` | `EFI` | +| `I2C1`–`I2C4` | `AD7091R5` | +| `CAN1`–`CAN2` | `DroneCAN-BatteryInfo` | +| `PWM` | `FuelLevelPWM` | +| `SPI` | `INA239_SPI` | +| `other` | `ESC` | +| `other` | `Sum Of Selected Monitors` | +| `other` | `Torqeedo` | +| `other` | `Scripting` | + +It is strongly recommended to use a battery monitor. +But if you do not have one select `none` in the flight controller connection: + +![battery monitor none](images/blog/component_editor_battery_monitor_none.png) + +If your battery monitor has an analog connection to the FC, select `analog` and one of the possible protocols: + +![battery monitor analog](images/blog/component_editor_battery_monitor_analog.png) + +If your battery monitor has an I2C connection to the FC, select the I2C bus and one of the possible protocols: + +![battery monitor i2c](images/blog/component_editor_battery_monitor_i2c.png) + +If your battery monitor has a CAN connection to the FC, select the CAN bus: + +![battery monitor can](images/blog/component_editor_battery_monitor_can.png) + +If your battery monitor has a SPI connection to the FC, select the SPI bus: + +![battery monitor spi](images/blog/component_editor_battery_monitor_spi.png) + +If your battery monitor has a PWM connection to the FC, select the PWM: + +![battery monitor pwm](images/blog/component_editor_battery_monitor_pwm.png) + +Otherwise select `other` and one of the possible protocols: + +![battery monitor other](images/blog/component_editor_battery_monitor_other.png) + +## Battery + +![battery](images/blog/component_editor_battery.png) + +Select the correct battery chemistry, doing so will automatically set typical voltage thresholds for that battery chemistry. + +Afterwards you should tweak the voltage thresholds to meet your requirements. + +- `Volt per cell max` - PID values will only scale when below this voltage +- `Volt per cell arm` - vehicle will only arm if battery voltage is above this threshold +- `Volt per cell low` - first failsafe level gets triggered when below this value +- `Volt per cell crit` - second failsafe level gets triggered when below this value +- `Volt per cell min` - PID values will only scale when above this voltage + +They must obey `Volt per cell crit` < `Volt per cell low` < `Volt per cell arm` < `Volt per cell max` + +`Number of cells` is the number of cells connected in series. +For a 6S battery this is 6. + +## ESC + +Electronic speed controllers have a `FC->ESC Connection` for control of the motor speed and +an optional `ESC->FC Telemetry` for telemetry feedback from the ESC to the flight controller. + +![esc main out](images/blog/component_editor_esc_main_out.png) + +The `FC->ESC Connection` type can be `Main Out`, an `AIO` integrated output, a serial port, or a CAN bus. +The protocol is determined by the `MOT_PWM_TYPE` parameter (e.g. `Normal`, `DShot600`) for PWM outputs, +or the serial/CAN protocol (e.g. `FETtecOneWire`, `DroneCAN`) for digital connections. + +The `ESC->FC Telemetry` type and protocol describe the return path: + +| Connection Type | Protocol | Notes | +| --------------- | -------- | ----- | +| `None` | `None` | No ESC telemetry | +| same as FC->ESC | `BDShot` | BDShot only on Main Out and/or AIO, without serial port backup channel | +| serial port | `ESC Telemetry` | DShot or BDShot serial telemetry backup channel | +| serial port | `FETtecOneWire` | Bidirectional FETtec protocol on the same wire | +| serial port | `Scripting` | For T-Motor/Hobbywing Datalink v2 serial telemetry | +| serial port | `Torqeedo` | For Torqeedo telemetry | +| serial port | `CoDevESC` | For CoDevESC serial telemetry | +| CAN port | `DroneCAN` | Telemetry over CAN bus | + +When using BDShot only on `Main Out` (1-8) and/or `Aux I/O` (9-14) connection, without serial port backup channel: + +![ESC telemetry BDshot only](images/blog/component_editor_esc_telem_main_out_aio.png) + +When using DShot or BDShot with a serial port backup channel: + +![ESC telemetry serial](images/blog/component_editor_esc_telem_serial.png) + +## Motors + +![Motor configuration interface showing pole count input](images/blog/component_editor_motors.png) + +Enter the number of magnetic **poles** of the motor rotor. +This is the **P** number in the common `nNmP` motor winding notation (e.g. `12N14P` → 14 poles). +The value must be an even integer. +It is used by ArduPilot to calculate the actual motor RPM from the ESC telemetry electrical frequency. + +## Propellers + +![Propeller configuration interface showing diameter input](images/blog/component_editor_propellers.png) + +Enter the propeller **diameter in inches**. +This value affects many initial PID values. + +## GNSS Receiver + +![GNSS receiver configuration interface](images/blog/component_editor_gnss.png) + +Select the FC connection **type** (serial port or CAN bus) and the matching **protocol**: + +| Connection Type | Protocol | +| --------------- | -------- | +| None | `None` | +| CAN bus | `DroneCAN` | +| serial port — auto-detect | `AUTO` | +| serial port — vendor-specific | other | + +If you do not have a GNSS receiver, select `None` as the connection type. + +## RC Controller + +The hand-held controller used by the pilot. +Enter the manufacturer and model for documentation purposes. +This component has no FC connection — it communicates wirelessly via the RC Transmitter and RC Receiver pair. + +## RC Transmitter + +The RF transmitter module (may be integrated in the RC Controller or a separate module). +Enter the manufacturer and model for documentation purposes. +This component has no FC connection. + +## RC Receiver + +Select the FC connection **type** and **protocol** that match how the receiver is wired to the flight controller: + +| Connection Type | Protocol | +| --------------- | -------- | +| RCin/SBUS — auto-detect all protocols | `All` | +| RCin/SBUS | `PPM` | +| RCin/SBUS or serial | `SBUS` / `SBUS_NI` | +| serial port | `DSM` | +| serial port | `CRSF` | +| serial port | `FPORT` | +| serial port | `MAVRadio` | +| serial port — vendor-specific | other | + +If your receiver is connected to a dedicated RC input pin, choose `RCin/SBUS` as the type. +If it is connected to a UART (e.g. CRSF, FPORT, DSM), choose the corresponding serial port. + +## Telemetry + +Select the FC connection **type** (serial port or CAN bus) and the matching **protocol**: + +| Connection Type | Protocol | Notes | +| --------------- | -------- | ----- | +| None | `None` | when not present | +| serial | `MAVLink2` | recommended for most ground stations | +| serial | `MAVLink1` | legacy ground stations | +| serial | `MAVLink High Latency` | satellite / low-bandwidth links | +| serial | `DDS XRCE` | ROS 2 micro-XRCE-DDS bridge | +| serial | other | vendor-specific | + +If you do not have a telemetry radio, select `None` as the connection type. + +Make sure to **scroll all the way down and enter all the information requested**, even if it does not seem important to you. +Click the `Save data and start configuration` button on the bottom + +You now have a vehicle configuration directory with the name that you selected. +But the files are just templates, you need to edit them in the next steps. # 4. Perform IMU temperature calibration before assembling the autopilot into the vehicle (optional) diff --git a/ardupilot_methodic_configurator/annotate_params.py b/ardupilot_methodic_configurator/annotate_params.py index dab6257e1..2668d7485 100755 --- a/ardupilot_methodic_configurator/annotate_params.py +++ b/ardupilot_methodic_configurator/annotate_params.py @@ -580,6 +580,7 @@ def get_fallback_xml_url(vehicle_type: str, firmware_version: str) -> str: "ArduPlane": "Plane-", "Rover": "Rover-", "ArduSub": "Sub-", + "Heli": "Copter-", } try: vehicle_subdir = vehicle_parm_subdir[vehicle_type] + firmware_version[0:3] diff --git a/ardupilot_methodic_configurator/backend_filesystem_vehicle_components.py b/ardupilot_methodic_configurator/backend_filesystem_vehicle_components.py index 99e5ffada..8de54b708 100644 --- a/ardupilot_methodic_configurator/backend_filesystem_vehicle_components.py +++ b/ardupilot_methodic_configurator/backend_filesystem_vehicle_components.py @@ -403,7 +403,8 @@ def wipe_component_info(self) -> None: }, }, "ESC": { - "FC Connection": {"Type": "Main Out", "Protocol": "Normal"}, + "FC->ESC Connection": {"Type": "Main Out", "Protocol": "Normal"}, + "ESC->FC Telemetry": {"Type": "None", "Protocol": "None"}, }, "Motors": { "Specifications": {"Poles": 14}, diff --git a/ardupilot_methodic_configurator/configuration_steps_ArduCopter.json b/ardupilot_methodic_configurator/configuration_steps_ArduCopter.json index 945150532..2ad8bfe89 100644 --- a/ardupilot_methodic_configurator/configuration_steps_ArduCopter.json +++ b/ardupilot_methodic_configurator/configuration_steps_ArduCopter.json @@ -106,11 +106,11 @@ }, "derived_parameters": { "ESC_HW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, - "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, + "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC->ESC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, "SERVO_FTW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } }, - "rename_connection": "vehicle_components['ESC']['FC Connection']['Type']", + "rename_connection": "vehicle_components['ESC']['FC->ESC Connection']['Type']", "old_filenames": [] }, "08_batt1.param": { diff --git a/ardupilot_methodic_configurator/configuration_steps_ArduPlane.json b/ardupilot_methodic_configurator/configuration_steps_ArduPlane.json index 837a4f49d..3cb5a77fb 100644 --- a/ardupilot_methodic_configurator/configuration_steps_ArduPlane.json +++ b/ardupilot_methodic_configurator/configuration_steps_ArduPlane.json @@ -106,11 +106,11 @@ }, "derived_parameters": { "ESC_HW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, - "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, + "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC->ESC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, "SERVO_FTW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } }, - "rename_connection": "vehicle_components['ESC']['FC Connection']['Type']", + "rename_connection": "vehicle_components['ESC']['FC->ESC Connection']['Type']", "old_filenames": [] }, "08_batt1.param": { diff --git a/ardupilot_methodic_configurator/configuration_steps_Heli.json b/ardupilot_methodic_configurator/configuration_steps_Heli.json index 0a59005e3..77ddf50a1 100644 --- a/ardupilot_methodic_configurator/configuration_steps_Heli.json +++ b/ardupilot_methodic_configurator/configuration_steps_Heli.json @@ -106,11 +106,11 @@ }, "derived_parameters": { "ESC_HW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, - "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, + "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC->ESC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, "SERVO_FTW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } }, - "rename_connection": "vehicle_components['ESC']['FC Connection']['Type']", + "rename_connection": "vehicle_components['ESC']['FC->ESC Connection']['Type']", "old_filenames": [] }, "08_batt1.param": { diff --git a/ardupilot_methodic_configurator/configuration_steps_Rover.json b/ardupilot_methodic_configurator/configuration_steps_Rover.json index 3025e0a8d..4e6222afc 100644 --- a/ardupilot_methodic_configurator/configuration_steps_Rover.json +++ b/ardupilot_methodic_configurator/configuration_steps_Rover.json @@ -106,11 +106,11 @@ }, "derived_parameters": { "ESC_HW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, - "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, + "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC->ESC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, "SERVO_FTW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } }, - "rename_connection": "vehicle_components['ESC']['FC Connection']['Type']", + "rename_connection": "vehicle_components['ESC']['FC->ESC Connection']['Type']", "old_filenames": [] }, "08_batt1.param": { @@ -129,14 +129,14 @@ "BATT_FS_LOW_ACT": { "New Value": 2, "Change Reason": "Return and land at home or rally point" } }, "derived_parameters": { - "BATT_ARM_VOLT": { "New Value": "(vehicle_components['Battery']['Specifications']['Number of cells']-1)*0.1+(vehicle_components['Battery']['Specifications']['Volt per cell crit']+0.3)*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "Do not allow arming below this voltage" }, - "BATT_CAPACITY": { "New Value": "(vehicle_components['Battery']['Specifications']['Capacity mAh'])", "Change Reason": "Total battery capacity specified in the component editor" }, - "BATT_CRT_VOLT": { "New Value": "(vehicle_components['Battery']['Specifications']['Volt per cell crit'])*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "(Critical voltage + 0.0) x no. of cells" }, - "BATT_LOW_VOLT": { "New Value": "(vehicle_components['Battery']['Specifications']['Volt per cell low'])*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "(Low voltage + 0.0) x no. of cells" }, + "BATT_ARM_VOLT": { "New Value": "vehicle_components['Battery']['Specifications']['Volt per cell arm']*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "Only arm above this voltage, to avoid taking off with insufficient battery capacity" }, + "BATT_CAPACITY": { "New Value": "vehicle_components['Battery']['Specifications']['Capacity mAh']", "Change Reason": "Total battery capacity specified in the component editor" }, + "BATT_CRT_VOLT": { "New Value": "vehicle_components['Battery']['Specifications']['Volt per cell crit']*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "Critical failsafe voltage x nr. of cells" }, + "BATT_LOW_VOLT": { "New Value": "vehicle_components['Battery']['Specifications']['Volt per cell low']*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "Low failsafe voltage x nr. of cells" }, "BATT_MONITOR": { "New Value": "vehicle_components['Battery Monitor']['FC Connection']['Protocol']", "Change Reason": "Selected in component editor window" }, "BATT_I2C_BUS": { "New Value": "1 if vehicle_components['Battery Monitor']['FC Connection']['Type'] == 'I2C2' else 2 if vehicle_components['Battery Monitor']['FC Connection']['Type'] == 'I2C3' else 3 if vehicle_components['Battery Monitor']['FC Connection']['Type'] == 'I2C4' else 0", "Change Reason": "Selected in component editor window" }, - "MOT_BAT_VOLT_MAX": { "New Value": "(vehicle_components['Battery']['Specifications']['Volt per cell max']+0.0)*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "(Max voltage + 0.0) x no. of cells" }, - "MOT_BAT_VOLT_MIN": { "New Value": "(vehicle_components['Battery']['Specifications']['Volt per cell crit']+0.0)*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "(Critical voltage + 0.0) x no. of cells" } + "MOT_BAT_VOLT_MAX": { "New Value": "vehicle_components['Battery']['Specifications']['Volt per cell max']*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "Scale the PIDs up when battery voltage is below this threshold" }, + "MOT_BAT_VOLT_MIN": { "New Value": "vehicle_components['Battery']['Specifications']['Volt per cell min']*vehicle_components['Battery']['Specifications']['Number of cells']", "Change Reason": "Scale the PIDs up when battery voltage is above this threshold" } }, "rename_connection": "vehicle_components['Battery Monitor']['FC Connection']['Type']", "old_filenames": [], @@ -170,7 +170,8 @@ "mandatory_text": "100% mandatory (0% optional)", "auto_changed_by": "", "derived_parameters": { - "GPS_TYPE": { "New Value": "vehicle_components['GNSS Receiver']['FC Connection']['Protocol']", "Change Reason": "Defined in component editor" } + "GPS_TYPE": { "New Value": "vehicle_components['GNSS Receiver']['FC Connection']['Protocol']", "Change Reason": "Defined in component editor" }, + "GPS1_TYPE": { "New Value": "vehicle_components['GNSS Receiver']['FC Connection']['Protocol']", "Change Reason": "Defined in component editor" } }, "rename_connection": "vehicle_components['GNSS Receiver']['FC Connection']['Type']", "old_filenames": [] @@ -269,7 +270,11 @@ "external_tool_url": "", "mandatory_text": "40% mandatory (60% optional)", "auto_changed_by": "", - "old_filenames": ["14_motor.param"] + "old_filenames": ["14_motor.param"], + "plugin": { + "name": "motor_test", + "placement": "left" + } }, "16_pid_adjustment.param": { "why": "With very large or very small vehicles the default PID values are not suitable for the first flight", diff --git a/ardupilot_methodic_configurator/data_model_template_overview.py b/ardupilot_methodic_configurator/data_model_template_overview.py index c15a35d56..d7965ea43 100644 --- a/ardupilot_methodic_configurator/data_model_template_overview.py +++ b/ardupilot_methodic_configurator/data_model_template_overview.py @@ -29,7 +29,7 @@ def __init__(self, components_data: dict) -> None: self.prop_diameter_inches = components_data.get("Propellers", {}).get("Specifications", {}).get("Diameter_inches", "") self.rc_protocol = components_data.get("RC Receiver", {}).get("FC Connection", {}).get("Protocol", "") self.telemetry_model = components_data.get("Telemetry", {}).get("Product", {}).get("Model", "") - self.esc_protocol = components_data.get("ESC", {}).get("FC Connection", {}).get("Protocol", "") + self.esc_protocol = components_data.get("ESC", {}).get("FC->ESC Connection", {}).get("Protocol", "") self.gnss_model = components_data.get("GNSS Receiver", {}).get("Product", {}).get("Model", "") self.gnss_connection = components_data.get("GNSS Receiver", {}).get("FC Connection", {}).get("Type", "") diff --git a/ardupilot_methodic_configurator/data_model_vehicle_components_base.py b/ardupilot_methodic_configurator/data_model_vehicle_components_base.py index 83abcb326..04af2f4ea 100644 --- a/ardupilot_methodic_configurator/data_model_vehicle_components_base.py +++ b/ardupilot_methodic_configurator/data_model_vehicle_components_base.py @@ -278,6 +278,20 @@ def update_json_structure( components = self._data.setdefault("Components", {}) components["GNSS Receiver"] = components.pop("GNSS receiver") + # Handle legacy ESC connection path rename (old projects might use FC Connection) + esc_component = self._data.get("Components", {}).get("ESC") + if isinstance(esc_component, dict) and "FC Connection" in esc_component: + esc_connection = esc_component.pop("FC Connection") + esc_component.setdefault("FC->ESC Connection", {}).update(esc_connection) + self._data["Components"]["ESC"] = esc_component + + # Ensure ESC->FC Telemetry section exists for files saved before it was introduced. + # setdefault leaves any existing values untouched; the neutral defaults here are overwritten + # by process_fc_parameters() once FC parameters are available. + esc_component = self._data.get("Components", {}).get("ESC") + if isinstance(esc_component, dict) and "FC->ESC Connection" in esc_component: + esc_component.setdefault("ESC->FC Telemetry", {"Type": "None", "Protocol": "None"}) + # Handle legacy battery monitor protocol migration for protocols that don't need hardware connections # This is a local import to avoid a circular import dependency from ardupilot_methodic_configurator.data_model_vehicle_components_validation import ( # pylint: disable=import-outside-toplevel, cyclic-import # noqa: PLC0415 diff --git a/ardupilot_methodic_configurator/data_model_vehicle_components_import.py b/ardupilot_methodic_configurator/data_model_vehicle_components_import.py index 6c2a95b32..ff5d0d2b9 100644 --- a/ardupilot_methodic_configurator/data_model_vehicle_components_import.py +++ b/ardupilot_methodic_configurator/data_model_vehicle_components_import.py @@ -27,13 +27,15 @@ from ardupilot_methodic_configurator.data_model_vehicle_components_validation import ( BATT_MONITOR_CONNECTION, CAN_PORTS, + ESC_TELEMETRY_PROTOCOLS, GNSS_RECEIVER_CONNECTION, I2C_PORTS, - MOT_PWM_TYPE_DICT, RC_PROTOCOLS_DICT, SERIAL_PORTS, SERIAL_PROTOCOLS_DICT, + SERVO_FUNCTION_ESC_CONTROL, ComponentDataModelValidation, + get_mot_pwm_type_sub_dict, ) @@ -104,6 +106,16 @@ def _reverse_key_search( logging_error(_("No values found for %s in the metadata"), param_name) return fallbacks + def _is_protocol_rename_exception(self, code_protocol: str, doc_protocol: str) -> bool: + """Check if a protocol mismatch is due to a known ArduPilot version rename.""" + return ( + (code_protocol == "Septentrio(SBF)" and doc_protocol == "SBF") + or (code_protocol == "Trimble(GSOF)" and doc_protocol == "GSOF") + or (code_protocol == "MAVLink" and doc_protocol == "MAV") + or (code_protocol == "Septentrio-DualAntenna(SBF)" and doc_protocol == "SBF-DualAntenna") + or (code_protocol == "Gimbal" and doc_protocol == "SToRM32 Gimbal Serial") + ) + def _verify_dict_is_uptodate( self, doc: dict[str, Any], dict_to_check: dict[str, dict[str, Any]], doc_key: str, doc_dict: str ) -> bool: @@ -137,7 +149,9 @@ def _verify_dict_is_uptodate( if check_key in dict_to_check: code_protocol = dict_to_check[check_key].get("protocol", None) - if code_protocol != doc_protocol: + if code_protocol is not None and code_protocol != doc_protocol: + if self._is_protocol_rename_exception(code_protocol, doc_protocol): + continue logging_warning(_("Protocol %s does not match %s in %s metadata"), code_protocol, doc_protocol, doc_key) is_valid = False else: @@ -165,7 +179,8 @@ def process_fc_parameters( self._verify_dict_is_uptodate(doc, GNSS_RECEIVER_CONNECTION, "GPS1_TYPE", "values") elif "GPS_TYPE" in doc: self._verify_dict_is_uptodate(doc, GNSS_RECEIVER_CONNECTION, "GPS_TYPE", "values") - self._verify_dict_is_uptodate(doc, MOT_PWM_TYPE_DICT, "MOT_PWM_TYPE", "values") + fw_type = str(self.get_component_value(("Flight Controller", "Firmware", "Type")) or "") + self._verify_dict_is_uptodate(doc, get_mot_pwm_type_sub_dict(fw_type), "MOT_PWM_TYPE", "values") self._verify_dict_is_uptodate(doc, RC_PROTOCOLS_DICT, "RC_PROTOCOLS", "Bitmask") # Process parameters in sequence @@ -191,11 +206,11 @@ def _set_gnss_type_from_fc_parameters(self, fc_parameters: dict) -> None: if str(gps1_type) in GNSS_RECEIVER_CONNECTION: gps1_connection_type = GNSS_RECEIVER_CONNECTION[str(gps1_type)].get("type") gps1_connection_protocol = GNSS_RECEIVER_CONNECTION[str(gps1_type)].get("protocol") - # Normalize gps1_connection_type to a list for consistent handling + # Normalize gps1_connection_type to a tuple for consistent handling if isinstance(gps1_connection_type, str): - gps1_connection_type = [gps1_connection_type] - # gps1_connection_type is now a list of possible connection types - if gps1_connection_type == ["None"]: + gps1_connection_type = (gps1_connection_type,) + # gps1_connection_type is now a tuple of possible connection types + if gps1_connection_type == ("None",): self.set_component_value(("GNSS Receiver", "FC Connection", "Type"), "None") self.set_component_value(("GNSS Receiver", "FC Connection", "Protocol"), "None") elif gps1_connection_type and any(conn_type in SERIAL_PORTS for conn_type in gps1_connection_type): @@ -231,35 +246,50 @@ def _set_gnss_type_from_fc_parameters(self, fc_parameters: dict) -> None: logging_error("%s value %u not in GNSS_RECEIVER_CONNECTION", param_name, gps1_type) self.set_component_value(("GNSS Receiver", "FC Connection", "Type"), "None") - def _set_serial_type_from_fc_parameters( # pylint: disable=too-many-branches,too-many-statements # noqa: PLR0915 - self, fc_parameters: dict - ) -> bool: + def _set_serial_type_from_fc_parameters(self, fc_parameters: dict) -> bool: """Process serial port parameters and update the data model. Returns True if ESC is serial controlled.""" + self._process_rc_protocols(fc_parameters) + return self._process_serial_components(fc_parameters) + + def _process_rc_protocols(self, fc_parameters: dict) -> None: + """Process RC_PROTOCOLS parameter and set RC receiver protocol and type.""" if "RC_PROTOCOLS" in fc_parameters: try: rc_protocols_nr = int(fc_parameters["RC_PROTOCOLS"]) except (ValueError, TypeError): logging_error(_("Invalid non-integer value for RC_PROTOCOLS %s"), fc_parameters["RC_PROTOCOLS"]) rc_protocols_nr = 0 - # RC_PROTOCOLS is a bitmask where each bit represents an enabled protocol - # Only set a specific protocol if exactly one bit is set (power of 2) - # If multiple bits are set, we can't determine which protocol is actually in use - if is_single_bit_set(rc_protocols_nr): - # Exactly one bit is set (power of 2) - use the value directly as the key - rc_value = str(rc_protocols_nr) - if rc_value in RC_PROTOCOLS_DICT: - protocol = RC_PROTOCOLS_DICT[rc_value].get("protocol") - self.set_component_value(("RC Receiver", "FC Connection", "Protocol"), str(protocol)) - elif rc_protocols_nr > 0: - # Multiple bits are set - cannot determine which protocol is active - logging_error( - _("RC_PROTOCOLS has multiple protocols enabled (%d). Cannot determine active protocol."), rc_protocols_nr - ) - rc = 1 - telem = 1 - gnss = 1 + if rc_protocols_nr > 0: + # Set the type to RCin/SBUS if not already set by serial processing + current_rc_type = self.get_component_value(("RC Receiver", "FC Connection", "Type")) + if current_rc_type is None or current_rc_type == "": + self.set_component_value(("RC Receiver", "FC Connection", "Type"), "RCin/SBUS") + + # RC_PROTOCOLS is a bitmask where each bit represents an enabled protocol + # Only set a specific protocol if exactly one bit is set (power of 2) + # If multiple bits are set, we can't determine which protocol is actually in use + if is_single_bit_set(rc_protocols_nr): + # Exactly one bit is set (power of 2) - use the value directly as the key + rc_value = str(rc_protocols_nr) + if rc_value in RC_PROTOCOLS_DICT: + protocol = RC_PROTOCOLS_DICT[rc_value].get("protocol") + self.set_component_value(("RC Receiver", "FC Connection", "Protocol"), str(protocol)) + else: + # Multiple bits are set - cannot determine which protocol is active + logging_error( + _("RC_PROTOCOLS has multiple protocols enabled (%d). Cannot determine active protocol."), + rc_protocols_nr, + ) + + def _process_serial_components(self, fc_parameters: dict) -> bool: # pylint: disable=too-many-branches + """Process serial port components and return True if ESC is serial controlled.""" + rc = telem = gnss = 1 + # esc counts FC->ESC *control* serial protocols only (FETtecOneWire, Torqeedo, CoDevESC). + # Telemetry-only protocols (ESC Telemetry=16, Scripting=28) do NOT count here because + # FC->ESC is still PWM/DShot/BDShot in those cases and _set_esc_type_from_fc_parameters must run. esc = 1 + esc_telemetry_set = False # True once ESC->FC Telemetry is populated from a serial port for serial in SERIAL_PORTS: if serial + "_PROTOCOL" not in fc_parameters: continue @@ -301,12 +331,23 @@ def _set_serial_type_from_fc_parameters( # pylint: disable=too-many-branches,to self.set_component_value(("GNSS Receiver", "FC Connection", "Type"), serial) gnss += 1 elif component == "ESC": - if esc == 1: - # Only set component values for the first ESC - self.set_component_value(("ESC", "FC Connection", "Type"), serial) - self.set_component_value(("ESC", "FC Connection", "Protocol"), protocol) - # Count all ESC components - esc += 1 + if protocol in ESC_TELEMETRY_PROTOCOLS: + # Serial ESC->FC telemetry only (DShot with UART feedback, or Hobbywing Datalink v2). + # FC->ESC connection is still PWM/DShot; _set_esc_type_from_fc_parameters handles it. + # Do NOT increment esc so that function is still called. + if not esc_telemetry_set: + self.set_component_value(("ESC", "ESC->FC Telemetry", "Type"), serial) + self.set_component_value(("ESC", "ESC->FC Telemetry", "Protocol"), protocol) + esc_telemetry_set = True + else: + # FC->ESC serial control protocol (FETtecOneWire, Torqeedo, CoDevESC): + # the same serial port carries both directions. + if esc == 1: + self.set_component_value(("ESC", "FC->ESC Connection", "Type"), serial) + self.set_component_value(("ESC", "FC->ESC Connection", "Protocol"), protocol) + self.set_component_value(("ESC", "ESC->FC Telemetry", "Type"), serial) + self.set_component_value(("ESC", "ESC->FC Telemetry", "Protocol"), protocol) + esc += 1 return esc >= 2 @@ -319,22 +360,43 @@ def _set_esc_type_from_fc_parameters(self, fc_parameters: dict[str, float], doc: logging_error(_("Invalid non-integer value for MOT_PWM_TYPE %s"), mot_pwm_type) mot_pwm_type = 0 - main_out_functions = [fc_parameters.get("SERVO" + str(i) + "_FUNCTION", 0) for i in range(1, 9)] + aio_functions = [fc_parameters.get("SERVO" + str(i) + "_FUNCTION", 0) for i in range(9, 15)] - # if any element of main_out_functions is in [33, 34, 35, 36] then ESC is connected to main_out - if any(servo_function in {33, 34, 35, 36} for servo_function in main_out_functions): - self.set_component_value(("ESC", "FC Connection", "Type"), "Main Out") + # if any element of aio_functions is in SERVO_FUNCTION_ESC_CONTROL then ESC is connected to AIO + if any(servo_function in SERVO_FUNCTION_ESC_CONTROL for servo_function in aio_functions): + self.set_component_value(("ESC", "FC->ESC Connection", "Type"), "AIO") else: - self.set_component_value(("ESC", "FC Connection", "Type"), "AIO") + self.set_component_value(("ESC", "FC->ESC Connection", "Type"), "Main Out") + protocol = "" if "MOT_PWM_TYPE" in doc and "values" in doc["MOT_PWM_TYPE"]: protocol = doc["MOT_PWM_TYPE"]["values"].get(str(mot_pwm_type), "") if protocol: - self.set_component_value(("ESC", "FC Connection", "Protocol"), protocol) + self.set_component_value(("ESC", "FC->ESC Connection", "Protocol"), protocol) # Fallback to MOT_PWM_TYPE_DICT if doc is not available - elif str(mot_pwm_type) in MOT_PWM_TYPE_DICT: - protocol = str(MOT_PWM_TYPE_DICT[str(mot_pwm_type)]["protocol"]) - self.set_component_value(("ESC", "FC Connection", "Protocol"), protocol) + else: + mot_pwm_sub = get_mot_pwm_type_sub_dict( + str(self.get_component_value(("Flight Controller", "Firmware", "Type")) or "") + ) + if str(mot_pwm_type) in mot_pwm_sub: + protocol = str(mot_pwm_sub[str(mot_pwm_type)]["protocol"]) + self.set_component_value(("ESC", "FC->ESC Connection", "Protocol"), protocol) + + # Set ESC->FC Telemetry: DShot supports BDShot telemetry on the same PWM wire. + # However, if _set_serial_type_from_fc_parameters already found a dedicated serial telemetry + # port (SERIAL*_PROTOCOL=16 or 28), that takes priority and must not be overwritten. + esc_conn_type = self.get_component_value(("ESC", "FC->ESC Connection", "Type")) + current_telemetry_type = self.get_component_value(("ESC", "ESC->FC Telemetry", "Type")) + if protocol and protocol.startswith("DShot"): + if current_telemetry_type not in SERIAL_PORTS and current_telemetry_type not in CAN_PORTS: + # No dedicated serial/CAN telemetry port detected; fall back to BDShot on the PWM wire + self.set_component_value(("ESC", "ESC->FC Telemetry", "Type"), esc_conn_type) + self.set_component_value(("ESC", "ESC->FC Telemetry", "Protocol"), "BDShot") + elif not current_telemetry_type or ( + current_telemetry_type not in SERIAL_PORTS and current_telemetry_type not in CAN_PORTS + ): + self.set_component_value(("ESC", "ESC->FC Telemetry", "Type"), "None") + self.set_component_value(("ESC", "ESC->FC Telemetry", "Protocol"), "None") def _set_battery_type_from_fc_parameters(self, fc_parameters: dict[str, float]) -> None: # pylint: disable=too-many-branches """Process battery monitor parameters and update the data model.""" @@ -351,7 +413,7 @@ def _set_battery_type_from_fc_parameters(self, fc_parameters: dict[str, float]) fc_conn_protocol = BATT_MONITOR_CONNECTION[batt_monitor_str].get("protocol", "Disabled") # Handle list of possible connection types - if isinstance(fc_conn_type, list): + if isinstance(fc_conn_type, tuple): # Check if it's I2C ports - need to determine which bus if set(fc_conn_type) <= set(I2C_PORTS): # subset of I2C ports # Use BATT_I2C_BUS to determine the actual I2C bus @@ -378,7 +440,7 @@ def _set_battery_type_from_fc_parameters(self, fc_parameters: dict[str, float]) # For other list types, take first element fc_conn_type = fc_conn_type[0] - if isinstance(fc_conn_protocol, list): + if isinstance(fc_conn_protocol, tuple): fc_conn_protocol = fc_conn_protocol[0] self.set_component_value(("Battery Monitor", "FC Connection", "Type"), fc_conn_type) @@ -430,6 +492,12 @@ def _import_bat_values_from_fc(self, specs: BatteryVoltageSpecs) -> None: self.import_bat_voltage(specs, "BATT_LOW_VOLT", "Volt per cell low") self.import_bat_voltage(specs, "BATT_CRT_VOLT", "Volt per cell crit") self.import_bat_voltage(specs, "MOT_BAT_VOLT_MIN", "Volt per cell min") + else: + self.set_component_value(("Battery", "Specifications", "Volt per cell max"), "0") + self.set_component_value(("Battery", "Specifications", "Volt per cell arm"), "0") + self.set_component_value(("Battery", "Specifications", "Volt per cell low"), "0") + self.set_component_value(("Battery", "Specifications", "Volt per cell crit"), "0") + self.set_component_value(("Battery", "Specifications", "Volt per cell min"), "0") def import_bat_voltage(self, specs: BatteryVoltageSpecs, param_name: str, voltage_type: str) -> None: if param_name in specs.fc_parameters: @@ -619,7 +687,10 @@ def _set_motor_poles_from_fc_parameters(self, fc_parameters: dict[str, float]) - poles = 0.0 if "MOT_PWM_TYPE" in fc_parameters: mot_pwm_type_str = str(int(fc_parameters["MOT_PWM_TYPE"])) - if mot_pwm_type_str in MOT_PWM_TYPE_DICT and MOT_PWM_TYPE_DICT[mot_pwm_type_str].get("is_dshot", False): + mot_pwm_sub = get_mot_pwm_type_sub_dict( + str(self.get_component_value(("Flight Controller", "Firmware", "Type")) or "") + ) + if mot_pwm_type_str in mot_pwm_sub and mot_pwm_sub[mot_pwm_type_str].get("is_dshot", False): if fc_parameters.get("SERVO_BLH_POLES"): # DShot ESCs poles = fc_parameters["SERVO_BLH_POLES"] elif fc_parameters.get("SERVO_FTW_MASK") and fc_parameters.get("SERVO_FTW_POLES"): diff --git a/ardupilot_methodic_configurator/data_model_vehicle_components_validation.py b/ardupilot_methodic_configurator/data_model_vehicle_components_validation.py index 3187515a8..796cf8a76 100644 --- a/ardupilot_methodic_configurator/data_model_vehicle_components_validation.py +++ b/ardupilot_methodic_configurator/data_model_vehicle_components_validation.py @@ -26,15 +26,18 @@ ) # Port definitions -ANALOG_PORTS = ["Analog"] -SERIAL_PORTS = ["SERIAL1", "SERIAL2", "SERIAL3", "SERIAL4", "SERIAL5", "SERIAL6", "SERIAL7", "SERIAL8"] -CAN_PORTS = ["CAN1", "CAN2"] -I2C_PORTS = ["I2C1", "I2C2", "I2C3", "I2C4"] -PWM_IN_PORTS = ["PWM"] -PWM_OUT_PORTS = ["Main Out", "AIO"] -RC_PORTS = ["RCin/SBUS"] -SPI_PORTS = ["SPI"] -OTHER_PORTS = ["other"] +ANALOG_PORTS: tuple[str, ...] = ("Analog",) +SERIAL_PORTS: tuple[str, ...] = ("SERIAL1", "SERIAL2", "SERIAL3", "SERIAL4", "SERIAL5", "SERIAL6", "SERIAL7", "SERIAL8") +CAN_PORTS: tuple[str, ...] = ("CAN1", "CAN2") +I2C_PORTS: tuple[str, ...] = ("I2C1", "I2C2", "I2C3", "I2C4") +PWM_IN_PORTS: tuple[str, ...] = ("PWM",) +PWM_OUT_PORTS: tuple[str, ...] = ("Main Out", "AIO") +RC_PORTS: tuple[str, ...] = ("RCin/SBUS",) +SPI_PORTS: tuple[str, ...] = ("SPI",) +OTHER_PORTS: tuple[str, ...] = ("other",) + +# Servo function constants for ESC detection +SERVO_FUNCTION_ESC_CONTROL: set[int] = {33, 34, 35, 36, 73, 74} # Functions that indicate ESC control on AIO # Bus labels for SERIAL ports - maps SERIAL port names to their common bus labels # These labels help users identify ports by their typical usage on flight controllers: @@ -84,7 +87,8 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> ("RC Receiver", "FC Connection", "Type"), ("Telemetry", "FC Connection", "Type"), ("Battery Monitor", "FC Connection", "Type"), - ("ESC", "FC Connection", "Type"), + ("ESC", "FC->ESC Connection", "Type"), + ("ESC", "ESC->FC Telemetry", "Type"), ("GNSS Receiver", "FC Connection", "Type"), ] @@ -94,7 +98,7 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> # Protocol dictionaries SERIAL_PROTOCOLS_DICT: dict[str, dict[str, Any]] = { - "-1": {"type": ["None"], "protocol": "None", "component": None}, + "-1": {"type": ("None",), "protocol": "None", "component": None}, "1": {"type": SERIAL_PORTS, "protocol": "MAVLink1", "component": "Telemetry"}, "2": {"type": SERIAL_PORTS, "protocol": "MAVLink2", "component": "Telemetry"}, "3": {"type": SERIAL_PORTS, "protocol": "Frsky D", "component": None}, @@ -108,7 +112,7 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> "13": {"type": SERIAL_PORTS, "protocol": "Beacon", "component": None}, "14": {"type": SERIAL_PORTS, "protocol": "Volz servo out", "component": None}, "15": {"type": SERIAL_PORTS, "protocol": "SBus servo out", "component": None}, - "16": {"type": SERIAL_PORTS, "protocol": "ESC Telemetry", "component": None}, + "16": {"type": SERIAL_PORTS, "protocol": "ESC Telemetry", "component": "ESC"}, "17": {"type": SERIAL_PORTS, "protocol": "Devo Telemetry", "component": None}, "18": {"type": SERIAL_PORTS, "protocol": "OpticalFlow", "component": None}, "19": {"type": SERIAL_PORTS, "protocol": "RobotisServo", "component": None}, @@ -120,7 +124,7 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> "25": {"type": SERIAL_PORTS, "protocol": "LTM", "component": None}, "26": {"type": SERIAL_PORTS, "protocol": "RunCam", "component": None}, "27": {"type": SERIAL_PORTS, "protocol": "HottTelem", "component": None}, - "28": {"type": SERIAL_PORTS, "protocol": "Scripting", "component": None}, + "28": {"type": SERIAL_PORTS, "protocol": "Scripting", "component": "ESC"}, "29": {"type": SERIAL_PORTS, "protocol": "Crossfire VTX", "component": None}, "30": {"type": SERIAL_PORTS, "protocol": "Generator", "component": None}, "31": {"type": SERIAL_PORTS, "protocol": "Winch", "component": None}, @@ -143,8 +147,11 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> "49": {"type": SERIAL_PORTS, "protocol": "i-BUS Telemetry", "component": None}, } -BATT_MONITOR_CONNECTION: dict[str, dict[str, Union[list[str], str]]] = { - "0": {"type": ["None"], "protocol": "Disabled"}, +# ESC protocol constants +ESC_TELEMETRY_PROTOCOLS = {"ESC Telemetry", "Scripting"} # Serial telemetry-only protocols + +BATT_MONITOR_CONNECTION: dict[str, dict[str, Union[tuple[str, ...], str]]] = { + "0": {"type": ("None",), "protocol": "Disabled"}, "3": {"type": ANALOG_PORTS, "protocol": "Analog Voltage Only"}, "4": {"type": ANALOG_PORTS, "protocol": "Analog Voltage and Current"}, "5": {"type": I2C_PORTS, "protocol": "Solo"}, @@ -174,8 +181,8 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> "29": {"type": OTHER_PORTS, "protocol": "Scripting"}, } -GNSS_RECEIVER_CONNECTION: dict[str, dict[str, Union[list[str], str]]] = { - "0": {"type": ["None"], "protocol": "None"}, +GNSS_RECEIVER_CONNECTION: dict[str, dict[str, Union[tuple[str, ...], str]]] = { + "0": {"type": ("None",), "protocol": "None"}, "1": {"type": SERIAL_PORTS, "protocol": "AUTO"}, "2": {"type": SERIAL_PORTS, "protocol": "uBlox"}, "5": {"type": SERIAL_PORTS, "protocol": "NMEA"}, @@ -201,23 +208,56 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> "26": {"type": SERIAL_PORTS, "protocol": "Septentrio-DualAntenna(SBF)"}, } -MOT_PWM_TYPE_DICT: dict[str, dict[str, Union[list[str], str, bool]]] = { - "0": {"type": PWM_OUT_PORTS, "protocol": "Normal", "is_dshot": False}, - "1": {"type": PWM_OUT_PORTS, "protocol": "OneShot", "is_dshot": True}, - "2": {"type": PWM_OUT_PORTS, "protocol": "OneShot125", "is_dshot": True}, - "3": {"type": PWM_OUT_PORTS, "protocol": "Brushed", "is_dshot": False}, - "4": {"type": PWM_OUT_PORTS, "protocol": "DShot150", "is_dshot": True}, - "5": {"type": PWM_OUT_PORTS, "protocol": "DShot300", "is_dshot": True}, - "6": {"type": PWM_OUT_PORTS, "protocol": "DShot600", "is_dshot": True}, - "7": {"type": PWM_OUT_PORTS, "protocol": "DShot1200", "is_dshot": True}, - "8": {"type": PWM_OUT_PORTS, "protocol": "PWMRange", "is_dshot": False}, - "9": {"type": PWM_OUT_PORTS, "protocol": "PWMAngle", "is_dshot": False}, +MOT_PWM_TYPE_DICT: dict[str, dict[str, dict[str, Union[tuple[str, ...], str, bool]]]] = { + "ArduCopter": { + "0": {"type": PWM_OUT_PORTS, "protocol": "Normal", "is_dshot": False}, + "1": {"type": PWM_OUT_PORTS, "protocol": "OneShot", "is_dshot": True}, + "2": {"type": PWM_OUT_PORTS, "protocol": "OneShot125", "is_dshot": True}, + "3": {"type": PWM_OUT_PORTS, "protocol": "Brushed", "is_dshot": False}, + "4": {"type": PWM_OUT_PORTS, "protocol": "DShot150", "is_dshot": True}, + "5": {"type": PWM_OUT_PORTS, "protocol": "DShot300", "is_dshot": True}, + "6": {"type": PWM_OUT_PORTS, "protocol": "DShot600", "is_dshot": True}, + "7": {"type": PWM_OUT_PORTS, "protocol": "DShot1200", "is_dshot": True}, + "8": {"type": PWM_OUT_PORTS, "protocol": "PWMRange", "is_dshot": False}, + "9": {"type": PWM_OUT_PORTS, "protocol": "PWMAngle", "is_dshot": False}, + }, + "Heli": { + "0": {"type": PWM_OUT_PORTS, "protocol": "Normal", "is_dshot": False}, + "1": {"type": PWM_OUT_PORTS, "protocol": "OneShot", "is_dshot": True}, + "2": {"type": PWM_OUT_PORTS, "protocol": "OneShot125", "is_dshot": True}, + "3": {"type": PWM_OUT_PORTS, "protocol": "Brushed", "is_dshot": False}, + "4": {"type": PWM_OUT_PORTS, "protocol": "DShot150", "is_dshot": True}, + "5": {"type": PWM_OUT_PORTS, "protocol": "DShot300", "is_dshot": True}, + "6": {"type": PWM_OUT_PORTS, "protocol": "DShot600", "is_dshot": True}, + "7": {"type": PWM_OUT_PORTS, "protocol": "DShot1200", "is_dshot": True}, + "8": {"type": PWM_OUT_PORTS, "protocol": "PWMRange", "is_dshot": False}, + "9": {"type": PWM_OUT_PORTS, "protocol": "PWMAngle", "is_dshot": False}, + }, + "Rover": { + "0": {"type": PWM_OUT_PORTS, "protocol": "Normal", "is_dshot": False}, + "1": {"type": PWM_OUT_PORTS, "protocol": "OneShot", "is_dshot": True}, + "2": {"type": PWM_OUT_PORTS, "protocol": "OneShot125", "is_dshot": True}, + "3": {"type": PWM_OUT_PORTS, "protocol": "BrushedWithRelay", "is_dshot": False}, + "4": {"type": PWM_OUT_PORTS, "protocol": "BrushedBiPolar", "is_dshot": False}, + "5": {"type": PWM_OUT_PORTS, "protocol": "DShot150", "is_dshot": True}, + "6": {"type": PWM_OUT_PORTS, "protocol": "DShot300", "is_dshot": True}, + "7": {"type": PWM_OUT_PORTS, "protocol": "DShot600", "is_dshot": True}, + "8": {"type": PWM_OUT_PORTS, "protocol": "DShot1200", "is_dshot": True}, + "9": {"type": PWM_OUT_PORTS, "protocol": "PWMRange", "is_dshot": False}, + "10": {"type": PWM_OUT_PORTS, "protocol": "PWMAngle", "is_dshot": False}, + }, } + +def get_mot_pwm_type_sub_dict(vehicle_type: str) -> dict[str, dict[str, Union[tuple[str, ...], str, bool]]]: + """Return the vehicle-type-specific entry sub-dict from MOT_PWM_TYPE_DICT.""" + return MOT_PWM_TYPE_DICT.get(vehicle_type, MOT_PWM_TYPE_DICT["ArduCopter"]) + + # RC_PROTOCOLS is a bitmask parameter, so keys are actual bitmask values (2^bit_position) # Special case: value 1 = All protocols enabled # Bit 1 (value 2) = PPM, Bit 2 (value 4) = IBUS, Bit 3 (value 8) = SBUS, etc. -RC_PROTOCOLS_DICT: dict[str, dict[str, Union[list[str], str]]] = { +RC_PROTOCOLS_DICT: dict[str, dict[str, Union[tuple[str, ...], str]]] = { "1": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "All"}, # Special case: 1 = All protocols "2": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "PPM"}, # Bit 1 "4": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "IBUS"}, # Bit 2 @@ -237,6 +277,23 @@ def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> "65536": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "MAVRadio"}, # Bit 16 } +# ESC->FC telemetry connections +ESC_TELEMETRY_DICT: dict[str, dict[str, Union[tuple[str, ...], str]]] = { + "0": {"type": ("None",), "protocol": "None"}, + # On DShot: FC->ESC is either Main Out or AIO; and ESC->FC Telemetry is serial + # On BDShot: FC->ESC is either Main Out or AIO; and ESC->FC Telemetry is also Main Out or AIO + # but there is an optional backup serial telemetry channel + "1": {"type": SERIAL_PORTS, "protocol": "ESC Telemetry"}, + # On BShot if the optional serial ESC->FC backup telemetry is unused, choose this + "2": {"type": PWM_OUT_PORTS, "protocol": "BDShot"}, + # The same CAN connection is used for both FC->ESC and ESC->FC telemetry + "3": {"type": CAN_PORTS, "protocol": "DroneCAN"}, + # The same serial connection is used for both FC->ESC and ESC->FC telemetry + "4": {"type": SERIAL_PORTS, "protocol": "FETtecOneWire"}, + # On T-Motor/Hobbywing Datalink v2: FC->ESC is either Main Out or AIO; and serial telemetry is received via scripting + "5": {"type": SERIAL_PORTS, "protocol": "Scripting"}, +} + class ComponentDataModelValidation(ComponentDataModelBase): """ @@ -289,10 +346,11 @@ def get_all_protocols(param_dict: dict) -> tuple[str, ...]: for value in param_dict.values() ) + fw_type = str(self.get_component_value(("Flight Controller", "Firmware", "Type")) or "") fallbacks: dict[str, tuple[str, ...]] = { "RC_PROTOCOLS": get_all_protocols(RC_PROTOCOLS_DICT), "BATT_MONITOR": get_all_protocols(BATT_MONITOR_CONNECTION), - "MOT_PWM_TYPE": get_all_protocols(MOT_PWM_TYPE_DICT), + "MOT_PWM_TYPE": get_all_protocols(get_mot_pwm_type_sub_dict(fw_type)), "GPS_TYPE": get_all_protocols(GNSS_RECEIVER_CONNECTION), "GPS1_TYPE": get_all_protocols(GNSS_RECEIVER_CONNECTION), # GPS_TYPE was renamed to GPS1_TYPE in 4.6 } @@ -315,7 +373,7 @@ def get_connection_types(conn_dict: dict) -> tuple[str, ...]: functools.reduce( operator.iadd, [ - type_val if isinstance(type_val, list) else [type_val] + type_val if isinstance(type_val, tuple) else [type_val] for type_val in [value["type"] for value in conn_dict.values()] ], [], @@ -338,90 +396,118 @@ def get_connection_types(conn_dict: dict) -> tuple[str, ...]: ), ("Battery Monitor", "FC Connection", "Type"): get_connection_types(BATT_MONITOR_CONNECTION), ("Battery Monitor", "FC Connection", "Protocol"): get_combobox_values("BATT_MONITOR"), - ("ESC", "FC Connection", "Type"): (*PWM_OUT_PORTS, *SERIAL_PORTS, *CAN_PORTS), - ("ESC", "FC Connection", "Protocol"): self._mot_pwm_types, + ("ESC", "FC->ESC Connection", "Type"): (*PWM_OUT_PORTS, *SERIAL_PORTS, *CAN_PORTS), + ("ESC", "FC->ESC Connection", "Protocol"): self._mot_pwm_types, + ("ESC", "ESC->FC Telemetry", "Type"): ("None", *PWM_OUT_PORTS, *SERIAL_PORTS, *CAN_PORTS), + ("ESC", "ESC->FC Telemetry", "Protocol"): tuple( + dict.fromkeys(str(v["protocol"]) for v in ESC_TELEMETRY_DICT.values()) + ), ("GNSS Receiver", "FC Connection", "Type"): ("None", *SERIAL_PORTS, *CAN_PORTS), ("GNSS Receiver", "FC Connection", "Protocol"): get_all_protocols(GNSS_RECEIVER_CONNECTION), ("Battery", "Specifications", "Chemistry"): BatteryCell.chemistries(), } for component in ["RC Receiver", "Telemetry", "Battery Monitor", "ESC", "GNSS Receiver"]: - if component in self._data["Components"]: + if component not in self._data.get("Components", {}): + continue + + if component == "ESC": self._update_possible_choices_for_path( - (component, "FC Connection", "Type"), self.get_component_value((component, "FC Connection", "Type")) + ("ESC", "FC->ESC Connection", "Type"), + self.get_component_value(("ESC", "FC->ESC Connection", "Type")), + ) + self._update_possible_choices_for_path( + ("ESC", "ESC->FC Telemetry", "Type"), + self.get_component_value(("ESC", "ESC->FC Telemetry", "Type")), + ) + else: + self._update_possible_choices_for_path( + (component, "FC Connection", "Type"), + self.get_component_value((component, "FC Connection", "Type")), ) def _update_possible_choices_for_path( # pylint: disable=too-many-branches self, path: ComponentPath, value: Union[ComponentData, ComponentValue, None] ) -> None: """Update _possible_choices when connection type values that affect protocol choices are changed.""" - # Only update if this is a connection type change that affects protocol choices - if len(path) >= 3 and path[1] == "FC Connection" and path[2] == "Type" and isinstance(value, str): - component_name = path[0] - protocol_path: ComponentPath = (component_name, "FC Connection", "Protocol") - - # Calculate the new possible choices for the corresponding protocol field - if component_name == "RC Receiver": - # Filter RC protocols based on the selected connection type - if value == "None": - new_choices: tuple[str, ...] = ("None",) - else: - # For any connection type, find protocols that support it - new_choices = tuple(str(v["protocol"]) for v in RC_PROTOCOLS_DICT.values() if value in v["type"]) - self._possible_choices[protocol_path] = new_choices - - elif component_name == "Telemetry": - if value == "None": - self._possible_choices[protocol_path] = ("None",) - else: - # For non-None telemetry connections, use the standard telemetry protocols - self._possible_choices[protocol_path] = tuple( - str(v["protocol"]) for v in SERIAL_PROTOCOLS_DICT.values() if v["component"] == "Telemetry" - ) + if len(path) < 3 or path[2] != "Type" or not isinstance(value, str): + return + + component_name = path[0] + section = path[1] + + if section not in ("FC Connection", "FC->ESC Connection", "ESC->FC Telemetry"): + return + + protocol_path: ComponentPath = (component_name, section, "Protocol") + + # Calculate the new possible choices for the corresponding protocol field + if component_name == "RC Receiver": + # Filter RC protocols based on the selected connection type + if value == "None": + new_choices: tuple[str, ...] = ("None",) + else: + # For any connection type, find protocols that support it + new_choices = tuple(str(v["protocol"]) for v in RC_PROTOCOLS_DICT.values() if value in v["type"]) + self._possible_choices[protocol_path] = new_choices + + elif component_name == "Telemetry": + if value == "None": + self._possible_choices[protocol_path] = ("None",) + else: + # For non-None telemetry connections, use the standard telemetry protocols + self._possible_choices[protocol_path] = tuple( + str(v["protocol"]) for v in SERIAL_PROTOCOLS_DICT.values() if v["component"] == "Telemetry" + ) - elif component_name == "Battery Monitor": - if value == "None": - self._possible_choices[protocol_path] = ("None",) - return + elif component_name == "Battery Monitor": + if value == "None": + self._possible_choices[protocol_path] = ("None",) + return - # Find protocols available for the selected connection type - batt_available_protocols: list[str] = [] - for conn_dict in BATT_MONITOR_CONNECTION.values(): - conn_type = conn_dict["type"] - if isinstance(conn_type, list) and value in conn_type: - batt_available_protocols.append(str(conn_dict["protocol"])) + # Find protocols available for the selected connection type + batt_available_protocols: list[str] = [] + for conn_dict in BATT_MONITOR_CONNECTION.values(): + conn_type = conn_dict["type"] + if isinstance(conn_type, tuple) and value in conn_type: + batt_available_protocols.append(str(conn_dict["protocol"])) - self._possible_choices[protocol_path] = ( - tuple(batt_available_protocols) if batt_available_protocols else ("None",) - ) + self._possible_choices[protocol_path] = tuple(batt_available_protocols) if batt_available_protocols else ("None",) - elif component_name == "ESC": + elif component_name == "ESC": + if section == "ESC->FC Telemetry": if value == "None": self._possible_choices[protocol_path] = ("None",) - elif value in CAN_PORTS: - self._possible_choices[protocol_path] = ("DroneCAN",) - elif value in SERIAL_PORTS: - self._possible_choices[protocol_path] = tuple( - str(v["protocol"]) for v in SERIAL_PROTOCOLS_DICT.values() if v["component"] == "ESC" - ) else: - # For PWM outputs, use motor PWM types - self._possible_choices[protocol_path] = self._mot_pwm_types + self._possible_choices[protocol_path] = tuple( + str(v["protocol"]) + for v in ESC_TELEMETRY_DICT.values() + if isinstance(v["type"], tuple) and value in v["type"] + ) or ("None",) + elif value == "None": + self._possible_choices[protocol_path] = ("None",) + elif value in CAN_PORTS: + self._possible_choices[protocol_path] = ("DroneCAN",) + elif value in SERIAL_PORTS: + self._possible_choices[protocol_path] = tuple( + str(v["protocol"]) for v in SERIAL_PROTOCOLS_DICT.values() if v["component"] == "ESC" + ) + else: + # For PWM outputs, use motor PWM types + self._possible_choices[protocol_path] = self._mot_pwm_types - elif component_name == "GNSS Receiver": - if value == "None": - self._possible_choices[protocol_path] = ("None",) - return + elif component_name == "GNSS Receiver": + if value == "None": + self._possible_choices[protocol_path] = ("None",) + return - # Find protocols available for the selected connection type - gnss_available_protocols: list[str] = [] - for conn_dict in GNSS_RECEIVER_CONNECTION.values(): - conn_type = conn_dict["type"] - if isinstance(conn_type, list) and value in conn_type: - gnss_available_protocols.append(str(conn_dict["protocol"])) + # Find protocols available for the selected connection type + gnss_available_protocols: list[str] = [] + for conn_dict in GNSS_RECEIVER_CONNECTION.values(): + conn_type = conn_dict["type"] + if isinstance(conn_type, tuple) and value in conn_type: + gnss_available_protocols.append(str(conn_dict["protocol"])) - self._possible_choices[protocol_path] = ( - tuple(gnss_available_protocols) if gnss_available_protocols else ("None",) - ) + self._possible_choices[protocol_path] = tuple(gnss_available_protocols) if gnss_available_protocols else ("None",) def _validate_tow_limits(self, value: str, path: ComponentPath) -> tuple[str, Optional[float]]: """Validate takeoff weight min/max cross-constraints.""" @@ -563,6 +649,26 @@ def validate_against_another_value( # pylint: disable=too-many-arguments,too-ma ), corrected return "", None # value is within valid interval, return empty string as there is no error + def _validate_limits_and_voltages(self, path: ComponentPath, value: str, paths_str: str, errors: list[str]) -> None: + """Validate entry limits and battery voltages.""" + if path in self.VALIDATION_RULES: + error_msg, corrected_value = self.validate_entry_limits(value, path) + if error_msg: + errors.append(error_msg.format(value=value, paths_str=paths_str)) + if corrected_value is not None: + self.set_component_value(path, corrected_value) + return + + if path in BATTERY_CELL_VOLTAGE_PATHS: + error_msg, corrected_value = self.validate_cell_voltage(value, path) + if error_msg: + errors.append(error_msg.format(value=value, paths_str=paths_str)) + if corrected_value is not None: + self.set_component_value(path, corrected_value) + return + + self._validate_motor_poles(errors, path, value, paths_str) + def validate_all_data(self, entry_values: dict[ComponentPath, str]) -> tuple[bool, list[str]]: """ Centralize all data validation logic. @@ -586,40 +692,34 @@ def validate_all_data(self, entry_values: dict[ComponentPath, str]) -> tuple[boo # Keep protocol choices in sync with connection type changes in this batch. # This ensures dependent fields like Battery Monitor protocol are validated correctly # when both Type and Protocol are present in entry_values. - if len(path) >= 3 and path[1] == "FC Connection" and path[2] == "Type" and isinstance(value, str): + if len(path) >= 3 and path[2] == "Type" and isinstance(value, str): self._update_possible_choices_for_path(path, value) # Check for duplicate connections - if len(path) >= 3 and path[1] == "FC Connection" and path[2] == "Type": + esc_conn_sections = {"FC->ESC Connection", "ESC->FC Telemetry"} + is_fc_conn_type = ( + len(path) >= 3 and path[2] == "Type" and (path[1] == "FC Connection" or path[1] in esc_conn_sections) + ) + if is_fc_conn_type: + # Type assertion: path has at least 3 elements as checked above + if len(path) < 3: + continue # Help type checker understand that path[2] is safe to access if value in fc_serial_connection and value not in {"CAN1", "CAN2", "I2C1", "I2C2", "I2C3", "I2C4", "None"}: # Allow certain combinations if path[0] in {"Telemetry", "RC Receiver"} and fc_serial_connection[value] in {"Telemetry", "RC Receiver"}: continue + # Allow ESC->FC Telemetry to share the same port as FC->ESC Connection (bidirectional serial) + if path[0] == "ESC" and path[1] in esc_conn_sections and fc_serial_connection[value] == "ESC": + continue + error_msg = _("Duplicate FC connection type '{value}' for {paths_str}") errors.append(error_msg.format(value=value, paths_str=paths_str)) continue fc_serial_connection[value] = path[0] - if path in self.VALIDATION_RULES: - # Validate entry limits - error_msg, corrected_value = self.validate_entry_limits(value, path) - if error_msg: - errors.append(error_msg.format(value=value, paths_str=paths_str)) - if corrected_value is not None: - self.set_component_value(path, corrected_value) - continue - - if path in BATTERY_CELL_VOLTAGE_PATHS: - # Validate battery cell voltages - error_msg, corrected_value = self.validate_cell_voltage(value, path) - if error_msg: - errors.append(error_msg.format(value=value, paths_str=paths_str)) - if corrected_value is not None: - self.set_component_value(path, corrected_value) - continue - - self._validate_motor_poles(errors, path, value, paths_str) + # Validate limits and voltages + self._validate_limits_and_voltages(path, value, paths_str, errors) return len(errors) == 0, errors diff --git a/ardupilot_methodic_configurator/vehicle_components_schema.json b/ardupilot_methodic_configurator/vehicle_components_schema.json index 87f462ea6..30530b023 100644 --- a/ardupilot_methodic_configurator/vehicle_components_schema.json +++ b/ardupilot_methodic_configurator/vehicle_components_schema.json @@ -52,7 +52,7 @@ "description": "Main power source for the vehicle" }, "ESC": { - "$ref": "#/definitions/connectionComponent", + "$ref": "#/definitions/escComponent", "description": "Electronic Speed Controller for the motors" }, "Motors": { @@ -242,6 +242,29 @@ } ] }, + "escComponent": { + "allOf": [ + { "$ref": "#/definitions/baseComponent" }, + { + "properties": { + "Firmware": { + "$ref": "#/definitions/firmware", + "description": "ESC firmware information", + "x-is-optional": true + }, + "FC->ESC Connection": { + "$ref": "#/definitions/fcConnection", + "description": "Data path from flight controller to ESC" + }, + "ESC->FC Telemetry": { + "$ref": "#/definitions/fcConnection", + "description": "Telemetry path from ESC to flight controller (if applicable)" + } + }, + "description": "Electronic Speed Controller component with (optional) telemetry" + } + ] + }, "battery": { "allOf": [ { "$ref": "#/definitions/baseComponent" }, diff --git a/ardupilot_methodic_configurator/vehicle_templates/ArduPlane/normal_plane/configuration_steps_ArduPlane.json b/ardupilot_methodic_configurator/vehicle_templates/ArduPlane/normal_plane/configuration_steps_ArduPlane.json index f2579a33b..bf9ec9ff0 100644 --- a/ardupilot_methodic_configurator/vehicle_templates/ArduPlane/normal_plane/configuration_steps_ArduPlane.json +++ b/ardupilot_methodic_configurator/vehicle_templates/ArduPlane/normal_plane/configuration_steps_ArduPlane.json @@ -103,11 +103,11 @@ "MOT_HOVER_LEARN": { "New Value": 2, "Change Reason": "So that it can tune the throttle controller on 20_throttle_controller.param file" } }, "derived_parameters": { - "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, + "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC->ESC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, "SERVO_FTW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } }, - "rename_connection": "vehicle_components['ESC']['FC Connection']['Type']", + "rename_connection": "vehicle_components['ESC']['FC->ESC Connection']['Type']", "old_filenames": [] }, "08_batt1.param": { diff --git a/ardupilot_methodic_configurator/vehicle_templates/Heli/OMP_M4/configuration_steps_Heli.json b/ardupilot_methodic_configurator/vehicle_templates/Heli/OMP_M4/configuration_steps_Heli.json index 6a018fb43..dc5f00355 100644 --- a/ardupilot_methodic_configurator/vehicle_templates/Heli/OMP_M4/configuration_steps_Heli.json +++ b/ardupilot_methodic_configurator/vehicle_templates/Heli/OMP_M4/configuration_steps_Heli.json @@ -103,11 +103,11 @@ "MOT_HOVER_LEARN": { "New Value": 2, "Change Reason": "So that it can tune the throttle controller on 20_throttle_controller.param file" } }, "derived_parameters": { - "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, + "MOT_PWM_TYPE": { "New Value": "vehicle_components['ESC']['FC->ESC Connection']['Protocol']", "Change Reason": "Specified in component editor window" }, "SERVO_BLH_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" }, "SERVO_FTW_POLES": { "New Value": "vehicle_components['Motors']['Specifications']['Poles']", "Change Reason": "Specified in component editor window" } }, - "rename_connection": "vehicle_components['ESC']['FC Connection']['Type']", + "rename_connection": "vehicle_components['ESC']['FC->ESC Connection']['Type']", "old_filenames": [] }, "08_batt1.param": { diff --git a/images/blog/component_editor_battery.png b/images/blog/component_editor_battery.png new file mode 100644 index 000000000..38dfacb4b Binary files /dev/null and b/images/blog/component_editor_battery.png differ diff --git a/images/blog/component_editor_battery_monitor_analog.png b/images/blog/component_editor_battery_monitor_analog.png new file mode 100644 index 000000000..571259d4b Binary files /dev/null and b/images/blog/component_editor_battery_monitor_analog.png differ diff --git a/images/blog/component_editor_battery_monitor_can.png b/images/blog/component_editor_battery_monitor_can.png new file mode 100644 index 000000000..13712ff60 Binary files /dev/null and b/images/blog/component_editor_battery_monitor_can.png differ diff --git a/images/blog/component_editor_battery_monitor_i2c.png b/images/blog/component_editor_battery_monitor_i2c.png new file mode 100644 index 000000000..7155dd78a Binary files /dev/null and b/images/blog/component_editor_battery_monitor_i2c.png differ diff --git a/images/blog/component_editor_battery_monitor_none.png b/images/blog/component_editor_battery_monitor_none.png new file mode 100644 index 000000000..42a3eba46 Binary files /dev/null and b/images/blog/component_editor_battery_monitor_none.png differ diff --git a/images/blog/component_editor_battery_monitor_other.png b/images/blog/component_editor_battery_monitor_other.png new file mode 100644 index 000000000..59a40f1ee Binary files /dev/null and b/images/blog/component_editor_battery_monitor_other.png differ diff --git a/images/blog/component_editor_battery_monitor_pwm.png b/images/blog/component_editor_battery_monitor_pwm.png new file mode 100644 index 000000000..37b58d02d Binary files /dev/null and b/images/blog/component_editor_battery_monitor_pwm.png differ diff --git a/images/blog/component_editor_battery_monitor_spi.png b/images/blog/component_editor_battery_monitor_spi.png new file mode 100644 index 000000000..05d6ae5d1 Binary files /dev/null and b/images/blog/component_editor_battery_monitor_spi.png differ diff --git a/images/blog/component_editor_esc_main_out.png b/images/blog/component_editor_esc_main_out.png new file mode 100644 index 000000000..050732e2d Binary files /dev/null and b/images/blog/component_editor_esc_main_out.png differ diff --git a/images/blog/component_editor_esc_telem_main_out_aio.png b/images/blog/component_editor_esc_telem_main_out_aio.png new file mode 100644 index 000000000..17cd57785 Binary files /dev/null and b/images/blog/component_editor_esc_telem_main_out_aio.png differ diff --git a/images/blog/component_editor_esc_telem_serial.png b/images/blog/component_editor_esc_telem_serial.png new file mode 100644 index 000000000..1a43ec09e Binary files /dev/null and b/images/blog/component_editor_esc_telem_serial.png differ diff --git a/images/blog/component_editor_firmware.png b/images/blog/component_editor_firmware.png new file mode 100644 index 000000000..43470ecac Binary files /dev/null and b/images/blog/component_editor_firmware.png differ diff --git a/images/blog/component_editor_flight_controller.png b/images/blog/component_editor_flight_controller.png new file mode 100644 index 000000000..535aa8806 Binary files /dev/null and b/images/blog/component_editor_flight_controller.png differ diff --git a/images/blog/component_editor_frame.png b/images/blog/component_editor_frame.png new file mode 100644 index 000000000..6c05a80fe Binary files /dev/null and b/images/blog/component_editor_frame.png differ diff --git a/images/blog/component_editor_gnss.png b/images/blog/component_editor_gnss.png new file mode 100644 index 000000000..49240be62 Binary files /dev/null and b/images/blog/component_editor_gnss.png differ diff --git a/images/blog/component_editor_motors.png b/images/blog/component_editor_motors.png new file mode 100644 index 000000000..fe63cc34d Binary files /dev/null and b/images/blog/component_editor_motors.png differ diff --git a/images/blog/component_editor_product.png b/images/blog/component_editor_product.png new file mode 100644 index 000000000..e41e9115a Binary files /dev/null and b/images/blog/component_editor_product.png differ diff --git a/images/blog/component_editor_propellers.png b/images/blog/component_editor_propellers.png new file mode 100644 index 000000000..913da8a62 Binary files /dev/null and b/images/blog/component_editor_propellers.png differ diff --git a/tests/acceptance_template_import_from_params.py b/tests/acceptance_template_import_from_params.py index 685d7eb99..f4393cfcd 100755 --- a/tests/acceptance_template_import_from_params.py +++ b/tests/acceptance_template_import_from_params.py @@ -730,8 +730,8 @@ def get_inferable_fields() -> list[tuple[str, str, str]]: ("Battery", "Specifications", "Capacity mAh"), ("Battery Monitor", "FC Connection", "Type"), ("Battery Monitor", "FC Connection", "Protocol"), - ("ESC", "FC Connection", "Type"), - ("ESC", "FC Connection", "Protocol"), + ("ESC", "FC->ESC Connection", "Type"), + ("ESC", "FC->ESC Connection", "Protocol"), ("GNSS Receiver", "FC Connection", "Type"), ("GNSS Receiver", "FC Connection", "Protocol"), ("RC Receiver", "FC Connection", "Type"), diff --git a/tests/test_data_model_vehicle_components_base.py b/tests/test_data_model_vehicle_components_base.py index 82e5d5cc3..e029d40d3 100755 --- a/tests/test_data_model_vehicle_components_base.py +++ b/tests/test_data_model_vehicle_components_base.py @@ -606,6 +606,36 @@ def test_system_recreates_missing_battery_component(self, realistic_model) -> No assert "Battery" in realistic_model._data["Components"] assert "Specifications" in realistic_model._data["Components"]["Battery"] + def test_system_migrates_legacy_esc_fc_connection_path(self) -> None: + """ + System migrates legacy ESC FC Connection to FC->ESC Connection when loading old files. + + GIVEN: A model with old ESC path data + WHEN: update_json_structure is called + THEN: ESC data is moved to the new FC->ESC Connection path and old path removed + """ + initial_data = { + "Components": { + "ESC": { + "Product": {"Manufacturer": "Test"}, + "FC Connection": {"Type": "Main Out", "Protocol": "DShot600"}, + } + }, + "Format version": 1, + } + + vehicle_components = VehicleComponents() + schema = VehicleComponentsJsonSchema(vehicle_components.load_schema()) + component_datatypes = schema.get_all_value_datatypes() + model = ComponentDataModelBase(initial_data, component_datatypes, schema) + + model.update_json_structure() + + assert "FC Connection" not in model._data["Components"]["ESC"] + assert "FC->ESC Connection" in model._data["Components"]["ESC"] + assert model._data["Components"]["ESC"]["FC->ESC Connection"]["Type"] == "Main Out" + assert model._data["Components"]["ESC"]["FC->ESC Connection"]["Protocol"] == "DShot600" + def test_system_recreates_missing_flight_controller_specifications(self, realistic_model) -> None: """ System recreates missing Flight Controller Specifications sub-section. @@ -882,7 +912,7 @@ def test_system_handles_sequential_access_to_different_components(self, basic_mo (("Battery", "Specifications", "Capacity mAh"), 2000), (("Frame", "Specifications", "Weight Kg"), 1.5), (("Flight Controller", "Product", "Manufacturer"), "TestCorp"), - (("ESC", "FC Connection", "Protocol"), "DShot600"), + (("ESC", "FC->ESC Connection", "Protocol"), "DShot600"), (("Motors", "Specifications", "Poles"), 14), ] diff --git a/tests/test_data_model_vehicle_components_import.py b/tests/test_data_model_vehicle_components_import.py index b796e3c97..318daa114 100755 --- a/tests/test_data_model_vehicle_components_import.py +++ b/tests/test_data_model_vehicle_components_import.py @@ -214,26 +214,28 @@ def test_system_handles_multiple_rc_protocols_configuration(self, realistic_mode @patch("ardupilot_methodic_configurator.data_model_vehicle_components_import.SERIAL_PORTS", ["SERIAL1", "SERIAL2"]) @patch( "ardupilot_methodic_configurator.data_model_vehicle_components_import.SERIAL_PROTOCOLS_DICT", - {"30": {"component": "ESC", "protocol": "ESC Telem"}}, + {"30": {"component": "ESC", "protocol": "ESC Telemetry"}}, ) def test_system_detects_multiple_serial_esc_connections(self, realistic_model) -> None: """ - System detects when multiple serial ports have ESC telemetry. + System uses first serial ESC telemetry port and allows ESC type detection to proceed. GIVEN: Flight controller with ESC telemetry on multiple serial ports WHEN: Importing serial port configuration - THEN: First ESC connection should be used - AND: Should return True indicating multiple ESC ports detected + THEN: First ESC telemetry connection should be used + AND: Should return False because telemetry-only protocols leave FC->ESC undetermined """ fc_parameters = {"SERIAL1_PROTOCOL": 30, "SERIAL2_PROTOCOL": 30} result = realistic_model._set_serial_type_from_fc_parameters(fc_parameters) - esc_type = realistic_model.get_component_value(("ESC", "FC Connection", "Type")) - esc_protocol = realistic_model.get_component_value(("ESC", "FC Connection", "Protocol")) - assert esc_type == "SERIAL1" - assert esc_protocol == "ESC Telem" - assert result is True # Multiple ESCs + esc_telem_type = realistic_model.get_component_value(("ESC", "ESC->FC Telemetry", "Type")) + esc_telem_protocol = realistic_model.get_component_value(("ESC", "ESC->FC Telemetry", "Protocol")) + assert esc_telem_type == "SERIAL1" + assert esc_telem_protocol == "ESC Telemetry" + assert ( + result is False + ) # Telemetry-only protocol: FC->ESC is still DShot/PWM, _set_esc_type_from_fc_parameters must run @patch("ardupilot_methodic_configurator.data_model_vehicle_components_import.SERIAL_PORTS", ["SERIAL1"]) def test_system_handles_invalid_serial_protocol_value(self, realistic_model) -> None: @@ -253,8 +255,8 @@ def test_system_handles_invalid_serial_protocol_value(self, realistic_model) -> assert result is False @patch( - "ardupilot_methodic_configurator.data_model_vehicle_components_import.MOT_PWM_TYPE_DICT", - {"6": {"protocol": "DShot600"}}, + "ardupilot_methodic_configurator.data_model_vehicle_components_import.get_mot_pwm_type_sub_dict", + lambda *_: {"6": {"protocol": "DShot600"}}, ) def test_system_imports_esc_on_main_outputs(self, realistic_model) -> None: """ @@ -273,14 +275,14 @@ def test_system_imports_esc_on_main_outputs(self, realistic_model) -> None: realistic_model._set_esc_type_from_fc_parameters(fc_parameters, doc) - esc_type = realistic_model.get_component_value(("ESC", "FC Connection", "Type")) - esc_protocol = realistic_model.get_component_value(("ESC", "FC Connection", "Protocol")) + esc_type = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) + esc_protocol = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) assert esc_type == "Main Out" assert esc_protocol == "DShot600" @patch( - "ardupilot_methodic_configurator.data_model_vehicle_components_import.MOT_PWM_TYPE_DICT", - {"6": {"protocol": "DShot600"}}, + "ardupilot_methodic_configurator.data_model_vehicle_components_import.get_mot_pwm_type_sub_dict", + lambda *_: {"6": {"protocol": "DShot600"}}, ) def test_system_imports_esc_aio_configuration(self, realistic_model) -> None: """ @@ -294,16 +296,41 @@ def test_system_imports_esc_aio_configuration(self, realistic_model) -> None: fc_parameters = { "MOT_PWM_TYPE": 6, "SERVO1_FUNCTION": 0, # Not motor function + "SERVO9_FUNCTION": 33, # Motor function on AUX output indicates AIO } doc: dict[str, Any] = {} realistic_model._set_esc_type_from_fc_parameters(fc_parameters, doc) - esc_type = realistic_model.get_component_value(("ESC", "FC Connection", "Type")) - esc_protocol = realistic_model.get_component_value(("ESC", "FC Connection", "Protocol")) + esc_type = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) + esc_protocol = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) assert esc_type == "AIO" assert esc_protocol == "DShot600" + def test_user_can_import_esc_connection_and_telemetry_from_serial_fc(self, realistic_model) -> None: + """ + Import ESC serial config into FC->ESC Connection and ESC->FC Telemetry. + + GIVEN: Flight controller serial port protocol maps to ESC. + + WHEN: User imports serial port configuration. + + THEN: ESC FC->ESC Connection and ESC->FC Telemetry should be populated. + """ + fc_parameters = {"SERIAL1_PROTOCOL": 38} + + realistic_model._set_serial_type_from_fc_parameters(fc_parameters) + + esc_conn_type = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) + esc_conn_protocol = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) + esc_telemetry_type = realistic_model.get_component_value(("ESC", "ESC->FC Telemetry", "Type")) + esc_telemetry_protocol = realistic_model.get_component_value(("ESC", "ESC->FC Telemetry", "Protocol")) + + assert esc_conn_type == "SERIAL1" + assert esc_conn_protocol == "FETtecOneWire" + assert esc_telemetry_type == "SERIAL1" + assert esc_telemetry_protocol == "FETtecOneWire" + def test_user_can_import_battery_monitor_configuration(self, realistic_model) -> None: """ User can import battery monitor configuration. @@ -447,8 +474,8 @@ def test_system_skips_disabled_serial_ports(self, realistic_model) -> None: realistic_model._set_esc_type_from_fc_parameters(fc_parameters, doc) - esc_type = realistic_model.get_component_value(("ESC", "FC Connection", "Type")) - assert esc_type == "AIO" # Should default to AIO when no main out functions + esc_type = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) + assert esc_type == "Main Out" # Should default to Main Out when no AUX functions def test_system_falls_back_to_mot_pwm_dict_when_doc_empty(self, realistic_model) -> None: """ @@ -460,15 +487,15 @@ def test_system_falls_back_to_mot_pwm_dict_when_doc_empty(self, realistic_model) AND: ESC protocol should be correctly identified """ with patch( - "ardupilot_methodic_configurator.data_model_vehicle_components_import.MOT_PWM_TYPE_DICT", - {"6": {"protocol": "DShot600"}}, + "ardupilot_methodic_configurator.data_model_vehicle_components_import.get_mot_pwm_type_sub_dict", + return_value={"6": {"protocol": "DShot600"}}, ): fc_parameters = {"MOT_PWM_TYPE": 6} doc: dict[str, Any] = {} # Empty doc should trigger fallback realistic_model._set_esc_type_from_fc_parameters(fc_parameters, doc) - esc_protocol = realistic_model.get_component_value(("ESC", "FC Connection", "Protocol")) + esc_protocol = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) assert esc_protocol == "DShot600" def test_system_handles_esc_protocol_not_found(self, realistic_model) -> None: @@ -885,8 +912,8 @@ def test_system_handles_dshot_without_poles_parameter(self, realistic_model) -> THEN: System should handle gracefully without setting poles """ with patch( - "ardupilot_methodic_configurator.data_model_vehicle_components_import.MOT_PWM_TYPE_DICT", - {"6": {"protocol": "DShot600", "is_dshot": True}}, + "ardupilot_methodic_configurator.data_model_vehicle_components_import.get_mot_pwm_type_sub_dict", + lambda *_: {"6": {"protocol": "DShot600", "is_dshot": True}}, ): fc_parameters = { "MOT_PWM_TYPE": 6, @@ -972,8 +999,8 @@ def test_user_can_import_complete_vehicle_configuration(self, realistic_model, s assert realistic_model.get_component_value(("GNSS Receiver", "FC Connection", "Type")) == "SERIAL2" assert realistic_model.get_component_value(("RC Receiver", "FC Connection", "Type")) == "SERIAL3" assert realistic_model.get_component_value(("RC Receiver", "FC Connection", "Protocol")) == "CRSF" - assert realistic_model.get_component_value(("ESC", "FC Connection", "Type")) == "Main Out" - assert realistic_model.get_component_value(("ESC", "FC Connection", "Protocol")) == "DShot600" + assert realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) == "Main Out" + assert realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) == "DShot600" assert realistic_model.get_component_value(("Motors", "Specifications", "Poles")) == 14 assert ( realistic_model.get_component_value(("Battery Monitor", "FC Connection", "Protocol")) @@ -1005,8 +1032,8 @@ def test_system_prioritizes_serial_esc_over_pwm_esc(self, realistic_model, sampl realistic_model.process_fc_parameters(fc_parameters, doc) # Should use serial ESC, not PWM ESC - esc_type = realistic_model.get_component_value(("ESC", "FC Connection", "Type")) - esc_protocol = realistic_model.get_component_value(("ESC", "FC Connection", "Protocol")) + esc_type = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) + esc_protocol = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) assert esc_type == "SERIAL1" assert esc_protocol == "FETtecOneWire" @@ -1164,21 +1191,24 @@ def test_system_detects_main_out_vs_aio_from_servo_functions(self, realistic_mod AND: AIO should be detected when no motor functions on SERVO outputs """ test_cases = [ - # Test case: (servo functions, expected_esc_type) - ([0, 0, 0, 0, 0, 0, 0, 0], "AIO"), # No motors on main out - ([33, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor1 on SERVO1 - ([0, 34, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor2 on SERVO2 - ([0, 0, 35, 0, 0, 0, 0, 0], "Main Out"), # Motor3 on SERVO3 - ([0, 0, 0, 36, 0, 0, 0, 0], "Main Out"), # Motor4 on SERVO4 - ([0, 0, 0, 0, 33, 0, 0, 0], "Main Out"), # Motor1 on SERVO5 (still main out, not AUX) - ([1, 2, 3, 4, 5, 6, 7, 8], "AIO"), # Other functions, no motors - ([33, 34, 35, 36, 0, 0, 0, 0], "Main Out"), # All 4 motors on main out + # Test case: (servo functions 1-14, expected_esc_type) + ([0] * 14, "Main Out"), # No motors anywhere + ([33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor1 on SERVO1 + ([0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor2 on SERVO2 + ([0, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor3 on SERVO3 + ([0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor4 on SERVO4 + ([0, 0, 0, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # Motor1 on SERVO5 + ([1, 2, 3, 4, 5, 6, 7, 8, 0, 0, 0, 0, 0, 0], "Main Out"), # Other functions on main, no motors + ([33, 34, 35, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], "Main Out"), # All 4 motors on main out + ([0, 0, 0, 0, 0, 0, 0, 0, 33, 0, 0, 0, 0, 0], "AIO"), # Motor1 on SERVO9 (AUX) + ([0, 0, 0, 0, 0, 0, 0, 0, 0, 34, 0, 0, 0, 0], "AIO"), # Motor2 on SERVO10 (AUX) + ([0, 0, 0, 0, 0, 0, 0, 0, 33, 34, 35, 36, 0, 0], "AIO"), # Motors on SERVO9-12 (AUX) ] for servo_functions, expected_esc_type in test_cases: fc_parameters = {"MOT_PWM_TYPE": 6} # DShot600 - # Set all servo functions + # Set all servo functions (SERVO1 to SERVO14) for i, function in enumerate(servo_functions, 1): fc_parameters[f"SERVO{i}_FUNCTION"] = function @@ -1186,7 +1216,7 @@ def test_system_detects_main_out_vs_aio_from_servo_functions(self, realistic_mod realistic_model._set_esc_type_from_fc_parameters(fc_parameters, doc) - esc_type = realistic_model.get_component_value(("ESC", "FC Connection", "Type")) + esc_type = realistic_model.get_component_value(("ESC", "FC->ESC Connection", "Type")) assert esc_type == expected_esc_type, f"Failed for servo functions {servo_functions}" def test_gps1_type_parameter_support(self, realistic_model) -> None: @@ -1659,15 +1689,19 @@ def test_import_bat_values_skips_all_voltages_when_cell_count_is_zero(self, basi "MOT_BAT_VOLT_MIN": 12.8, }, ) - original_max = basic_model.get_component_value(("Battery", "Specifications", "Volt per cell max")) + basic_model.get_component_value(("Battery", "Specifications", "Volt per cell max")) # Act basic_model._import_bat_values_from_fc(specs) - # Assert: capacity IS set (not guarded by cell count), voltages are NOT set + # Assert: capacity IS set, voltages are set to 0.0 (invalid marker) when cell_count is 0 capacity = basic_model.get_component_value(("Battery", "Specifications", "Capacity mAh")) assert capacity == 4500 - assert basic_model.get_component_value(("Battery", "Specifications", "Volt per cell max")) == original_max + assert basic_model.get_component_value(("Battery", "Specifications", "Volt per cell max")) == 0.0 + assert basic_model.get_component_value(("Battery", "Specifications", "Volt per cell arm")) == 0.0 + assert basic_model.get_component_value(("Battery", "Specifications", "Volt per cell low")) == 0.0 + assert basic_model.get_component_value(("Battery", "Specifications", "Volt per cell crit")) == 0.0 + assert basic_model.get_component_value(("Battery", "Specifications", "Volt per cell min")) == 0.0 def test_estimate_cell_count_uses_batt_arm_volt_as_fallback(self, basic_model) -> None: """ @@ -1743,19 +1777,19 @@ def test_detect_chemistry_from_mot_bat_volt_min(self, realistic_model) -> None: def test_estimate_cell_count_returns_zero_for_all_invalid_volt_per_cell(self, basic_model) -> None: """ - System returns 0 when all volt-per-cell values are zero/invalid. + System returns 0 when all voltage parameter values are zero or negative. - GIVEN: FC parameters with voltage params but all volt-per-cell stored values are zero + GIVEN: FC parameters where all voltage values are zero WHEN: Calling _estimate_battery_cell_count THEN: Returns 0 and an error is logged """ - # Arrange: all voltage specs are zero (invalid) - basic_model has default 0s + # Arrange: all voltage parameter values are 0, triggering the 'voltage <= 0' guard fc_parameters = { - "MOT_BAT_VOLT_MAX": 16.8, - "BATT_LOW_VOLT": 14.4, - "BATT_CRT_VOLT": 13.2, - "BATT_ARM_VOLT": 15.2, - "MOT_BAT_VOLT_MIN": 12.8, + "MOT_BAT_VOLT_MAX": 0.0, + "BATT_LOW_VOLT": 0.0, + "BATT_CRT_VOLT": 0.0, + "BATT_ARM_VOLT": 0.0, + "MOT_BAT_VOLT_MIN": 0.0, } # Act @@ -2058,7 +2092,7 @@ def test_system_uses_mot_pwm_type_dict_fallback_when_doc_has_no_mot_pwm_type(sel basic_model._set_esc_type_from_fc_parameters(fc_parameters, doc) - result = basic_model.get_component_value(("ESC", "FC Connection", "Protocol")) + result = basic_model.get_component_value(("ESC", "FC->ESC Connection", "Protocol")) assert result == "Normal" # ------------------------------------------------------------------ diff --git a/tests/test_data_model_vehicle_components_validation.py b/tests/test_data_model_vehicle_components_validation.py index 4a68b6a67..6557ed804 100755 --- a/tests/test_data_model_vehicle_components_validation.py +++ b/tests/test_data_model_vehicle_components_validation.py @@ -704,8 +704,8 @@ def test_validate_all_data_valid_entries(self, realistic_model) -> None: ("RC Receiver", "FC Connection", "Protocol"): "CRSF", ("GNSS Receiver", "FC Connection", "Type"): "SERIAL3", ("GNSS Receiver", "FC Connection", "Protocol"): "uBlox", - ("ESC", "FC Connection", "Type"): "Main Out", - ("ESC", "FC Connection", "Protocol"): "DShot600", + ("ESC", "FC->ESC Connection", "Type"): "Main Out", + ("ESC", "FC->ESC Connection", "Protocol"): "DShot600", } is_valid, errors = model.validate_all_data(valid_entries) @@ -818,7 +818,7 @@ def test_validate_all_data_battery_esc_combinations(self, realistic_model) -> No allowed_entries = { ("Battery Monitor", "FC Connection", "Type"): "other", ("Battery Monitor", "FC Connection", "Protocol"): "ESC", - ("ESC", "FC Connection", "Type"): "Main Out", + ("ESC", "FC->ESC Connection", "Type"): "Main Out", } is_valid, errors = model.validate_all_data(allowed_entries) @@ -1311,8 +1311,8 @@ def test_pwm_output_protocol_choices(self, realistic_model) -> None: model.init_possible_choices({"MOT_PWM_TYPE": {"values": {"0": "Normal", "6": "DShot600"}}}) # Test ESC connection to PWM outputs (not serial or CAN) - model._update_possible_choices_for_path(("ESC", "FC Connection", "Type"), "Main Out") - protocol_choices = model._possible_choices.get(("ESC", "FC Connection", "Protocol"), ()) + model._update_possible_choices_for_path(("ESC", "FC->ESC Connection", "Type"), "Main Out") + protocol_choices = model._possible_choices.get(("ESC", "FC->ESC Connection", "Protocol"), ()) # Should use motor PWM types for PWM outputs assert len(protocol_choices) > 0 @@ -1338,8 +1338,8 @@ def test_comprehensive_connection_type_coverage(self, realistic_model) -> None: ("RC Receiver", "FC Connection", "Type", "I2C1", False), # May not have protocols (not common for RC) ("Telemetry", "FC Connection", "Type", "None", True), # Should have protocols ("Telemetry", "FC Connection", "Type", "SERIAL1", True), # Should have protocols - ("ESC", "FC Connection", "Type", "None", True), # Should have protocols - ("ESC", "FC Connection", "Type", "CAN1", True), # Should have protocols + ("ESC", "FC->ESC Connection", "Type", "None", True), # Should have protocols + ("ESC", "FC->ESC Connection", "Type", "CAN1", True), # Should have protocols ("GNSS Receiver", "FC Connection", "Type", "None", True), # Should have protocols ("GNSS Receiver", "FC Connection", "Type", "SERIAL3", True), # Should have protocols ("Battery Monitor", "FC Connection", "Type", "None", True), # Should have protocols @@ -1348,7 +1348,10 @@ def test_comprehensive_connection_type_coverage(self, realistic_model) -> None: for component, section, field, value, should_have_protocols in test_cases: model._update_possible_choices_for_path((component, section, field), value) - protocol_path = (component, "FC Connection", "Protocol") + if component == "ESC": + protocol_path = (component, "FC->ESC Connection", "Protocol") + else: + protocol_path = (component, "FC Connection", "Protocol") protocol_choices = model._possible_choices.get(protocol_path, ()) if should_have_protocols: diff --git a/tests/test_data_model_vehicle_components_validation_bdd.py b/tests/test_data_model_vehicle_components_validation_bdd.py index 322941f47..0c81fe3f3 100755 --- a/tests/test_data_model_vehicle_components_validation_bdd.py +++ b/tests/test_data_model_vehicle_components_validation_bdd.py @@ -133,7 +133,7 @@ def test_user_sees_validation_errors_for_invalid_combobox_selections(self, valid invalid_entries = { ("Battery", "Specifications", "Chemistry"): "UnknownChemistry", # Chemistry has combobox choices ("RC Receiver", "FC Connection", "Protocol"): "InvalidProtocol", # RC Protocol has choices - ("ESC", "FC Connection", "Protocol"): "NonExistentProtocol", # ESC Protocol has choices + ("ESC", "FC->ESC Connection", "Protocol"): "NonExistentProtocol", # ESC Protocol has choices } # Act: Validate all data @@ -161,7 +161,7 @@ def test_user_sees_validation_errors_for_duplicate_fc_connections(self, validati # Arrange: Create entries with duplicate FC connections that are NOT allowed duplicate_entries = { ("GNSS Receiver", "FC Connection", "Type"): "SERIAL2", - ("ESC", "FC Connection", "Type"): "SERIAL2", # Not allowed duplicate + ("ESC", "FC->ESC Connection", "Type"): "SERIAL2", # Not allowed duplicate ("RC Receiver", "FC Connection", "Type"): "SERIAL3", ( "Battery Monitor", @@ -358,7 +358,7 @@ def test_validation_performance_with_large_dataset(self, validation_model) -> No large_entries[("Battery", "Specifications", "Chemistry")] = "InvalidChem" # Invalid combobox large_entries[("Battery", "Specifications", "Volt per cell max")] = "5.0" # Invalid battery voltage for Lipo large_entries[("RC Receiver", "FC Connection", "Type")] = "SERIAL1" - large_entries[("ESC", "FC Connection", "Type")] = "SERIAL1" # Not allowed duplicate + large_entries[("ESC", "FC->ESC Connection", "Type")] = "SERIAL1" # Not allowed duplicate # Act: Validate all data is_valid, errors = validation_model.validate_all_data(large_entries) diff --git a/tests/unit_data_model_vehicle_components_import.py b/tests/unit_data_model_vehicle_components_import.py index 06721ed69..0d2fe8e67 100755 --- a/tests/unit_data_model_vehicle_components_import.py +++ b/tests/unit_data_model_vehicle_components_import.py @@ -365,17 +365,17 @@ def test_set_battery_type_handles_type_error(self, realistic_model) -> None: realistic_model._set_battery_type_from_fc_parameters(fc_parameters) # pylint: enable=duplicate-code - def test_set_battery_type_handles_list_type_values(self, realistic_model) -> None: + def test_set_battery_type_handles_tuple_type_values(self, realistic_model) -> None: """ - Internal battery type setter handles list-type configuration values. + Internal battery type setter handles tuple-type configuration values. - GIVEN: Battery configuration with list values for type and protocol + GIVEN: Battery configuration with tuple values for type and protocol WHEN: Setting battery type from parameters - THEN: First element of each list should be used + THEN: First element of each tuple should be used """ with patch( "ardupilot_methodic_configurator.data_model_vehicle_components_import.BATT_MONITOR_CONNECTION", - {"4": {"type": ["Analog", "Digital"], "protocol": ["Voltage", "Current"]}}, + {"4": {"type": ("Analog", "Digital"), "protocol": ("Voltage", "Current")}}, ): fc_parameters = {"BATT_MONITOR": 4} realistic_model._set_battery_type_from_fc_parameters(fc_parameters) diff --git a/tests/unit_data_model_vehicle_components_validation.py b/tests/unit_data_model_vehicle_components_validation.py index afe7519fe..a6d2a7326 100755 --- a/tests/unit_data_model_vehicle_components_validation.py +++ b/tests/unit_data_model_vehicle_components_validation.py @@ -100,8 +100,8 @@ def test_update_possible_choices_for_esc_can(self, realistic_model) -> None: model = realistic_model model.init_possible_choices({"MOT_PWM_TYPE": {"values": {"0": "Normal", "6": "DShot600"}}}) - model._update_possible_choices_for_path(("ESC", "FC Connection", "Type"), "CAN1") - protocol_choices = model._possible_choices.get(("ESC", "FC Connection", "Protocol"), ()) + model._update_possible_choices_for_path(("ESC", "FC->ESC Connection", "Type"), "CAN1") + protocol_choices = model._possible_choices.get(("ESC", "FC->ESC Connection", "Protocol"), ()) assert protocol_choices == ("DroneCAN",) @@ -110,8 +110,8 @@ def test_update_possible_choices_for_esc_pwm(self, realistic_model) -> None: model = realistic_model model.init_possible_choices({"MOT_PWM_TYPE": {"values": {"0": "Normal", "6": "DShot600"}}}) - model._update_possible_choices_for_path(("ESC", "FC Connection", "Type"), "Main Out") - protocol_choices = model._possible_choices.get(("ESC", "FC Connection", "Protocol"), ()) + model._update_possible_choices_for_path(("ESC", "FC->ESC Connection", "Type"), "Main Out") + protocol_choices = model._possible_choices.get(("ESC", "FC->ESC Connection", "Protocol"), ()) assert len(protocol_choices) > 0 # pylint: enable=duplicate-code @@ -244,7 +244,7 @@ def test_correct_display_values_preserves_key_values(self, validation_model) -> initial_data = { "Components": { "RC Receiver": {"FC Connection": {"Type": "SERIAL2"}}, - "ESC": {"FC Connection": {"Type": "CAN1"}}, + "ESC": {"FC->ESC Connection": {"Type": "CAN1"}}, }, "Format version": 1, } @@ -258,7 +258,7 @@ def test_correct_display_values_preserves_key_values(self, validation_model) -> # Assert assert model.get_component_value(("RC Receiver", "FC Connection", "Type")) == "SERIAL2" - assert model.get_component_value(("ESC", "FC Connection", "Type")) == "CAN1" + assert model.get_component_value(("ESC", "FC->ESC Connection", "Type")) == "CAN1" def test_correct_display_values_handles_nested_data(self, validation_model) -> None: """Test that correct_display_values_in_loaded_data() handles nested data structures.""" diff --git a/tests/unit_data_model_vehicle_components_validation_constants.py b/tests/unit_data_model_vehicle_components_validation_constants.py index 0193b6bdd..cff893a7e 100755 --- a/tests/unit_data_model_vehicle_components_validation_constants.py +++ b/tests/unit_data_model_vehicle_components_validation_constants.py @@ -52,7 +52,11 @@ def test_fc_connection_type_paths_structure(self) -> None: # All paths should follow the pattern (Component, "FC Connection", "Type") for path in FC_CONNECTION_TYPE_PATHS: - assert path[1] == "FC Connection" + assert path[1] in [ + "FC Connection", + "FC->ESC Connection", + "ESC->FC Telemetry", + ] assert path[2] == "Type" def test_battery_cell_voltage_paths_structure(self) -> None: @@ -111,7 +115,7 @@ def test_serial_protocols_dict_structure(self) -> None: assert set(value.keys()) == required_fields, f"Value for key '{key}' missing required fields" # Check field types - assert isinstance(value["type"], list), f"'type' field for key '{key}' is not a list" + assert isinstance(value["type"], tuple), f"'type' field for key '{key}' is not a tuple" assert isinstance(value["protocol"], str), f"'protocol' field for key '{key}' is not a string" assert value["component"] is None or isinstance(value["component"], str), ( @@ -127,7 +131,7 @@ def test_serial_protocols_dict_structure(self) -> None: assert isinstance(port_type, str), f"Port type in key '{key}' is not a string" # Type should reference known port lists - assert type_list in (SERIAL_PORTS, ["None"]), f"'type' field for key '{key}' does not reference SERIAL_PORTS" + assert type_list in (SERIAL_PORTS, ("None",)), f"'type' field for key '{key}' does not reference SERIAL_PORTS" # Verify some expected protocols exist expected_protocols = { @@ -163,7 +167,7 @@ def test_batt_monitor_connection_structure(self) -> None: assert set(value.keys()) == required_fields, f"Value for key '{key}' has incorrect fields" # Check field types - assert isinstance(value["type"], list), f"'type' field for key '{key}' is not a list" + assert isinstance(value["type"], tuple), f"'type' field for key '{key}' is not a tuple" assert isinstance(value["protocol"], str), f"'protocol' field for key '{key}' is not a string" # Type should reference known port lists or be specific port names @@ -229,7 +233,7 @@ def test_gnss_receiver_connection_structure(self) -> None: assert set(value.keys()) == required_fields, f"Value for key '{key}' has incorrect fields" # Check field types - assert isinstance(value["type"], list), f"'type' field for key '{key}' is not a list" + assert isinstance(value["type"], tuple), f"'type' field for key '{key}' is not a tuple" assert isinstance(value["protocol"], str), f"'protocol' field for key '{key}' is not a string" # Type should reference known port lists or be specific port names @@ -263,43 +267,47 @@ def test_gnss_receiver_connection_structure(self) -> None: def test_mot_pwm_type_dict_structure(self) -> None: """Test MOT_PWM_TYPE_DICT structure and data types.""" - # Should be a dict + # Should be a dict of vehicle-type sub-dicts assert isinstance(MOT_PWM_TYPE_DICT, dict) assert len(MOT_PWM_TYPE_DICT) > 0 - # Keys should be strings representing PWM type numbers - for key in MOT_PWM_TYPE_DICT: - assert isinstance(key, str) - # Should be convertible to int - try: - int(key) - except ValueError: - pytest.fail(f"Key '{key}' is not a valid integer string") - - # Values should be dicts with specific structure - required_fields = {"type", "protocol", "is_dshot"} - for key, value in MOT_PWM_TYPE_DICT.items(): - assert isinstance(value, dict), f"Value for key '{key}' is not a dict" - assert set(value.keys()) == required_fields, f"Value for key '{key}' has incorrect fields" - - # Check field types - assert isinstance(value["type"], list), f"'type' field for key '{key}' is not a list" - assert isinstance(value["protocol"], str), f"'protocol' field for key '{key}' is not a string" - assert isinstance(value["is_dshot"], bool), f"'is_dshot' field for key '{key}' is not a boolean" - - # Type should reference PWM output ports - assert value["type"] == PWM_OUT_PORTS, f"'type' field for key '{key}' does not reference PWM_OUT_PORTS" - - # Verify some expected PWM types exist + # Top-level keys are vehicle type strings (e.g. "ArduCopter", "Rover") + for vtype, sub_dict in MOT_PWM_TYPE_DICT.items(): + assert isinstance(vtype, str), f"Vehicle type key '{vtype}' is not a string" + assert isinstance(sub_dict, dict), f"Sub-dict for '{vtype}' is not a dict" + + # Inner keys should be integer strings representing PWM type numbers + for key in sub_dict: + assert isinstance(key, str) + try: + int(key) + except ValueError: + pytest.fail(f"Key '{key}' in MOT_PWM_TYPE_DICT['{vtype}'] is not a valid integer string") + + # Values should be dicts with specific structure + required_fields = {"type", "protocol", "is_dshot"} + for key, value in sub_dict.items(): + assert isinstance(value, dict), f"Value for key '{key}' in '{vtype}' is not a dict" + assert set(value.keys()) == required_fields, f"Value for key '{key}' in '{vtype}' has incorrect fields" + + # Check field types + assert isinstance(value["type"], tuple), f"'type' field for key '{key}' in '{vtype}' is not a tuple" + assert isinstance(value["protocol"], str), f"'protocol' field for key '{key}' in '{vtype}' is not a string" + assert isinstance(value["is_dshot"], bool), f"'is_dshot' field for key '{key}' in '{vtype}' is not a boolean" + + # Type should reference PWM output ports + assert value["type"] == PWM_OUT_PORTS, f"'type' for key '{key}' in '{vtype}' does not reference PWM_OUT_PORTS" + + # Verify expected PWM types exist in the ArduCopter sub-dict expected_pwm_types = { "0": {"protocol": "Normal", "is_dshot": False}, "6": {"protocol": "DShot600", "is_dshot": True}, } - + copter_sub = MOT_PWM_TYPE_DICT["ArduCopter"] for key, expected_data in expected_pwm_types.items(): - assert key in MOT_PWM_TYPE_DICT - assert MOT_PWM_TYPE_DICT[key]["protocol"] == expected_data["protocol"] - assert MOT_PWM_TYPE_DICT[key]["is_dshot"] == expected_data["is_dshot"] + assert key in copter_sub + assert copter_sub[key]["protocol"] == expected_data["protocol"] + assert copter_sub[key]["is_dshot"] == expected_data["is_dshot"] def test_rc_protocols_dict_structure(self) -> None: """Test RC_PROTOCOLS_DICT structure and data types.""" @@ -323,7 +331,7 @@ def test_rc_protocols_dict_structure(self) -> None: assert set(value.keys()) == required_fields, f"Value for key '{key}' has incorrect fields" # Check field types - assert isinstance(value["type"], list), f"'type' field for key '{key}' is not a list" + assert isinstance(value["type"], tuple), f"'type' field for key '{key}' is not a tuple" assert isinstance(value["protocol"], str), f"'protocol' field for key '{key}' is not a string" # Type should be combination of RC_PORTS + SERIAL_PORTS or CAN_PORTS @@ -370,8 +378,8 @@ def test_port_definitions_consistency(self) -> None: ] for port_name, port_list in port_lists: - # Should be a list - assert isinstance(port_list, list), f"{port_name} is not a list" + # Should be a tuple (constants use tuple for immutability) + assert isinstance(port_list, tuple), f"{port_name} is not a tuple" # Should not be empty assert len(port_list) > 0, f"{port_name} is empty" @@ -418,9 +426,10 @@ def test_protocol_number_ranges(self) -> None: assert 0 <= gps_num <= 50, f"GPS type number {gps_num} is out of expected range" # Motor PWM type numbers should be reasonable (typically 0-10) - for key in MOT_PWM_TYPE_DICT: - pwm_num = int(key) - assert 0 <= pwm_num <= 20, f"Motor PWM type number {pwm_num} is out of expected range" + for sub_dict in MOT_PWM_TYPE_DICT.values(): + for key in sub_dict: + pwm_num = int(key) + assert 0 <= pwm_num <= 20, f"Motor PWM type number {pwm_num} is out of expected range" # RC protocol numbers should be reasonable bit positions (typically 0-15) for key in RC_PROTOCOLS_DICT: @@ -433,7 +442,6 @@ def test_protocol_names_not_empty(self) -> None: ("SERIAL_PROTOCOLS_DICT", SERIAL_PROTOCOLS_DICT), ("BATT_MONITOR_CONNECTION", BATT_MONITOR_CONNECTION), ("GNSS_RECEIVER_CONNECTION", GNSS_RECEIVER_CONNECTION), - ("MOT_PWM_TYPE_DICT", MOT_PWM_TYPE_DICT), ("RC_PROTOCOLS_DICT", RC_PROTOCOLS_DICT), ] @@ -443,13 +451,22 @@ def test_protocol_names_not_empty(self) -> None: assert isinstance(protocol_name, str), f"Protocol name for key '{key}' in {dict_name} is not a string" assert len(protocol_name.strip()) > 0, f"Protocol name for key '{key}' in {dict_name} is empty or whitespace" + for vtype, sub_dict in MOT_PWM_TYPE_DICT.items(): + for key, value in sub_dict.items(): + protocol_name = value["protocol"] + assert isinstance(protocol_name, str), ( + f"Protocol name for key '{key}' in MOT_PWM_TYPE_DICT['{vtype}'] is not a string" + ) + assert len(protocol_name.strip()) > 0, ( + f"Protocol name for key '{key}' in MOT_PWM_TYPE_DICT['{vtype}'] is empty" + ) + def test_no_protocol_duplicates_within_dict(self) -> None: """Test that there are no duplicate protocol names within each dictionary.""" protocol_dicts = [ ("SERIAL_PROTOCOLS_DICT", SERIAL_PROTOCOLS_DICT), ("BATT_MONITOR_CONNECTION", BATT_MONITOR_CONNECTION), ("GNSS_RECEIVER_CONNECTION", GNSS_RECEIVER_CONNECTION), - ("MOT_PWM_TYPE_DICT", MOT_PWM_TYPE_DICT), ("RC_PROTOCOLS_DICT", RC_PROTOCOLS_DICT), ] @@ -467,6 +484,17 @@ def test_no_protocol_duplicates_within_dict(self) -> None: f"Too many duplicate protocol names in {dict_name}: {len(unique_names)}/{len(protocol_names)} unique" ) + # Check uniqueness within each vehicle-type sub-dict of MOT_PWM_TYPE_DICT + for vtype, sub_dict in MOT_PWM_TYPE_DICT.items(): + protocol_names = [value["protocol"] for value in sub_dict.values()] + unique_names = set(protocol_names) + assert len(unique_names) > 0, f"No protocols found in MOT_PWM_TYPE_DICT['{vtype}']" + uniqueness_ratio = len(unique_names) / len(protocol_names) + assert uniqueness_ratio >= 0.8, ( + f"Too many duplicate protocol names in MOT_PWM_TYPE_DICT['{vtype}']: " + f"{len(unique_names)}/{len(protocol_names)} unique" + ) + def test_serial_bus_labels_structure(self) -> None: """Test SERIAL_BUS_LABELS structure and data types.""" # Should be a dictionary diff --git a/update_vehicle_templates.py b/update_vehicle_templates.py index 0d87f7f92..2ff378317 100755 --- a/update_vehicle_templates.py +++ b/update_vehicle_templates.py @@ -13,6 +13,7 @@ SPDX-License-Identifier: GPL-3.0-or-later """ +import contextlib import json import logging import os @@ -103,6 +104,24 @@ def process_template_directory(template_dir: Path) -> None: datatypes = schema.get_all_value_datatypes() data_model = ComponentDataModel(local_fs.vehicle_components_fs.data, datatypes, schema) data_model.update_json_structure(fc_parameters={}, file_parameters=local_fs.file_parameters) + + # Build a flat {param_name: float} dict so process_fc_parameters() can detect ESC protocols, + # serial telemetry channels, etc. + # Seed from 00_default.param first (read_params_from_files skips it), then let the + # numbered step files overwrite — later configuration steps take priority. + flat_params: dict[str, float] = {} + with contextlib.suppress(ValueError, TypeError): + # for param_name, par in local_fs.param_default_dict.items(): + # try: + # flat_params[param_name] = float(par.value) + # except (ValueError, TypeError): + # pass + for par_dict in local_fs.file_parameters.values(): + for param_name, par in par_dict.items(): + flat_params[param_name] = float(par.value) + + data_model.process_fc_parameters(flat_params, local_fs.doc_dict) + local_fs.vehicle_components_fs.data = data_model.get_component_data() local_fs.save_vehicle_components_json_data(local_fs.vehicle_components_fs.data, str(template_dir))