From aa529f61bb86aa5af3f50827a0e0d0e986945bf8 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Sun, 9 Feb 2025 23:50:08 +0100 Subject: [PATCH] feature(param_logic): Initial work on RPM telemetry improvements --- .../frontend_tkinter_component_editor.py | 51 ++++++++++++++++++- 1 file changed, 50 insertions(+), 1 deletion(-) mode change 100755 => 100644 ardupilot_methodic_configurator/frontend_tkinter_component_editor.py diff --git a/ardupilot_methodic_configurator/frontend_tkinter_component_editor.py b/ardupilot_methodic_configurator/frontend_tkinter_component_editor.py old mode 100755 new mode 100644 index 5f8c5621..e3b21656 --- a/ardupilot_methodic_configurator/frontend_tkinter_component_editor.py +++ b/ardupilot_methodic_configurator/frontend_tkinter_component_editor.py @@ -258,6 +258,7 @@ def __init__(self, version: str, local_filesystem: LocalFilesystem) -> None: _vehicle_components_strings = _("Number of cells") _vehicle_components_strings = _("Capacity mAh") _vehicle_components_strings = _("ESC") + _vehicle_components_strings = _("RPM Telemetry") _vehicle_components_strings = _("Motors") _vehicle_components_strings = _("Poles") _vehicle_components_strings = _("Propellers") @@ -305,6 +306,19 @@ def update_json_data(self) -> None: "Notes": self.data["Components"]["Flight Controller"]["Notes"], } + # To update old JSON files that do not have these new + # "ESC.RPM Telemetry.Connection" and "ESC.RPM Telemetry.Protocol" fields + if "ESC" not in self.data["Components"]: + self.data["Components"]["ESC"] = {} + if "RPM Telemetry" not in self.data["Components"]["ESC"]: + self.data["Components"]["ESC"] = { + "Product": self.data["Components"]["ESC"]["Product"], + "Firmware": self.data["Components"]["ESC"]["Firmware"], + "FC Connection": self.data["Components"]["ESC"]["FC Connection"], + "RPM Telemetry": {"Connection": "None", "Protocol": "None"}, + "Notes": self.data["Components"]["ESC"]["Notes"], + } + def set_vehicle_type_and_version(self, vehicle_type: str, version: str) -> None: self._set_component_value_and_update_ui(("Flight Controller", "Firmware", "Type"), vehicle_type) if version: @@ -487,19 +501,25 @@ def __set_motor_poles_from_fc_parameters(self, fc_parameters: dict) -> None: elif "SERVO_FTW_MASK" in fc_parameters and fc_parameters["SERVO_FTW_MASK"] and "SERVO_FTW_POLES" in fc_parameters: self.data["Components"]["Motors"]["Specifications"]["Poles"] = fc_parameters["SERVO_FTW_POLES"] - def update_esc_protocol_combobox_entries(self, esc_connection_type: str) -> None: + def update_esc_protocol_combobox_entries(self, esc_connection_type: str) -> None: # noqa: PLR0915 """Updates the ESC Protocol combobox entries based on the selected ESC Type.""" if len(esc_connection_type) > 3 and esc_connection_type[:3] == "CAN": protocols = ["DroneCAN"] + rpm_connections = [esc_connection_type] elif len(esc_connection_type) > 6 and esc_connection_type[:6] == "SERIAL": protocols = [value["protocol"] for value in serial_protocols_dict.values() if value["component"] == "ESC"] + rpm_connections = [esc_connection_type] elif "MOT_PWM_TYPE" in self.local_filesystem.doc_dict: protocols = list(self.local_filesystem.doc_dict["MOT_PWM_TYPE"]["values"].values()) + rpm_connections = ["None", "I/O Only", *serial_ports, *can_ports] elif "Q_M_PWM_TYPE" in self.local_filesystem.doc_dict: protocols = list(self.local_filesystem.doc_dict["Q_M_PWM_TYPE"]["values"].values()) + rpm_connections = ["None", "I/O Only", *serial_ports, *can_ports] else: protocols = [] + rpm_connections = [] + protocol = "" protocol_path = ("ESC", "FC Connection", "Protocol") if protocol_path in self.entry_widgets: protocol_combobox = self.entry_widgets[protocol_path] @@ -507,6 +527,35 @@ def update_esc_protocol_combobox_entries(self, esc_connection_type: str) -> None if protocol_combobox.get() not in protocols and isinstance(protocol_combobox, ttk.Combobox): protocol_combobox.set(protocols[0] if protocols else "") protocol_combobox.update_idletasks() # re-draw the combobox ASAP + protocol = protocol_combobox.get() + if protocol in ["Normal", "OneShot", "OneShot125", "Brushed", "PWMRange"]: + rpm_connections = ["None"] + elif "DShot" in protocol: + rpm_connections = ["None", "Main Out/AIO", *serial_ports] + + rpm_connection_path = ("ESC", "RPM Telemetry", "Connection") + if rpm_connection_path in self.entry_widgets: + rpm_connection_combobox = self.entry_widgets[rpm_connection_path] + rpm_connection_combobox["values"] = rpm_connections # Update the combobox entries + if rpm_connection_combobox.get() not in rpm_connections and isinstance(rpm_connection_combobox, ttk.Combobox): + rpm_connection_combobox.set(rpm_connections[0] if rpm_connections else "") + rpm_connection_combobox.update_idletasks() # re-draw the combobox ASAP + + if len(esc_connection_type) > 3 and esc_connection_type[:3] == "CAN": + rpm_protocols = ["None", "DroneCAN"] + elif len(esc_connection_type) > 6 and esc_connection_type[:6] == "SERIAL": + rpm_protocols = ["None", protocol] + elif "MOT_PWM_TYPE" in self.local_filesystem.doc_dict or "Q_M_PWM_TYPE" in self.local_filesystem.doc_dict: + rpm_protocols = ["None", "Dshot", "BDshot"] + else: + rpm_protocols = [] + rpm_protocol_path = ("ESC", "RPM Telemetry", "Protocol") + if rpm_protocol_path in self.entry_widgets: + rpm_protocol_combobox = self.entry_widgets[rpm_protocol_path] + rpm_protocol_combobox["values"] = rpm_protocols # Update the combobox entries + if rpm_protocol_combobox.get() not in rpm_protocols and isinstance(rpm_protocol_combobox, ttk.Combobox): + rpm_protocol_combobox.set(rpm_protocols[0] if rpm_protocols else "") + rpm_protocol_combobox.update_idletasks() # re-draw the combobox ASAP def add_entry_or_combobox( self, value: float, entry_frame: ttk.Frame, path: tuple[str, str, str]