From eab913646e4765b2331322becd664db8f22e185f Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Wed, 6 Jan 2021 21:38:35 +0900 Subject: [PATCH] Copter: fix ignore pilot yaw option for guided --- ArduCopter/mode_guided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 77d3fb45fa..e487032728 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -516,7 +516,7 @@ void ModeGuided::posvel_control_run() // process pilot's yaw input float target_yaw_rate = 0; - if (!copter.failsafe.radio && ((copter.g2.auto_options & (uint32_t)Options::IgnorePilotYaw) == 0)) { + if (!copter.failsafe.radio && use_pilot_yaw()) { // 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)) {