diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 1419554b08..20e49f9264 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -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 diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 2fd3714ef1..9b31635887 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -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