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:
parent
865ff753f3
commit
5135a11fbc
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user