AP_Math: change fast_atan2 to use atan2f on fast CPUs

This commit is contained in:
Jonathan Challinger 2015-02-02 15:02:39 -08:00 committed by Randy Mackay
parent b64077ac2e
commit 5f7480b740
1 changed files with 41 additions and 34 deletions

View File

@ -38,13 +38,14 @@ float fast_atan(float v)
return (v*(1.6867629106f + v2*0.4378497304f)/(1.6867633134f + v2)); return (v*(1.6867629106f + v2*0.4378497304f)/(1.6867633134f + v2));
} }
#define FAST_ATAN2_PIBY2_FLOAT 1.5707963f #if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
// fast_atan2 - faster version of atan2 #define FAST_ATAN2_PIBY2_FLOAT 1.5707963f
// 126 us on AVR cpu vs 199 for regular atan2 // fast_atan2 - faster version of atan2
// absolute error is < 0.005 radians or 0.28 degrees // 126 us on AVR cpu vs 199 for regular atan2
// origin source: https://gist.github.com/volkansalma/2972237/raw/ // absolute error is < 0.005 radians or 0.28 degrees
float fast_atan2(float y, float x) // origin source: https://gist.github.com/volkansalma/2972237/raw/
{ float fast_atan2(float y, float x)
{
if (x == 0.0f) { if (x == 0.0f) {
if (y > 0.0f) { if (y > 0.0f) {
return FAST_ATAN2_PIBY2_FLOAT; return FAST_ATAN2_PIBY2_FLOAT;
@ -71,7 +72,13 @@ float fast_atan2(float y, float x)
} }
} }
return atan; return atan;
} }
#else
float fast_atan2(float y, float x)
{
return atan2f(y,x);
}
#endif
#if ROTATION_COMBINATION_SUPPORT #if ROTATION_COMBINATION_SUPPORT
// find a rotation that is the combination of two other // find a rotation that is the combination of two other