Copter: protect against arming while already armed

Previously it was possible to arm the vehicle (from the GCS) even thought the vehicle was already armed which would lead to the motors stopping for 2 seconds
This commit is contained in:
Randy Mackay 2016-12-01 10:24:53 +09:00
parent b4784d8204
commit 7ce7dd7f16

View File

@ -130,6 +130,11 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
}
in_arm_motors = true;
// return true if already armed
if (motors.armed()) {
return true;
}
// run pre-arm-checks and display failures
if (!all_arming_checks_passing(arming_from_gcs)) {
AP_Notify::events.arming_failed = true;