mirror of https://github.com/ArduPilot/ardupilot
Copter: cancelling no-gps-land switches to AltHold
Previously it could switch to Loiter
This commit is contained in:
parent
dc2ec5db18
commit
d989cf29e2
|
@ -159,9 +159,7 @@ void Copter::land_nogps_run()
|
|||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||
// exit land if throttle is high
|
||||
if (!set_mode(LOITER)) {
|
||||
set_mode(ALT_HOLD);
|
||||
}
|
||||
set_mode(ALT_HOLD);
|
||||
}
|
||||
|
||||
if (g.land_repositioning) {
|
||||
|
|
Loading…
Reference in New Issue