AP_Compass: added message for compass cal when armed

This commit is contained in:
Andrew Tridgell 2015-09-03 16:50:56 +10:00
parent 347d1f0a25
commit e4b2fc711d
1 changed files with 6 additions and 1 deletions

View File

@ -254,7 +254,12 @@ uint8_t Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
switch (packet.command) {
case MAV_CMD_DO_START_MAG_CAL: {
result = MAV_RESULT_ACCEPTED;
if (hal.util->get_soft_armed() || packet.param1 < 0 || packet.param1 > 255) {
if (hal.util->get_soft_armed()) {
hal.console->println("Disarm for compass calibration");
result = MAV_RESULT_FAILED;
break;
}
if (packet.param1 < 0 || packet.param1 > 255) {
result = MAV_RESULT_FAILED;
break;
}