AC_PosControl: protect against negative angle max

This commit is contained in:
Iampete1 2021-09-12 15:31:45 +01:00 committed by Randy Mackay
parent fe9d655cc2
commit ffac134014
1 changed files with 1 additions and 1 deletions

View File

@ -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;