|
|
@ -13,6 +13,10 @@ |
|
|
|
#include <AP_ESC_Telem/AP_ESC_Telem.h> |
|
|
|
#include <AP_ESC_Telem/AP_ESC_Telem.h> |
|
|
|
#include "EKF_Maths.h" |
|
|
|
#include "EKF_Maths.h" |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS |
|
|
|
|
|
|
|
#include <arm_math.h> |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
void setup(); |
|
|
|
void setup(); |
|
|
|
void loop(); |
|
|
|
void loop(); |
|
|
|
|
|
|
|
|
|
|
@ -132,24 +136,31 @@ static void show_timings(void) |
|
|
|
TIMEIT("dmul", v_out_d *= v_d, 100); |
|
|
|
TIMEIT("dmul", v_out_d *= v_d, 100); |
|
|
|
TIMEIT("ddiv", v_out_d /= v_d, 100); |
|
|
|
TIMEIT("ddiv", v_out_d /= v_d, 100); |
|
|
|
|
|
|
|
|
|
|
|
TIMEIT("sinf()", v_out = sinf(v_f), 20); |
|
|
|
TIMEIT("sinf()", v_out = sinf(v_f), 100); |
|
|
|
TIMEIT("cosf()", v_out = cosf(v_f), 20); |
|
|
|
TIMEIT("cosf()", v_out = cosf(v_f), 100); |
|
|
|
TIMEIT("tanf()", v_out = tanf(v_f), 20); |
|
|
|
#if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS |
|
|
|
TIMEIT("acosf()", v_out = acosf(v_f * 0.2), 20); |
|
|
|
TIMEIT("arm_sin_f32()", v_out = arm_sin_f32(v_f), 100); |
|
|
|
TIMEIT("asinf()", v_out = asinf(v_f * 0.2), 20); |
|
|
|
TIMEIT("arm_cos_f32()", v_out = arm_cos_f32(v_f), 100); |
|
|
|
TIMEIT("atan2f()", v_out = atan2f(v_f * 0.2, v_f * 0.3), 20); |
|
|
|
#endif |
|
|
|
TIMEIT("sqrtf()",v_out = sqrtf(v_f), 20); |
|
|
|
TIMEIT("tanf()", v_out = tanf(v_f), 100); |
|
|
|
|
|
|
|
TIMEIT("acosf()", v_out = acosf(v_f * 0.2), 100); |
|
|
|
TIMEIT("sin()", v_out = sin(v_f), 20); |
|
|
|
TIMEIT("asinf()", v_out = asinf(v_f * 0.2), 100); |
|
|
|
TIMEIT("cos()", v_out = cos(v_f), 20); |
|
|
|
TIMEIT("atan2f()", v_out = atan2f(v_f * 0.2, v_f * 0.3), 100); |
|
|
|
TIMEIT("tan()", v_out = tan(v_f), 20); |
|
|
|
TIMEIT("sqrtf()",v_out = sqrtf(v_f), 100); |
|
|
|
TIMEIT("acos()", v_out = acos(v_f * 0.2), 20); |
|
|
|
|
|
|
|
TIMEIT("asin()", v_out = asin(v_f * 0.2), 20); |
|
|
|
TIMEIT("sin()", v_out = sin(v_f), 100); |
|
|
|
TIMEIT("atan2()", v_out = atan2(v_f * 0.2, v_f * 0.3), 20); |
|
|
|
TIMEIT("cos()", v_out = cos(v_f), 100); |
|
|
|
TIMEIT("sqrt()",v_out = sqrt(v_f), 20); |
|
|
|
TIMEIT("tan()", v_out = tan(v_f), 100); |
|
|
|
TIMEIT("sq()",v_out = sq(v_f), 20); |
|
|
|
TIMEIT("acos()", v_out = acos(v_f * 0.2), 100); |
|
|
|
TIMEIT("powf(v,2)",v_out = powf(v_f, 2), 20); |
|
|
|
TIMEIT("asin()", v_out = asin(v_f * 0.2), 100); |
|
|
|
TIMEIT("powf(v,3.1)",v_out = powf(v_f, 3.1), 20); |
|
|
|
TIMEIT("atan2()", v_out = atan2(v_f * 0.2, v_f * 0.3), 100); |
|
|
|
|
|
|
|
TIMEIT("sqrt()",v_out = sqrt(v_f), 100); |
|
|
|
|
|
|
|
#if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS |
|
|
|
|
|
|
|
TIMEIT("arm_sqrt_f32()", arm_sqrt_f32(v_f, (float32_t*)&v_out), 100); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
TIMEIT("sq()",v_out = sq(v_f), 100); |
|
|
|
|
|
|
|
TIMEIT("powf(v,2)",v_out = powf(v_f, 2), 100); |
|
|
|
|
|
|
|
TIMEIT("powf(v,3.1)",v_out = powf(v_f, 3.1), 100); |
|
|
|
TIMEIT("EKF",v_out = ekf.test(), 5); |
|
|
|
TIMEIT("EKF",v_out = ekf.test(), 5); |
|
|
|
|
|
|
|
|
|
|
|
TIMEIT("iadd8", v_out_8 += v_8, 100); |
|
|
|
TIMEIT("iadd8", v_out_8 += v_8, 100); |
|
|
|