mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AC_AttControl_Multi: add divide by zero check
This commit is contained in:
parent
a0409e4f9e
commit
bab08cbcc1
@ -9,6 +9,12 @@ float AC_AttitudeControl_Multi::get_althold_lean_angle_max() const
|
||||
{
|
||||
// calc maximum tilt angle based on throttle
|
||||
float thr_max = _motors_multi.throttle_max();
|
||||
|
||||
// divide by zero check
|
||||
if (is_zero(thr_max)) {
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
return ToDeg(acos(constrain_float(_throttle_in_filt.get()/(0.9f * thr_max / 1000.0f), 0.0f, 1000.0f) / 1000.0f)) * 100.0f;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user