mirror of https://github.com/ArduPilot/ardupilot
Copter: Clear the counter when rudder arm operation is disabled
This commit is contained in:
parent
5b05a171a2
commit
c376781c08
|
@ -16,6 +16,7 @@ void Copter::arm_motors_check()
|
|||
// check if arming/disarm using rudder is allowed
|
||||
AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
|
||||
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
|
||||
arming_counter = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue