From a5cb22207a5f44e4d4ca164b49644ae647080051 Mon Sep 17 00:00:00 2001 From: "rmackay9@yahoo.com" Date: Wed, 3 Nov 2010 07:49:37 +0000 Subject: [PATCH] modified APM_PerfMon to display results sorted by %cpu git-svn-id: https://arducopter.googlecode.com/svn/trunk@766 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/APM_PerfMon/APM_PerfMon.cpp | 62 +++++++++++++++---- .../APM_PerfMon_test/APM_PerfMon_test.pde | 5 +- 2 files changed, 51 insertions(+), 16 deletions(-) diff --git a/libraries/APM_PerfMon/APM_PerfMon.cpp b/libraries/APM_PerfMon/APM_PerfMon.cpp index 4726755329..874010f471 100644 --- a/libraries/APM_PerfMon/APM_PerfMon.cpp +++ b/libraries/APM_PerfMon/APM_PerfMon.cpp @@ -86,29 +86,61 @@ int APM_PerfMon::recordFunctionName(const char funcName[]) void APM_PerfMon::ClearAll() { int i; - - allStartTime = 0; - allEndTime = 0; + APM_PerfMon *p = lastCreated; for(i=0; i_startTime = allStartTime; + p = p->_parent; + } } // ClearAll - clears all data from static members void APM_PerfMon::DisplayResults(HardwareSerial* aSerial) { - int i,j,padding; + 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; iprintln("PerfMon: \tcpu%\tmils\t#called\tHz"); for( i=0; iprint(functionNames[i]); - for(j=0;jprint(functionNames[j]); + for(k=0;kprint(" "); aSerial->print("\t"); aSerial->print(pct); aSerial->print("%\t"); - aSerial->print(time[i]/1000); + aSerial->print(time[j]/1000); aSerial->print("\t"); - aSerial->print(numCalls[i]); + aSerial->print(numCalls[j]); aSerial->print("\t"); aSerial->print(hz,0); aSerial->print("hz"); @@ -153,7 +186,10 @@ void APM_PerfMon::DisplayResults(HardwareSerial* aSerial) 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) diff --git a/libraries/APM_PerfMon/APM_PerfMon_test/APM_PerfMon_test.pde b/libraries/APM_PerfMon/APM_PerfMon_test/APM_PerfMon_test.pde index f001c74c9b..2d8537e13e 100644 --- a/libraries/APM_PerfMon/APM_PerfMon_test/APM_PerfMon_test.pde +++ b/libraries/APM_PerfMon/APM_PerfMon_test/APM_PerfMon_test.pde @@ -24,11 +24,10 @@ void loop() } APM_PerfMon::DisplayResults(&Serial); + + delay(10000); APM_PerfMon::ClearAll(); - - delay(10000); - } void testFunction()