Plane: Quadplane: 0 rate_bf_yaw_target as more or less the same as radians value in cd funcion

This commit is contained in:
Iampete1 2022-11-05 12:41:01 +00:00 committed by Andrew Tridgell
parent 90220e83ac
commit edf89b02ea
1 changed files with 2 additions and 2 deletions

View File

@ -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;
}