mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: reset land_repo_active flag in RTL mode
This commit is contained in:
parent
b4277c49ca
commit
5b3515a1c2
@ -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
Block a user