@@ -85,17 +85,17 @@ def update_json_data(self):
85
85
self .data ['Components' ]['Frame' ]['Specifications' ]['TOW max Kg' ] = 1
86
86
87
87
def set_vehicle_type_and_version (self , vehicle_type : str , version : str ):
88
- self .set_component_value_and_update_ui (('Flight Controller' , 'Firmware' , 'Type' ), vehicle_type )
88
+ self ._set_component_value_and_update_ui (('Flight Controller' , 'Firmware' , 'Type' ), vehicle_type )
89
89
if version :
90
- self .set_component_value_and_update_ui (('Flight Controller' , 'Firmware' , 'Version' ), version )
90
+ self ._set_component_value_and_update_ui (('Flight Controller' , 'Firmware' , 'Version' ), version )
91
91
92
92
def set_fc_manufacturer (self , manufacturer : str ):
93
93
if manufacturer and manufacturer != "Unknown" and manufacturer != "ArduPilot" :
94
- self .set_component_value_and_update_ui (('Flight Controller' , 'Product' , 'Manufacturer' ), manufacturer )
94
+ self ._set_component_value_and_update_ui (('Flight Controller' , 'Product' , 'Manufacturer' ), manufacturer )
95
95
96
96
def set_fc_model (self , model : str ):
97
97
if model and model != "Unknown" and model != "MAVLink" :
98
- self .set_component_value_and_update_ui (('Flight Controller' , 'Product' , 'Model' ), model )
98
+ self ._set_component_value_and_update_ui (('Flight Controller' , 'Product' , 'Model' ), model )
99
99
100
100
@staticmethod
101
101
def reverse_key_search (doc : dict , param_name : str , values : list ) -> list :
@@ -202,47 +202,45 @@ def add_entry_or_combobox(self, value, entry_frame, path):
202
202
return cb
203
203
204
204
entry = ttk .Entry (entry_frame )
205
- entry_config = {
206
- ('Frame' , 'Specifications' , 'TOW min Kg' ): {
207
- "type" : float ,
208
- "validate" : lambda event , entry = entry , path = path : self .validate_takeoff_weight (event , entry , path ),
209
- },
210
- ('Frame' , 'Specifications' , 'TOW max Kg' ): {
211
- "type" : float ,
212
- "validate" : lambda event , entry = entry , path = path : self .validate_takeoff_weight (event , entry , path ),
213
- },
214
- ('Battery' , 'Specifications' , 'Volt per cell max' ): {
215
- "type" : float ,
216
- "validate" : lambda event , entry = entry , path = path : self .validate_cell_voltage (event , entry , path ),
217
- },
218
- ('Battery' , 'Specifications' , 'Volt per cell low' ): {
219
- "type" : float ,
220
- "validate" : lambda event , entry = entry , path = path : self .validate_cell_voltage (event , entry , path ),
221
- },
222
- ('Battery' , 'Specifications' , 'Volt per cell crit' ): {
223
- "type" : float ,
224
- "validate" : lambda event , entry = entry , path = path : self .validate_cell_voltage (event , entry , path ),
225
- },
226
- ('Battery' , 'Specifications' , 'Number of cells' ): {
227
- "type" : int ,
228
- "validate" : lambda event , entry = entry , path = path : self .validate_nr_cells (event , entry , path ),
229
- },
230
- ('Motors' , 'Specifications' , 'Poles' ): {
231
- "type" : int ,
232
- "validate" : lambda event , entry = entry , path = path : self .validate_motor_poles (event , entry , path ),
233
- },
234
- ('Propellers' , 'Specifications' , 'Diameter_inches' ): {
235
- "type" : float ,
236
- "validate" : lambda event , entry = entry , path = path : self .validate_propeller (event , entry , path ),
237
- },
238
- }
239
- config = entry_config .get (path )
240
- if config :
241
- entry .bind ("<FocusOut>" , config ["validate" ])
242
- entry .bind ("<KeyRelease>" , config ["validate" ])
205
+ validate_function = self .get_validate_function (entry , path )
206
+ if validate_function :
207
+ entry .bind ("<FocusOut>" , validate_function )
208
+ entry .bind ("<KeyRelease>" , validate_function )
243
209
entry .insert (0 , str (value ))
244
210
return entry
245
211
212
+ def get_validate_function (self , entry , path ):
213
+ validate_functions = {
214
+ ('Frame' , 'Specifications' , 'TOW min Kg' ): lambda event , entry = entry , path = path :
215
+ self .validate_entry_limits (event , entry , float , (0.01 , 600 ), "Takeoff Weight" , path ),
216
+
217
+ ('Frame' , 'Specifications' , 'TOW max Kg' ): lambda event , entry = entry , path = path :
218
+ self .validate_entry_limits (event , entry , float , (0.01 , 600 ), "Takeoff Weight" , path ),
219
+
220
+ ('Battery' , 'Specifications' , 'Volt per cell max' ): lambda event , entry = entry , path = path :
221
+ self .validate_cell_voltage (event , entry , path ),
222
+
223
+ ('Battery' , 'Specifications' , 'Volt per cell low' ): lambda event , entry = entry , path = path :
224
+ self .validate_cell_voltage (event , entry , path ),
225
+
226
+ ('Battery' , 'Specifications' , 'Volt per cell crit' ): lambda event , entry = entry , path = path :
227
+ self .validate_cell_voltage (event , entry , path ),
228
+
229
+ ('Battery' , 'Specifications' , 'Number of cells' ): lambda event , entry = entry , path = path :
230
+ self .validate_entry_limits (event , entry , int , (1 , 50 ), "Nr of cells" , path ),
231
+
232
+ ('Battery' , 'Specifications' , 'Capacity mAh' ): lambda event , entry = entry , path = path :
233
+ self .validate_entry_limits (event , entry , int , (100 , 1000000 ), "mAh capacity" , path ),
234
+
235
+ ('Motors' , 'Specifications' , 'Poles' ): lambda event , entry = entry , path = path :
236
+ self .validate_entry_limits (event , entry , int , (3 , 50 ), "Motor Poles" , path ),
237
+
238
+ ('Propellers' , 'Specifications' , 'Diameter_inches' ): lambda event , entry = entry , path = path :
239
+ self .validate_entry_limits (event , entry , float , (0.3 , 400 ), "Propeller Diameter" , path ),
240
+
241
+ }
242
+ return validate_functions .get (path , None )
243
+
246
244
def validate_combobox (self , event , path ) -> bool :
247
245
"""
248
246
Validates the value of a combobox.
@@ -274,20 +272,6 @@ def validate_entry_limits(self, event, entry, data_type, limits, name, path): #
274
272
entry .configure (style = "entry_input_valid.TEntry" )
275
273
return True
276
274
277
- def validate_takeoff_weight (self , event , entry , path ):
278
- is_focusout_event = event and event .type == "10"
279
- try :
280
- weight = float (entry .get ())
281
- if weight < 0.01 or weight > 600 :
282
- entry .configure (style = "entry_input_invalid.TEntry" )
283
- raise ValueError ("Takeoff weight must be a float between 0.01 and 600" )
284
- except ValueError as e :
285
- if is_focusout_event :
286
- show_error_message ("Error" , f"Invalid value '{ weight } ' for { '>' .join (list (path ))} \n { e } " )
287
- return False
288
- entry .configure (style = "entry_input_valid.TEntry" )
289
- return True
290
-
291
275
def validate_cell_voltage (self , event , entry , path ): # pylint: disable=too-many-branches
292
276
"""
293
277
Validates the value of a battery cell voltage entry.
@@ -340,48 +324,6 @@ def validate_cell_voltage(self, event, entry, path): # pylint: disable=too-many
340
324
entry .configure (style = "entry_input_valid.TEntry" )
341
325
return True
342
326
343
- def validate_nr_cells (self , event , entry , path ):
344
- is_focusout_event = event and event .type == "10"
345
- try :
346
- value = int (entry .get ())
347
- if value < 1 or value > 50 :
348
- entry .configure (style = "entry_input_invalid.TEntry" )
349
- raise ValueError ("Nr of cells must be an integer between 1 and 50" )
350
- except ValueError as e :
351
- if is_focusout_event :
352
- show_error_message ("Error" , f"Invalid value '{ value } ' for { '>' .join (list (path ))} \n { e } " )
353
- return False
354
- entry .configure (style = "entry_input_valid.TEntry" )
355
- return True
356
-
357
- def validate_motor_poles (self , event , entry , path ):
358
- is_focusout_event = event and event .type == "10"
359
- try :
360
- value = int (entry .get ())
361
- if value < 3 or value > 50 :
362
- entry .configure (style = "entry_input_invalid.TEntry" )
363
- raise ValueError ("Motor poles must be an integer between 3 and 50" )
364
- except ValueError as e :
365
- if is_focusout_event :
366
- show_error_message ("Error" , f"Invalid value '{ value } ' for { '>' .join (list (path ))} \n { e } " )
367
- return False
368
- entry .configure (style = "entry_input_valid.TEntry" )
369
- return True
370
-
371
- def validate_propeller (self , event , entry , path ):
372
- is_focusout_event = event and event .type == "10"
373
- try :
374
- value = float (entry .get ())
375
- if value < 0.3 or value > 400 :
376
- entry .configure (style = "entry_input_invalid.TEntry" )
377
- raise ValueError ("Propeller diameter in inches must be a float between 0.3 and 400" )
378
- except ValueError as e :
379
- if is_focusout_event :
380
- show_error_message ("Error" , f"Invalid value '{ value } ' for { '>' .join (list (path ))} \n { e } " )
381
- return False
382
- entry .configure (style = "entry_input_valid.TEntry" )
383
- return True
384
-
385
327
def save_data (self ):
386
328
if self .validate_data ():
387
329
ComponentEditorWindowBase .save_data (self )
@@ -414,11 +356,10 @@ def validate_data(self): # pylint: disable=too-many-branches
414
356
fc_serial_connection [value ] = path [0 ]
415
357
entry .configure (style = "comb_input_valid.TCombobox" )
416
358
417
- if path == ('Frame' , 'Specifications' , 'TOW min Kg' ):
418
- if not self .validate_takeoff_weight (None , entry , path ):
419
- invalid_values = True
420
- if path == ('Frame' , 'Specifications' , 'TOW max Kg' ):
421
- if not self .validate_takeoff_weight (None , entry , path ):
359
+ validate_function = self .get_validate_function (entry , path )
360
+ if validate_function :
361
+ mock_focus_out_event = type ('' , (), {'type' : '10' })()
362
+ if not validate_function (mock_focus_out_event ):
422
363
invalid_values = True
423
364
if path in [('Battery' , 'Specifications' , 'Volt per cell max' ), ('Battery' , 'Specifications' , 'Volt per cell low' ),
424
365
('Battery' , 'Specifications' , 'Volt per cell crit' )]:
@@ -434,15 +375,6 @@ def validate_data(self): # pylint: disable=too-many-branches
434
375
show_error_message ("Error" , "Battery Cell Crit voltage must be lower than low voltage" )
435
376
entry .configure (style = "entry_input_invalid.TEntry" )
436
377
invalid_values = True
437
- if path == ('Battery' , 'Specifications' , 'Number of cells' ):
438
- if not self .validate_nr_cells (None , entry , path ):
439
- invalid_values = True
440
- if path == ('Motors' , 'Specifications' , 'Poles' ):
441
- if not self .validate_motor_poles (None , entry , path ):
442
- invalid_values = True
443
- if path == ('Propellers' , 'Specifications' , 'Diameter_inches' ):
444
- if not self .validate_propeller (None , entry , path ):
445
- invalid_values = True
446
378
447
379
return not (invalid_values or duplicated_connections )
448
380
0 commit comments