Skip to content

Commit

Permalink
add yaw control for tiltrotor in TRANSITION_TIMER state
Browse files Browse the repository at this point in the history
  • Loading branch information
ClayFG committed Oct 23, 2024
1 parent f91861b commit 594072e
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1754,7 +1754,7 @@ void SLT_Transition::update()
// control surfaces at this stage.
// We disable this for vectored yaw tilt rotors as they do need active
// yaw control throughout the transition
if (!quadplane.tiltrotor.is_vectored()) {
if (!quadplane.tiltrotor.is_vectored() && !quadplane.option_is_set(QuadPlane::OPTION::FORCE_TRANSITION_TILT_YAW)) {
quadplane.attitude_control->reset_yaw_target_and_rate();
quadplane.attitude_control->rate_bf_yaw_target(0.0);
}
Expand Down

0 comments on commit 594072e

Please sign in to comment.