AP_Landing: Make flare extension aim point compensation tuneable

This commit is contained in:
Paul Riseborough 2021-12-03 18:06:16 +11:00 committed by Andrew Tridgell
parent 60ec5f5076
commit 9f806cad80
3 changed files with 13 additions and 2 deletions

View File

@ -145,6 +145,15 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
// @User: Advanced
AP_GROUPINFO("OPTIONS", 16, AP_Landing, _options, 0),
// @Param: FLARE_AIM
// @DisplayName: Flare aim point adjustment percentage.
// @Description: This parameter controls how much the aim point is moved to allow for the time spent in the flare manoeuvre. When set to 100% the aim point is adjusted on the assumption that the flare sink rate controller instantly achieves the sink rate set by TECS_LAND_SINK. when set to 0%, no aim point adjustment is made. If the plane consistently touches down short of the aim point reduce the parameter and vice verse.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("FLARE_AIM", 17, AP_Landing, flare_effectivness_pct, 50),
// @Param: TYPE
// @DisplayName: Auto-landing type
// @Description: Specifies the auto-landing type to use

View File

@ -165,6 +165,7 @@ private:
AP_Int8 flap_percent;
AP_Int8 throttle_slewrate;
AP_Int8 type;
AP_Int8 flare_effectivness_pct;
// Land Type STANDARD GLIDE SLOPE

View File

@ -284,8 +284,9 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
}
// calculate time spent in flare assuming the sink rate reduces over time from sink_rate at aim_height
// to tecs_controller->get_land_sinkrate() at touchdown with more reduction in sink rate initially
const float flare_sink_rate_avg = MAX(0.67f * tecs_Controller->get_land_sinkrate() + 0.33f * sink_rate, 0.1f);
// to tecs_controller->get_land_sinkrate() at touchdown
const float weight = constrain_float(0.01f*(float)flare_effectivness_pct, 0.0f, 1.0f);
const float flare_sink_rate_avg = MAX(weight * tecs_Controller->get_land_sinkrate() + (1.0f - weight) * sink_rate, 0.1f);
const float flare_time = aim_height / flare_sink_rate_avg;
// distance to flare is based on ground speed, adjusted as we