Browse Source

AC_PosControl: protect against negative angle max

gps-1.3.1
Iampete1 3 years ago committed by Randy Mackay
parent
commit
ffac134014
  1. 2
      libraries/AC_AttitudeControl/AC_PosControl.cpp

2
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -1032,7 +1032,7 @@ void AC_PosControl::update_z_controller() @@ -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;

Loading…
Cancel
Save