mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: Notify arming failure when using MAVLink
This commit is contained in:
parent
608b8b0a2c
commit
9e7021cc20
@ -1273,6 +1273,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
init_arm_motors();
|
init_arm_motors();
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
}else{
|
}else{
|
||||||
|
AP_Notify::flags.arming_failed = true; // init_arm_motors function will reset flag back to false
|
||||||
result = MAV_RESULT_UNSUPPORTED;
|
result = MAV_RESULT_UNSUPPORTED;
|
||||||
}
|
}
|
||||||
} else if (packet.param1 == 0.0f) {
|
} else if (packet.param1 == 0.0f) {
|
||||||
|
Loading…
Reference in New Issue
Block a user