mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: fix arming while armed bug
If a mavlink command was sent to arm the vehicle while it was already armed, the in_arm_motors boolean was left as true meaning the vehicle could never be armed again using a mavlink message. This resolves issue #5546.
This commit is contained in:
parent
b910f230fb
commit
742cdf6b13
@ -132,6 +132,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
|
||||
|
||||
// return true if already armed
|
||||
if (motors.armed()) {
|
||||
in_arm_motors = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user