Skip to content

Commit

Permalink
FIX: more printf issues
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Jan 7, 2025
1 parent 10cafcf commit a7d9ef6
Showing 1 changed file with 9 additions and 16 deletions.
25 changes: 9 additions & 16 deletions ardupilot_methodic_configurator/tempcal_imu.py
Original file line number Diff line number Diff line change
Expand Up @@ -301,8 +301,7 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br
progress_callback: Union[Callable[[int], None], None],
) -> None:
"""Find IMU calibration parameters from a log file."""
msg = f"Processing log {logfile}"
logging.info(msg)
logging.info("Processing log %s", logfile)
mlog = mavutil.mavlink_connection(logfile, progress_callback=progress_callback)

data = IMUData()
Expand All @@ -327,8 +326,7 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br
for mtype in messages:
total_msgs += mlog.counts[mlog.name_to_id[mtype]]

msg = f"Found {total_msgs} messages"
logging.info(msg)
logging.info("Found %d messages", total_msgs)

pct = 0
msgcnt = 0
Expand All @@ -354,13 +352,11 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br
if stop_capture[imu]:
continue
if msg.Value == 1 and c.enable[imu] == 2:
msg = f"TCAL[{imu}] enabled"
logging.info(msg)
logging.info("TCAL[%d] enabled", imu)
stop_capture[imu] = True
continue
if msg.Value == 0 and c.enable[imu] == 1:
msg = f"TCAL[{imu}] disabled"
logging.info(msg)
logging.info("TCAL[%d] disabled", imu)
stop_capture[imu] = True
continue
c.set_enable(imu, msg.Value)
Expand Down Expand Up @@ -420,8 +416,7 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br
continue
if msg.Name == "AHRS_ORIENTATION":
orientation = int(msg.Value)
msg = f"Using orientation {orientation}"
logging.info(msg)
logging.info("Using orientation %d", orientation)
continue

if msg_type == "TCLR" and tclr:
Expand Down Expand Up @@ -455,8 +450,7 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br
acc = acc.rotate_by_inverse_id(orientation)
gyr = gyr.rotate_by_inverse_id(orientation)
if acc is None or gyr is None:
msg = f"Invalid AHRS_ORIENTATION {orientation}"
logging.critical(msg)
logging.critical("Invalid AHRS_ORIENTATION %d", orientation)
sys.exit(1)

if c.enable[imu] == 1:
Expand All @@ -471,8 +465,8 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br
logging.critical("No data found")
sys.exit(1)

msg = f"Loaded {len(data.accel[0]['T'])} accel and {len(data.gyro[0]['T'])} gyro samples"
logging.info(msg)
info_msg = f"Loaded {len(data.accel[0]['T'])} accel and {len(data.gyro[0]['T'])} gyro samples"
logging.info(info_msg)

if progress_callback:
progress_callback(210)
Expand Down Expand Up @@ -548,8 +542,7 @@ def generate_calibration_file( # pylint: disable=too-many-locals
else:
os.fsync(calfile.fileno()) # Use fsync as a fallback

msg = f"Calibration written to {outfile}"
logging.info(msg)
logging.info("Calibration written to %s", outfile)
return c, clog


Expand Down

0 comments on commit a7d9ef6

Please sign in to comment.