AP_Landing: prevent a landing division by zero

if sink rate set to zero
This commit is contained in:
Andrew Tridgell 2022-12-03 12:25:31 +11:00 committed by Randy Mackay
parent fef5c75e23
commit 66df43176c
1 changed files with 1 additions and 1 deletions

View File

@ -284,7 +284,7 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
}
// time before landing that we will flare
float flare_time = aim_height / tecs_Controller->get_land_sinkrate();
float flare_time = aim_height / MAX(tecs_Controller->get_land_sinkrate(), 0.1);
// distance to flare is based on ground speed, adjusted as we
// get closer. This takes into account the wind