Skip to content

Commit

Permalink
ArduPlane: Add Q_Option for tilt yaw control in transition
Browse files Browse the repository at this point in the history
add yaw control for tiltrotor in TRANSITION_TIMER state

pick ce2ec32 ArduPlane: Add Q_Option for tilt yaw control in
transition

ArduPlane: Add Q_Option for tilt yaw control in transition

add yaw control for tiltrotor in TRANSITION_TIMER state

ArduPlane: Add Q_Option for tilt yaw control in transition
  • Loading branch information
ClayFG committed Jan 22, 2025
1 parent d6eedf7 commit 19e8c7d
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
5 changes: 3 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Bitmask: 20: Force RTL mode-forces RTL mode on rc failsafe in VTOL modes overriding bit 5(USE_QRTL)
// @Bitmask: 21: Tilt rotor-tilt motors up when disarmed in FW modes (except manual) to prevent ground strikes.
// @Bitmask: 22: Scale FF by the ratio of VTOL/plane angle P gains in VTOL modes rather than reducing VTOL angle P based on airspeed.
// @Bitmask: 23: Force yaw control in transition for tiltrotors
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),

AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
Expand Down Expand Up @@ -1680,7 +1681,7 @@ void SLT_Transition::update()
}
quadplane.hold_hover(climb_rate_cms);

if (!quadplane.tiltrotor.is_vectored()) {
if (!quadplane.tiltrotor.is_vectored() && !quadplane.option_is_set(QuadPlane::OPTION::FORCE_TRANSITION_TILT_YAW)) {
// set desired yaw to current yaw in both desired angle
// and rate request. This reduces wing twist in transition
// due to multicopter yaw demands. This is disabled when
Expand Down Expand Up @@ -1753,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
1 change: 1 addition & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -618,6 +618,7 @@ class QuadPlane
FS_RTL=(1<<20),
DISARMED_TILT_UP=(1<<21),
SCALE_FF_ANGLE_P=(1<<22),
FORCE_TRANSITION_TILT_YAW=(1<<23),
};
bool option_is_set(OPTION option) const {
return (options.get() & int32_t(option)) != 0;
Expand Down

0 comments on commit 19e8c7d

Please sign in to comment.