@@ -258,6 +258,7 @@ def __init__(self, version: str, local_filesystem: LocalFilesystem) -> None:
258
258
_vehicle_components_strings = _ ("Number of cells" )
259
259
_vehicle_components_strings = _ ("Capacity mAh" )
260
260
_vehicle_components_strings = _ ("ESC" )
261
+ _vehicle_components_strings = _ ("RPM Telemetry" )
261
262
_vehicle_components_strings = _ ("Motors" )
262
263
_vehicle_components_strings = _ ("Poles" )
263
264
_vehicle_components_strings = _ ("Propellers" )
@@ -305,6 +306,19 @@ def update_json_data(self) -> None:
305
306
"Notes" : self .data ["Components" ]["Flight Controller" ]["Notes" ],
306
307
}
307
308
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
+
308
322
def set_vehicle_type_and_version (self , vehicle_type : str , version : str ) -> None :
309
323
self ._set_component_value_and_update_ui (("Flight Controller" , "Firmware" , "Type" ), vehicle_type )
310
324
if version :
@@ -487,26 +501,61 @@ def __set_motor_poles_from_fc_parameters(self, fc_parameters: dict) -> None:
487
501
elif "SERVO_FTW_MASK" in fc_parameters and fc_parameters ["SERVO_FTW_MASK" ] and "SERVO_FTW_POLES" in fc_parameters :
488
502
self .data ["Components" ]["Motors" ]["Specifications" ]["Poles" ] = fc_parameters ["SERVO_FTW_POLES" ]
489
503
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
491
505
"""Updates the ESC Protocol combobox entries based on the selected ESC Type."""
492
506
if len (esc_connection_type ) > 3 and esc_connection_type [:3 ] == "CAN" :
493
507
protocols = ["DroneCAN" ]
508
+ rpm_connections = [esc_connection_type ]
494
509
elif len (esc_connection_type ) > 6 and esc_connection_type [:6 ] == "SERIAL" :
495
510
protocols = [value ["protocol" ] for value in serial_protocols_dict .values () if value ["component" ] == "ESC" ]
511
+ rpm_connections = [esc_connection_type ]
496
512
elif "MOT_PWM_TYPE" in self .local_filesystem .doc_dict :
497
513
protocols = list (self .local_filesystem .doc_dict ["MOT_PWM_TYPE" ]["values" ].values ())
514
+ rpm_connections = ["None" , "I/O Only" , * serial_ports , * can_ports ]
498
515
elif "Q_M_PWM_TYPE" in self .local_filesystem .doc_dict :
499
516
protocols = list (self .local_filesystem .doc_dict ["Q_M_PWM_TYPE" ]["values" ].values ())
517
+ rpm_connections = ["None" , "I/O Only" , * serial_ports , * can_ports ]
500
518
else :
501
519
protocols = []
520
+ rpm_connections = []
502
521
522
+ protocol = ""
503
523
protocol_path = ("ESC" , "FC Connection" , "Protocol" )
504
524
if protocol_path in self .entry_widgets :
505
525
protocol_combobox = self .entry_widgets [protocol_path ]
506
526
protocol_combobox ["values" ] = protocols # Update the combobox entries
507
527
if protocol_combobox .get () not in protocols and isinstance (protocol_combobox , ttk .Combobox ):
508
528
protocol_combobox .set (protocols [0 ] if protocols else "" )
509
529
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
510
559
511
560
def add_entry_or_combobox (
512
561
self , value : float , entry_frame : ttk .Frame , path : tuple [str , str , str ]
0 commit comments