Plane: protect against short stop_distance

This commit is contained in:
Andrew Tridgell 2022-03-10 11:10:00 +11:00 committed by Randy Mackay
parent f6e5a11571
commit 8cd961838e
1 changed files with 1 additions and 1 deletions

View File

@ -3541,7 +3541,7 @@ float QuadPlane::stopping_distance(float ground_speed_squared) const
*/ */
float QuadPlane::accel_needed(float stop_distance, float ground_speed_squared) const float QuadPlane::accel_needed(float stop_distance, float ground_speed_squared) const
{ {
return ground_speed_squared / (2 * stop_distance); return ground_speed_squared / (2 * MAX(1,stop_distance));
} }
/* /*