AP_Landing: Correct `WIND_COMP` gain to percent

This commit is contained in:
Ryan Beall 2022-12-13 03:28:07 -05:00 committed by Andrew Tridgell
parent 5b00c9b030
commit 2a4c453cb0
2 changed files with 4 additions and 4 deletions

View File

@ -157,11 +157,11 @@ 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.
// @Range: 0 1
// @Range: 0 100
// @Units: %
// @Increment: 0.1
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("WIND_COMP", 18, AP_Landing, wind_comp, 0.5),
AP_GROUPINFO("WIND_COMP", 18, AP_Landing, wind_comp, 50),
// @Param: TYPE
// @DisplayName: Auto-landing type

View File

@ -369,7 +369,7 @@ 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, 1.0f);
const float head_wind_comp = constrain_float((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`