Ardupilot2/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp

61 lines
1.1 KiB
C++
Raw Normal View History

2012-12-20 00:45:04 -04:00
/*
AP_PerfMon
Code by Randy Mackay
*/
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <StorageManager/StorageManager.h>
#include <AP_PerfMon/AP_PerfMon.h> // PerfMonitor library
2012-12-20 00:45:04 -04:00
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
2012-12-20 00:45:04 -04:00
2013-10-11 00:20:50 -03:00
AP_PERFMON_REGISTER_FN(setup)
AP_PERFMON_REGISTER_FN(loop)
AP_PERFMON_REGISTER_FN(testFn)
AP_PERFMON_REGISTER_FN(testFn2)
2012-12-20 00:45:04 -04:00
void setup()
{
2013-10-11 00:20:50 -03:00
AP_PERFMON_FUNCTION(setup)
hal.console->print_P(PSTR("Performance Monitor test v1.1\n"));
2012-12-20 00:45:04 -04:00
}
void loop()
{
2013-10-11 00:20:50 -03:00
AP_PERFMON_FUNCTION(loop)
2012-12-20 00:45:04 -04:00
int16_t i = 0;
for( i=0; i<10; i++ ) {
testFn();
}
2013-10-11 00:20:50 -03:00
AP_PerfMon::DisplayAndClear(5);
//AP_PerfMon::DisplayResults();
//AP_PerfMon::ClearAll();
2012-12-20 00:45:04 -04:00
2013-10-11 00:20:50 -03:00
hal.scheduler->delay(2000);
2012-12-20 00:45:04 -04:00
}
void testFn()
{
2013-10-11 00:20:50 -03:00
AP_PERFMON_FUNCTION(testFn)
hal.scheduler->delay(10);
testFn2();
hal.scheduler->delay(10);
2012-12-20 00:45:04 -04:00
}
void testFn2()
{
2013-10-11 00:20:50 -03:00
AP_PERFMON_FUNCTION(testFn2)
hal.scheduler->delay(10);
2012-12-20 00:45:04 -04:00
}
2013-10-11 00:20:50 -03:00
AP_HAL_MAIN();