mirror of https://github.com/ArduPilot/ardupilot
Copter: reject preflight calibration when armed
This commit is contained in:
parent
b0e7990c90
commit
10724f5738
|
@ -1122,6 +1122,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
// exit immediately if armed
|
||||
if (motors.armed()) {
|
||||
result = MAV_RESULT_FAILED;
|
||||
break;
|
||||
}
|
||||
if (packet.param1 == 1) {
|
||||
// gyro offset calibration
|
||||
ins.init_gyro();
|
||||
|
|
Loading…
Reference in New Issue