mirror of https://github.com/ArduPilot/ardupilot
Plane: protect against short stop_distance
This commit is contained in:
parent
f6e5a11571
commit
8cd961838e
|
@ -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
|
||||
{
|
||||
return ground_speed_squared / (2 * stop_distance);
|
||||
return ground_speed_squared / (2 * MAX(1,stop_distance));
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue