mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: fix ignore pilot yaw option for guided
This commit is contained in:
parent
ad29be14c6
commit
eab913646e
@ -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)) {
|
||||
|
Loading…
Reference in New Issue
Block a user