mirror of https://github.com/ArduPilot/ardupilot
Copter: refuse to start mag cal if armed
This commit is contained in:
parent
fa6bfee433
commit
2864d58474
|
@ -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;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue