mirror of https://github.com/ArduPilot/ardupilot
APM_PerfMon - removed because it's too big to use with our limited memory now anyway! I have a backup in case we need to resurrect it in the future.
This commit is contained in:
parent
bde1ebb56e
commit
a694e16540
|
@ -1,201 +0,0 @@
|
||||||
|
|
||||||
extern "C" {
|
|
||||||
// AVR LibC Includes
|
|
||||||
#include "WConstants.h"
|
|
||||||
}
|
|
||||||
|
|
||||||
#include "APM_PerfMon.h"
|
|
||||||
|
|
||||||
// don't know why i need these
|
|
||||||
// see http://www.avrfreaks.net/index.php?name=PNphpBB2&file=viewtopic&p=410870
|
|
||||||
int __cxa_guard_acquire(__guard *g) {return !*(char *)(g);};
|
|
||||||
void __cxa_guard_release (__guard *g) {*(char *)g = 1;};
|
|
||||||
void __cxa_guard_abort (__guard *) {};
|
|
||||||
|
|
||||||
// static class variable definitions
|
|
||||||
int APM_PerfMon::nextFuncNum;
|
|
||||||
char APM_PerfMon::functionNames[PERFMON_MAX_FUNCTIONS][PERFMON_FUNCTION_NAME_LENGTH];
|
|
||||||
unsigned long APM_PerfMon::time[PERFMON_MAX_FUNCTIONS];
|
|
||||||
unsigned long APM_PerfMon::numCalls[PERFMON_MAX_FUNCTIONS];
|
|
||||||
unsigned long APM_PerfMon::allStartTime;
|
|
||||||
unsigned long APM_PerfMon::allEndTime;
|
|
||||||
APM_PerfMon* APM_PerfMon::lastCreated = NULL;
|
|
||||||
|
|
||||||
// constructor
|
|
||||||
APM_PerfMon::APM_PerfMon(int funcNum)
|
|
||||||
{
|
|
||||||
// stop recording time from parent
|
|
||||||
if( lastCreated != NULL )
|
|
||||||
lastCreated->stop();
|
|
||||||
|
|
||||||
// check global start time
|
|
||||||
if( allStartTime == 0 )
|
|
||||||
allStartTime = micros();
|
|
||||||
|
|
||||||
_funcNum = funcNum; // record which function we should assign time to
|
|
||||||
_parent = lastCreated; // add pointer to parent
|
|
||||||
lastCreated = this; // record myself as the last created instance
|
|
||||||
|
|
||||||
numCalls[_funcNum]++; // record that this function has been called
|
|
||||||
start(); // start recording time spent in this function
|
|
||||||
}
|
|
||||||
|
|
||||||
// destructor
|
|
||||||
APM_PerfMon::~APM_PerfMon()
|
|
||||||
{
|
|
||||||
stop(); // stop recording time spent in this function
|
|
||||||
lastCreated = _parent; // make my parent the last created instance
|
|
||||||
|
|
||||||
// restart recording time for parent
|
|
||||||
if( lastCreated != NULL )
|
|
||||||
lastCreated->start();
|
|
||||||
}
|
|
||||||
|
|
||||||
// stop recording time
|
|
||||||
void APM_PerfMon::stop()
|
|
||||||
{
|
|
||||||
time[_funcNum] += (micros()-_startTime);
|
|
||||||
}
|
|
||||||
|
|
||||||
// stop recording time
|
|
||||||
void APM_PerfMon::start()
|
|
||||||
{
|
|
||||||
_startTime = micros(); // restart recording time spent in this function
|
|
||||||
}
|
|
||||||
|
|
||||||
// record function name in static list
|
|
||||||
int APM_PerfMon::recordFunctionName(const char funcName[])
|
|
||||||
{
|
|
||||||
int nextNum = nextFuncNum++;
|
|
||||||
int i;
|
|
||||||
|
|
||||||
// clear existing function name (if any)
|
|
||||||
functionNames[nextNum][0] = 0;
|
|
||||||
|
|
||||||
// store function name
|
|
||||||
for( i=0; i<PERFMON_FUNCTION_NAME_LENGTH-1 && funcName[i] != 0; i++ )
|
|
||||||
{
|
|
||||||
functionNames[nextNum][i] = funcName[i];
|
|
||||||
}
|
|
||||||
functionNames[nextNum][i] = 0;
|
|
||||||
|
|
||||||
return nextNum;
|
|
||||||
}
|
|
||||||
|
|
||||||
// ClearAll - clears all data from static members
|
|
||||||
void APM_PerfMon::ClearAll()
|
|
||||||
{
|
|
||||||
int i;
|
|
||||||
APM_PerfMon *p = lastCreated;
|
|
||||||
|
|
||||||
for(i=0; i<PERFMON_MAX_FUNCTIONS; i++)
|
|
||||||
{
|
|
||||||
time[i] = 0; // reset times
|
|
||||||
numCalls[i] = 0; // reset num times called
|
|
||||||
}
|
|
||||||
|
|
||||||
// reset start time to now
|
|
||||||
allStartTime = micros();
|
|
||||||
allEndTime = 0;
|
|
||||||
|
|
||||||
// reset start times of any active counters
|
|
||||||
while( p != NULL ) {
|
|
||||||
p->_startTime = allStartTime;
|
|
||||||
p = p->_parent;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// ClearAll - clears all data from static members
|
|
||||||
void APM_PerfMon::DisplayResults(HardwareSerial* aSerial)
|
|
||||||
{
|
|
||||||
int i,j,k,padding,changed;
|
|
||||||
float hz;
|
|
||||||
float pct;
|
|
||||||
unsigned long totalTime;
|
|
||||||
unsigned long sumOfTime = 0;
|
|
||||||
unsigned long unExplainedTime;
|
|
||||||
int order[PERFMON_MAX_FUNCTIONS];
|
|
||||||
APM_PerfMon* p = lastCreated;
|
|
||||||
|
|
||||||
// record end time
|
|
||||||
if( allEndTime == 0 )
|
|
||||||
allEndTime = micros();
|
|
||||||
|
|
||||||
// turn off any time recording
|
|
||||||
if( lastCreated != NULL )
|
|
||||||
lastCreated->stop();
|
|
||||||
|
|
||||||
// reorder results
|
|
||||||
for(i=0; i<nextFuncNum; i++)
|
|
||||||
order[i] = i;
|
|
||||||
changed=0;
|
|
||||||
do{
|
|
||||||
changed = 0;
|
|
||||||
for(i=0; i<nextFuncNum-1; i++)
|
|
||||||
if(time[order[i]]<time[order[i+1]])
|
|
||||||
{
|
|
||||||
j = order[i];
|
|
||||||
order[i] = order[i+1];
|
|
||||||
order[i+1] = j;
|
|
||||||
changed = 1;
|
|
||||||
}
|
|
||||||
}while(changed != 0);
|
|
||||||
// sort results
|
|
||||||
|
|
||||||
totalTime = allEndTime - allStartTime;
|
|
||||||
|
|
||||||
aSerial->print("PerfMon start:");
|
|
||||||
aSerial->print(allStartTime/1000);
|
|
||||||
aSerial->print(" (mils) end:");
|
|
||||||
aSerial->print(allEndTime/1000);
|
|
||||||
aSerial->print(" (mils) elapsed:");
|
|
||||||
aSerial->print(totalTime/1000);
|
|
||||||
aSerial->print(" (mils)");
|
|
||||||
aSerial->println();
|
|
||||||
aSerial->println("PerfMon: \tcpu%\tmils\t#called\tHz");
|
|
||||||
for( i=0; i<nextFuncNum; i++ )
|
|
||||||
{
|
|
||||||
j=order[i];
|
|
||||||
sumOfTime += time[j];
|
|
||||||
hz = numCalls[j]/(totalTime/1000000);
|
|
||||||
pct = ((float)time[j] / (float)totalTime) * 100.0;
|
|
||||||
padding = PERFMON_FUNCTION_NAME_LENGTH - strLen(functionNames[j]);
|
|
||||||
|
|
||||||
aSerial->print(functionNames[j]);
|
|
||||||
for(k=0;k<padding;k++)
|
|
||||||
aSerial->print(" ");
|
|
||||||
aSerial->print("\t");
|
|
||||||
aSerial->print(pct);
|
|
||||||
aSerial->print("%\t");
|
|
||||||
aSerial->print(time[j]/1000);
|
|
||||||
aSerial->print("\t");
|
|
||||||
aSerial->print(numCalls[j]);
|
|
||||||
aSerial->print("\t");
|
|
||||||
aSerial->print(hz,0);
|
|
||||||
aSerial->print("hz");
|
|
||||||
aSerial->println();
|
|
||||||
}
|
|
||||||
// display unexplained time
|
|
||||||
if( sumOfTime >= totalTime )
|
|
||||||
unExplainedTime = 0;
|
|
||||||
else
|
|
||||||
unExplainedTime = totalTime - sumOfTime;
|
|
||||||
pct = ((float)unExplainedTime / (float)totalTime) * 100.0;
|
|
||||||
aSerial->print("unexplained \t");
|
|
||||||
aSerial->print(pct);
|
|
||||||
aSerial->print("%\t");
|
|
||||||
aSerial->print(unExplainedTime/1000);
|
|
||||||
aSerial->println();
|
|
||||||
|
|
||||||
// turn back on any time recording
|
|
||||||
if( lastCreated != NULL )
|
|
||||||
lastCreated->start();
|
|
||||||
}
|
|
||||||
|
|
||||||
int APM_PerfMon::strLen(char* str)
|
|
||||||
{
|
|
||||||
int i = 0;
|
|
||||||
while( str[i] != 0 )
|
|
||||||
i++;
|
|
||||||
return i;
|
|
||||||
}
|
|
|
@ -1,49 +0,0 @@
|
||||||
#ifndef APM_PerfMon_h
|
|
||||||
#define APM_PerfMon_h
|
|
||||||
|
|
||||||
// macros to make integrating into code easier
|
|
||||||
#define APM_PERFMON_REGISTER static int myFunc = APM_PerfMon::recordFunctionName(__func__); APM_PerfMon perfMon(myFunc);
|
|
||||||
#define APM_PERFMON_REGISTER_NAME(functionName) static int myFunc = APM_PerfMon::recordFunctionName(functionName); APM_PerfMon perfMon(myFunc);
|
|
||||||
|
|
||||||
#define PERFMON_MAX_FUNCTIONS 50
|
|
||||||
#define PERFMON_FUNCTION_NAME_LENGTH 20
|
|
||||||
|
|
||||||
__extension__ typedef int __guard __attribute__((mode (__DI__)));
|
|
||||||
|
|
||||||
extern "C" int __cxa_guard_acquire(__guard *);
|
|
||||||
extern "C" void __cxa_guard_release (__guard *);
|
|
||||||
extern "C" void __cxa_guard_abort (__guard *);
|
|
||||||
|
|
||||||
#include "HardwareSerial.h"
|
|
||||||
|
|
||||||
class APM_PerfMon
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
// static variables
|
|
||||||
static int nextFuncNum;
|
|
||||||
static char functionNames[PERFMON_MAX_FUNCTIONS][PERFMON_FUNCTION_NAME_LENGTH];
|
|
||||||
static unsigned long time[PERFMON_MAX_FUNCTIONS];
|
|
||||||
static unsigned long numCalls[PERFMON_MAX_FUNCTIONS];
|
|
||||||
static unsigned long allStartTime;
|
|
||||||
static unsigned long allEndTime;
|
|
||||||
static APM_PerfMon* lastCreated;
|
|
||||||
|
|
||||||
// static methods
|
|
||||||
static int recordFunctionName(const char funcName[]);
|
|
||||||
static void DisplayResults(HardwareSerial* aSerial);
|
|
||||||
static void ClearAll();
|
|
||||||
static int strLen(char* str);
|
|
||||||
|
|
||||||
// normal variables
|
|
||||||
int _funcNum;
|
|
||||||
unsigned long _startTime;
|
|
||||||
APM_PerfMon* _parent;
|
|
||||||
|
|
||||||
// normal methods
|
|
||||||
APM_PerfMon(int funcNum); // Constructor - records function start time
|
|
||||||
~APM_PerfMon(); // Destructor - records function end time
|
|
||||||
void stop(); // stops recording time spent in this function - meant to be called by a child.
|
|
||||||
void start(); // restarts recording time spent in this function
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // APM_PerfMon_h
|
|
|
@ -1,45 +0,0 @@
|
||||||
/*
|
|
||||||
APM_PerfMon
|
|
||||||
Code by Randy Mackay
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "APM_PerfMon.h" // PerfMonitor library
|
|
||||||
|
|
||||||
void setup()
|
|
||||||
{
|
|
||||||
APM_PERFMON_REGISTER_NAME("setupA")
|
|
||||||
Serial.begin(115200);
|
|
||||||
Serial.println("Performance Monitor test v1.0");
|
|
||||||
}
|
|
||||||
|
|
||||||
void loop()
|
|
||||||
{
|
|
||||||
APM_PERFMON_REGISTER
|
|
||||||
|
|
||||||
int i = 0;
|
|
||||||
|
|
||||||
for( i=0; i<100; i++ )
|
|
||||||
{
|
|
||||||
testFunction();
|
|
||||||
}
|
|
||||||
|
|
||||||
APM_PerfMon::DisplayResults(&Serial);
|
|
||||||
|
|
||||||
delay(10000);
|
|
||||||
|
|
||||||
APM_PerfMon::ClearAll();
|
|
||||||
}
|
|
||||||
|
|
||||||
void testFunction()
|
|
||||||
{
|
|
||||||
APM_PERFMON_REGISTER
|
|
||||||
delay(10);
|
|
||||||
testFunction2();
|
|
||||||
delay(10);
|
|
||||||
}
|
|
||||||
|
|
||||||
void testFunction2()
|
|
||||||
{
|
|
||||||
APM_PERFMON_REGISTER
|
|
||||||
delay(10);
|
|
||||||
}
|
|
Loading…
Reference in New Issue