Skip to content

Commit aa529f6

Browse files
committed
feature(param_logic): Initial work on RPM telemetry improvements
1 parent 14b5ae9 commit aa529f6

File tree

1 file changed

+50
-1
lines changed

1 file changed

+50
-1
lines changed

ardupilot_methodic_configurator/frontend_tkinter_component_editor.py

100755100644
Lines changed: 50 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -258,6 +258,7 @@ def __init__(self, version: str, local_filesystem: LocalFilesystem) -> None:
258258
_vehicle_components_strings = _("Number of cells")
259259
_vehicle_components_strings = _("Capacity mAh")
260260
_vehicle_components_strings = _("ESC")
261+
_vehicle_components_strings = _("RPM Telemetry")
261262
_vehicle_components_strings = _("Motors")
262263
_vehicle_components_strings = _("Poles")
263264
_vehicle_components_strings = _("Propellers")
@@ -305,6 +306,19 @@ def update_json_data(self) -> None:
305306
"Notes": self.data["Components"]["Flight Controller"]["Notes"],
306307
}
307308

309+
# To update old JSON files that do not have these new
310+
# "ESC.RPM Telemetry.Connection" and "ESC.RPM Telemetry.Protocol" fields
311+
if "ESC" not in self.data["Components"]:
312+
self.data["Components"]["ESC"] = {}
313+
if "RPM Telemetry" not in self.data["Components"]["ESC"]:
314+
self.data["Components"]["ESC"] = {
315+
"Product": self.data["Components"]["ESC"]["Product"],
316+
"Firmware": self.data["Components"]["ESC"]["Firmware"],
317+
"FC Connection": self.data["Components"]["ESC"]["FC Connection"],
318+
"RPM Telemetry": {"Connection": "None", "Protocol": "None"},
319+
"Notes": self.data["Components"]["ESC"]["Notes"],
320+
}
321+
308322
def set_vehicle_type_and_version(self, vehicle_type: str, version: str) -> None:
309323
self._set_component_value_and_update_ui(("Flight Controller", "Firmware", "Type"), vehicle_type)
310324
if version:
@@ -487,26 +501,61 @@ def __set_motor_poles_from_fc_parameters(self, fc_parameters: dict) -> None:
487501
elif "SERVO_FTW_MASK" in fc_parameters and fc_parameters["SERVO_FTW_MASK"] and "SERVO_FTW_POLES" in fc_parameters:
488502
self.data["Components"]["Motors"]["Specifications"]["Poles"] = fc_parameters["SERVO_FTW_POLES"]
489503

490-
def update_esc_protocol_combobox_entries(self, esc_connection_type: str) -> None:
504+
def update_esc_protocol_combobox_entries(self, esc_connection_type: str) -> None: # noqa: PLR0915
491505
"""Updates the ESC Protocol combobox entries based on the selected ESC Type."""
492506
if len(esc_connection_type) > 3 and esc_connection_type[:3] == "CAN":
493507
protocols = ["DroneCAN"]
508+
rpm_connections = [esc_connection_type]
494509
elif len(esc_connection_type) > 6 and esc_connection_type[:6] == "SERIAL":
495510
protocols = [value["protocol"] for value in serial_protocols_dict.values() if value["component"] == "ESC"]
511+
rpm_connections = [esc_connection_type]
496512
elif "MOT_PWM_TYPE" in self.local_filesystem.doc_dict:
497513
protocols = list(self.local_filesystem.doc_dict["MOT_PWM_TYPE"]["values"].values())
514+
rpm_connections = ["None", "I/O Only", *serial_ports, *can_ports]
498515
elif "Q_M_PWM_TYPE" in self.local_filesystem.doc_dict:
499516
protocols = list(self.local_filesystem.doc_dict["Q_M_PWM_TYPE"]["values"].values())
517+
rpm_connections = ["None", "I/O Only", *serial_ports, *can_ports]
500518
else:
501519
protocols = []
520+
rpm_connections = []
502521

522+
protocol = ""
503523
protocol_path = ("ESC", "FC Connection", "Protocol")
504524
if protocol_path in self.entry_widgets:
505525
protocol_combobox = self.entry_widgets[protocol_path]
506526
protocol_combobox["values"] = protocols # Update the combobox entries
507527
if protocol_combobox.get() not in protocols and isinstance(protocol_combobox, ttk.Combobox):
508528
protocol_combobox.set(protocols[0] if protocols else "")
509529
protocol_combobox.update_idletasks() # re-draw the combobox ASAP
530+
protocol = protocol_combobox.get()
531+
if protocol in ["Normal", "OneShot", "OneShot125", "Brushed", "PWMRange"]:
532+
rpm_connections = ["None"]
533+
elif "DShot" in protocol:
534+
rpm_connections = ["None", "Main Out/AIO", *serial_ports]
535+
536+
rpm_connection_path = ("ESC", "RPM Telemetry", "Connection")
537+
if rpm_connection_path in self.entry_widgets:
538+
rpm_connection_combobox = self.entry_widgets[rpm_connection_path]
539+
rpm_connection_combobox["values"] = rpm_connections # Update the combobox entries
540+
if rpm_connection_combobox.get() not in rpm_connections and isinstance(rpm_connection_combobox, ttk.Combobox):
541+
rpm_connection_combobox.set(rpm_connections[0] if rpm_connections else "")
542+
rpm_connection_combobox.update_idletasks() # re-draw the combobox ASAP
543+
544+
if len(esc_connection_type) > 3 and esc_connection_type[:3] == "CAN":
545+
rpm_protocols = ["None", "DroneCAN"]
546+
elif len(esc_connection_type) > 6 and esc_connection_type[:6] == "SERIAL":
547+
rpm_protocols = ["None", protocol]
548+
elif "MOT_PWM_TYPE" in self.local_filesystem.doc_dict or "Q_M_PWM_TYPE" in self.local_filesystem.doc_dict:
549+
rpm_protocols = ["None", "Dshot", "BDshot"]
550+
else:
551+
rpm_protocols = []
552+
rpm_protocol_path = ("ESC", "RPM Telemetry", "Protocol")
553+
if rpm_protocol_path in self.entry_widgets:
554+
rpm_protocol_combobox = self.entry_widgets[rpm_protocol_path]
555+
rpm_protocol_combobox["values"] = rpm_protocols # Update the combobox entries
556+
if rpm_protocol_combobox.get() not in rpm_protocols and isinstance(rpm_protocol_combobox, ttk.Combobox):
557+
rpm_protocol_combobox.set(rpm_protocols[0] if rpm_protocols else "")
558+
rpm_protocol_combobox.update_idletasks() # re-draw the combobox ASAP
510559

511560
def add_entry_or_combobox(
512561
self, value: float, entry_frame: ttk.Frame, path: tuple[str, str, str]

0 commit comments

Comments
 (0)