From 2a4c453cb0b05163304ca3c845fbb2d7a62c33f9 Mon Sep 17 00:00:00 2001 From: Ryan Beall Date: Tue, 13 Dec 2022 03:28:07 -0500 Subject: [PATCH] AP_Landing: Correct `WIND_COMP` gain to percent --- libraries/AP_Landing/AP_Landing.cpp | 6 +++--- libraries/AP_Landing/AP_Landing_Slope.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 957ce18dc4..2d2f020493 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -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 diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index b312fabedc..3ca5e157da 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -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`