Skip to content

Commit

Permalink
ArduPlane: expand explanations in FWD THR docs
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Nov 5, 2023
1 parent 9c9205c commit 91b7f2d
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 4 deletions.
5 changes: 2 additions & 3 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {

// @Param: VFWD_GAIN
// @DisplayName: Forward velocity hold gain
// @Description: The use of this parameter is no longer recommended and has been superseded by a method that works in all VTOL modes with the exception of autotune which is controlled by the Q_FWD_THR_USE parameter. This Q_VFD_GAIN parameter controls use of the forward motor in VTOL modes that use the velocity controller. Set to 0 to disable this function. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use QLOITER for position hold with the forward motor.
// @Description: The use of this parameter is no longer recommended and has been superseded by a method that works in all VTOL position-controlled modes with the ppossible exception of QAUTOTUNE which is controlled by the Q_FWD_THR_USE parameter. This Q_VFD_GAIN parameter controls use of the forward motor in VTOL modes that use the velocity controller. Set to 0 to disable this function. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use with QLOITER for position hold with the forward motor.
// @Range: 0 0.5
// @Increment: 0.01
// @User: Standard
Expand Down Expand Up @@ -507,7 +507,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {

// @Param: FWD_THR_GAIN
// @DisplayName: Q mode fwd throttle gain
// @Description: This parameter sets the gain from forward accel/tilt to forward throttle in Q modes. The Q modes this feature operates in is controlled by the Q_FWD_THR_USE parameter. Vehicles using separate forward thrust motors, eg quadplanes, should set this parameter to (all up weight) / (maximum combined thrust of forward motors) with a value of 2 being typical. Vehicles that tilt lifting rotors to provide forward thrust should set this parameter to (all up weight) / (weight lifted by tilting rotors) which for most aircraft can be approximated as (total number of lifting rotors) / (number of lifting rotors that tilt). When using this method of forward throttle control, the forward tilt angle limit is controlled by the Q_FWD_PIT_LIM parameter.
// @Description: This parameter sets the gain from forward accel/tilt to forward throttle in Q modes, determined by Q_FWD_THR_USE. The Q modes this feature operates in is controlled by the Q_FWD_THR_USE parameter. Vehicles using separate forward thrust motors, eg quadplanes, should set this parameter to (all up weight) / (maximum combined thrust of forward motors) with a value of 2 being typical. Vehicles that tilt lifting rotors to provide forward thrust should set this parameter to (all up weight) / (weight lifted by tilting rotors) which for most aircraft can be approximated as (total number of lifting rotors) / (number of lifting rotors that tilt). When using this method of forward throttle control, the forward tilt angle limit is controlled by the Q_FWD_PIT_LIM parameter.
// @Range: 0.0 5.0
// @Increment: 0.1
// @User: Standard
Expand All @@ -524,7 +524,6 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {

// @Param: FWD_THR_USE
// @DisplayName: Q mode forward throttle use
// @Description: This parameter determines when the feature that uses forward throttle instead of forward tilt is used. The amount of forward throttle is controlled by the Q_FWD_THR_GAIN parameter. The maximum amount of forward pitch allowed is controlled by the Q_FWD_PIT_LIM parameter. Q_FWD_THR_USE = 0 disables the feature. Q_FWD_THR_USE = 1 enables the feature in all position controlled modes such as QLOITER, QLAND, QRTL and VTOL TAKEOFF. Q_FWD_THR_USE = 2 enables the feature in all Q modes except QAUTOTUNE and QACRO. When enabling the feature, the legacy method of controlling forward throttle use via velocity controller error should be disabled by setting Q_VFWD_GAIN to 0. Do not use this feature with tailsitters.
// @Values: 0:Off,1:On in all position controlled Q modes,2:On in all Q modes except QAUTOTUNE and QACRO
// @User: Standard
AP_GROUPINFO("FWD_THR_USE", 37, QuadPlane, q_fwd_thr_use, uint8_t(FwdThrUse::OFF)),
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ void Tiltrotor::continuous_update(void)
needed. There are 5 strategies we will use:
1) With use of a forward throttle controlled by Q_FWD_THR_GAIN in all
VTOL modes except Q_AUTOTUNE, we set the angle based on a calculated
VTOL position-controlled modes except Q_AUTOTUNE, we set the angle based on a calculated
forward throttle.
2) With manual forward throttle control we set the angle based on the
Expand Down

0 comments on commit 91b7f2d

Please sign in to comment.