Copter: fix ignore pilot yaw option for guided

This commit is contained in:
Tatsuya Yamaguchi 2021-01-06 21:38:35 +09:00 committed by Randy Mackay
parent ad29be14c6
commit eab913646e
1 changed files with 1 additions and 1 deletions

View File

@ -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)) {