mirror of https://github.com/ArduPilot/ardupilot
AP_Landing: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
This commit is contained in:
parent
f935cbaead
commit
180a738e19
|
@ -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,1: Increase Target landing airspeed constraint From Trim Airspeed to ARSPD_FBW_MAX
|
||||
// @Bitmask: 0: honor min throttle during landing flare,1: Increase Target landing airspeed constraint From Trim Airspeed to AIRSPEED_MAX
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 16, AP_Landing, _options, 0),
|
||||
|
||||
|
@ -156,7 +156,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
|||
|
||||
// @Param: WIND_COMP
|
||||
// @DisplayName: Headwind Compensation when Landing
|
||||
// @Description: This param controls how much headwind compensation is used when landing. Headwind speed component multiplied by this parameter is added to TECS_LAND_ARSPD command. Set to Zero to disable. Note: The target landing airspeed command is still limited to ARSPD_FBW_MAX.
|
||||
// @Description: This param controls how much headwind compensation is used when landing. Headwind speed component multiplied by this parameter is added to TECS_LAND_ARSPD command. Set to Zero to disable. Note: The target landing airspeed command is still limited to AIRSPEED_MAX.
|
||||
// @Range: 0 100
|
||||
// @Units: %
|
||||
// @Increment: 1
|
||||
|
|
|
@ -61,7 +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)
|
||||
ON_LANDING_USE_ARSPD_MAX = (1<<1), // If set then allow landing throttle constraint to be increased from trim airspeed to max airspeed (AIRSPEED_MAX)
|
||||
};
|
||||
|
||||
void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
|
||||
|
|
Loading…
Reference in New Issue