Skip to content

Commit

Permalink
Plane: Prevent overloading quadplane wing during VTOL braking
Browse files Browse the repository at this point in the history
  • Loading branch information
priseborough committed Feb 13, 2024
1 parent b4ce4dd commit 1e44007
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 3 deletions.
24 changes: 21 additions & 3 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,6 +529,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @User: Standard
AP_GROUPINFO("FWD_THR_USE", 37, QuadPlane, q_fwd_thr_use, uint8_t(FwdThrUse::OFF)),

// @Param: BCK_PIT_LIM
// @DisplayName: Q mode rearward pitch limit
// @Description: This sets the maximum number of degrees of back or pitch up in Q modes when the airspeed is at AIRSPEED_FBW_MIN and is used to prevent excessive sutructural loads when pitching up decelerate. If airspeed is above or below AIRSPEED_FBW_MIN the pitch up/back will be adjusted according to the formula pitch_limit = BCK_PIT_LIM * (AIRSPEED_FBW_MIN / IAS)^2. The backwards/up pitch limit controlled by this parameter is in addition to limiting applied by PTCH_LIM_MAX and Q_ANGLE_MAX. The BCK_PIT_LIM limit is only applied when Q_FWD_THR_USE is set to 1 or 2 and the vehicle is flying in a mode that uses forward throttle instead of forward tilt to generate forward speed. Set to a non positive value 0 to deactivate this limit.
// @Units: deg
// @Range: 0.0 15.0
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO("BCK_PIT_LIM", 38, QuadPlane, q_bck_pitch_lim, 10.0f),

AP_GROUPEND
};

Expand Down Expand Up @@ -3036,6 +3045,14 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
}
}

// Prevent the wing from being overloaded when braking from high speed in a VTOL mode
// Re-normalise the surface speed scaler to be 1.0 when flying at airspeed_min
float nav_pitch_upper_limit_cd = 100.0f * q_bck_pitch_lim;
if (is_positive(q_bck_pitch_lim)) {
nav_pitch_upper_limit_cd *= sq(plane.surface_speed_scaler * (float)plane.aparm.airspeed_min / plane.g.scaling_speed);
plane.nav_pitch_cd = MIN(plane.nav_pitch_cd, (int32_t)nav_pitch_upper_limit_cd);
}

float fwd_thr_scaler;
if (!in_vtol_land_approach()) {
// To prevent forward motor prop strike, reduce throttle to zero when close to ground.
Expand All @@ -3057,14 +3074,15 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
#if HAL_LOGGING_ENABLED
// Diagnostics logging - remove when feature is fully flight tested.
AP::logger().WriteStreaming("FWDT",
"TimeUS,fts,qfplcd,npllcd,npcd,qft", // labels
"Qfffff", // fmt
"TimeUS,fts,qfplcd,npllcd,npcd,qft,npulcd", // labels
"Qffffff", // fmt
AP_HAL::micros64(),
(double)fwd_thr_scaler,
(double)q_fwd_pitch_lim_cd,
(double)nav_pitch_lower_limit_cd,
(double)plane.nav_pitch_cd,
(double)q_fwd_throttle);
(double)q_fwd_throttle,
(float)nav_pitch_upper_limit_cd);
#endif

plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, (int32_t)nav_pitch_lower_limit_cd);
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,9 @@ class QuadPlane
// limit applied to forward pitch to prevent wing producing negative lift
AP_Float q_fwd_pitch_lim;

// limit applied to back pitch to prevent wing producing excessive lift
AP_Float q_bck_pitch_lim;

// which fwd throttle handling method is active
enum class ActiveFwdThr : uint8_t {
NONE = 0,
Expand Down

0 comments on commit 1e44007

Please sign in to comment.