modified APM_PerfMon to display results sorted by %cpu
git-svn-id: https://arducopter.googlecode.com/svn/trunk@766 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
c9e7d227fe
commit
a5cb22207a
@ -86,29 +86,61 @@ int APM_PerfMon::recordFunctionName(const char funcName[])
|
|||||||
void APM_PerfMon::ClearAll()
|
void APM_PerfMon::ClearAll()
|
||||||
{
|
{
|
||||||
int i;
|
int i;
|
||||||
|
APM_PerfMon *p = lastCreated;
|
||||||
allStartTime = 0;
|
|
||||||
allEndTime = 0;
|
|
||||||
|
|
||||||
for(i=0; i<PERFMON_MAX_FUNCTIONS; i++)
|
for(i=0; i<PERFMON_MAX_FUNCTIONS; i++)
|
||||||
{
|
{
|
||||||
time[i] = 0; // reset times
|
time[i] = 0; // reset times
|
||||||
numCalls[i] = 0; // reset num times called
|
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
|
// ClearAll - clears all data from static members
|
||||||
void APM_PerfMon::DisplayResults(HardwareSerial* aSerial)
|
void APM_PerfMon::DisplayResults(HardwareSerial* aSerial)
|
||||||
{
|
{
|
||||||
int i,j,padding;
|
int i,j,k,padding,changed;
|
||||||
float hz;
|
float hz;
|
||||||
float pct;
|
float pct;
|
||||||
unsigned long totalTime;
|
unsigned long totalTime;
|
||||||
unsigned long sumOfTime = 0;
|
unsigned long sumOfTime = 0;
|
||||||
unsigned long unExplainedTime;
|
unsigned long unExplainedTime;
|
||||||
|
int order[PERFMON_MAX_FUNCTIONS];
|
||||||
|
APM_PerfMon* p = lastCreated;
|
||||||
|
|
||||||
|
// record end time
|
||||||
if( allEndTime == 0 )
|
if( allEndTime == 0 )
|
||||||
allEndTime = micros();
|
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;
|
totalTime = allEndTime - allStartTime;
|
||||||
|
|
||||||
@ -123,20 +155,21 @@ void APM_PerfMon::DisplayResults(HardwareSerial* aSerial)
|
|||||||
aSerial->println("PerfMon: \tcpu%\tmils\t#called\tHz");
|
aSerial->println("PerfMon: \tcpu%\tmils\t#called\tHz");
|
||||||
for( i=0; i<nextFuncNum; i++ )
|
for( i=0; i<nextFuncNum; i++ )
|
||||||
{
|
{
|
||||||
sumOfTime += time[i];
|
j=order[i];
|
||||||
hz = numCalls[i]/(totalTime/1000000);
|
sumOfTime += time[j];
|
||||||
pct = ((float)time[i] / (float)totalTime) * 100.0;
|
hz = numCalls[j]/(totalTime/1000000);
|
||||||
padding = PERFMON_FUNCTION_NAME_LENGTH - strLen(functionNames[i]);
|
pct = ((float)time[j] / (float)totalTime) * 100.0;
|
||||||
|
padding = PERFMON_FUNCTION_NAME_LENGTH - strLen(functionNames[j]);
|
||||||
|
|
||||||
aSerial->print(functionNames[i]);
|
aSerial->print(functionNames[j]);
|
||||||
for(j=0;j<padding;j++)
|
for(k=0;k<padding;k++)
|
||||||
aSerial->print(" ");
|
aSerial->print(" ");
|
||||||
aSerial->print("\t");
|
aSerial->print("\t");
|
||||||
aSerial->print(pct);
|
aSerial->print(pct);
|
||||||
aSerial->print("%\t");
|
aSerial->print("%\t");
|
||||||
aSerial->print(time[i]/1000);
|
aSerial->print(time[j]/1000);
|
||||||
aSerial->print("\t");
|
aSerial->print("\t");
|
||||||
aSerial->print(numCalls[i]);
|
aSerial->print(numCalls[j]);
|
||||||
aSerial->print("\t");
|
aSerial->print("\t");
|
||||||
aSerial->print(hz,0);
|
aSerial->print(hz,0);
|
||||||
aSerial->print("hz");
|
aSerial->print("hz");
|
||||||
@ -153,7 +186,10 @@ void APM_PerfMon::DisplayResults(HardwareSerial* aSerial)
|
|||||||
aSerial->print("%\t");
|
aSerial->print("%\t");
|
||||||
aSerial->print(unExplainedTime/1000);
|
aSerial->print(unExplainedTime/1000);
|
||||||
aSerial->println();
|
aSerial->println();
|
||||||
|
|
||||||
|
// turn back on any time recording
|
||||||
|
if( lastCreated != NULL )
|
||||||
|
lastCreated->start();
|
||||||
}
|
}
|
||||||
|
|
||||||
int APM_PerfMon::strLen(char* str)
|
int APM_PerfMon::strLen(char* str)
|
||||||
|
@ -24,11 +24,10 @@ void loop()
|
|||||||
}
|
}
|
||||||
|
|
||||||
APM_PerfMon::DisplayResults(&Serial);
|
APM_PerfMon::DisplayResults(&Serial);
|
||||||
|
|
||||||
|
delay(10000);
|
||||||
|
|
||||||
APM_PerfMon::ClearAll();
|
APM_PerfMon::ClearAll();
|
||||||
|
|
||||||
delay(10000);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void testFunction()
|
void testFunction()
|
||||||
|
Loading…
Reference in New Issue
Block a user