mirror of https://github.com/ArduPilot/ardupilot
Tools: improved CPUInfo test
This commit is contained in:
parent
0cd8840866
commit
c67ec11cc5
|
@ -3,6 +3,8 @@
|
|||
Andrew Tridgell September 2011
|
||||
*/
|
||||
|
||||
#define ALLOW_DOUBLE_MATH_FUNCTIONS
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
@ -13,11 +15,21 @@ void loop();
|
|||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
#ifdef STM32_SYS_CK
|
||||
static uint32_t sysclk = STM32_SYS_CK;
|
||||
#elif defined(STM32_SYSCLK)
|
||||
static uint32_t sysclk = STM32_SYSCLK;
|
||||
#else
|
||||
static uint32_t sysclk = 0;
|
||||
#endif
|
||||
|
||||
void setup() {
|
||||
}
|
||||
|
||||
static void show_sizes(void)
|
||||
{
|
||||
hal.console->printf("SYSCLK %uMHz\n", unsigned(sysclk/1000000U));
|
||||
|
||||
hal.console->printf("Type sizes:\n");
|
||||
hal.console->printf("char : %lu\n", (unsigned long)sizeof(char));
|
||||
hal.console->printf("short : %lu\n", (unsigned long)sizeof(short));
|
||||
|
@ -43,6 +55,7 @@ static void show_sizes(void)
|
|||
} \
|
||||
us_end = AP_HAL::micros(); \
|
||||
hal.console->printf("%-10s %7.2f usec/call\n", name, double(us_end - us_start) / double(count * 50.0)); \
|
||||
hal.scheduler->delay(10); \
|
||||
} while (0)
|
||||
|
||||
volatile float v_f = 1.0;
|
||||
|
@ -94,14 +107,22 @@ static void show_timings(void)
|
|||
TIMEIT("dmul", v_out_d *= v_d, 100);
|
||||
TIMEIT("ddiv", v_out_d /= v_d, 100);
|
||||
|
||||
TIMEIT("sin()", v_out = sinf(v_f), 20);
|
||||
TIMEIT("cos()", v_out = cosf(v_f), 20);
|
||||
TIMEIT("tan()", v_out = tanf(v_f), 20);
|
||||
TIMEIT("acos()", v_out = acosf(v_f * 0.2), 20);
|
||||
TIMEIT("asin()", v_out = asinf(v_f * 0.2), 20);
|
||||
TIMEIT("atan2()", v_out = atan2f(v_f * 0.2, v_f * 0.3), 20);
|
||||
TIMEIT("sqrt()",v_out = sqrtf(v_f), 20);
|
||||
TIMEIT("sinf()", v_out = sinf(v_f), 20);
|
||||
TIMEIT("cosf()", v_out = cosf(v_f), 20);
|
||||
TIMEIT("tanf()", v_out = tanf(v_f), 20);
|
||||
TIMEIT("acosf()", v_out = acosf(v_f * 0.2), 20);
|
||||
TIMEIT("asinf()", v_out = asinf(v_f * 0.2), 20);
|
||||
TIMEIT("atan2f()", v_out = atan2f(v_f * 0.2, v_f * 0.3), 20);
|
||||
TIMEIT("sqrtf()",v_out = sqrtf(v_f), 20);
|
||||
|
||||
TIMEIT("sin()", v_out = sin(v_f), 20);
|
||||
TIMEIT("cos()", v_out = cos(v_f), 20);
|
||||
TIMEIT("tan()", v_out = tan(v_f), 20);
|
||||
TIMEIT("acos()", v_out = acos(v_f * 0.2), 20);
|
||||
TIMEIT("asin()", v_out = asin(v_f * 0.2), 20);
|
||||
TIMEIT("atan2()", v_out = atan2(v_f * 0.2, v_f * 0.3), 20);
|
||||
TIMEIT("sqrt()",v_out = sqrt(v_f), 20);
|
||||
|
||||
TIMEIT("iadd8", v_out_8 += v_8, 100);
|
||||
TIMEIT("isub8", v_out_8 -= v_8, 100);
|
||||
TIMEIT("imul8", v_out_8 *= v_8, 100);
|
||||
|
@ -122,8 +143,8 @@ static void show_timings(void)
|
|||
TIMEIT("imul64", v_out_64 *= v_64, 100);
|
||||
TIMEIT("idiv64", v_out_64 /= v_64, 100);
|
||||
|
||||
TIMEIT("memcpy128", memcpy((void*)mbuf1, (const void *)mbuf2, sizeof(mbuf1)), 20);
|
||||
TIMEIT("memset128", memset((void*)mbuf1, 1, sizeof(mbuf1)), 20);
|
||||
TIMEIT("memcpy128", memcpy((void*)mbuf1, (const void *)mbuf2, sizeof(mbuf1)); v_out_8 += mbuf1[0], 200);
|
||||
TIMEIT("memset128", memset((void*)mbuf1, 1, sizeof(mbuf1)); v_out_8 += mbuf1[0], 200);
|
||||
TIMEIT("delay(1)", hal.scheduler->delay(1), 5);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue