mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Tools: convert CPUInfo to AP_HAL
This commit is contained in:
parent
d473203737
commit
07d8690fbe
@ -5,27 +5,42 @@
|
|||||||
Andrew Tridgell September 2011
|
Andrew Tridgell September 2011
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <math.h>
|
#include <AP_HAL.h>
|
||||||
#include <FastSerial.h>
|
#include <AP_HAL_AVR.h>
|
||||||
|
#include <AP_HAL_AVR_SITL.h>
|
||||||
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Baro.h>
|
||||||
|
#include <AP_Compass.h>
|
||||||
|
#include <AP_Declination.h>
|
||||||
|
#include <SITL.h>
|
||||||
|
#include <Filter.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
|
#include <AP_Progmem.h>
|
||||||
|
#include <AP_Math.h>
|
||||||
|
|
||||||
FastSerialPort0(Serial);
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
#define SERIAL0_BAUD 115200
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_SITL;
|
||||||
|
#else
|
||||||
|
#error "Unknown CONFIG_HAL_BOARD type"
|
||||||
|
#endif
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(SERIAL0_BAUD, 128, 128);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void show_sizes(void)
|
static void show_sizes(void)
|
||||||
{
|
{
|
||||||
Serial.println("Type sizes:");
|
hal.console->println("Type sizes:");
|
||||||
Serial.printf("char : %d\n", sizeof(char));
|
hal.console->printf("char : %d\n", sizeof(char));
|
||||||
Serial.printf("short : %d\n", sizeof(short));
|
hal.console->printf("short : %d\n", sizeof(short));
|
||||||
Serial.printf("int : %d\n", sizeof(int));
|
hal.console->printf("int : %d\n", sizeof(int));
|
||||||
Serial.printf("long : %d\n", sizeof(long));
|
hal.console->printf("long : %d\n", sizeof(long));
|
||||||
Serial.printf("long long : %d\n", sizeof(long long));
|
hal.console->printf("long long : %d\n", sizeof(long long));
|
||||||
Serial.printf("bool : %d\n", sizeof(bool));
|
hal.console->printf("bool : %d\n", sizeof(bool));
|
||||||
Serial.printf("void* : %d\n", sizeof(void *));
|
hal.console->printf("void* : %d\n", sizeof(void *));
|
||||||
}
|
}
|
||||||
|
|
||||||
#define TENTIMES(x) do { x; x; x; x; x; x; x; x; x; x; } while (0)
|
#define TENTIMES(x) do { x; x; x; x; x; x; x; x; x; x; } while (0)
|
||||||
@ -33,12 +48,12 @@ static void show_sizes(void)
|
|||||||
|
|
||||||
#define TIMEIT(name, op, count) do { \
|
#define TIMEIT(name, op, count) do { \
|
||||||
uint32_t us_end, us_start; \
|
uint32_t us_end, us_start; \
|
||||||
us_start = micros(); \
|
us_start = hal.scheduler->micros(); \
|
||||||
for (uint8_t i=0; i<count; i++) { \
|
for (uint8_t i=0; i<count; i++) { \
|
||||||
FIFTYTIMES(op); \
|
FIFTYTIMES(op); \
|
||||||
} \
|
} \
|
||||||
us_end = micros(); \
|
us_end = hal.scheduler->micros(); \
|
||||||
Serial.printf("%-10s %7.2f usec/call\n", name, double(us_end-us_start)/(count*50.0)); \
|
hal.console->printf("%-10s %7.2f usec/call\n", name, double(us_end-us_start)/(count*50.0)); \
|
||||||
} while (0)
|
} while (0)
|
||||||
|
|
||||||
volatile float v_f = 1.0;
|
volatile float v_f = 1.0;
|
||||||
@ -58,27 +73,27 @@ volatile uint64_t v_out_64 = 1;
|
|||||||
static void show_timings(void)
|
static void show_timings(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
v_f = 1+(micros() % 5);
|
v_f = 1+(hal.scheduler->micros() % 5);
|
||||||
v_out = 1+(micros() % 3);
|
v_out = 1+(hal.scheduler->micros() % 3);
|
||||||
|
|
||||||
v_32 = 1+(micros() % 5);
|
v_32 = 1+(hal.scheduler->micros() % 5);
|
||||||
v_out_32 = 1+(micros() % 3);
|
v_out_32 = 1+(hal.scheduler->micros() % 3);
|
||||||
|
|
||||||
v_16 = 1+(micros() % 5);
|
v_16 = 1+(hal.scheduler->micros() % 5);
|
||||||
v_out_16 = 1+(micros() % 3);
|
v_out_16 = 1+(hal.scheduler->micros() % 3);
|
||||||
|
|
||||||
v_8 = 1+(micros() % 5);
|
v_8 = 1+(hal.scheduler->micros() % 5);
|
||||||
v_out_8 = 1+(micros() % 3);
|
v_out_8 = 1+(hal.scheduler->micros() % 3);
|
||||||
|
|
||||||
|
|
||||||
Serial.println("Operation timings:");
|
hal.console->println("Operation timings:");
|
||||||
Serial.println("Note: timings for some operations are very data dependent");
|
hal.console->println("Note: timings for some operations are very data dependent");
|
||||||
|
|
||||||
TIMEIT("nop", asm volatile("nop"::), 255);
|
TIMEIT("nop", asm volatile("nop"::), 255);
|
||||||
TIMEIT("cli/sei", cli(); sei(), 255);
|
TIMEIT("cli/sei", hal.scheduler->begin_atomic(); hal.scheduler->end_atomic(), 255);
|
||||||
|
|
||||||
TIMEIT("micros()", micros(), 200);
|
TIMEIT("micros()", hal.scheduler->micros(), 200);
|
||||||
TIMEIT("millis()", millis(), 200);
|
TIMEIT("millis()", hal.scheduler->millis(), 200);
|
||||||
|
|
||||||
TIMEIT("fadd", v_out += v_f, 100);
|
TIMEIT("fadd", v_out += v_f, 100);
|
||||||
TIMEIT("fsub", v_out -= v_f, 100);
|
TIMEIT("fsub", v_out -= v_f, 100);
|
||||||
@ -120,14 +135,16 @@ static void show_timings(void)
|
|||||||
|
|
||||||
TIMEIT("memcpy128", memcpy((void*)mbuf1, (const void *)mbuf2, sizeof(mbuf1)), 20);
|
TIMEIT("memcpy128", memcpy((void*)mbuf1, (const void *)mbuf2, sizeof(mbuf1)), 20);
|
||||||
TIMEIT("memset128", memset((void*)mbuf1, 1, sizeof(mbuf1)), 20);
|
TIMEIT("memset128", memset((void*)mbuf1, 1, sizeof(mbuf1)), 20);
|
||||||
TIMEIT("delay(1)", delay(1), 5);
|
TIMEIT("delay(1)", hal.scheduler->delay(1), 5);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
show_sizes();
|
show_sizes();
|
||||||
Serial.println("");
|
hal.console->println("");
|
||||||
show_timings();
|
show_timings();
|
||||||
Serial.println("");
|
hal.console->println("");
|
||||||
delay(3000);
|
hal.scheduler->delay(3000);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
AP_HAL_MAIN();
|
||||||
|
0
Tools/CPUInfo/nocore.inoflag
Normal file
0
Tools/CPUInfo/nocore.inoflag
Normal file
Loading…
Reference in New Issue
Block a user