From b4ec303d7465833d6077261c989cf2d57930d827 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 22 Dec 2021 21:16:49 +1030 Subject: [PATCH] Copter: Guided: When yaw is not specified use default yaw behaviour. --- ArduCopter/mode_guided.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 6dd0af4717..82175fbfd2 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -1023,6 +1023,8 @@ void ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, fl auto_yaw.set_yaw_angle_rate(yaw_cd * 0.01f, 0.0f); } else if (use_yaw_rate) { auto_yaw.set_rate(yaw_rate_cds); + } else { + auto_yaw.set_mode_to_default(false); } }