AP_Landing: Add Landing Max Throttle Option

This commit is contained in:
Ryan Beall 2023-01-17 17:11:32 -05:00 committed by Andrew Tridgell
parent 2a4c453cb0
commit 1d70180809
4 changed files with 15 additions and 5 deletions

View File

@ -141,7 +141,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
// @Param: OPTIONS
// @DisplayName: Landing options bitmask
// @Description: Bitmask of options to use with landing.
// @Bitmask: 0: honor min throttle during landing flare
// @Bitmask: 0: honor min throttle during landing flare,1: Increase Target landing airspeed constraint From Trim Airspeed to ARSPD_FBW_MAX
// @User: Advanced
AP_GROUPINFO("OPTIONS", 16, AP_Landing, _options, 0),
@ -693,6 +693,12 @@ bool AP_Landing::use_thr_min_during_flare(void) const
return (OptionsMask::ON_LANDING_FLARE_USE_THR_MIN & _options) != 0;
}
//defaults to false, but _options bit zero enables it.
bool AP_Landing::allow_max_airspeed_on_land(void) const
{
return (OptionsMask::ON_LANDING_USE_ARSPD_MAX & _options) != 0;
}
/*
* returns false when the vehicle might not be flying forward while landing
*/

View File

@ -61,6 +61,7 @@ public:
// we support upto 32 boolean bits for users wanting to change landing behaviour.
enum OptionsMask {
ON_LANDING_FLARE_USE_THR_MIN = (1<<0), // If set then set trottle to thr_min instead of zero on final flare
ON_LANDING_USE_ARSPD_MAX = (1<<1), // If set then allow landing throttle constraint to be increased from trim airspeed to max airspeed (ARSPD_FBW_MAX)
};
void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
@ -79,6 +80,7 @@ public:
bool is_throttle_suppressed(void) const;
bool is_flying_forward(void) const;
bool use_thr_min_during_flare(void) const; //defaults to false, but _options bit zero enables it.
bool allow_max_airspeed_on_land(void) const; //defaults to false, but _options bit one enables it.
void handle_flight_stage_change(const bool _in_landing_stage);
int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
bool get_target_altitude_location(Location &location);

View File

@ -369,11 +369,13 @@ int32_t AP_Landing::type_slope_get_target_airspeed_cm(void)
}
// when landing, add half of head-wind.
const float head_wind_comp = constrain_float((float)wind_comp, 0.0f, 100.0f)*0.01;
const float head_wind_comp = constrain_float(wind_comp, 0.0f, 100.0f)*0.01;
const int32_t head_wind_compensation_cm = head_wind() * head_wind_comp * 100;
// Do not lower it or exceed max airspeed `ARSPD_FBW_MAX`
return constrain_int32(target_airspeed_cm + head_wind_compensation_cm, target_airspeed_cm, aparm.airspeed_max*100);
const uint32_t max_airspeed_cm = AP_Landing::allow_max_airspeed_on_land() ? aparm.airspeed_max*100 : aparm.airspeed_cruise_cm;
return constrain_int32(target_airspeed_cm + head_wind_compensation_cm, target_airspeed_cm, max_airspeed_cm);
}
int32_t AP_Landing::type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)

View File

@ -116,7 +116,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
// @Param: LAND_ARSPD
// @DisplayName: Airspeed during landing approach (m/s)
// @Description: When performing an autonomus landing, this value is used as the goal airspeed during approach. Max airspeed allowed is ARSPD_FBW_MAX. Note that this parameter is not useful if your platform does not have an airspeed sensor (use TECS_LAND_THR instead). If negative then this value is not used during landing.
// @Description: When performing an autonomus landing, this value is used as the goal airspeed during approach. Max airspeed allowed is Trim Airspeed or ARSPD_FBW_MAX as defined by LAND_OPTIONS bitmask. Note that this parameter is not useful if your platform does not have an airspeed sensor (use TECS_LAND_THR instead). If negative then this value is not used during landing.
// @Range: -1 127
// @Increment: 1
// @User: Standard