diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 0b397d0890..c753aae54e 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -34,6 +34,9 @@ bool ModeLand::init(bool ignore_checks) // reset flag indicating if pilot has applied roll or pitch inputs during landing copter.ap.land_repo_active = false; + // initialise yaw + auto_yaw.set_mode(AUTO_YAW_HOLD); + return true; }