AP_Landing: use TECS landing sink rate estimate in flare distance calc

This commit is contained in:
Paul Riseborough 2021-11-27 08:25:49 +11:00 committed by Andrew Tridgell
parent 0840bf5a21
commit 60ec5f5076
1 changed files with 4 additions and 2 deletions

View File

@ -283,8 +283,10 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
aim_height = flare_alt*2;
}
// time before landing that we will flare
float flare_time = aim_height / tecs_Controller->get_land_sinkrate();
// 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);
const float flare_time = aim_height / flare_sink_rate_avg;
// distance to flare is based on ground speed, adjusted as we
// get closer. This takes into account the wind