mirror of https://github.com/ArduPilot/ardupilot
Copter: auto_armed goes false for Heli when landed and motor shut off.
This commit is contained in:
parent
3da78052a1
commit
ef80634435
|
@ -369,6 +369,13 @@ void Copter::update_auto_armed()
|
|||
if(mode_has_manual_throttle(control_mode) && ap.throttle_zero && !failsafe.radio) {
|
||||
set_auto_armed(false);
|
||||
}
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// if helicopters are on the ground, and the motor is switched off, auto-armed should be false
|
||||
// so that rotor runup is checked again before attempting to take-off
|
||||
if(ap.land_complete && !motors.rotor_runup_complete()) {
|
||||
set_auto_armed(false);
|
||||
}
|
||||
#endif // HELI_FRAME
|
||||
}else{
|
||||
// arm checks
|
||||
|
||||
|
|
Loading…
Reference in New Issue