From ffac134014f5abe36f4e2ccc253865a4c67969a9 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 12 Sep 2021 15:31:45 +0100 Subject: [PATCH] AC_PosControl: protect against negative angle max --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 365aa687e2..ab63c43ef5 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1032,7 +1032,7 @@ void AC_PosControl::update_z_controller() /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request float AC_PosControl::get_lean_angle_max_cd() const { - if (is_zero(_lean_angle_max)) { + if (!is_positive(_lean_angle_max)) { return _attitude_control.lean_angle_max_cd(); } return _lean_angle_max * 100.0f;