mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Math: removed fast_atan
This commit is contained in:
parent
872583f441
commit
77a2b4acf6
@ -32,13 +32,6 @@ float safe_sqrt(float v)
|
||||
return ret;
|
||||
}
|
||||
|
||||
// a faster varient of atan. accurate to 6 decimal places for values between -1 ~ 1 but then diverges quickly
|
||||
float fast_atan(float v)
|
||||
{
|
||||
float v2 = v*v;
|
||||
return (v*(1.6867629106f + v2*0.4378497304f)/(1.6867633134f + v2));
|
||||
}
|
||||
|
||||
#if ROTATION_COMBINATION_SUPPORT
|
||||
// find a rotation that is the combination of two other
|
||||
// rotations. This is used to allow us to add an overall board
|
||||
|
@ -88,9 +88,6 @@ float safe_asin(float v);
|
||||
// a varient of sqrt() that always gives a valid answer.
|
||||
float safe_sqrt(float v);
|
||||
|
||||
// a faster varient of atan. accurate to 6 decimal places for values between -1 ~ 1 but then diverges quickly
|
||||
float fast_atan(float v);
|
||||
|
||||
#if ROTATION_COMBINATION_SUPPORT
|
||||
// find a rotation that is the combination of two other
|
||||
// rotations. This is used to allow us to add an overall board
|
||||
|
Loading…
Reference in New Issue
Block a user