From 00b5de4b9b3e5f423a92e579f2a13d7b906e90ea Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Sat, 11 May 2024 12:58:57 +0200 Subject: [PATCH] BUGFIX: fixes issue #9 fixes #9 --- .../frontend_tkinter_component_editor.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/MethodicConfigurator/frontend_tkinter_component_editor.py b/MethodicConfigurator/frontend_tkinter_component_editor.py index ee2c479..09a5082 100644 --- a/MethodicConfigurator/frontend_tkinter_component_editor.py +++ b/MethodicConfigurator/frontend_tkinter_component_editor.py @@ -116,7 +116,7 @@ def add_entry_or_combobox(self, value, entry_frame, path): # pylint: disable=to 'Synthetic Current and Analog Voltage', 'INA239_SPI', 'EFI', 'AD7091R5', 'Scripting'], }, ('ESC', 'FC Connection', 'Type'): { - "values": ['Main Out'] + serial_ports + can_ports, + "values": ['Main Out', 'AIO'] + serial_ports + can_ports, }, ('ESC', 'FC Connection', 'Protocol'): { # TODO get this list from MOT_PWM_TYPE pdef metadata pylint: disable=fixme @@ -297,7 +297,7 @@ def save_data(self): def validate_data(self): # pylint: disable=too-many-branches invalid_values = False duplicated_connections = False - fc_connection_types = set() + fc_serial_connection = {} for path, entry in self.entry_widgets.items(): value = entry.get() @@ -310,12 +310,16 @@ def validate_data(self): # pylint: disable=too-many-branches invalid_values = True continue if 'FC Connection' in path and 'Type' in path: - if value in fc_connection_types and value not in ["CAN1", "CAN2", "I2C1", "I2C2", "I2C3", "I2C4"]: + if value in fc_serial_connection and value not in ["CAN1", "CAN2", "I2C1", "I2C2", "I2C3", "I2C4"]: + if path[0] in ['Telemetry', 'RC Receiver'] and \ + fc_serial_connection[value] in ['Telemetry', 'RC Receiver']: + entry.configure(style="comb_input_valid.TCombobox") + continue # Allow telemetry and RC Receiver connections using the same SERIAL port show_error_message("Error", f"Duplicate FC connection type '{value}' for {'>'.join(list(path))}") entry.configure(style="comb_input_invalid.TCombobox") duplicated_connections = True continue - fc_connection_types.add(value) + fc_serial_connection[value] = path[0] entry.configure(style="comb_input_valid.TCombobox") if path in [('Battery', 'Specifications', 'Volt per cell max'), ('Battery', 'Specifications', 'Volt per cell low'),