mirror of https://github.com/ArduPilot/ardupilot
Copter: reset land_repo_active flag in RTL mode
This commit is contained in:
parent
902560953b
commit
8bc65e4ea1
|
@ -22,6 +22,8 @@ bool ModeRTL::init(bool ignore_checks)
|
|||
_state = SubMode::STARTING;
|
||||
_state_complete = true; // see run() method below
|
||||
terrain_following_allowed = !copter.failsafe.terrain;
|
||||
// reset flag indicating if pilot has applied roll or pitch inputs during landing
|
||||
copter.ap.land_repo_active = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue