diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 96c8060255..9756efc65b 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1468,7 +1468,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAV_CMD_DO_START_MAG_CAL: { result = MAV_RESULT_ACCEPTED; - if(packet.param1 < 0 || packet.param1 > 255) { + if(motors.armed() || packet.param1 < 0 || packet.param1 > 255) { result = MAV_RESULT_FAILED; break; }