diff --git a/MethodicConfigurator/frontend_tkinter_connection_selection.py b/MethodicConfigurator/frontend_tkinter_connection_selection.py index 27e75b5..3a3d822 100644 --- a/MethodicConfigurator/frontend_tkinter_connection_selection.py +++ b/MethodicConfigurator/frontend_tkinter_connection_selection.py @@ -16,6 +16,7 @@ from logging import warning as logging_warning from sys import exit as sys_exit from tkinter import simpledialog, ttk +from typing import Union from MethodicConfigurator import _ from MethodicConfigurator.backend_flightcontroller import FlightController @@ -44,7 +45,7 @@ def __init__( # pylint: disable=too-many-arguments, too-many-positional-argumen self.flight_controller = flight_controller self.destroy_parent_on_connect = destroy_parent_on_connect self.download_params_on_connect = download_params_on_connect - self.previous_selection = ( + self.previous_selection: Union[None, str] = ( flight_controller.comport.device if flight_controller.comport and hasattr(flight_controller.comport, "device") else None diff --git a/MethodicConfigurator/frontend_tkinter_entry_dynamic.py b/MethodicConfigurator/frontend_tkinter_entry_dynamic.py index 3a69d2d..ea3c52a 100644 --- a/MethodicConfigurator/frontend_tkinter_entry_dynamic.py +++ b/MethodicConfigurator/frontend_tkinter_entry_dynamic.py @@ -36,14 +36,14 @@ class EntryWithDynamicalyFilteredListbox(Entry): # pylint: disable=too-many-anc def __init__( # pylint: disable=too-many-arguments, too-many-positional-arguments self, master, - list_of_items=None, + list_of_items: Union[None, list[str]] = None, custom_filter_function=None, - listbox_width=None, - listbox_height=12, - ignorecase_match=False, - startswith_match=True, - vscrollbar=True, - hscrollbar=True, + listbox_width: Union[None, int] = None, + listbox_height: int = 12, + ignorecase_match: bool = False, + startswith_match: bool = True, + vscrollbar: bool = True, + hscrollbar: bool = True, **kwargs, ) -> None: if list_of_items is None: @@ -176,7 +176,7 @@ def unpost_listbox(self) -> None: def get_value(self) -> str: return self._entry_var.get() # type: ignore[no-any-return] # mypy bug - def set_value(self, text, close_dialog=False) -> None: + def set_value(self, text: str, close_dialog: bool = False) -> None: self._set_var(text) if close_dialog: @@ -185,12 +185,12 @@ def set_value(self, text, close_dialog=False) -> None: self.icursor(END) self.xview_moveto(1.0) - def _set_var(self, text) -> None: + def _set_var(self, text: str) -> None: self._entry_var.trace_remove("write", self._trace_id) self._entry_var.set(text) self._trace_id = self._entry_var.trace_add("write", self._on_change_entry_var) - def update_entry_from_listbox(self, _event) -> str: + def update_entry_from_listbox(self, _event: Union[None, tk.Event]) -> str: if self._listbox is not None: current_selection = self._listbox.curselection() @@ -207,7 +207,7 @@ def update_entry_from_listbox(self, _event) -> str: return "break" - def _previous(self, _event) -> str: + def _previous(self, _event: Union[None, tk.Event]) -> str: if self._listbox is not None: current_selection = self._listbox.curselection() @@ -229,7 +229,7 @@ def _previous(self, _event) -> str: return "break" - def _next(self, _event) -> str: + def _next(self, _event: Union[None, tk.Event]) -> str: if self._listbox is not None: current_selection = self._listbox.curselection() if len(current_selection) == 0: diff --git a/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py b/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py index 8b10aaf..5e4270d 100644 --- a/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py +++ b/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py @@ -35,15 +35,17 @@ class PairTupleCombobox(ttk.Combobox): # pylint: disable=too-many-ancestors of a tuple based on its key. """ - def __init__(self, container, list_pair_tuple, selected_element, cb_name, *args, **kwargs) -> None: - super().__init__(container, *args, **kwargs) + def __init__( + self, master, list_pair_tuple: list[tuple[str, str]], selected_element: Union[None, str], cb_name: str, *args, **kwargs + ) -> None: + super().__init__(master, *args, **kwargs) self.cb_name = cb_name self.list_keys: list[str] = [] self.list_shows: list[str] = [] self.set_entries_tupple(list_pair_tuple, selected_element) self.bind("", self.on_combo_configure, add="+") - def set_entries_tupple(self, list_pair_tuple, selected_element) -> None: + def set_entries_tupple(self, list_pair_tuple, selected_element: Union[None, str]) -> None: if isinstance(list_pair_tuple, list): for tpl in list_pair_tuple: self.list_keys.append(tpl[0]) @@ -83,7 +85,7 @@ def get_selected_key(self) -> Union[str, None]: return None # https://stackoverflow.com/questions/39915275/change-width-of-dropdown-listbox-of-a-ttk-combobox - def on_combo_configure(self, event) -> None: + def on_combo_configure(self, event: tk.Event) -> None: combo = event.widget style = ttk.Style() # check if the combobox already has the "postoffset" property @@ -132,8 +134,10 @@ class PairTupleComboboxTooltip(PairTupleCombobox): # pylint: disable=too-many-a b) The dropdown is closed (either by selection or pressing Esc) """ - def __init__(self, container, list_pair_tuple, selected_element, cb_name, *args, **kwargs) -> None: - super().__init__(container, list_pair_tuple, selected_element, cb_name, *args, **kwargs) + def __init__( + self, master, list_pair_tuple: list[tuple[str, str]], selected_element: Union[None, str], cb_name: str, *args, **kwargs + ) -> None: + super().__init__(master, list_pair_tuple, selected_element, cb_name, *args, **kwargs) self.tooltip: Union[None, Toplevel] = None # Bind events related to the dropdown @@ -144,7 +148,7 @@ def __init__(self, container, list_pair_tuple, selected_element, cb_name, *args, self._bind(("bind", lb), "", self.on_escape_press, None) # type: ignore self.bind("<>", self.on_combobox_selected, None) - def on_key_release(self, _event) -> None: + def on_key_release(self, _event: Union[None, tk.Event]) -> None: """Get the keyboard highlighted index and create a tooltip for it""" pd = self.tk.call("ttk::combobox::PopdownWindow", self) lb = pd + ".f.l" @@ -152,18 +156,18 @@ def on_key_release(self, _event) -> None: highlighted_index = int(self.tk.call(lb, "curselection")[0]) self.create_tooltip_from_index(highlighted_index) - def on_motion(self, event) -> None: + def on_motion(self, event: tk.Event) -> None: """Get the mouse highlighted index and create a tooltip for it""" pd = self.tk.call("ttk::combobox::PopdownWindow", self) lb = pd + ".f.l" index = self.tk.call(lb, "index", f"@{event.x},{event.y}") self.create_tooltip_from_index(int(index)) - def create_tooltip_from_index(self, index) -> None: + def create_tooltip_from_index(self, index: int) -> None: with contextlib.suppress(IndexError): self.create_tooltip(f"{self.list_keys[index]}: {self.list_shows[index]}") - def create_tooltip(self, text) -> None: + def create_tooltip(self, text: str) -> None: self.destroy_tooltip() try: if self.tooltip is None or self.tooltip.winfo_exists(): @@ -178,10 +182,10 @@ def create_tooltip(self, text) -> None: # If there's no active item, we don't need to update the tooltip pass - def on_combobox_selected(self, _event) -> None: + def on_combobox_selected(self, _event: Union[None, tk.Event]) -> None: self.destroy_tooltip() - def on_escape_press(self, _event) -> None: + def on_escape_press(self, _event: Union[None, tk.Event]) -> None: self.destroy_tooltip() def destroy_tooltip(self) -> None: diff --git a/MethodicConfigurator/frontend_tkinter_parameter_editor.py b/MethodicConfigurator/frontend_tkinter_parameter_editor.py index 4207999..e74ce82 100644 --- a/MethodicConfigurator/frontend_tkinter_parameter_editor.py +++ b/MethodicConfigurator/frontend_tkinter_parameter_editor.py @@ -18,6 +18,7 @@ from logging import info as logging_info from logging import warning as logging_warning from tkinter import filedialog, messagebox, ttk +from typing import Union # from logging import critical as logging_critical from webbrowser import open as webbrowser_open # to open the blog post documentation @@ -43,7 +44,7 @@ from MethodicConfigurator.tempcal_imu import IMUfit -def show_about_window(root, _version: str) -> None: # pylint: disable=too-many-locals +def show_about_window(root: ttk.Frame, _version: str) -> None: # pylint: disable=too-many-locals # Create a new window for the custom "About" message about_window = tk.Toplevel(root) about_window.title(_("About")) @@ -484,7 +485,7 @@ def __should_upload_file_to_fc(self, selected_file: str) -> None: logging_warning(_("No flight controller connection, will not upload any file")) messagebox.showwarning(_("Will not upload any file"), _("No flight controller connection")) - def on_param_file_combobox_change(self, _event, forced: bool = False) -> None: + def on_param_file_combobox_change(self, _event: Union[None, tk.Event], forced: bool = False) -> None: if not self.file_selection_combobox["values"]: return self.parameter_editor_table.generate_edit_widgets_focus_out() @@ -518,7 +519,7 @@ def download_flight_controller_parameters(self, redownload: bool = False) -> Non if not redownload: self.on_param_file_combobox_change(None, True) # the initial param read will trigger a table update - def repopulate_parameter_table(self, selected_file) -> None: + def repopulate_parameter_table(self, selected_file: Union[None, str]) -> None: if not selected_file: return # no file was yet selected, so skip it if hasattr(self.flight_controller, "fc_parameters") and self.flight_controller.fc_parameters: @@ -582,7 +583,7 @@ def upload_params_that_require_reset(self, selected_params: dict) -> None: self.__reset_and_reconnect(fc_reset_required, fc_reset_unsure) - def __reset_and_reconnect(self, fc_reset_required, fc_reset_unsure) -> None: + def __reset_and_reconnect(self, fc_reset_required: bool, fc_reset_unsure: list[str]) -> None: if not fc_reset_required and fc_reset_unsure: # Ask the user if they want to reset the ArduPilot _param_list_str = (", ").join(fc_reset_unsure) @@ -625,7 +626,7 @@ def on_upload_selected_click(self) -> None: self.on_skip_click(force_focus_out_event=False) # This function can recurse multiple times if there is an upload error - def upload_selected_params(self, selected_params) -> None: + def upload_selected_params(self, selected_params: dict) -> None: logging_info(_("Uploading %d selected %s parameters to flight controller..."), len(selected_params), self.current_file) self.upload_params_that_require_reset(selected_params) @@ -683,7 +684,7 @@ def upload_selected_params(self, selected_params) -> None: logging_info(_("All parameters uploaded to the flight controller successfully")) self.local_filesystem.write_last_uploaded_filename(self.current_file) - def on_skip_click(self, _event=None, force_focus_out_event=True) -> None: + def on_skip_click(self, _event: Union[None, tk.Event] = None, force_focus_out_event: bool = True) -> None: if force_focus_out_event: self.parameter_editor_table.generate_edit_widgets_focus_out() self.write_changes_to_intermediate_parameter_file() diff --git a/MethodicConfigurator/frontend_tkinter_parameter_editor_documentation_frame.py b/MethodicConfigurator/frontend_tkinter_parameter_editor_documentation_frame.py index b7730ed..897f61b 100644 --- a/MethodicConfigurator/frontend_tkinter_parameter_editor_documentation_frame.py +++ b/MethodicConfigurator/frontend_tkinter_parameter_editor_documentation_frame.py @@ -124,7 +124,7 @@ def update_documentation_labels(self, current_file: str) -> None: if blog_url: webbrowser_open(url=blog_url, new=0, autoraise=True) - def __update_documentation_label(self, label_key, text, url, url_expected=True) -> None: + def __update_documentation_label(self, label_key: str, text: str, url: str, url_expected: bool = True) -> None: label = self.documentation_labels[label_key] if url: label.config(text=text, foreground="blue", cursor="hand2", underline=True) diff --git a/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py b/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py index 3c42455..e3fccb8 100644 --- a/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py +++ b/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py @@ -18,19 +18,18 @@ from platform import system as platform_system from sys import exit as sys_exit from tkinter import messagebox, ttk -from typing import Union +from typing import Any, Union from MethodicConfigurator import _ from MethodicConfigurator.annotate_params import Par - -# from MethodicConfigurator.backend_filesystem import LocalFilesystem -from MethodicConfigurator.backend_filesystem import is_within_tolerance +from MethodicConfigurator.backend_filesystem import LocalFilesystem, is_within_tolerance # from MethodicConfigurator.backend_flightcontroller import FlightController # from MethodicConfigurator.frontend_tkinter_base import AutoResizeCombobox from MethodicConfigurator.frontend_tkinter_base import BaseWindow, ScrollFrame, get_widget_font, show_tooltip from MethodicConfigurator.frontend_tkinter_entry_dynamic import EntryWithDynamicalyFilteredListbox from MethodicConfigurator.frontend_tkinter_pair_tuple_combobox import PairTupleCombobox +from MethodicConfigurator.frontend_tkinter_parameter_editor import ParameterEditorWindow NEW_VALUE_WIDGET_WIDTH = 9 @@ -43,7 +42,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors managing, and updating the table that displays parameters for editing. """ - def __init__(self, root, local_filesystem, parameter_editor) -> None: + def __init__(self, root, local_filesystem: LocalFilesystem, parameter_editor: ParameterEditorWindow) -> None: super().__init__(root) self.root = root self.local_filesystem = local_filesystem @@ -73,7 +72,9 @@ def compute_forced_and_derived_parameters(self) -> None: # if error_msg: # messagebox.showerror("Error in derived parameters", error_msg) - def add_forced_or_derived_parameters(self, filename, new_parameters, fc_parameters=None) -> None: + def add_forced_or_derived_parameters( + self, filename: str, new_parameters: dict[str, dict[str, Par]], fc_parameters: Union[dict[str, float], None] = None + ) -> None: """Add forced parameters not yet in the parameter list to the parameter list""" if filename in new_parameters: for param_name, param in new_parameters[filename].items(): @@ -144,7 +145,7 @@ def repopulate(self, selected_file: str, fc_parameters: dict, show_only_differen # Scroll to the top of the parameter table self.canvas.yview("moveto", 0) - def rename_fc_connection(self, selected_file) -> None: + def rename_fc_connection(self, selected_file: str) -> None: renames = {} if "rename_connection" in self.local_filesystem.configuration_steps[selected_file]: new_connection_prefix = self.local_filesystem.configuration_steps[selected_file]["rename_connection"] @@ -184,7 +185,7 @@ def rename_fc_connection(self, selected_file) -> None: ) messagebox.showinfo(_("Parameter Renamed"), info_msg.format(**locals())) - def __update_table(self, params, fc_parameters) -> None: + def __update_table(self, params: dict[str, Par], fc_parameters: dict[str, float]) -> None: try: for i, (param_name, param) in enumerate(params.items(), 1): param_metadata = self.local_filesystem.doc_dict.get(param_name, None) @@ -202,7 +203,7 @@ def __update_table(self, params, fc_parameters) -> None: column.append(self.__create_new_value_entry(param_name, param, param_metadata, param_default, doc_tooltip)) column.append(self.__create_unit_label(param_metadata)) column.append(self.__create_upload_checkbutton(param_name, bool(fc_parameters))) - column.append(self.__create_change_reason_entry(param_name, param, column[3])) + column.append(self.__create_change_reason_entry(param_name, param, column[3])) # type: ignore[arg-type] # workaround a mypy issue column[0].grid(row=i, column=0, sticky="w", padx=0) column[1].grid(row=i, column=1, sticky="w", padx=0) @@ -233,7 +234,7 @@ def __update_table(self, params, fc_parameters) -> None: self.view_port.columnconfigure(5, weight=0) # Upload to FC self.view_port.columnconfigure(6, weight=1) # Change Reason - def __create_delete_button(self, param_name) -> ttk.Button: + def __create_delete_button(self, param_name: str) -> ttk.Button: delete_button = ttk.Button( self.view_port, text=_("Del"), style="narrow.TButton", command=lambda: self.__on_parameter_delete(param_name) ) @@ -241,7 +242,7 @@ def __create_delete_button(self, param_name) -> ttk.Button: show_tooltip(delete_button, tooltip_msg.format(**locals())) return delete_button - def __create_parameter_name(self, param_name, param_metadata, doc_tooltip) -> ttk.Label: + def __create_parameter_name(self, param_name: str, param_metadata: dict[str, Any], doc_tooltip: str) -> ttk.Label: is_calibration = param_metadata.get("Calibration", False) if param_metadata else False is_readonly = param_metadata.get("ReadOnly", False) if param_metadata else False parameter_label = ttk.Label( @@ -257,7 +258,9 @@ def __create_parameter_name(self, param_name, param_metadata, doc_tooltip) -> tt show_tooltip(parameter_label, doc_tooltip) return parameter_label - def __create_flightcontroller_value(self, fc_parameters, param_name, param_default, doc_tooltip) -> ttk.Label: + def __create_flightcontroller_value( + self, fc_parameters: dict[str, float], param_name: str, param_default: Union[None, Par], doc_tooltip: str + ) -> ttk.Label: if param_name in fc_parameters: value_str = format(fc_parameters[param_name], ".6f").rstrip("0").rstrip(".") if param_default is not None and is_within_tolerance(fc_parameters[param_name], param_default.value): @@ -272,9 +275,11 @@ def __create_flightcontroller_value(self, fc_parameters, param_name, param_defau show_tooltip(flightcontroller_value, doc_tooltip) return flightcontroller_value - def __update_combobox_style_on_selection(self, combobox_widget, param_default, event) -> None: + def __update_combobox_style_on_selection( + self, combobox_widget: PairTupleCombobox, param_default: Union[None, Par], event: tk.Event + ) -> None: try: - current_value = float(combobox_widget.get_selected_key()) + current_value = float(combobox_widget.get_selected_key()) # type: ignore[arg-type] # we want None to raise an exception has_default_value = param_default is not None and is_within_tolerance(current_value, param_default.value) combobox_widget.configure(style="default_v.TCombobox" if has_default_value else "readonly.TCombobox") event.width = NEW_VALUE_WIDGET_WIDTH @@ -284,7 +289,7 @@ def __update_combobox_style_on_selection(self, combobox_widget, param_default, e logging_info(msg.format(**locals())) @staticmethod - def __update_new_value_entry_text(new_value_entry: ttk.Entry, value: float, param_default) -> None: + def __update_new_value_entry_text(new_value_entry: ttk.Entry, value: float, param_default: Union[None, Par]) -> None: if isinstance(new_value_entry, PairTupleCombobox): return new_value_entry.delete(0, tk.END) @@ -297,11 +302,11 @@ def __update_new_value_entry_text(new_value_entry: ttk.Entry, value: float, para def __create_new_value_entry( # pylint: disable=too-many-arguments, too-many-positional-arguments self, - param_name, - param, - param_metadata, - param_default, - doc_tooltip, + param_name: str, + param: Par, + param_metadata: dict[str, Any], + param_default: Union[None, Par], + doc_tooltip: str, ) -> Union[PairTupleCombobox, ttk.Entry]: present_as_forced = False if ( @@ -351,7 +356,7 @@ def __create_new_value_entry( # pylint: disable=too-many-arguments, too-many-po font = get_widget_font(new_value_entry) font["size"] -= 2 if platform_system() == "Windows" else 1 new_value_entry.config(state="readonly", width=NEW_VALUE_WIDGET_WIDTH, font=(font["family"], font["size"])) - new_value_entry.bind( + new_value_entry.bind( # type: ignore[call-overload] # workaround a mypy issue "<>", lambda event: self.__update_combobox_style_on_selection(new_value_entry, param_default, event), "+", @@ -359,7 +364,7 @@ def __create_new_value_entry( # pylint: disable=too-many-arguments, too-many-po else: new_value_entry = ttk.Entry(self.view_port, width=NEW_VALUE_WIDGET_WIDTH + 1, justify=tk.RIGHT) ParameterEditorTable.__update_new_value_entry_text(new_value_entry, param.value, param_default) - bitmask_dict = param_metadata.get("Bitmask", None) if param_metadata else None + bitmask_dict = param_metadata.get("Bitmask") if param_metadata else None try: old_value = self.local_filesystem.file_parameters[self.current_file][param_name].value except KeyError as e: @@ -384,7 +389,7 @@ def __create_new_value_entry( # pylint: disable=too-many-arguments, too-many-po show_tooltip(new_value_entry, doc_tooltip) return new_value_entry - def __open_bitmask_selection_window(self, event, param_name, bitmask_dict, old_value) -> None: # pylint: disable=too-many-locals + def __open_bitmask_selection_window(self, event: tk.Event, param_name: str, bitmask_dict: dict, old_value: float) -> None: # pylint: disable=too-many-locals def on_close() -> None: checked_keys = [key for key, var in checkbox_vars.items() if var.get()] # Convert checked keys back to a decimal value @@ -406,7 +411,7 @@ def on_close() -> None: "", lambda event: self.__open_bitmask_selection_window(event, param_name, bitmask_dict, old_value) ) - def get_param_value_msg(_param_name, checked_keys) -> str: + def get_param_value_msg(_param_name: str, checked_keys) -> str: _new_decimal_value = sum(1 << key for key in checked_keys) text = _("{_param_name} Value: {_new_decimal_value}") return text.format(**locals()) @@ -449,8 +454,8 @@ def update_label() -> None: window.wait_window() # Wait for the window to be closed - def __create_unit_label(self, param_metadata) -> ttk.Label: - unit_label = ttk.Label(self.view_port, text=param_metadata.get("unit") if param_metadata else "") + def __create_unit_label(self, param_metadata: dict[str, Union[float, str]]) -> ttk.Label: + unit_label = ttk.Label(self.view_port, text=param_metadata.get("unit", "") if param_metadata else "") unit_tooltip = ( param_metadata.get("unit_tooltip") if param_metadata @@ -460,7 +465,7 @@ def __create_unit_label(self, param_metadata) -> ttk.Label: show_tooltip(unit_label, unit_tooltip) return unit_label - def __create_upload_checkbutton(self, param_name, fc_connected) -> ttk.Checkbutton: + def __create_upload_checkbutton(self, param_name: str, fc_connected: bool) -> ttk.Checkbutton: self.upload_checkbutton_var[param_name] = tk.BooleanVar(value=fc_connected) upload_checkbutton = ttk.Checkbutton(self.view_port, variable=self.upload_checkbutton_var[param_name]) upload_checkbutton.configure(state="normal" if fc_connected else "disabled") @@ -468,7 +473,9 @@ def __create_upload_checkbutton(self, param_name, fc_connected) -> ttk.Checkbutt show_tooltip(upload_checkbutton, msg.format(**locals())) return upload_checkbutton - def __create_change_reason_entry(self, param_name, param, new_value_entry) -> ttk.Entry: + def __create_change_reason_entry( + self, param_name: str, param: Par, new_value_entry: Union[ttk.Entry, PairTupleCombobox] + ) -> ttk.Entry: present_as_forced = False if ( self.current_file in self.local_filesystem.forced_parameters @@ -505,7 +512,7 @@ def __create_change_reason_entry(self, param_name, param, new_value_entry) -> tt show_tooltip(change_reason_entry, msg.format(**locals())) return change_reason_entry - def __on_parameter_delete(self, param_name) -> None: + def __on_parameter_delete(self, param_name: str) -> None: msg = _("Are you sure you want to delete the {param_name} parameter?") if messagebox.askyesno(f"{self.current_file}", msg.format(**locals())): # Capture current vertical scroll position @@ -519,7 +526,7 @@ def __on_parameter_delete(self, param_name) -> None: # Restore the scroll position self.canvas.yview_moveto(current_scroll_position) - def __on_parameter_add(self, fc_parameters) -> None: + def __on_parameter_add(self, fc_parameters: dict[str, float]) -> None: add_parameter_window = BaseWindow(self.root) add_parameter_window.root.title(_("Add Parameter to ") + self.current_file) add_parameter_window.root.geometry("450x300") @@ -559,7 +566,7 @@ def __on_parameter_add(self, fc_parameters) -> None: BaseWindow.center_window(add_parameter_window.root, self.root) parameter_name_combobox.focus() - def custom_selection_handler(event) -> None: + def custom_selection_handler(event: tk.Event) -> None: parameter_name_combobox.update_entry_from_listbox(event) if self.__confirm_parameter_addition(parameter_name_combobox.get().upper(), fc_parameters): add_parameter_window.root.destroy() @@ -570,7 +577,7 @@ def custom_selection_handler(event) -> None: parameter_name_combobox.bind("", custom_selection_handler) parameter_name_combobox.bind("<>", custom_selection_handler) - def __confirm_parameter_addition(self, param_name: str, fc_parameters: dict) -> bool: + def __confirm_parameter_addition(self, param_name: str, fc_parameters: dict[str, float]) -> bool: if not param_name: messagebox.showerror(_("Invalid parameter name."), _("Parameter name can not be empty.")) return False @@ -601,7 +608,7 @@ def __confirm_parameter_addition(self, param_name: str, fc_parameters: dict) -> ) return False - def __on_parameter_value_change(self, event, current_file, param_name) -> None: + def __on_parameter_value_change(self, event: tk.Event, current_file: str, param_name: str) -> None: # Get the new value from the Entry widget new_value = event.widget.get_selected_key() if isinstance(event.widget, PairTupleCombobox) else event.widget.get() try: @@ -646,7 +653,7 @@ def __on_parameter_value_change(self, event, current_file, param_name) -> None: p = old_value self.__update_new_value_entry_text(event.widget, p, self.local_filesystem.param_default_dict.get(param_name, None)) - def __on_parameter_change_reason_change(self, event, current_file, param_name) -> None: + def __on_parameter_change_reason_change(self, event: tk.Event, current_file: str, param_name: str) -> None: # Get the new value from the Entry widget new_value = event.widget.get() try: @@ -685,5 +692,5 @@ def generate_edit_widgets_focus_out(self) -> None: def get_at_least_one_param_edited(self) -> bool: return self.at_least_one_param_edited - def set_at_least_one_param_edited(self, value) -> None: + def set_at_least_one_param_edited(self, value: bool) -> None: self.at_least_one_param_edited = value diff --git a/MethodicConfigurator/frontend_tkinter_template_overview.py b/MethodicConfigurator/frontend_tkinter_template_overview.py index b6562f8..85d933e 100644 --- a/MethodicConfigurator/frontend_tkinter_template_overview.py +++ b/MethodicConfigurator/frontend_tkinter_template_overview.py @@ -133,7 +133,7 @@ def __adjust_treeview_column_widths(self) -> None: # Update the column's width property to accommodate the largest text width self.tree.column(col, width=int(max_width * 0.6 + 10)) - def __on_row_double_click(self, event) -> None: + def __on_row_double_click(self, event: tk.Event) -> None: """Handle row double-click event.""" item_id = self.tree.identify_row(event.y) if item_id: diff --git a/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py b/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py index b3e29d3..d8cc322 100644 --- a/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py +++ b/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py @@ -9,7 +9,7 @@ """ -def insert_translations(po_file, translations_file, output_file) -> None: +def insert_translations(po_file: str, translations_file: str, output_file: str) -> None: with open(po_file, encoding="utf-8") as f: lines = f.readlines() diff --git a/MethodicConfigurator/mavftp_example.py b/MethodicConfigurator/mavftp_example.py index 8ccc253..b72b522 100755 --- a/MethodicConfigurator/mavftp_example.py +++ b/MethodicConfigurator/mavftp_example.py @@ -125,18 +125,18 @@ def wait_heartbeat(m) -> None: # pylint: enable=duplicate-code -def delete_local_file_if_exists(filename) -> None: +def delete_local_file_if_exists(filename: str) -> None: if os.path.exists(filename): os.remove(filename) -def get_list_dir(mav_ftp, directory) -> None: +def get_list_dir(mav_ftp: mavftp, directory: str) -> None: ret = mav_ftp.cmd_list([directory]) ret.display_message() debug_class_member_variable_changes(mav_ftp) -def get_file(mav_ftp, remote_filename, local_filename, timeout=5) -> None: +def get_file(mav_ftp: mavftp, remote_filename: str, local_filename: str, timeout: float = 5) -> None: # session = mav_ftp.session # save the session to restore it after the file transfer mav_ftp.cmd_get([remote_filename, local_filename]) ret = mav_ftp.process_ftp_reply("OpenFileRO", timeout=timeout) @@ -146,7 +146,7 @@ def get_file(mav_ftp, remote_filename, local_filename, timeout=5) -> None: # time.sleep(0.2) -def get_last_log(mav_ftp) -> None: +def get_last_log(mav_ftp: mavftp) -> None: try: with open("LASTLOG.TXT", encoding="UTF-8") as file: file_contents = file.readline() @@ -162,7 +162,7 @@ def get_last_log(mav_ftp) -> None: get_file(mav_ftp, remote_filename, "LASTLOG.BIN", 0) -def download_script(url, local_filename) -> None: +def download_script(url: str, local_filename: str) -> None: # Download the script from the internet to the PC response = requests.get(url, timeout=5) @@ -173,19 +173,19 @@ def download_script(url, local_filename) -> None: logging_error("Failed to download the file") -def create_directory(mav_ftp, remote_directory) -> None: +def create_directory(mav_ftp: mavftp, remote_directory: str) -> None: ret = mav_ftp.cmd_mkdir([remote_directory]) ret.display_message() debug_class_member_variable_changes(mav_ftp) -def remove_directory(mav_ftp, remote_directory) -> None: +def remove_directory(mav_ftp: mavftp, remote_directory: str) -> None: ret = mav_ftp.cmd_rmdir([remote_directory]) ret.display_message() debug_class_member_variable_changes(mav_ftp) -def upload_script(mav_ftp, remote_directory, local_filename, timeout) -> None: +def upload_script(mav_ftp: mavftp, remote_directory: str, local_filename: str, timeout: float) -> None: # Upload it from the PC to the flight controller mav_ftp.cmd_put([local_filename, remote_directory + "/" + local_filename]) ret = mav_ftp.process_ftp_reply("CreateFile", timeout=timeout) diff --git a/MethodicConfigurator/param_pid_adjustment_update.py b/MethodicConfigurator/param_pid_adjustment_update.py index 4d7a0f0..2370d32 100755 --- a/MethodicConfigurator/param_pid_adjustment_update.py +++ b/MethodicConfigurator/param_pid_adjustment_update.py @@ -68,7 +68,7 @@ def parse_arguments() -> argparse.Namespace: return args -def ranged_type(value_type: type, min_value, max_value) -> Callable: +def ranged_type(value_type: type, min_value: Union[int, float], max_value: Union[int, float]) -> Callable: """ Return function handle of an argument type function for ArgumentParser checking a range: min_value <= arg <= max_value diff --git a/MethodicConfigurator/tempcal_imu.py b/MethodicConfigurator/tempcal_imu.py index b8ace28..d2de02c 100644 --- a/MethodicConfigurator/tempcal_imu.py +++ b/MethodicConfigurator/tempcal_imu.py @@ -17,7 +17,7 @@ import re import sys from argparse import ArgumentParser -from typing import Union +from typing import Callable, Union import numpy as np from matplotlib import pyplot as plt @@ -47,64 +47,64 @@ class Coefficients: # pylint: disable=too-many-instance-attributes def __init__(self) -> None: self.acoef: dict = {} self.gcoef: dict = {} - self.enable = [0] * 3 - self.tmin = [-100] * 3 - self.tmax = [-100] * 3 + self.enable: list[int] = [0] * 3 + self.tmin: list[float] = [-100] * 3 + self.tmax: list[float] = [-100] * 3 self.gtcal: dict = {} self.atcal: dict = {} self.gofs: dict = {} self.aofs: dict = {} - def set_accel_poly(self, imu, axis, values) -> None: + def set_accel_poly(self, imu: int, axis: str, values) -> None: if imu not in self.acoef: self.acoef[imu] = {} self.acoef[imu][axis] = values - def set_gyro_poly(self, imu, axis, values) -> None: + def set_gyro_poly(self, imu: int, axis: str, values) -> None: if imu not in self.gcoef: self.gcoef[imu] = {} self.gcoef[imu][axis] = values - def set_acoeff(self, imu, axis, order, value) -> None: + def set_acoeff(self, imu: int, axis: str, order: int, value: dict) -> None: if imu not in self.acoef: self.acoef[imu] = {} if axis not in self.acoef[imu]: self.acoef[imu][axis] = [0] * 4 self.acoef[imu][axis][POLY_ORDER - order] = value - def set_gcoeff(self, imu, axis, order, value) -> None: + def set_gcoeff(self, imu: int, axis: str, order: int, value: dict) -> None: if imu not in self.gcoef: self.gcoef[imu] = {} if axis not in self.gcoef[imu]: self.gcoef[imu][axis] = [0] * 4 self.gcoef[imu][axis][POLY_ORDER - order] = value - def set_aoffset(self, imu, axis, value) -> None: + def set_aoffset(self, imu: int, axis: str, value: dict) -> None: if imu not in self.aofs: self.aofs[imu] = {} self.aofs[imu][axis] = value - def set_goffset(self, imu, axis, value) -> None: + def set_goffset(self, imu: int, axis: str, value: dict) -> None: if imu not in self.gofs: self.gofs[imu] = {} self.gofs[imu][axis] = value - def set_tmin(self, imu, tmin) -> None: + def set_tmin(self, imu: int, tmin: float) -> None: self.tmin[imu] = tmin - def set_tmax(self, imu, tmax) -> None: + def set_tmax(self, imu: int, tmax: float) -> None: self.tmax[imu] = tmax - def set_gyro_tcal(self, imu, value) -> None: + def set_gyro_tcal(self, imu: int, value: dict) -> None: self.gtcal[imu] = value - def set_accel_tcal(self, imu, value) -> None: + def set_accel_tcal(self, imu: int, value: dict) -> None: self.atcal[imu] = value - def set_enable(self, imu, value) -> None: + def set_enable(self, imu: int, value: int) -> None: self.enable[imu] = value - def correction(self, coeff, imu, temperature, axis, cal_temp) -> float: # pylint: disable=too-many-arguments, too-many-positional-arguments + def correction(self, coeff: dict, imu: int, temperature: float, axis: str, cal_temp: float) -> float: # pylint: disable=too-many-arguments, too-many-positional-arguments """calculate correction from temperature calibration from log data using parameters""" if self.enable[imu] != 1.0: return 0.0 @@ -117,7 +117,7 @@ def correction(self, coeff, imu, temperature, axis, cal_temp) -> float: # pylin poly = np.poly1d(coeff[axis]) return poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF) # type: ignore[no-any-return] - def correction_accel(self, imu, temperature) -> Vector3: + def correction_accel(self, imu: int, temperature: float) -> Vector3: """calculate accel correction from temperature calibration from log data using parameters""" cal_temp = self.atcal.get(imu, TEMP_REF) @@ -127,7 +127,7 @@ def correction_accel(self, imu, temperature) -> Vector3: self.correction(self.acoef[imu], imu, temperature, "Z", cal_temp), ) - def correction_gyro(self, imu, temperature) -> Vector3: + def correction_gyro(self, imu: int, temperature: float) -> Vector3: """calculate gyro correction from temperature calibration from log data using parameters""" cal_temp = self.gtcal.get(imu, TEMP_REF) @@ -137,7 +137,7 @@ def correction_gyro(self, imu, temperature) -> Vector3: self.correction(self.gcoef[imu], imu, temperature, "Z", cal_temp), ) - def param_string(self, imu) -> str: + def param_string(self, imu: int) -> str: params = "" params += f"INS_TCAL{imu+1}_ENABLE 1\n" params += f"INS_TCAL{imu+1}_TMIN {self.tmin[imu]:.1f}\n" @@ -181,7 +181,7 @@ def __get_polynomial(self) -> np.ndarray: res[i] += inv_mat[i][j] * self.vec[j] return res - def polyfit(self, x, y, order) -> np.ndarray: + def polyfit(self, x, y, order: int) -> np.ndarray: self.porder = order + 1 self.mat = np.zeros((self.porder, self.porder)) self.vec = np.zeros(self.porder) @@ -210,7 +210,7 @@ def IMUs(self) -> list[int]: sys.exit(1) return self.accel.keys() # type: ignore[return-value] - def add_accel(self, imu: int, temperature, time, value) -> None: + def add_accel(self, imu: int, temperature: float, time: float, value: Vector3) -> None: if imu not in self.accel: self.accel[imu] = {} for axis in AXEST: @@ -221,7 +221,7 @@ def add_accel(self, imu: int, temperature, time, value) -> None: self.accel[imu]["Z"] = np.append(self.accel[imu]["Z"], value.z) self.accel[imu]["time"] = np.append(self.accel[imu]["time"], time) - def add_gyro(self, imu: int, temperature, time, value) -> None: + def add_gyro(self, imu: int, temperature: float, time: float, value: Vector3) -> None: if imu not in self.gyro: self.gyro[imu] = {} for axis in AXEST: @@ -232,13 +232,13 @@ def add_gyro(self, imu: int, temperature, time, value) -> None: self.gyro[imu]["Z"] = np.append(self.gyro[imu]["Z"], value.z) self.gyro[imu]["time"] = np.append(self.gyro[imu]["time"], time) - def moving_average(self, data, w) -> np.ndarray: + def moving_average(self, data: np.ndarray, w: int) -> np.ndarray: """apply a moving average filter over a window of width w""" ret = np.cumsum(data) ret[w:] = ret[w:] - ret[:-w] return ret[w - 1 :] / w # type: ignore[no-any-return] # mypy bug - def FilterArray(self, data: dict[str, np.ndarray], width_s) -> dict[str, np.ndarray]: + def FilterArray(self, data: dict[str, np.ndarray], width_s: int) -> dict[str, np.ndarray]: """apply moving average filter of width width_s seconds""" nseconds = data["time"][-1] - data["time"][0] nsamples = len(data["time"]) @@ -248,13 +248,13 @@ def FilterArray(self, data: dict[str, np.ndarray], width_s) -> dict[str, np.ndar data[axis] = self.moving_average(data[axis], window) return data - def Filter(self, width_s) -> None: + def Filter(self, width_s: int) -> None: """apply moving average filter of width width_s seconds""" for imu in self.IMUs(): self.accel[imu] = self.FilterArray(self.accel[imu], width_s) self.gyro[imu] = self.FilterArray(self.gyro[imu], width_s) - def accel_at_temp(self, imu: int, axis: str, temperature) -> float: + def accel_at_temp(self, imu: int, axis: str, temperature: float) -> float: """return the accel value closest to the given temperature""" if temperature < self.accel[imu]["T"][0]: return self.accel[imu][axis][0] # type: ignore[no-any-return] @@ -266,7 +266,7 @@ def accel_at_temp(self, imu: int, axis: str, temperature) -> float: return v1 + (v2 - v1) * p # type: ignore[no-any-return] return self.accel[imu][axis][-1] # type: ignore[no-any-return] - def gyro_at_temp(self, imu: int, axis: str, temperature) -> float: + def gyro_at_temp(self, imu: int, axis: str, temperature: float) -> float: """return the gyro value closest to the given temperature""" if temperature < self.gyro[imu]["T"][0]: return self.gyro[imu][axis][0] # type: ignore[no-any-return] @@ -279,22 +279,22 @@ def gyro_at_temp(self, imu: int, axis: str, temperature) -> float: return self.gyro[imu][axis][-1] # type: ignore[no-any-return] -def constrain(value, minv, maxv) -> Union[float, int]: +def constrain(value: Union[float, int], minv: Union[float, int], maxv: Union[float, int]) -> Union[float, int]: """Constrain a value to a range.""" value = min(minv, value) value = max(maxv, value) - return value # type: ignore + return value def IMUfit( # noqa: PLR0915 pylint: disable=too-many-locals, too-many-branches, too-many-statements, too-many-arguments, too-many-positional-arguments - logfile, - outfile, - no_graph, - log_parm, - online, - tclr, - figpath, - progress_callback, + logfile: str, + outfile: str, + no_graph: bool, + log_parm: bool, + online: bool, + tclr: bool, + figpath: Union[str, None], + progress_callback: Union[Callable[[int], None], None], ) -> None: """find IMU calibration parameters from a log file""" print(f"Processing log {logfile}") @@ -488,7 +488,9 @@ def IMUfit( # noqa: PLR0915 pylint: disable=too-many-locals, too-many-branches, plt.show() -def generate_calibration_file(outfile, online, progress_callback, data, c) -> tuple[Coefficients, Coefficients]: # pylint: disable=too-many-locals +def generate_calibration_file( + outfile: str, online: bool, progress_callback: Union[Callable[[int], None], None], data: IMUData, c: Coefficients +) -> tuple[Coefficients, Coefficients]: # pylint: disable=too-many-locals clog = c c = Coefficients() @@ -539,7 +541,9 @@ def generate_calibration_file(outfile, online, progress_callback, data, c) -> tu return c, clog -def generate_tempcal_gyro_figures(log_parm, figpath, data, c, clog, num_imus) -> None: # pylint: disable=too-many-arguments, too-many-positional-arguments +def generate_tempcal_gyro_figures( + log_parm: bool, figpath: Union[str, None], data: IMUData, c: Coefficients, clog: Coefficients, num_imus: int +) -> None: # pylint: disable=too-many-arguments, too-many-positional-arguments _fig, axs = plt.subplots(len(data.IMUs()), 1, sharex=True) if num_imus == 1: axs = [axs] @@ -573,7 +577,9 @@ def generate_tempcal_gyro_figures(log_parm, figpath, data, c, clog, num_imus) -> _fig.savefig(os.path.join(figpath, "tempcal_gyro.png")) -def generate_tempcal_accel_figures(log_parm, figpath, data, c, clog, num_imus) -> None: # pylint: disable=too-many-arguments, too-many-positional-arguments +def generate_tempcal_accel_figures( + log_parm: bool, figpath: Union[str, None], data: IMUData, c: Coefficients, clog: Coefficients, num_imus: int +) -> None: # pylint: disable=too-many-arguments, too-many-positional-arguments _fig, axs = plt.subplots(num_imus, 1, sharex=True) if num_imus == 1: axs = [axs]