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

Tempcal imu support #3

Merged
merged 8 commits into from
Apr 19, 2024
4 changes: 4 additions & 0 deletions MethodicConfigurator/backend_filesystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -440,3 +440,7 @@ def valid_directory_name(dir_name: str):
# Include os.sep in the pattern
pattern = r'^[\w' + re_escape(os_sep) + '-]+$'
return re_match(pattern, dir_name) is not None

def tempcal_imu_result_param_tuple(self):
tempcal_imu_result_param_filename = "03_imu_temperature_calibration_results.param"
return [tempcal_imu_result_param_filename, os_path.join(self.vehicle_dir, tempcal_imu_result_param_filename)]
106 changes: 45 additions & 61 deletions MethodicConfigurator/frontend_tkinter.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import tkinter as tk
from tkinter import messagebox
from tkinter import ttk
from tkinter import filedialog

from logging import debug as logging_debug
from logging import info as logging_info
Expand All @@ -36,12 +37,14 @@
from frontend_tkinter_base import show_tooltip
from frontend_tkinter_base import AutoResizeCombobox
from frontend_tkinter_base import ScrollFrame
from frontend_tkinter_base import ProgressWindow
from frontend_tkinter_base import BaseWindow

from frontend_tkinter_connection_selection import ConnectionSelectionWidgets

from frontend_tkinter_directory_selection import VehicleDirectorySelectionWidgets

from tempcal_imu import IMUfit


class DocumentationFrame: # pylint: disable=too-few-public-methods
Expand Down Expand Up @@ -191,25 +194,26 @@ def __init__(self, current_file: str, flight_controller: FlightController,
self.at_least_one_changed_parameter_written = False
self.write_checkbutton_var = {}
self.file_selection_combobox = None
self.documentation_frame = None
self.show_only_differences = None
self.scroll_frame = None
self.reset_progress_window = None
self.reset_progress_bar = None
self.reset_progress_label = None
self.param_read_progress_window = None
self.param_read_progress_bar = None
self.param_read_progress_label = None
self.tempcal_imu_progress_window = None

self.root.title("Amilcar Lucas's - ArduPilot methodic configurator - " + version)
self.root.geometry("880x500") # Set the window width

# Bind the close_connection_and_quit function to the window close event
self.root.protocol("WM_DELETE_WINDOW", self.close_connection_and_quit)

self.__create_widgets(version)
self.__create_conf_widgets(version)

# Create a DocumentationFrame object for the Documentation Content
self.documentation_frame = DocumentationFrame(self.root, self.local_filesystem, self.current_file)

self.__create_parameter_area_widgets()

def __create_widgets(self, version: str): # pylint: disable=too-many-locals, too-many-statements
def __create_conf_widgets(self, version: str): # pylint: disable=too-many-locals
config_frame = tk.Frame(self.root)
config_frame.pack(side=tk.TOP, fill="x", expand=False, pady=(4, 0)) # Pack the frame at the top of the window

Expand Down Expand Up @@ -265,9 +269,7 @@ def __create_widgets(self, version: str): # pylint: disable=too-many-locals, to
image_label.bind("<Button-1>", lambda event: show_about_window(self.root, version))
show_tooltip(image_label, "User Manual, Support Forum, Report a Bug, Credits, Source Code")

# Create a DocumentationFrame object for the Documentation Content
self.documentation_frame = DocumentationFrame(self.root, self.local_filesystem, self.current_file)

def __create_parameter_area_widgets(self):
self.show_only_differences = tk.BooleanVar(value=False)

# Create a Frame for the Scrollable Content
Expand Down Expand Up @@ -304,25 +306,50 @@ def __create_widgets(self, version: str): # pylint: disable=too-many-locals, to
self.root.after(50, self.read_flight_controller_parameters(reread=False)) # 50 milliseconds
self.root.mainloop()

def __do_tempcal_imu(self, selected_file:str):
tempcal_imu_result_param_filename, tempcal_imu_result_param_fullpath = \
self.local_filesystem.tempcal_imu_result_param_tuple()
if selected_file == tempcal_imu_result_param_filename:
if messagebox.askyesno("IMU temperature calibration",
f"If you proceed the {tempcal_imu_result_param_filename}\n"
"will be overwritten with the new calibration results.\n"
"Do you want to provide a .bin log file and\n"
"run the IMU temperature calibration using it?"):
# file selection dialog to select the *.bin file to be used in the IMUfit temperature calibration
filename = filedialog.askopenfilename(filetypes=[("ArduPilot binary log files", ["*.bin", "*.BIN"])])
if filename:
messagebox.showwarning("IMU temperature calibration", "Please wait, this can take a really long time and\n"
"the GUI will be unresponsive until it finishes.")
self.tempcal_imu_progress_window = ProgressWindow(self.root, "Reading IMU calibration messages",
"Please wait, this can take a long time")
# Pass the selected filename to the IMUfit class
IMUfit(filename, tempcal_imu_result_param_fullpath, False, False, False, False,
self.local_filesystem.vehicle_dir, self.tempcal_imu_progress_window.update_progress_bar_300_pct)
self.tempcal_imu_progress_window.destroy()
self.local_filesystem.file_parameters = self.local_filesystem.read_params_from_files()
self.at_least_one_param_edited = True # force writing doc annotations to file

def on_param_file_combobox_change(self, _event, forced: bool = False):
if not self.file_selection_combobox['values']:
return
self.param_edit_widgets_event_generate_focus_out()
selected_file = self.file_selection_combobox.get()
if self.current_file != selected_file or forced:
self.write_changes_to_intermediate_parameter_file()
self.__do_tempcal_imu(selected_file)

# Update the current_file attribute to the selected file
self.current_file = selected_file
self.at_least_one_changed_parameter_written = False
self.documentation_frame.update_documentation_labels(selected_file)
self.repopulate_parameter_table(selected_file)

def read_flight_controller_parameters(self, reread: bool = False):
[self.param_read_progress_window,
self.param_read_progress_bar,
self.param_read_progress_label] = self.create_progress_window(("Re-r" if reread else "R") + "eading FC parameters")
self.param_read_progress_window = ProgressWindow(self.root, ("Re-r" if reread else "R") + "eading FC parameters",
"Read {} of {} parameters")
# Download all parameters from the flight controller
self.flight_controller.fc_parameters = self.flight_controller.read_params(self.update_param_download_progress_bar)
self.flight_controller.fc_parameters = self.flight_controller.read_params(
self.param_read_progress_window.update_progress_bar)
self.param_read_progress_window.destroy() # for the case that we are doing test and there is no real FC connected
if not reread:
self.on_param_file_combobox_change(None, True) # the initial param read will trigger a table update
Expand All @@ -334,7 +361,7 @@ def repopulate_parameter_table(self, selected_file):
fc_parameters = self.flight_controller.fc_parameters
else:
fc_parameters = {}
# Different parameters based on the thresholdfile_value
# Different parameters based on the tolerance value
different_params = {param_name: file_value for param_name, file_value in
self.local_filesystem.file_parameters[selected_file].items()
if param_name not in fc_parameters or (param_name in fc_parameters and \
Expand Down Expand Up @@ -525,48 +552,6 @@ def get_write_selected_params(self):
def on_show_only_changed_checkbox_change(self):
self.repopulate_parameter_table(self.current_file)

def update_reset_progress_bar(self, current_value: int, max_value: int):
"""
Update the FC reset progress bar and the progress message with the current progress.

Args:
current_value (int): The current progress value.
max_value (int): The maximum progress value.
"""
self.reset_progress_window.lift()

self.reset_progress_bar['value'] = current_value
self.reset_progress_bar['maximum'] = max_value
self.reset_progress_bar.update()

# Update the reset progress message
self.reset_progress_label.config(text=f"waiting for {current_value} of {max_value} seconds")

# Close the reset progress window when the process is complete
if current_value == max_value:
self.reset_progress_window.destroy()

def update_param_download_progress_bar(self, current_value: int, max_value: int):
"""
Update the FC parameter read progress bar the progress message with the current progress.

Args:
current_value (int): The current progress value.
max_value (int): The maximum progress value.
"""
self.param_read_progress_window.lift()

self.param_read_progress_bar['value'] = current_value
self.param_read_progress_bar['maximum'] = max_value
self.param_read_progress_bar.update()

# Update the param read progress message
self.param_read_progress_label.config(text=f"Reading parameter {current_value} of {max_value}")

# Close the param read progress window when the process is complete
if current_value == max_value:
self.param_read_progress_window.destroy()

def param_edit_widgets_event_generate_focus_out(self):
# Trigger the <FocusOut> event for all entry widgets to ensure all changes are processed
for widget in self.scroll_frame.view_port.winfo_children():
Expand Down Expand Up @@ -619,11 +604,10 @@ def write_params_that_require_reset(self, selected_params: dict):
"(s) potentially require a reset\nDo you want to reset the ArduPilot?")

if fc_reset_required:
[self.reset_progress_window,
self.reset_progress_bar,
self.reset_progress_label] = self.create_progress_window("Resetting Flight Controller")
self.reset_progress_window = ProgressWindow(self.root, "Resetting Flight Controller",
"Waiting for {} of {} seconds")
# Call reset_and_reconnect with a callback to update the reset progress bar and the progress message
self.flight_controller.reset_and_reconnect(self.update_reset_progress_bar)
self.flight_controller.reset_and_reconnect(self.reset_progress_window.update_progress_bar)
self.reset_progress_window.destroy() # for the case that we are doing test and there is no real FC connected

def on_write_selected_click(self):
Expand Down
86 changes: 66 additions & 20 deletions MethodicConfigurator/frontend_tkinter_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,72 @@ def on_leave(self, _event): # unbind wheel events wh
self.canvas.unbind_all("<MouseWheel>")


class BaseWindow:
class ProgressWindow:
"""
A class for creating and managing a progress window in the application.

This class is responsible for creating a progress window that displays the progress of
a task. It includes a progress bar and a label to display the progress message.
"""
def __init__(self, parent, title, message: str="", width: int=300, height: int=80): # pylint: disable=too-many-arguments
self.parent = parent
self.message = message
self.progress_window = None
self.progress_bar = None
self.progress_label = None
self.__create_progress_window(title, message, width, height)

def __create_progress_window(self, title: str, message, width, height):
self.progress_window = tk.Toplevel(self.parent)
self.progress_window.title(title)
self.progress_window.geometry(f"{width}x{height}")

# Create a progress bar
self.progress_bar = ttk.Progressbar(self.progress_window, length=100, mode='determinate')
self.progress_bar.pack(side=tk.TOP, fill=tk.X, expand=False, padx=(5, 5), pady=(10, 10))

# Create a label to display the progress message
self.progress_label = tk.Label(self.progress_window, text=message.format(0, 0))
self.progress_label.pack(side=tk.TOP, fill=tk.X, expand=False, pady=(10, 10))

self.progress_window.lift()

# Center the progress window on the parent window
BaseWindow.center_window(self.progress_window, self.parent)

self.progress_bar.update()

def update_progress_bar_300_pct(self, percent: int):
self.message = "Please be patient, {:.1f}% of {}% complete"
self.update_progress_bar(percent/3, max_value=100)

def update_progress_bar(self, current_value: int, max_value: int):
"""
Update progress bar and the progress message with the current progress.

Args:
current_value (int): The current progress value.
max_value (int): The maximum progress value, if 0 uses percentage.
"""
self.progress_window.lift()

self.progress_bar['value'] = current_value
self.progress_bar['maximum'] = max_value

# Update the progress message
self.progress_label.config(text=self.message.format(current_value, max_value))

self.progress_bar.update()

# Close the progress window when the process is complete
if current_value == max_value:
self.progress_window.destroy()

def destroy(self):
self.progress_window.destroy()


class BaseWindow: # pylint: disable=too-few-public-methods
"""
A base class for creating windows in the ArduPilot Methodic Configurator application.

Expand Down Expand Up @@ -222,25 +287,6 @@ def __init__(self, root_tk: tk.Tk=None):
style.configure('TCheckbutton', background=self.default_background_color)
style.configure('TCombobox', background=self.default_background_color)

def create_progress_window(self, title: str):
# Create a new window for the param_read progress bar
progress_window = tk.Toplevel(self.root)
progress_window.title(title)
progress_window.geometry("300x80")

# Center the param_read progress window on the main window
BaseWindow.center_window(progress_window, self.root)

# Create a param_read progress bar
progress_bar = ttk.Progressbar(progress_window, length=100, mode='determinate')
progress_bar.pack(side=tk.TOP, fill=tk.X, expand=False, padx=(5, 5), pady=(10, 10))

# Create a param_read label to display the progress message
progress_label = tk.Label(progress_window, text="")
progress_label.pack(side=tk.TOP, fill=tk.X, expand=False, pady=(10, 10))

return progress_window, progress_bar, progress_label

@staticmethod
def center_window(window, parent):
"""
Expand Down
32 changes: 5 additions & 27 deletions MethodicConfigurator/frontend_tkinter_connection_selection.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
from frontend_tkinter_base import show_no_connection_error
from frontend_tkinter_base import show_tooltip
from frontend_tkinter_base import update_combobox_width
from frontend_tkinter_base import ProgressWindow
from frontend_tkinter_base import BaseWindow

from version import VERSION
Expand Down Expand Up @@ -96,8 +97,6 @@ def __init__(self, parent, parent_frame, flight_controller: FlightController, #
self.previous_selection = flight_controller.comport.device if hasattr(self.flight_controller.comport, "device") \
else None
self.connection_progress_window = None
self.connection_progress_bar = None
self.connection_progress_label = None

# Create a new frame for the flight controller connection selection label and combobox
self.container_frame = tk.Frame(parent_frame)
Expand Down Expand Up @@ -147,10 +146,10 @@ def add_connection(self):
return selected_connection

def reconnect(self, selected_connection: str = ""): # defaults to auto-connect
[self.connection_progress_window,
self.connection_progress_bar,
self.connection_progress_label] = self.parent.create_progress_window("Connecting with the FC")
error_message = self.flight_controller.connect(selected_connection, self.update_connection_progress_bar)
self.connection_progress_window = ProgressWindow(self.parent.root, "Connecting with the FC",
"Connection step {} of {}")
error_message = self.flight_controller.connect(selected_connection,
self.connection_progress_window.update_progress_bar)
if error_message:
show_no_connection_error(error_message)
return True
Expand All @@ -163,27 +162,6 @@ def reconnect(self, selected_connection: str = ""): # defaults to auto-connect
self.parent.read_flight_controller_parameters(reread=False)
return False

def update_connection_progress_bar(self, current_value: int, max_value: int):
"""
Update the FC connection progress bar and the progress message with the current progress.

Args:
current_value (int): The current progress value.
max_value (int): The maximum progress value.
"""
self.connection_progress_window.lift()

self.connection_progress_bar['value'] = current_value
self.connection_progress_bar['maximum'] = max_value
self.connection_progress_bar.update()

# Update the reset progress message
self.connection_progress_label.config(text=f"waiting for {current_value} of {max_value} seconds")

# Close the reset progress window when the process is complete
if current_value == max_value:
self.connection_progress_window.destroy()


class ConnectionSelectionWindow(BaseWindow):
"""
Expand Down
Loading
Loading