mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: Jason's fix to auto disarming
Added check so that it only starts counting down when motors are armed. This removes the issue in which the copter sometimes disarms shortly aftering being armed.
This commit is contained in:
parent
8046fe2cf3
commit
a185fa950c
@ -1295,7 +1295,7 @@ static void super_slow_loop()
|
||||
|
||||
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 25 seconds
|
||||
// but only of the control mode is manual
|
||||
if((control_mode <= ACRO) && (g.rc_3.control_in == 0)) {
|
||||
if((control_mode <= ACRO) && (g.rc_3.control_in == 0) && motors.armed()) {
|
||||
auto_disarming_counter++;
|
||||
|
||||
if(auto_disarming_counter == AUTO_DISARMING_DELAY) {
|
||||
|
Loading…
Reference in New Issue
Block a user