mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AC_AttitudeControl: fixed use of double precision maths
This commit is contained in:
parent
48e27ab242
commit
9766c4ed26
@ -268,7 +268,7 @@ void AC_AttitudeControl_Heli::rate_controller_run()
|
||||
// Update Alt_Hold angle maximum
|
||||
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
|
||||
{
|
||||
float althold_lean_angle_max = acos(constrain_float(_throttle_in/AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
|
||||
float althold_lean_angle_max = acosf(constrain_float(_throttle_in/AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
|
||||
_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+_angle_limit_tc))*(althold_lean_angle_max-_althold_lean_angle_max);
|
||||
}
|
||||
|
||||
|
@ -188,7 +188,7 @@ void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in)
|
||||
return;
|
||||
}
|
||||
|
||||
float althold_lean_angle_max = acos(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
|
||||
float althold_lean_angle_max = acosf(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
|
||||
_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+_angle_limit_tc))*(althold_lean_angle_max-_althold_lean_angle_max);
|
||||
}
|
||||
|
||||
|
@ -195,7 +195,7 @@ void AC_AttitudeControl_Sub::update_althold_lean_angle_max(float throttle_in)
|
||||
return;
|
||||
}
|
||||
|
||||
float althold_lean_angle_max = acos(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
|
||||
float althold_lean_angle_max = acosf(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
|
||||
_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+_angle_limit_tc))*(althold_lean_angle_max-_althold_lean_angle_max);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user