forked from ArduPilot/MethodicConfigurator
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathdata_model_vehicle_components_validation.py
More file actions
673 lines (591 loc) · 35.2 KB
/
data_model_vehicle_components_validation.py
File metadata and controls
673 lines (591 loc) · 35.2 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
"""
Data model for vehicle components.
This file is part of ArduPilot Methodic Configurator. https://github.com/ArduPilot/MethodicConfigurator
SPDX-FileCopyrightText: 2024-2026 Amilcar do Carmo Lucas <amilcar.lucas@iav.de>
SPDX-License-Identifier: GPL-3.0-or-later
"""
# from logging import debug as logging_debug
import functools
import operator
from logging import error as logging_error
from types import MappingProxyType
from typing import Any, Optional, Union
from ardupilot_methodic_configurator import _
from ardupilot_methodic_configurator.backend_filesystem_vehicle_components import VehicleComponents
from ardupilot_methodic_configurator.battery_cell_voltages import BatteryCell
from ardupilot_methodic_configurator.data_model_vehicle_components_base import (
ComponentData,
ComponentDataModelBase,
ComponentPath,
ComponentValue,
)
# 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"]
# 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:
# - Telem1/Telem2: Commonly used for telemetry connections
# - GPS1/GPS2: Commonly used for GNSS receiver connections
# - SERIAL5-8: No standard labels, use port name as label
SERIAL_BUS_LABELS: dict[str, str] = {
"SERIAL1": "Telem1 (SERIAL1)",
"SERIAL2": "Telem2 (SERIAL2)",
"SERIAL3": "GPS1 (SERIAL3)",
"SERIAL4": "GPS2 (SERIAL4)",
"SERIAL5": "SERIAL5",
"SERIAL6": "SERIAL6",
"SERIAL7": "SERIAL7",
"SERIAL8": "SERIAL8",
}
# Reverse mapping for efficient lookup: display label -> key (e.g., "GPS1 (SERIAL3)" -> "SERIAL3")
SERIAL_DISPLAY_TO_KEY: dict[str, str] = {display: key for key, display in SERIAL_BUS_LABELS.items()}
def get_connection_type_tuples_with_labels(connection_types: tuple[str, ...]) -> list[tuple[str, str]]:
"""
Convert connection type values to tuples with bus labels for display.
Args:
connection_types: Tuple of connection type values (e.g., ("SERIAL1", "SERIAL2", ...))
Returns:
List of tuples where first element is the value and second is the display string.
For SERIAL ports, returns (value, "Label (value)"), e.g., ("SERIAL3", "GPS1 (SERIAL3)")
For other ports, returns (value, value), e.g., ("CAN1", "CAN1")
"""
result = []
for conn_type in connection_types:
if conn_type in SERIAL_BUS_LABELS:
label = SERIAL_BUS_LABELS[conn_type]
result.append((conn_type, label))
else:
result.append((conn_type, conn_type))
return result
# Map paths to component names for unified protocol update
FC_CONNECTION_TYPE_PATHS: list[ComponentPath] = [
("RC Receiver", "FC Connection", "Type"),
("Telemetry", "FC Connection", "Type"),
("Battery Monitor", "FC Connection", "Type"),
("ESC", "FC Connection", "Type"),
("GNSS Receiver", "FC Connection", "Type"),
]
BATTERY_CELL_VOLTAGE_PATHS: list[ComponentPath] = [
("Battery", "Specifications", "Volt per cell max"),
("Battery", "Specifications", "Volt per cell low"),
("Battery", "Specifications", "Volt per cell crit"),
]
# Protocol dictionaries
SERIAL_PROTOCOLS_DICT: dict[str, dict[str, Any]] = {
"-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},
"4": {"type": SERIAL_PORTS, "protocol": "Frsky SPort", "component": None},
"5": {"type": SERIAL_PORTS, "protocol": "GPS", "component": "GNSS Receiver"},
"7": {"type": SERIAL_PORTS, "protocol": "Alexmos Gimbal Serial", "component": None},
"8": {"type": SERIAL_PORTS, "protocol": "Gimbal", "component": None},
"9": {"type": SERIAL_PORTS, "protocol": "Rangefinder", "component": None},
"10": {"type": SERIAL_PORTS, "protocol": "FrSky SPort Passthrough (OpenTX)", "component": None},
"11": {"type": SERIAL_PORTS, "protocol": "Lidar360", "component": None},
"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},
"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},
"20": {"type": SERIAL_PORTS, "protocol": "NMEA Output", "component": None},
"21": {"type": SERIAL_PORTS, "protocol": "WindVane", "component": None},
"22": {"type": SERIAL_PORTS, "protocol": "SLCAN", "component": None},
"23": {"type": SERIAL_PORTS, "protocol": "RCIN", "component": "RC Receiver"},
"24": {"type": SERIAL_PORTS, "protocol": "EFI Serial", "component": None},
"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},
"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},
"32": {"type": SERIAL_PORTS, "protocol": "MSP", "component": None},
"33": {"type": SERIAL_PORTS, "protocol": "DJI FPV", "component": None},
"34": {"type": SERIAL_PORTS, "protocol": "AirSpeed", "component": None},
"35": {"type": SERIAL_PORTS, "protocol": "ADSB", "component": None},
"36": {"type": SERIAL_PORTS, "protocol": "AHRS", "component": None},
"37": {"type": SERIAL_PORTS, "protocol": "SmartAudio", "component": None},
"38": {"type": SERIAL_PORTS, "protocol": "FETtecOneWire", "component": "ESC"},
"39": {"type": SERIAL_PORTS, "protocol": "Torqeedo", "component": "ESC"},
"40": {"type": SERIAL_PORTS, "protocol": "AIS", "component": None},
"41": {"type": SERIAL_PORTS, "protocol": "CoDevESC", "component": "ESC"},
"42": {"type": SERIAL_PORTS, "protocol": "DisplayPort", "component": None},
"43": {"type": SERIAL_PORTS, "protocol": "MAVLink High Latency", "component": "Telemetry"},
"44": {"type": SERIAL_PORTS, "protocol": "IRC Tramp", "component": None},
"45": {"type": SERIAL_PORTS, "protocol": "DDS XRCE", "component": None},
"46": {"type": SERIAL_PORTS, "protocol": "IMUDATA", "component": None},
"48": {"type": SERIAL_PORTS, "protocol": "PPP", "component": "Telemetry"},
"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"},
"3": {"type": ANALOG_PORTS, "protocol": "Analog Voltage Only"},
"4": {"type": ANALOG_PORTS, "protocol": "Analog Voltage and Current"},
"5": {"type": I2C_PORTS, "protocol": "Solo"},
"6": {"type": I2C_PORTS, "protocol": "Bebop"},
"7": {"type": I2C_PORTS, "protocol": "SMBus-Generic"},
"8": {"type": CAN_PORTS, "protocol": "DroneCAN-BatteryInfo"},
"9": {"type": OTHER_PORTS, "protocol": "ESC"},
"10": {"type": OTHER_PORTS, "protocol": "Sum Of Selected Monitors"},
"11": {"type": I2C_PORTS, "protocol": "FuelFlow"},
"12": {"type": PWM_IN_PORTS, "protocol": "FuelLevelPWM"},
"13": {"type": I2C_PORTS, "protocol": "SMBUS-SUI3"},
"14": {"type": I2C_PORTS, "protocol": "SMBUS-SUI6"},
"15": {"type": I2C_PORTS, "protocol": "NeoDesign"},
"16": {"type": I2C_PORTS, "protocol": "SMBus-Maxell"},
"17": {"type": I2C_PORTS, "protocol": "Generator-Elec"},
"18": {"type": I2C_PORTS, "protocol": "Generator-Fuel"},
"19": {"type": I2C_PORTS, "protocol": "Rotoye"},
"20": {"type": I2C_PORTS, "protocol": "MPPT"},
"21": {"type": I2C_PORTS, "protocol": "INA2XX"},
"22": {"type": I2C_PORTS, "protocol": "LTC2946"},
"23": {"type": OTHER_PORTS, "protocol": "Torqeedo"},
"24": {"type": ANALOG_PORTS, "protocol": "FuelLevelAnalog"},
"25": {"type": ANALOG_PORTS, "protocol": "Synthetic Current and Analog Voltage"},
"26": {"type": SPI_PORTS, "protocol": "INA239_SPI"},
"27": {"type": I2C_PORTS, "protocol": "EFI"},
"28": {"type": I2C_PORTS, "protocol": "AD7091R5"},
"29": {"type": OTHER_PORTS, "protocol": "Scripting"},
}
GNSS_RECEIVER_CONNECTION: dict[str, dict[str, Union[list[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"},
"6": {"type": SERIAL_PORTS, "protocol": "SiRF"},
"7": {"type": SERIAL_PORTS, "protocol": "HIL"},
"8": {"type": SERIAL_PORTS, "protocol": "SwiftNav"},
"9": {"type": CAN_PORTS, "protocol": "DroneCAN"},
"10": {"type": SERIAL_PORTS, "protocol": "Septentrio(SBF)"},
"11": {"type": SERIAL_PORTS, "protocol": "Trimble(GSOF)"},
"13": {"type": SERIAL_PORTS, "protocol": "ERB"},
"14": {"type": SERIAL_PORTS, "protocol": "MAVLink"},
"15": {"type": SERIAL_PORTS, "protocol": "NOVA"},
"16": {"type": SERIAL_PORTS, "protocol": "HemisphereNMEA"},
"17": {"type": SERIAL_PORTS, "protocol": "uBlox-MovingBaseline-Base"},
"18": {"type": SERIAL_PORTS, "protocol": "uBlox-MovingBaseline-Rover"},
"19": {"type": SERIAL_PORTS, "protocol": "MSP"},
"20": {"type": SERIAL_PORTS, "protocol": "AllyStar"},
"21": {"type": SERIAL_PORTS, "protocol": "ExternalAHRS"},
"22": {"type": CAN_PORTS, "protocol": "DroneCAN-MovingBaseline-Base"},
"23": {"type": CAN_PORTS, "protocol": "DroneCAN-MovingBaseline-Rover"},
"24": {"type": SERIAL_PORTS, "protocol": "UnicoreNMEA"},
"25": {"type": SERIAL_PORTS, "protocol": "UnicoreMovingBaselineNMEA"},
"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},
}
# 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]]] = {
"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
"8": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "SBUS"}, # Bit 3
"16": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "SBUS_NI"}, # Bit 4
"32": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "DSM"}, # Bit 5
"64": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "SUMD"}, # Bit 6
"128": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "SRXL"}, # Bit 7
"256": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "SRXL2"}, # Bit 8
"512": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "CRSF"}, # Bit 9
"1024": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "ST24"}, # Bit 10
"2048": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "FPORT"}, # Bit 11
"4096": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "FPORT2"}, # Bit 12
"8192": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "FastSBUS"}, # Bit 13
"16384": {"type": CAN_PORTS, "protocol": "DroneCAN"}, # Bit 14
"32768": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "Ghost"}, # Bit 15
"65536": {"type": RC_PORTS + SERIAL_PORTS, "protocol": "MAVRadio"}, # Bit 16
}
class ComponentDataModelValidation(ComponentDataModelBase):
"""
A class to handle component data operations separate from UI logic.
This improves testability by isolating data operations.
"""
# Class attribute for validation rules - use immutable mapping
VALIDATION_RULES: MappingProxyType[ComponentPath, tuple[type, tuple[float, float], str]] = MappingProxyType(
{
("Frame", "Specifications", "TOW min Kg"): (float, (0.01, 600), "Takeoff Weight"),
("Frame", "Specifications", "TOW max Kg"): (float, (0.01, 600), "Takeoff Weight"),
("Battery", "Specifications", "Number of cells"): (int, (1, 50), "Nr of cells"),
("Battery", "Specifications", "Capacity mAh"): (int, (100, 1000000), "mAh capacity"),
("Motors", "Specifications", "Poles"): (int, (2, 59), "Motor Poles"),
("Propellers", "Specifications", "Diameter_inches"): (float, (0.3, 400), "Propeller Diameter"),
}
)
def set_component_value(self, path: ComponentPath, value: Union[ComponentData, ComponentValue, None]) -> None:
ComponentDataModelBase.set_component_value(self, path, value)
# and change side effects
if path == ("Battery", "Specifications", "Chemistry") and isinstance(value, str) and self._battery_chemistry != value:
self._battery_chemistry = value
self.set_component_value(
("Battery", "Specifications", "Volt per cell max"), BatteryCell.recommended_max_voltage(value)
)
self.set_component_value(
("Battery", "Specifications", "Volt per cell low"), BatteryCell.recommended_low_voltage(value)
)
self.set_component_value(
("Battery", "Specifications", "Volt per cell crit"), BatteryCell.recommended_crit_voltage(value)
)
# Update possible choices for protocol fields when connection type changes
self._update_possible_choices_for_path(path, value)
def is_valid_component_data(self) -> bool:
"""
Validate the component data structure.
Performs basic validation to ensure the data has the expected format.
"""
return isinstance(self._data, dict) and "Components" in self._data and isinstance(self._data["Components"], dict)
def init_possible_choices(self, doc_dict: dict) -> None:
"""Get valid combobox values for a given path."""
# Default values for comboboxes in case the apm.pdef.xml metadata is not available
def get_all_protocols(param_dict: dict) -> tuple[str, ...]:
return tuple(
value["protocol"] if isinstance(value["protocol"], str) else value["protocol"][0]
for value in param_dict.values()
)
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),
"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
}
def get_combobox_values(param_name: str) -> tuple[str, ...]:
if param_name in doc_dict:
if "values" in doc_dict[param_name] and doc_dict[param_name]["values"]:
return tuple(doc_dict[param_name]["values"].values())
if "Bitmask" in doc_dict[param_name] and doc_dict[param_name]["Bitmask"]:
return tuple(doc_dict[param_name]["Bitmask"].values())
logging_error(_("No values found for %s in the metadata"), param_name)
if param_name in fallbacks:
return fallbacks[param_name]
logging_error(_("No fallback values found for %s"), param_name)
return ()
def get_connection_types(conn_dict: dict) -> tuple[str, ...]:
return tuple(
dict.fromkeys( # Use dict.fromkeys to preserve order while removing duplicates
functools.reduce(
operator.iadd,
[
type_val if isinstance(type_val, list) else [type_val]
for type_val in [value["type"] for value in conn_dict.values()]
],
[],
)
)
)
if "MOT_PWM_TYPE" in doc_dict:
self._mot_pwm_types = get_combobox_values("MOT_PWM_TYPE")
if "Q_M_PWM_TYPE" in doc_dict:
self._mot_pwm_types = get_combobox_values("Q_M_PWM_TYPE")
self._possible_choices = {
("Flight Controller", "Firmware", "Type"): VehicleComponents.supported_vehicles(),
("RC Receiver", "FC Connection", "Type"): get_connection_types(RC_PROTOCOLS_DICT),
("RC Receiver", "FC Connection", "Protocol"): get_combobox_values("RC_PROTOCOLS"),
("Telemetry", "FC Connection", "Type"): ("None", *SERIAL_PORTS, *CAN_PORTS),
("Telemetry", "FC Connection", "Protocol"): tuple(
value["protocol"] for value in SERIAL_PROTOCOLS_DICT.values() if value["component"] == "Telemetry"
),
("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,
("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"]:
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"
)
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"]
# Handle both list and direct port type references
if isinstance(conn_type, list):
if value in conn_type:
batt_available_protocols.append(str(conn_dict["protocol"]))
elif value in conn_type:
# conn_type is a reference to a port list (e.g., ANALOG_PORTS, I2C_PORTS)
batt_available_protocols.append(str(conn_dict["protocol"]))
self._possible_choices[protocol_path] = (
tuple(batt_available_protocols) if batt_available_protocols else ("None",)
)
elif component_name == "ESC":
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
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"]
# Handle both list and direct port type references
if isinstance(conn_type, list):
if value in conn_type:
gnss_available_protocols.append(str(conn_dict["protocol"]))
elif value in conn_type:
# conn_type is a reference to a port list (e.g., SERIAL_PORTS, CAN_PORTS)
gnss_available_protocols.append(str(conn_dict["protocol"]))
self._possible_choices[protocol_path] = (
tuple(gnss_available_protocols) if gnss_available_protocols else ("None",)
)
def validate_entry_limits(self, value: str, path: ComponentPath) -> tuple[str, Optional[float]]: # noqa: PLR0911 # pylint: disable=too-many-return-statements
"""
Validate entry values against limits.
Returns: (error_message, limited_value) if validation fails, or ("", None) if valid.
"""
if path in self.VALIDATION_RULES:
data_type, limits, name = self.VALIDATION_RULES[path]
try:
typed_value = data_type(value)
if typed_value < limits[0] or typed_value > limits[1]:
error_msg = _("{name} must be a {data_type_name} between {min} and {max}")
limited_value = limits[0] if typed_value < limits[0] else limits[1]
type_name = getattr(data_type, "__name__", repr(data_type))
return error_msg.format(name=name, data_type_name=type_name, min=limits[0], max=limits[1]), limited_value
except ValueError:
error_msg = _("Invalid {data_type_name} value for {name}")
type_name = getattr(data_type, "__name__", repr(data_type))
return error_msg.format(data_type_name=type_name, name=name), None
# Validate takeoff weight limits
if path[0] == "Frame" and path[1] == "Specifications" and "TOW" in path[2]:
if path[2] == "TOW max Kg":
try:
tow_max = float(value)
except ValueError:
return _("Takeoff Weight max must be a float"), None
lim = self.get_component_value(("Frame", "Specifications", "TOW min Kg"))
if lim:
return self.validate_against_another_value(tow_max, lim, "TOW min Kg", above=True, delta=0.01)
if path[2] == "TOW min Kg":
try:
tow_min = float(value)
except ValueError:
return _("Takeoff Weight min must be a float"), None
lim = self.get_component_value(("Frame", "Specifications", "TOW max Kg"))
if lim:
return self.validate_against_another_value(tow_min, lim, "TOW max Kg", above=False, delta=0.01)
if path in BATTERY_CELL_VOLTAGE_PATHS:
return self.validate_cell_voltage(value, path)
return "", None # value is within valid interval, return empty string as there is no error
def validate_cell_voltage(self, value: str, path: ComponentPath) -> tuple[str, Optional[float]]: # noqa: PLR0911 # pylint: disable=too-many-return-statements
"""
Validate battery cell voltage.
Returns (error_message, corrected_value) if validation fails, or ("", None) if valid.
"""
if path[0] == "Battery" and path[1] == "Specifications" and "Volt per cell" in path[2]:
recommended_cell_voltage: float = self.recommended_cell_voltage(path)
try:
voltage = float(value)
volt_limit = BatteryCell.limit_min_voltage(self._battery_chemistry)
if voltage < volt_limit:
error_msg = _("is below the {chemistry} minimum limit of {volt_limit}")
return error_msg.format(chemistry=self._battery_chemistry, volt_limit=volt_limit), volt_limit
volt_limit = BatteryCell.limit_max_voltage(self._battery_chemistry)
if voltage > volt_limit:
error_msg = _("is above the {chemistry} maximum limit of {volt_limit}")
return error_msg.format(chemistry=self._battery_chemistry, volt_limit=volt_limit), volt_limit
except ValueError as e:
error_msg = _("Invalid value. Will be set to the recommended value.")
return f"{e!s}\n{error_msg}", recommended_cell_voltage
if path[-1] == "Volt per cell max":
lim = self.get_component_value(("Battery", "Specifications", "Volt per cell low"))
return self.validate_against_another_value(voltage, lim, "Volt per cell low", above=True, delta=0.01)
if path[-1] == "Volt per cell low":
lim = self.get_component_value(("Battery", "Specifications", "Volt per cell max"))
err_msg, corr = self.validate_against_another_value(voltage, lim, "Volt per cell max", above=False, delta=0.01)
if err_msg:
return err_msg, corr
lim = self.get_component_value(("Battery", "Specifications", "Volt per cell crit"))
return self.validate_against_another_value(voltage, lim, "Volt per cell crit", above=True, delta=0.01)
if path[-1] == "Volt per cell crit":
lim = self.get_component_value(("Battery", "Specifications", "Volt per cell low"))
return self.validate_against_another_value(voltage, lim, "Volt per cell low", above=False, delta=0.01)
return "", None
def recommended_cell_voltage(self, path: ComponentPath) -> float:
"""Get recommended cell voltage based on the path."""
if path[-1] == "Volt per cell max":
return BatteryCell.recommended_max_voltage(self._battery_chemistry)
if path[-1] == "Volt per cell low":
return BatteryCell.recommended_low_voltage(self._battery_chemistry)
if path[-1] == "Volt per cell crit":
return BatteryCell.recommended_crit_voltage(self._battery_chemistry)
return 3.8
def validate_against_another_value( # pylint: disable=too-many-arguments,too-many-positional-arguments
self,
value: float,
limit_value, # limit_value has no type, because it can have any type # noqa: ANN001
limit_name: str,
above: bool,
delta: float,
) -> tuple[str, Optional[float]]:
"""Validate user defined value against another user defined value."""
if not isinstance(limit_value, (float, str, int)):
return _("{limit_name} is not a float nor string").format(limit_name=limit_name), None
try:
limit_value = float(limit_value)
except ValueError:
return _("{limit_name} is not convertible to float").format(limit_name=limit_name), None
if above:
if value < limit_value:
corrected = limit_value + delta
return _("is below the {limit_name} of {limit_value}").format(
limit_name=limit_name, limit_value=limit_value
), corrected
elif value > limit_value:
corrected = limit_value - delta
return _("is above the {limit_name} of {limit_value}").format(
limit_name=limit_name, limit_value=limit_value
), corrected
return "", None # value is within valid interval, return empty string as there is no error
def validate_all_data(self, entry_values: dict[ComponentPath, str]) -> tuple[bool, list[str]]:
"""
Centralize all data validation logic.
Returns (is_valid, error_messages).
"""
errors = []
fc_serial_connection: dict[str, str] = {}
for path, value in entry_values.items():
paths_str = ">".join(list(path))
# Validate combobox values
combobox_values = self.get_combobox_values_for_path(path)
if combobox_values and value not in combobox_values:
allowed_str = ", ".join(combobox_values)
error_msg = _("Invalid value '{value}' for {paths_str}\nAllowed values are: {allowed_str}")
errors.append(error_msg.format(value=value, paths_str=paths_str, allowed_str=allowed_str))
continue
# Check for duplicate connections
if len(path) >= 3 and path[1] == "FC Connection" and path[2] == "Type":
if value in fc_serial_connection and value not in {"CAN1", "CAN2", "I2C1", "I2C2", "I2C3", "I2C4", "None"}:
battery_monitor_protocol = self.get_component_value(("Battery Monitor", "FC Connection", "Protocol"))
# Allow certain combinations
if path[0] in {"Telemetry", "RC Receiver"} and fc_serial_connection[value] in {"Telemetry", "RC Receiver"}:
continue
if (
battery_monitor_protocol == "ESC"
and path[0] in {"Battery Monitor", "ESC"}
and fc_serial_connection[value] in {"Battery Monitor", "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)
return len(errors) == 0, errors
def _validate_motor_poles(self, errors: list, path: ComponentPath, value: str, paths_str: str) -> None:
if path == ("Motors", "Specifications", "Poles"):
# Number of magnetic rotor poles must be even
# On a common 12N14P BLDC/PMSM motor this is 14, the P number
try:
poles = int(value)
if poles % 2 != 0:
error_msg = _("Number of magnetic rotor poles must be even for {paths_str}")
errors.append(error_msg.format(paths_str=paths_str))
except ValueError:
error_msg = _("Invalid integer value for {paths_str}")
errors.append(error_msg.format(paths_str=paths_str))
def correct_display_values_in_loaded_data(self) -> None:
"""
Correct display values that may have been stored in JSON instead of key values.
After loading data from JSON, some fields may have display values (e.g., "SERIAL1 (GPS1)")
instead of key values (e.g., "SERIAL1"). This method corrects such values using the
display-to-key mapping built during initialization.
This ensures data integrity without requiring pre-save synchronization in the GUI.
"""
for path in self._data["Components"]:
self._correct_values_recursive(self._data["Components"][path], path)
def _correct_values_recursive(self, data: dict[str, Any], path: ComponentPath) -> None:
"""
Recursively correct display values in nested component data.
Args:
data: Component data dictionary to correct
path: Current path in the component hierarchy
"""
for key, value in data.items():
current_path: ComponentPath = (*path, key)
if isinstance(value, dict):
# Recurse into nested dictionaries
self._correct_values_recursive(value, current_path)
elif isinstance(value, str) and value in SERIAL_DISPLAY_TO_KEY:
# This is a display label, use the pre-computed reverse mapping for O(1) lookup
data[key] = SERIAL_DISPLAY_TO_KEY[value]