diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h index 9cb55fe64c..cfbd87329e 100644 --- a/src/modules/commander/calibration_messages.h +++ b/src/modules/commander/calibration_messages.h @@ -52,7 +52,8 @@ #define CAL_QGC_STARTED_MSG "[cal] calibration started: 2 %s" #define CAL_QGC_DONE_MSG "[cal] calibration done: %s" #define CAL_QGC_FAILED_MSG "[cal] calibration failed: %s" -#define CAL_QGC_WARNING_MSG "[cal] calibration warning: %s" +// Warnings are deprecated because they were only used when it failed anyway. +//#define CAL_QGC_WARNING_MSG "[cal] calibration warning: %s" #define CAL_QGC_CANCELLED_MSG "[cal] calibration cancelled" #define CAL_QGC_PROGRESS_MSG "[cal] progress <%u>" #define CAL_QGC_ORIENTATION_DETECTED_MSG "[cal] %s orientation detected" diff --git a/src/modules/commander/esc_calibration.cpp b/src/modules/commander/esc_calibration.cpp index 9d9713e34f..2e69ea97e2 100644 --- a/src/modules/commander/esc_calibration.cpp +++ b/src/modules/commander/esc_calibration.cpp @@ -196,13 +196,13 @@ Out: } if (fd != -1) { if (px4_ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0) != PX4_OK) { - calibration_log_info(mavlink_log_pub, CAL_QGC_WARNING_MSG, "Safety switch still off"); + calibration_log_info(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Safety switch still off"); } if (px4_ioctl(fd, PWM_SERVO_DISARM, 0) != PX4_OK) { - calibration_log_info(mavlink_log_pub, CAL_QGC_WARNING_MSG, "Servos still armed"); + calibration_log_info(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Servos still armed"); } if (px4_ioctl(fd, PWM_SERVO_CLEAR_ARM_OK, 0) != PX4_OK) { - calibration_log_info(mavlink_log_pub, CAL_QGC_WARNING_MSG, "Safety switch still deactivated"); + calibration_log_info(mavlink_log_pub, CAL_QGC_FAILED_MSG, "Safety switch still deactivated"); } px4_close(fd); }