mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Landing: prevent a landing division by zero
if sink rate set to zero
This commit is contained in:
parent
6902165cb3
commit
7832beedf0
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user