diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 19db54b1d2..e98be10980 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -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; }