Browse Source

AP_Compass: Alert GCS if user tries to calibrate compass while vehicle is armed

c415-sdk
Rishabh 5 years ago committed by Andrew Tridgell
parent
commit
cbccdfa8a3
  1. 2
      libraries/AP_Compass/AP_Compass_Calibration.cpp

2
libraries/AP_Compass/AP_Compass_Calibration.cpp

@ -313,7 +313,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) @@ -313,7 +313,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
case MAV_CMD_DO_START_MAG_CAL: {
result = MAV_RESULT_ACCEPTED;
if (hal.util->get_soft_armed()) {
hal.console->printf("Disarm for compass calibration\n");
gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");
result = MAV_RESULT_FAILED;
break;
}

Loading…
Cancel
Save