mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: Control: protect against divide by zero
This commit is contained in:
parent
8cd70f2569
commit
397cd8cbe0
@ -400,7 +400,7 @@ float stopping_distance(float velocity, float p, float accel_max)
|
||||
// based on horizontal and vertical limits.
|
||||
float kinematic_limit(Vector3f direction, float max_xy, float max_z_pos, float max_z_neg)
|
||||
{
|
||||
if (is_zero(direction.length_squared())) {
|
||||
if (is_zero(direction.length_squared()) || is_zero(max_xy) || is_zero(max_z_pos) || is_zero(max_z_neg)) {
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user