diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 25c255d6d8..3cfdcd61c9 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1606,7 +1606,7 @@ void SLT_Transition::update() // is needed to maintain good control in forward // transitions quadplane.attitude_control->reset_yaw_target_and_rate(); - quadplane.attitude_control->rate_bf_yaw_target(quadplane.ahrs.get_gyro().z); + quadplane.attitude_control->rate_bf_yaw_target(0.0); } if (quadplane.tiltrotor.enabled() && !quadplane.tiltrotor.has_fw_motor()) { // tilt rotors without decidated fw motors do not have forward throttle output in this stage @@ -1672,7 +1672,7 @@ void SLT_Transition::update() // yaw control throughout the transition if (!quadplane.tiltrotor.is_vectored()) { quadplane.attitude_control->reset_yaw_target_and_rate(); - quadplane.attitude_control->rate_bf_yaw_target(quadplane.ahrs.get_gyro().z); + quadplane.attitude_control->rate_bf_yaw_target(0.0); } break; }