mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Math: change fast_atan2 to use atan2f on fast CPUs
This commit is contained in:
parent
b64077ac2e
commit
5f7480b740
@ -38,6 +38,7 @@ float fast_atan(float v)
|
||||
return (v*(1.6867629106f + v2*0.4378497304f)/(1.6867633134f + v2));
|
||||
}
|
||||
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#define FAST_ATAN2_PIBY2_FLOAT 1.5707963f
|
||||
// fast_atan2 - faster version of atan2
|
||||
// 126 us on AVR cpu vs 199 for regular atan2
|
||||
@ -72,6 +73,12 @@ float fast_atan2(float y, float x)
|
||||
}
|
||||
return atan;
|
||||
}
|
||||
#else
|
||||
float fast_atan2(float y, float x)
|
||||
{
|
||||
return atan2f(y,x);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ROTATION_COMBINATION_SUPPORT
|
||||
// find a rotation that is the combination of two other
|
||||
|
Loading…
Reference in New Issue
Block a user