From 7e60feab4a00f4c5642dffb650922cc219f36e99 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 2 Aug 2021 15:53:30 +0930 Subject: [PATCH] AP_Math: Control: protect against divide by zero --- libraries/AP_Math/control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Math/control.cpp b/libraries/AP_Math/control.cpp index d53d7d8261..e3767f4f18 100644 --- a/libraries/AP_Math/control.cpp +++ b/libraries/AP_Math/control.cpp @@ -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; }