AP_PerfMon: fixes to make it work under AP_HAL (almost)

This commit is contained in:
Randy Mackay 2013-01-23 21:22:17 +09:00
parent 966b9b9b9c
commit 542e2e1358
3 changed files with 29 additions and 35 deletions

View File

@ -1,9 +1,7 @@
#include <AP_Math.h>
#include <FastSerial.h>
#include "Arduino.h"
#include "AP_PerfMon.h"
extern const AP_HAL::HAL& hal;
// static class variable definitions
uint8_t AP_PerfMon::nextFuncNum;
char AP_PerfMon::functionNames[PERFMON_MAX_FUNCTIONS][PERFMON_FUNCTION_NAME_LENGTH];
@ -25,7 +23,7 @@ AP_PerfMon::AP_PerfMon(uint8_t funcNum) : _funcNum(funcNum), _time_this_iteratio
// check global start time
if( allStartTime == 0 ) {
allStartTime = micros();
allStartTime = hal.scheduler->micros();
}
// stop recording time from parent
@ -83,13 +81,13 @@ uint8_t AP_PerfMon::recordFunctionName(const char funcName[])
// stop recording time
void AP_PerfMon::start()
{
_startTime = micros(); // start recording time spent in this function
_startTime = hal.scheduler->micros(); // start recording time spent in this function
}
// stop recording time
void AP_PerfMon::stop()
{
uint32_t temp_time = micros()-_startTime;
uint32_t temp_time = hal.scheduler->micros()-_startTime;
_time_this_iteration += temp_time;
time[_funcNum] += temp_time;
}
@ -107,7 +105,7 @@ void AP_PerfMon::ClearAll()
}
// reset start time to now
allStartTime = micros();
allStartTime = hal.scheduler->micros();
allEndTime = 0;
// reset start times of any active counters
@ -132,7 +130,7 @@ void AP_PerfMon::DisplayResults()
// record end time
if( allEndTime == 0 ) {
allEndTime = micros();
allEndTime = hal.scheduler->micros();
}
// turn off any time recording
@ -161,13 +159,12 @@ void AP_PerfMon::DisplayResults()
totalTime = allEndTime - allStartTime;
// ensure serial is blocking
blocking_writes = Serial.get_blocking_writes();
Serial.set_blocking_writes(true);
Serial.printf_P(PSTR("blocking was:%d\n"),(int)blocking_writes);
//blocking_writes = hal.console->get_blocking_writes();
//hal.console->set_blocking_writes(true);
// print table of results
Serial.printf_P(PSTR("\nPerfMon elapsed:%lu(ms)\n"),(unsigned long)totalTime/1000);
Serial.printf_P(PSTR("Fn:\t\tcpu\ttot(ms)\tavg(ms)\tmax(ms)\t#calls\tHz\n"));
hal.console->printf_P(PSTR("\nPerfMon elapsed:%lu(ms)\n"),(unsigned long)totalTime/1000);
hal.console->printf_P(PSTR("Fn:\t\tcpu\ttot(ms)\tavg(ms)\tmax(ms)\t#calls\tHz\n"));
for( i=0; i<nextFuncNum; i++ ) {
j=order[i];
sumOfTime += time[j];
@ -181,7 +178,7 @@ void AP_PerfMon::DisplayResults()
hz = numCalls[j]/(totalTime/1000000);
pct = ((float)time[j] / (float)totalTime) * 100.0;
Serial.printf_P(PSTR("%-10s\t%4.2f\t%lu\t%4.3f\t%4.3f\t%lu\t%4.1f\n"),
hal.console->printf_P(PSTR("%-10s\t%4.2f\t%lu\t%4.3f\t%4.3f\t%lu\t%4.1f\n"),
functionNames[j],
pct,
(unsigned long)time[j]/1000,
@ -197,10 +194,10 @@ void AP_PerfMon::DisplayResults()
unExplainedTime = totalTime - sumOfTime;
}
pct = ((float)unExplainedTime / (float)totalTime) * 100.0;
Serial.printf_P(PSTR("unexpl:\t\t%4.2f\t%lu\n"),pct,(unsigned long)unExplainedTime/1000);
hal.console->printf_P(PSTR("unexpl:\t\t%4.2f\t%lu\n"),pct,(unsigned long)unExplainedTime/1000);
// restore to blocking writes if necessary
Serial.set_blocking_writes(blocking_writes);
//hal.console->set_blocking_writes(blocking_writes);
// turn back on any time recording
if( lastCreated != NULL ) {
@ -212,7 +209,7 @@ void AP_PerfMon::DisplayResults()
// DisplayAndClear - will display results after this many milliseconds. should be called regularly
void AP_PerfMon::DisplayAndClear(uint32_t display_after_seconds)
{
if( (micros() - allStartTime) > (uint32_t)(display_after_seconds * 1000000) ) {
if( (hal.scheduler->micros() - allStartTime) > (uint32_t)(display_after_seconds * 1000000) ) {
DisplayResults();
ClearAll();
}

View File

@ -8,8 +8,8 @@
#define PERFMON_MAX_FUNCTIONS 11
#define PERFMON_FUNCTION_NAME_LENGTH 10
#include <AP_Common.h>
#include "HardwareSerial.h"
#include <AP_HAL.h>
#include <AP_Math.h>
class AP_PerfMon
{

View File

@ -3,23 +3,21 @@
Code by Randy Mackay
*/
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_PerfMon.h> // PerfMonitor library
FastSerialPort0(Serial);
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
void setup()
{
AP_PERFMON_REGISTER_NAME("setupA")
Serial.begin(115200);
Serial.println("Performance Monitor test v1.1");
// let tx buffer clear & display available space
delay(100);
Serial.printf_P(PSTR("Tx buf:%d available:%d\n"),Serial.txspace(),Serial.available());
delay(100);
Serial.set_blocking_writes(false);
hal.console->print_P(PSTR("Performance Monitor test v1.1\n"));
}
void loop()
@ -36,20 +34,19 @@ void loop()
AP_PerfMon::DisplayResults();
AP_PerfMon::ClearAll();
delay(10000);
hal.scheduler->delay(10000);
}
void testFn()
{
AP_PERFMON_REGISTER
//delay(10);
//testFn2();
//delay(10);
Serial.printf_P(PSTR("1234567890"));
hal.scheduler->delay(10);
testFn2();
hal.scheduler->delay(10);
}
void testFn2()
{
AP_PERFMON_REGISTER
delay(10);
hal.scheduler->delay(10);
}