AP_Landing: Add Headwind Compensation Param

Remove git action
This commit is contained in:
Ryan Beall 2022-12-11 00:51:04 -05:00 committed by Andrew Tridgell
parent 4355d852b1
commit 5b00c9b030
3 changed files with 12 additions and 1 deletions

View File

@ -154,6 +154,15 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
// @User: Advanced
AP_GROUPINFO("FLARE_AIM", 17, AP_Landing, flare_effectivness_pct, 50),
// @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.
// @Range: 0 1
// @Units: %
// @Increment: 0.1
// @User: Advanced
AP_GROUPINFO("WIND_COMP", 18, AP_Landing, wind_comp, 0.5),
// @Param: TYPE
// @DisplayName: Auto-landing type
// @Description: Specifies the auto-landing type to use

View File

@ -166,6 +166,7 @@ private:
AP_Int8 throttle_slewrate;
AP_Int8 type;
AP_Int8 flare_effectivness_pct;
AP_Float wind_comp;
// Land Type STANDARD GLIDE SLOPE

View File

@ -369,7 +369,8 @@ int32_t AP_Landing::type_slope_get_target_airspeed_cm(void)
}
// when landing, add half of head-wind.
const int32_t head_wind_compensation_cm = head_wind() * 0.5f * 100;
const float head_wind_comp = constrain_float((float)wind_comp, 0.0f, 1.0f);
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);