AC_AttitudeControl: fixed accel limit trigonometry

Leonard had mentioned the limit should be tan(angle) not sin(angle). I
noticed this one was wrong.
This commit is contained in:
Andrew Tridgell 2016-04-28 16:15:15 +10:00
parent bec8bf8880
commit 23a64e1227
1 changed files with 1 additions and 1 deletions

View File

@ -915,7 +915,7 @@ void AC_PosControl::accel_to_lean_angles(float dt, float ekfNavVelGainScaler, bo
// limit acceleration if necessary
if (use_althold_lean_angle) {
accel_max = MIN(accel_max, GRAVITY_MSS * 100.0f * sinf(ToRad(constrain_float(_attitude_control.get_althold_lean_angle_max(),1000,8000)/100.0f)));
accel_max = MIN(accel_max, GRAVITY_MSS * 100.0f * tanf(ToRad(constrain_float(_attitude_control.get_althold_lean_angle_max(),1000,8000)/100.0f)));
}
// scale desired acceleration if it's beyond acceptable limit