mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: Quadplane: 0 rate_bf_yaw_target as more or less the same as radians value in cd funcion
This commit is contained in:
parent
90220e83ac
commit
edf89b02ea
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user