AC_AttControl_Multi: get_althold_lean_angle_max uses motor thrust in 0 to 1 range
This commit is contained in:
parent
24f975c16a
commit
6f29bbafb4
@ -8,14 +8,14 @@
|
||||
float AC_AttitudeControl_Multi::get_althold_lean_angle_max() const
|
||||
{
|
||||
// calc maximum tilt angle based on throttle
|
||||
float thr_max = _motors_multi.throttle_max();
|
||||
float thr_max = _motors_multi.get_throttle_thrust_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;
|
||||
return ToDeg(acos(constrain_float(_throttle_in_filt.get()/(0.9f * thr_max), 0.0f, 1.0f))) * 100.0f;
|
||||
}
|
||||
|
||||
// returns a throttle including compensation for roll/pitch angle
|
||||
|
Loading…
Reference in New Issue
Block a user