From 6cb0259b79b0773fcb9d0aad16c0f86d327d23de Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 30 Aug 2021 09:19:30 +0200 Subject: [PATCH] commander: improve progress output Instead of outputting progress at weird percentages and dropping 100%, this now sends the progress every 10 %. --- src/modules/commander/gyro_calibration.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index ddba5a4232..282bfe695b 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -141,8 +141,10 @@ static calibrate_return gyro_calibration_worker(gyro_worker_data_t &worker_data) } } - if (update_count % (CALIBRATION_COUNT / 20) == 0) { - calibration_log_info(worker_data.mavlink_log_pub, CAL_QGC_PROGRESS_MSG, (update_count * 100) / CALIBRATION_COUNT); + const unsigned progress = (update_count * 100) / CALIBRATION_COUNT; + + if (progress % 10 == 0) { + calibration_log_info(worker_data.mavlink_log_pub, CAL_QGC_PROGRESS_MSG, progress); } // Propagate out the slowest sensor's count