diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 2d979f46ce..a7361c7ee5 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -105,6 +105,9 @@ void Copter::ModeLand::nogps_run() // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + if (!is_zero(target_yaw_rate)) { + auto_yaw.set_mode(AUTO_YAW_HOLD); + } } // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately