mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
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
b4784d8204
commit
7ce7dd7f16
@ -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