Skip to content

Commit

Permalink
FEATURE: integrate tempcal_IMU.py into the tool
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Apr 18, 2024
1 parent 4ffc77b commit 3731b9b
Show file tree
Hide file tree
Showing 4 changed files with 77 additions and 19 deletions.
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)]
34 changes: 29 additions & 5 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 Down Expand Up @@ -45,7 +46,6 @@
from tempcal_imu import IMUfit



class DocumentationFrame: # pylint: disable=too-few-public-methods
"""
A class to manage and display documentation within the GUI.
Expand Down Expand Up @@ -313,6 +313,27 @@ def on_param_file_combobox_change(self, _event, forced: bool = False):
selected_file = self.file_selection_combobox.get()
if self.current_file != selected_file or forced:
self.write_changes_to_intermediate_parameter_file()
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")])
if filename:
[self.param_read_progress_window,
self.param_read_progress_bar,
self.param_read_progress_label] = self.create_progress_window("Reading IMU calibration messages")
# 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.update_param_download_progress_bar)
self.param_read_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

# Update the current_file attribute to the selected file
self.current_file = selected_file
self.at_least_one_changed_parameter_written = False
Expand Down Expand Up @@ -548,7 +569,7 @@ def update_reset_progress_bar(self, current_value: int, max_value: int):
if current_value == max_value:
self.reset_progress_window.destroy()

def update_param_download_progress_bar(self, current_value: int, max_value: int):
def update_param_download_progress_bar(self, current_value: int, max_value: int=0):
"""
Update the FC parameter read progress bar the progress message with the current progress.
Expand All @@ -559,14 +580,17 @@ def update_param_download_progress_bar(self, current_value: int, max_value: int)
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['maximum'] = 100 if max_value == 0 else 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}")
if max_value == 0:
self.param_read_progress_label.config(text=f"{current_value} percent complete")
else:
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:
if current_value == max_value and max_value != 0:
self.param_read_progress_window.destroy()

def param_edit_widgets_event_generate_focus_out(self):
Expand Down
56 changes: 42 additions & 14 deletions MethodicConfigurator/tempcal_IMU.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import math
import re
import sys
import os
from argparse import ArgumentParser

import numpy as np
Expand Down Expand Up @@ -277,11 +278,13 @@ def constrain(value, minv, maxv):
return value


def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disable=too-many-locals, too-many-branches,
# pylint: disable=too-many-statements, too-many-arguments
def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-branches, too-many-statements, too-many-arguments
no_graph, log_parm,
online, tclr, figpath,
progress_callback):
'''find IMU calibration parameters from a log file'''
print(f"Processing log {logfile}")
mlog = mavutil.mavlink_connection(logfile)
mlog = mavutil.mavlink_connection(logfile, progress_callback=progress_callback)

data = IMUData()

Expand All @@ -295,15 +298,25 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
else:
messages = ['PARM', 'IMU']

# Pre-compile regular expressions used frequently inside the loop
enable_pattern = re.compile(r"^INS_TCAL(\d)_ENABLE$")
coeff_pattern = re.compile(r"^INS_TCAL(\d)_(ACC|GYR)([1-3])_([XYZ])$")
tmin_pattern = re.compile(r"^INS_TCAL(\d)_TMIN$")
tmax_pattern = re.compile(r"^INS_TCAL(\d)_TMAX$")
gyr_caltemp_pattern = re.compile(r"^INS_GYR(\d)_CALTEMP")
acc_caltemp_pattern = re.compile(r"^INS_ACC(\d)_CALTEMP")
offset_pattern = re.compile(r"^INS_(ACC|GYR)(\d?)OFFS_([XYZ])$")

while True:
msg = mlog.recv_match(type=messages)
if msg is None:
break

if msg.get_type() == 'PARM':
msg_type = msg.get_type()
if msg_type == 'PARM':
# build up the old coefficients so we can remove the impact of
# existing coefficients from the data
m = re.match(r"^INS_TCAL(\d)_ENABLE$", msg.Name)
m = enable_pattern.match(msg.Name)
if m:
imu = int(m.group(1))-1
if stop_capture[imu]:
Expand All @@ -317,7 +330,8 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
stop_capture[imu] = True
continue
c.set_enable(imu, msg.Value)
m = re.match(r"^INS_TCAL(\d)_(ACC|GYR)([1-3])_([XYZ])$", msg.Name)
continue
m = coeff_pattern.match(msg.Name)
if m:
imu = int(m.group(1))-1
stype = m.group(2)
Expand All @@ -329,31 +343,36 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
c.set_acoeff(imu, axis, p, msg.Value/SCALE_FACTOR)
if stype == 'GYR':
c.set_gcoeff(imu, axis, p, msg.Value/SCALE_FACTOR)
m = re.match(r"^INS_TCAL(\d)_TMIN$", msg.Name)
continue
m = tmin_pattern.match(msg.Name)
if m:
imu = int(m.group(1))-1
if stop_capture[imu]:
continue
c.set_tmin(imu, msg.Value)
m = re.match(r"^INS_TCAL(\d)_TMAX", msg.Name)
continue
m = tmax_pattern.match(msg.Name)
if m:
imu = int(m.group(1))-1
if stop_capture[imu]:
continue
c.set_tmax(imu, msg.Value)
m = re.match(r"^INS_GYR(\d)_CALTEMP", msg.Name)
continue
m = gyr_caltemp_pattern.match(msg.Name)
if m:
imu = int(m.group(1))-1
if stop_capture[imu]:
continue
c.set_gyro_tcal(imu, msg.Value)
m = re.match(r"^INS_ACC(\d)_CALTEMP", msg.Name)
continue
m = acc_caltemp_pattern.match(msg.Name)
if m:
imu = int(m.group(1))-1
if stop_capture[imu]:
continue
c.set_accel_tcal(imu, msg.Value)
m = re.match(r"^INS_(ACC|GYR)(\d?)OFFS_([XYZ])$", msg.Name)
continue
m = offset_pattern.match(msg.Name)
if m:
stype = m.group(1)
if m.group(2) == "":
Expand All @@ -367,11 +386,13 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
c.set_aoffset(imu, axis, msg.Value)
if stype == 'GYR':
c.set_goffset(imu, axis, msg.Value)
continue
if msg.Name == 'AHRS_ORIENTATION':
orientation = int(msg.Value)
print(f"Using orientation {orientation}")
continue

if msg.get_type() == 'TCLR' and tclr:
if msg_type == 'TCLR' and tclr:
imu = msg.I

T = msg.Temp
Expand All @@ -385,8 +406,9 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
gyr = Vector3(msg.X, msg.Y, msg.Z)
time = msg.TimeUS*1.0e-6
data.add_gyro(imu, T, time, gyr)
continue

if msg.get_type() == 'IMU' and not tclr:
if msg_type == 'IMU' and not tclr:
imu = msg.I

if stop_capture[imu]:
Expand Down Expand Up @@ -489,6 +511,9 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
axs[imu].legend(loc='upper left')
axs[imu].set_title(f'IMU[{imu}] Gyro (deg/s)')

if figpath:
_fig.savefig(os.path.join(figpath, 'tempcal_gyro.png'))

_fig, axs = pyplot.subplots(num_imus, 1, sharex=True)
if num_imus == 1:
axs = [axs]
Expand Down Expand Up @@ -520,6 +545,9 @@ def IMUfit(logfile, outfile, no_graph, log_parm, online, tclr): # pylint: disab
axs[imu].legend(loc='upper left')
axs[imu].set_title(f'IMU[{imu}] Accel (m/s^2)')

if figpath:
_fig.savefig(os.path.join(figpath, 'tempcal_acc.png'))

pyplot.show()


Expand All @@ -539,7 +567,7 @@ def main():

args = parser.parse_args()

IMUfit(args.log, args.outfile, args.no_graph, args.log_parm, args.online, args.tclr)
IMUfit(args.log, args.outfile, args.no_graph, args.log_parm, args.online, args.tclr, None, None)

if __name__ == "__main__":
main()
2 changes: 2 additions & 0 deletions setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,8 @@ def package_files(directory):
author_email='[email protected]',
packages=find_packages(),
install_requires=[
'matplotlib',
'numpy',
'pymavlink',
'pyserial',
'pillow',
Expand Down

0 comments on commit 3731b9b

Please sign in to comment.