mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Perfmon: fixes to work with HAL
This commit is contained in:
parent
e34cc6dd9a
commit
499bc52c5b
@ -160,7 +160,7 @@ void AP_PerfMon::DisplayResults()
|
||||
|
||||
// ensure serial is blocking
|
||||
//blocking_writes = hal.console->get_blocking_writes();
|
||||
//hal.console->set_blocking_writes(true);
|
||||
hal.console->set_blocking_writes(true);
|
||||
|
||||
// print table of results
|
||||
hal.console->printf_P(PSTR("\nPerfMon elapsed:%lu(ms)\n"),(unsigned long)totalTime/1000);
|
||||
@ -197,7 +197,7 @@ void AP_PerfMon::DisplayResults()
|
||||
hal.console->printf_P(PSTR("unexpl:\t\t%4.2f\t%lu\n"),pct,(unsigned long)unExplainedTime/1000);
|
||||
|
||||
// restore to blocking writes if necessary
|
||||
//hal.console->set_blocking_writes(blocking_writes);
|
||||
hal.console->set_blocking_writes(false);
|
||||
|
||||
// turn back on any time recording
|
||||
if( lastCreated != NULL ) {
|
||||
|
@ -5,7 +5,11 @@
|
||||
#define AP_PERFMON_REGISTER static uint8_t myFunc = AP_PerfMon::recordFunctionName(__func__); AP_PerfMon perfMon(myFunc);
|
||||
#define AP_PERFMON_REGISTER_NAME(functionName) static uint8_t myFunc = AP_PerfMon::recordFunctionName(functionName); AP_PerfMon perfMon(myFunc);
|
||||
|
||||
#define PERFMON_MAX_FUNCTIONS 11
|
||||
#define AP_PERFMON_REGISTER_FN(func_name) static uint8_t func_name ## _num = AP_PerfMon::recordFunctionName(#func_name);
|
||||
#define AP_PERFMON_FUNCTION(func_name) AP_PerfMon perfMon(func_name ## _num);
|
||||
|
||||
|
||||
#define PERFMON_MAX_FUNCTIONS 12
|
||||
#define PERFMON_FUNCTION_NAME_LENGTH 10
|
||||
|
||||
#include <AP_HAL.h>
|
||||
|
@ -13,16 +13,21 @@
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
AP_PERFMON_REGISTER_FN(setup)
|
||||
AP_PERFMON_REGISTER_FN(loop)
|
||||
AP_PERFMON_REGISTER_FN(testFn)
|
||||
AP_PERFMON_REGISTER_FN(testFn2)
|
||||
|
||||
void setup()
|
||||
{
|
||||
AP_PERFMON_REGISTER_NAME("setupA")
|
||||
AP_PERFMON_FUNCTION(setup)
|
||||
|
||||
hal.console->print_P(PSTR("Performance Monitor test v1.1\n"));
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
AP_PERFMON_REGISTER
|
||||
AP_PERFMON_FUNCTION(loop)
|
||||
|
||||
int16_t i = 0;
|
||||
|
||||
@ -30,16 +35,16 @@ void loop()
|
||||
testFn();
|
||||
}
|
||||
|
||||
//AP_PerfMon::DisplayAndClear(5);
|
||||
AP_PerfMon::DisplayResults();
|
||||
AP_PerfMon::ClearAll();
|
||||
AP_PerfMon::DisplayAndClear(5);
|
||||
//AP_PerfMon::DisplayResults();
|
||||
//AP_PerfMon::ClearAll();
|
||||
|
||||
hal.scheduler->delay(10000);
|
||||
hal.scheduler->delay(2000);
|
||||
}
|
||||
|
||||
void testFn()
|
||||
{
|
||||
AP_PERFMON_REGISTER
|
||||
AP_PERFMON_FUNCTION(testFn)
|
||||
hal.scheduler->delay(10);
|
||||
testFn2();
|
||||
hal.scheduler->delay(10);
|
||||
@ -47,6 +52,8 @@ void testFn()
|
||||
|
||||
void testFn2()
|
||||
{
|
||||
AP_PERFMON_REGISTER
|
||||
AP_PERFMON_FUNCTION(testFn2)
|
||||
hal.scheduler->delay(10);
|
||||
}
|
||||
|
||||
AP_HAL_MAIN();
|
||||
|
Loading…
Reference in New Issue
Block a user