Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Avoid f strings in translations #60

Merged
merged 4 commits into from
Nov 1, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 8 additions & 7 deletions MethodicConfigurator/argparse_check_range.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,20 +41,21 @@ def __init__(self, *args, **kwargs):

def interval(self):
if hasattr(self, "min"):
lo = f"[{self.min}"
_lo = f"[{self.min}"
elif hasattr(self, "inf"):
lo = f"({self.inf}"
_lo = f"({self.inf}"
else:
lo = "(-infinity"
_lo = "(-infinity"

if hasattr(self, "max"):
up = f"{self.max}]"
_up = f"{self.max}]"
elif hasattr(self, "sup"):
up = f"{self.sup})"
_up = f"{self.sup})"
else:
up = "+infinity)"
_up = "+infinity)"

return f"valid range: {lo}, {up}"
msg = _("valid range: {_lo}, {_up}")
return msg.format(**locals())

def __call__(self, parser, namespace, values, option_string=None):
for name, op in self.ops.items():
Expand Down
19 changes: 11 additions & 8 deletions MethodicConfigurator/backend_filesystem_configuration_steps.py
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,9 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str
try:
if ('fc_parameters' in str(parameter_info["New Value"])) and \
('fc_parameters' not in variables or variables['fc_parameters'] == {}):
error_msg = _(f"In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " \
f"parameter '{parameter}' could not be computed: 'fc_parameters' not found, is an FC connected?")
error_msg = _("In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " \
"parameter '{parameter}' could not be computed: 'fc_parameters' not found, is an FC connected?")
error_msg = error_msg.format(**locals())
if parameter_type == 'forced':
logging_error(error_msg)
return error_msg
Expand All @@ -136,9 +137,10 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str
if filename not in destination:
destination[filename] = {}
destination[filename][parameter] = Par(float(result), parameter_info["Change Reason"])
except (SyntaxError, NameError, KeyError, StopIteration) as e:
error_msg = _(f"In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " \
f"parameter '{parameter}' could not be computed: {e}")
except (SyntaxError, NameError, KeyError, StopIteration) as _e:
error_msg = _("In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " \
"parameter '{parameter}' could not be computed: {_e}")
error_msg = error_msg.format(**locals())
if parameter_type == 'forced':
logging_error(error_msg)
return error_msg
Expand All @@ -159,11 +161,12 @@ def get_documentation_text_and_url(self, selected_file: str, prefix_key: str) ->
documentation = self.configuration_steps.get(selected_file, {}) if \
self.configuration_steps else None
if documentation is None:
text = _(f"File '{self.configuration_steps_filename}' not found. " \
text = _("File '{self.configuration_steps_filename}' not found. " \
"No intermediate parameter configuration steps available")
text = text.format(**locals())
url = None
else:
text = documentation.get(prefix_key + "_text", _(f"No documentation available for {selected_file} in the "
f"{self.configuration_steps_filename} file"))
text = _("No documentation available for {selected_file} in the {self.configuration_steps_filename} file")
text = documentation.get(prefix_key + "_text", text.format(**locals()))
url = documentation.get(prefix_key + "_url", None)
return text, url
12 changes: 8 additions & 4 deletions MethodicConfigurator/backend_filesystem_program_settings.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,11 @@ def __user_config_dir():
user_config_directory = user_config_dir(".ardupilot_methodic_configurator", False, roaming=True, ensure_exists=True)

if not os_path.exists(user_config_directory):
raise FileNotFoundError(_(f"The user configuration directory '{user_config_directory}' does not exist."))
error_msg = _("The user configuration directory '{user_config_directory}' does not exist.")
raise FileNotFoundError(error_msg.format(**locals()))
if not os_path.isdir(user_config_directory):
raise NotADirectoryError(_(f"The path '{user_config_directory}' is not a directory."))
error_msg = _("The path '{user_config_directory}' is not a directory.")
raise NotADirectoryError(error_msg.format(**locals()))

return user_config_directory

Expand All @@ -101,9 +103,11 @@ def __site_config_dir():
ensure_exists=True)

if not os_path.exists(site_config_directory):
raise FileNotFoundError(_(f"The site configuration directory '{site_config_directory}' does not exist."))
error_msg = _("The site configuration directory '{site_config_directory}' does not exist.")
raise FileNotFoundError(error_msg.format(**locals()))
if not os_path.isdir(site_config_directory):
raise NotADirectoryError(_(f"The path '{site_config_directory}' is not a directory."))
error_msg = _("The path '{site_config_directory}' is not a directory.")
raise NotADirectoryError(error_msg.format(**locals()))

return site_config_directory

Expand Down
6 changes: 4 additions & 2 deletions MethodicConfigurator/backend_filesystem_vehicle_components.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,8 @@ def get_fc_fw_type_from_vehicle_components_json(self) -> str:
fw_type = components.get('Flight Controller', {}).get('Firmware', {}).get('Type', '')
if fw_type in self.supported_vehicles():
return fw_type
logging_error(f"Firmware type {fw_type} in {self.vehicle_components_json_filename} is not supported")
error_msg = _("Firmware type {fw_type} in {self.vehicle_components_json_filename} is not supported")
logging_error(error_msg.format(**locals()))
return ""

def get_fc_fw_version_from_vehicle_components_json(self) -> str:
Expand All @@ -85,7 +86,8 @@ def get_fc_fw_version_from_vehicle_components_json(self) -> str:
version_str = version_str.lstrip().split(' ')[0] if version_str else ''
if re_match(r'^\d+\.\d+\.\d+$', version_str):
return version_str
logging_error(_(f"FW version string {version_str} on {self.vehicle_components_json_filename} is invalid"))
error_msg = _("FW version string {version_str} on {self.vehicle_components_json_filename} is invalid")
logging_error(error_msg.format(**locals()))
return None

@staticmethod
Expand Down
9 changes: 6 additions & 3 deletions MethodicConfigurator/backend_flightcontroller.py
Original file line number Diff line number Diff line change
Expand Up @@ -254,12 +254,15 @@ def __create_connection_with_retry(self, progress_callback, retries: int = 3,

self.info.set_autopilot(m.autopilot)
if self.info.is_supported:
logging_info(_(f"Autopilot type {self.info.autopilot}"))
msg = _("Autopilot type {self.info.autopilot}")
logging_info(msg.format(**locals()))
else:
return _(f"Unsupported autopilot type {self.info.autopilot}")
msg = _("Unsupported autopilot type {self.info.autopilot}")
return msg.format(**locals())

self.info.set_type(m.type)
logging_info(_(f"Vehicle type: {self.info.mav_type} running {self.info.vehicle_type} firmware"))
msg = _("Vehicle type: {self.info.mav_type} running {self.info.vehicle_type} firmware")
logging_info(msg.format(**locals()))

self.__request_banner()
banner_msgs = self.__receive_banner_text()
Expand Down
17 changes: 9 additions & 8 deletions MethodicConfigurator/frontend_tkinter_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,17 +40,17 @@ def show_error_message(title: str, message: str):
root.destroy()


def show_no_param_files_error(dirname: str):
error_message = _(f"No intermediate parameter files found in the selected '{dirname}' vehicle directory.\n" \
def show_no_param_files_error(_dirname: str):
error_message = _("No intermediate parameter files found in the selected '{_dirname}' vehicle directory.\n" \
"Please select and step inside a vehicle directory containing valid ArduPilot intermediate parameter files.\n\n" \
"Make sure to step inside the directory (double-click) and not just select it.")
show_error_message(_("No Parameter Files Found"), error_message)
show_error_message(_("No Parameter Files Found"), error_message.format(**locals()))


def show_no_connection_error(error_string: str):
error_message = _(f"{error_string}\n\nPlease connect a flight controller to the PC,\n" \
def show_no_connection_error(_error_string: str):
error_message = _("{_error_string}\n\nPlease connect a flight controller to the PC,\n" \
"wait at least 7 seconds and retry.")
show_error_message(_("No Connection to the Flight Controller"), error_message)
show_error_message(_("No Connection to the Flight Controller"), error_message.format(**locals()))


def show_tooltip(widget, text):
Expand Down Expand Up @@ -258,8 +258,9 @@ def update_progress_bar(self, current_value: int, max_value: int):
"""
try:
self.progress_window.lift()
except tk.TclError as e:
logging_error(_(f"Lifting window: {e} on file {__file__}"))
except tk.TclError as _e:
msg = _("Lifting window: {_e} on file {__file__}")
logging_error(msg.format(**locals()))
return

self.progress_bar['value'] = current_value
Expand Down
60 changes: 36 additions & 24 deletions MethodicConfigurator/frontend_tkinter_component_editor.py
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,8 @@ def __set_serial_type_and_protocol_from_fc_parameters(self, fc_parameters: dict)
try:
serial_protocol_nr = int(serial_protocol_nr)
except ValueError:
logging_error(_("Invalid non-integer value for %s_PROTOCOL %f"), serial, serial_protocol_nr)
msg = _("Invalid non-integer value for {serial}_PROTOCOL {serial_protocol_nr}")
logging_error(msg.format(**locals()))
serial_protocol_nr = 0
component = serial_protocols_dict[str(serial_protocol_nr)].get('component')
protocol = serial_protocols_dict[str(serial_protocol_nr)].get('protocol')
Expand Down Expand Up @@ -555,8 +556,10 @@ def validate_combobox(self, event, path) -> bool:

if value not in allowed_values:
if event.type == "10": # FocusOut events
show_error_message(_("Error"), _(f"Invalid value '{value}' for {'>'.join(list(path))}\n"
f"Allowed values are: {', '.join(allowed_values)}"))
_paths_str = '>'.join(list(path))
_allowed_str = ', '.join(allowed_values)
error_msg = _("Invalid value '{value}' for {_paths_str}\nAllowed values are: {_allowed_str}")
show_error_message(_("Error"), error_msg.format(**locals()))
combobox.configure(style="comb_input_invalid.TCombobox")
return False

Expand All @@ -566,17 +569,20 @@ def validate_combobox(self, event, path) -> bool:
combobox.configure(style="comb_input_valid.TCombobox")
return True

def validate_entry_limits(self, event, entry, data_type, limits, name, path): # pylint: disable=too-many-arguments
def validate_entry_limits(self, event, entry, data_type, limits, _name, path): # pylint: disable=too-many-arguments
is_focusout_event = event and event.type == "10"
try:
value = entry.get() # make sure value is defined to prevent exception in the except block
value = data_type(value)
if value < limits[0] or value > limits[1]:
entry.configure(style="entry_input_invalid.TEntry")
raise ValueError(f"{name} must be a {data_type.__name__} between {limits[0]} and {limits[1]}")
except ValueError as e:
error_msg = _("{_name} must be a {data_type.__name__} between {limits[0]} and {limits[1]}")
raise ValueError(error_msg.format(**locals()))
except ValueError as _e:
if is_focusout_event:
show_error_message(_("Error"), _(f"Invalid value '{value}' for {'>'.join(list(path))}\n{e}"))
_paths_str = '>'.join(list(path))
error_msg = _("Invalid value '{value}' for {_paths_str}\n{e}")
show_error_message(_("Error"), error_msg.format(**locals()))
return False
entry.configure(style="entry_input_valid.TEntry")
return True
Expand All @@ -593,31 +599,34 @@ def validate_cell_voltage(self, event, entry, path): # pylint: disable=too-many
chemistry = self.entry_widgets[chemistry_path].get()
value = entry.get()
is_focusout_event = event and event.type == "10"
_path_str = '>'.join(list(path))
try:
voltage = float(value)
if voltage < BatteryCell.limit_min_voltage(chemistry):
volt_limit = BatteryCell.limit_min_voltage(chemistry)
if voltage < volt_limit:
if is_focusout_event:
entry.delete(0, tk.END)
entry.insert(0, BatteryCell.limit_min_voltage(chemistry))
raise VoltageTooLowError(_(f"is below the {chemistry} minimum limit of "
f"{BatteryCell.limit_min_voltage(chemistry)}"))
if voltage > BatteryCell.limit_max_voltage(chemistry):
entry.insert(0, volt_limit)
error_msg = _("is below the {chemistry} minimum limit of {volt_limit}")
raise VoltageTooLowError(error_msg.format(**locals()))
volt_limit = BatteryCell.limit_max_voltage(chemistry)
if voltage > volt_limit:
if is_focusout_event:
entry.delete(0, tk.END)
entry.insert(0, BatteryCell.limit_max_voltage(chemistry))
raise VoltageTooHighError(_(f"is above the {chemistry} maximum limit of "
f"{BatteryCell.limit_max_voltage(chemistry)}"))
except (VoltageTooLowError, VoltageTooHighError) as e:
entry.insert(0, volt_limit)
error_msg = _("is above the {chemistry} maximum limit of {volt_limit}")
raise VoltageTooHighError(error_msg.format(**locals()))
except (VoltageTooLowError, VoltageTooHighError) as _e:
if is_focusout_event:
show_error_message(_("Error"), _(f"Invalid value '{value}' for {'>'.join(list(path))}\n"
f"{e}"))
error_msg = _("Invalid value '{value}' for {_path_str}\n{_e}")
show_error_message(_("Error"), error_msg.format(**locals()))
else:
entry.configure(style="entry_input_invalid.TEntry")
return False
except ValueError as e:
except ValueError as _e:
if is_focusout_event:
show_error_message(_("Error"), _(f"Invalid value '{value}' for {'>'.join(list(path))}\n"
f"{e}\nWill be set to the recommended value."))
error_msg = _("Invalid value '{value}' for {_path_str}\n{_e}\nWill be set to the recommended value.")
show_error_message(_("Error"), error_msg.format(**locals()))
entry.delete(0, tk.END)
if path[-1] == "Volt per cell max":
entry.insert(0, str(BatteryCell.recommended_max_voltage(chemistry)))
Expand Down Expand Up @@ -645,12 +654,14 @@ def validate_data(self): # pylint: disable=too-many-branches
for path, entry in self.entry_widgets.items():
value = entry.get()

_path_str = '>'.join(list(path))
if isinstance(entry, ttk.Combobox):
if path == ('ESC', 'FC Connection', 'Type'):
self.update_esc_protocol_combobox_entries(value)
if value not in entry.cget("values"):
show_error_message(_("Error"), _(f"Invalid value '{value}' for {'>'.join(list(path))}\n"
f"Allowed values are: {', '.join(entry.cget('values'))}"))
_values_str = ', '.join(entry.cget('values'))
error_msg = _("Invalid value '{value}' for {_path_str}\nAllowed values are: {_values_str}")
show_error_message(_("Error"), error_msg.format(**locals()))
entry.configure(style="comb_input_invalid.TCombobox")
invalid_values = True
continue
Expand All @@ -665,7 +676,8 @@ def validate_data(self): # pylint: disable=too-many-branches
fc_serial_connection[value] in ['Battery Monitor', 'ESC']:
entry.configure(style="comb_input_valid.TCombobox")
continue # Allow 'Battery Monitor' and 'ESC' connections using the same SERIAL port
show_error_message(_("Error"), _(f"Duplicate FC connection type '{value}' for {'>'.join(list(path))}"))
error_msg = _("Duplicate FC connection type '{value}' for {_path_str}")
show_error_message(_("Error"), error_msg.format(**locals()))
entry.configure(style="comb_input_invalid.TCombobox")
duplicated_connections = True
continue
Expand Down
12 changes: 8 additions & 4 deletions MethodicConfigurator/frontend_tkinter_connection_selection.py
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,8 @@ def __init__(self, parent, parent_frame, flight_controller: FlightController, #

def on_select_connection_combobox_change(self, _event):
selected_connection = self.conn_selection_combobox.get_selected_key()
logging_debug(_(f"Connection combobox changed to: {selected_connection}"))
error_msg = _("Connection combobox changed to: {selected_connection}")
logging_debug(error_msg.format(**locals()))
if self.flight_controller.master is None or selected_connection != self.flight_controller.comport.device:
if selected_connection == 'Add another':
if not self.add_connection() and self.previous_selection:
Expand All @@ -146,14 +147,17 @@ def add_connection(self):
"tcp:127.0.0.1:5761\n"
"udp:127.0.0.1:14551"))
if selected_connection:
logging_debug(_(f"Will add new connection: {selected_connection} if not duplicated"))
error_msg = _("Will add new connection: {selected_connection} if not duplicated")
logging_debug(error_msg.format(**locals()))
self.flight_controller.add_connection(selected_connection)
connection_tuples = self.flight_controller.get_connection_tuples()
logging_debug(_(f"Updated connection tuples: {connection_tuples} with selected connection: {selected_connection}"))
error_msg = _("Updated connection tuples: {connection_tuples} with selected connection: {selected_connection}")
logging_debug(error_msg.format(**locals()))
self.conn_selection_combobox.set_entries_tupple(connection_tuples, selected_connection)
self.reconnect(selected_connection)
else:
logging_debug(_(f"Add connection canceled or string empty {selected_connection}"))
error_msg = _("Add connection canceled or string empty {selected_connection}")
logging_debug(error_msg.format(**locals()))
return selected_connection

def reconnect(self, selected_connection: str = ""): # defaults to auto-connect
Expand Down
Loading