aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp10
-rw-r--r--src/modules/commander/commander.cpp6
2 files changed, 8 insertions, 8 deletions
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 0cb41489f..d4cd97be6 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -263,7 +263,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
const int samples_num = 2500;
float accel_ref[6][3];
bool data_collected[6] = { false, false, false, false, false, false };
- const char *orientation_strs[6] = { "front", "back", "left", "right", "top", "bottom" };
+ const char *orientation_strs[6] = { "back", "front", "left", "right", "up", "down" };
int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
@@ -294,12 +294,12 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
/* inform user which axes are still needed */
mavlink_log_info(mavlink_fd, "pending: %s%s%s%s%s%s",
- (!data_collected[0]) ? "front " : "",
- (!data_collected[1]) ? "back " : "",
+ (!data_collected[5]) ? "down " : "",
+ (!data_collected[0]) ? "back " : "",
+ (!data_collected[1]) ? "front " : "",
(!data_collected[2]) ? "left " : "",
(!data_collected[3]) ? "right " : "",
- (!data_collected[4]) ? "up " : "",
- (!data_collected[5]) ? "down " : "");
+ (!data_collected[4]) ? "up " : "");
/* allow user enough time to read the message */
sleep(3);
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 4c7664cd0..744323c01 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1697,7 +1697,7 @@ int commander_thread_main(int argc, char *argv[])
if (telemetry_lost[i] &&
hrt_elapsed_time(&telemetry_last_dl_loss[i]) > datalink_regain_timeout * 1e6) {
- mavlink_log_critical(mavlink_fd, "data link %i regained", i);
+ mavlink_log_info(mavlink_fd, "data link %i regained", i);
telemetry_lost[i] = false;
have_link = true;
@@ -1711,7 +1711,7 @@ int commander_thread_main(int argc, char *argv[])
telemetry_last_dl_loss[i] = hrt_absolute_time();
if (!telemetry_lost[i]) {
- mavlink_log_critical(mavlink_fd, "data link %i lost", i);
+ mavlink_log_info(mavlink_fd, "data link %i lost", i);
telemetry_lost[i] = true;
}
}
@@ -1726,7 +1726,7 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (!status.data_link_lost) {
- mavlink_log_critical(mavlink_fd, "ALL DATA LINKS LOST");
+ mavlink_log_info(mavlink_fd, "ALL DATA LINKS LOST");
status.data_link_lost = true;
status.data_link_lost_counter++;
status_changed = true;