aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/commander.c
diff options
context:
space:
mode:
Diffstat (limited to 'apps/commander/commander.c')
-rw-r--r--apps/commander/commander.c10
1 files changed, 6 insertions, 4 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 36e484f10..c569a6aa4 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -293,7 +293,7 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
struct sensor_combined_s raw;
/* 30 seconds */
- const uint64_t calibration_interval_us = 45 * 1000000;
+ int calibration_interval_ms = 30 * 1000;
unsigned int calibration_counter = 0;
float mag_max[3] = {-FLT_MAX, -FLT_MAX, -FLT_MAX};
@@ -312,10 +312,10 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
warn("WARNING: failed to set scale / offsets for mag");
close(fd);
- mavlink_log_info(mavlink_fd, "[commander] Please rotate around all axes.");
+ mavlink_log_info(mavlink_fd, "[commander] Please rotate around X");
uint64_t calibration_start = hrt_absolute_time();
- while ((hrt_absolute_time() - calibration_start) < calibration_interval_us) {
+ while ((hrt_absolute_time() - calibration_start)/1000 < calibration_interval_ms) {
/* wait blocking for new data */
struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
@@ -348,11 +348,13 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
calibration_counter++;
} else {
/* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "[commander] mag calibration aborted, please retry.");
+ mavlink_log_info(mavlink_fd, "[commander] mag cal canceled");
break;
}
}
+ mavlink_log_info(mavlink_fd, "[commander] mag calibration done");
+
/* disable calibration mode */
status->flag_preflight_mag_calibration = false;
state_machine_publish(status_pub, status, mavlink_fd);