mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AC_PosControl: protect against negative angle max
This commit is contained in:
parent
fe9d655cc2
commit
ffac134014
@ -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…
Reference in New Issue
Block a user