Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Allow lower speeds in landing final #29265

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,7 +323,7 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: AIRSPEED_STALL
// @DisplayName: Stall airspeed
// @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed. Value is as an indicated (calibrated/apparent) airspeed.
// @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. It is also used during landing final as the minimum airspeed that can be demanded by the TECS, which allows using TECS_LAND_ARSPD or LAND_PF_ARSPD to achieve landings slower than AIRSPEED_MIN. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed.
// @Units: m/s
// @Range: 5 75
// @User: Standard
Expand Down
6 changes: 5 additions & 1 deletion ArduPlane/navigation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -267,8 +267,12 @@ void Plane::calc_airspeed_errors()
target_airspeed_cm += airspeed_nudge_cm;
}

int32_t airspeed_lower_bound = is_positive(aparm.airspeed_stall)
? aparm.airspeed_stall
: aparm.airspeed_min;

// Apply airspeed limit
target_airspeed_cm = constrain_int32(target_airspeed_cm, aparm.airspeed_min*100, aparm.airspeed_max*100);
target_airspeed_cm = constrain_int32(target_airspeed_cm, airspeed_lower_bound*100, aparm.airspeed_max*100);

// use the TECS view of the target airspeed for reporting, to take
// account of the landing speed
Expand Down
18 changes: 18 additions & 0 deletions libraries/AP_Landing/AP_Landing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,6 +347,24 @@ bool AP_Landing::is_flaring(void) const
}
}

// return true if the landing is at the pre-flare stage or later
bool AP_Landing::is_on_final(void) const
{
if (!flags.in_progress) {
return false;
}

switch (type) {
case TYPE_STANDARD_GLIDE_SLOPE:
return type_slope_is_on_final();
#if HAL_LANDING_DEEPSTALL_ENABLED
case TYPE_DEEPSTALL:
#endif
default:
return false;
}
}

// return true while the aircraft is performing a landing approach
// when true the vehicle will:
// - disable ground steering
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Landing/AP_Landing.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ class AP_Landing {
void check_if_need_to_abort(const AP_FixedWing::Rangefinder_State &rangefinder_state);
bool request_go_around(void);
bool is_flaring(void) const;
bool is_on_final(void) const;
bool is_on_approach(void) const;
bool is_ground_steering_allowed(void) const;
bool is_throttle_suppressed(void) const;
Expand Down Expand Up @@ -206,6 +207,7 @@ class AP_Landing {
void type_slope_log(void) const;
bool type_slope_is_complete(void) const;
bool type_slope_is_flaring(void) const;
bool type_slope_is_on_final(void) const;
bool type_slope_is_on_approach(void) const;
bool type_slope_is_expecting_impact(void) const;
bool type_slope_is_throttle_suppressed(void) const;
Expand Down
9 changes: 7 additions & 2 deletions libraries/AP_Landing/AP_Landing_Slope.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,12 @@ bool AP_Landing::type_slope_is_flaring(void) const
return (type_slope_stage == SlopeStage::FINAL);
}

bool AP_Landing::type_slope_is_on_final(void) const
{
return (type_slope_stage == SlopeStage::PREFLARE ||
type_slope_stage == SlopeStage::FINAL);
}

bool AP_Landing::type_slope_is_on_approach(void) const
{
return (type_slope_stage == SlopeStage::APPROACH ||
Expand All @@ -398,8 +404,7 @@ bool AP_Landing::type_slope_is_on_approach(void) const

bool AP_Landing::type_slope_is_expecting_impact(void) const
{
return (type_slope_stage == SlopeStage::PREFLARE ||
type_slope_stage == SlopeStage::FINAL);
return type_slope_is_on_final();
}

bool AP_Landing::type_slope_is_complete(void) const
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -411,6 +411,12 @@ void AP_TECS::_update_speed(float DT)
_TASmax = MIN(_TASmax, aparm.airspeed_max * EAS2TAS);
_TASmin = aparm.airspeed_min * EAS2TAS;

if (_landing.is_on_final()) {
if (is_positive(aparm.airspeed_stall)) {
_TASmin = aparm.airspeed_stall * EAS2TAS;
}
}

if (aparm.stall_prevention) {
// when stall prevention is active we raise the minimum
// airspeed based on aerodynamic load factor
Expand Down
Loading