mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_PerfMon: use millis/micros/panic functions
This commit is contained in:
parent
d186704724
commit
26c06ae3a9
@ -23,7 +23,7 @@ AP_PerfMon::AP_PerfMon(uint8_t funcNum) : _funcNum(funcNum), _time_this_iteratio
|
|||||||
|
|
||||||
// check global start time
|
// check global start time
|
||||||
if( allStartTime == 0 ) {
|
if( allStartTime == 0 ) {
|
||||||
allStartTime = hal.scheduler->micros();
|
allStartTime = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
// stop recording time from parent
|
// stop recording time from parent
|
||||||
@ -81,13 +81,13 @@ uint8_t AP_PerfMon::recordFunctionName(const char funcName[])
|
|||||||
// stop recording time
|
// stop recording time
|
||||||
void AP_PerfMon::start()
|
void AP_PerfMon::start()
|
||||||
{
|
{
|
||||||
_startTime = hal.scheduler->micros(); // start recording time spent in this function
|
_startTime = AP_HAL::micros(); // start recording time spent in this function
|
||||||
}
|
}
|
||||||
|
|
||||||
// stop recording time
|
// stop recording time
|
||||||
void AP_PerfMon::stop()
|
void AP_PerfMon::stop()
|
||||||
{
|
{
|
||||||
uint32_t temp_time = hal.scheduler->micros()-_startTime;
|
uint32_t temp_time = AP_HAL::micros()-_startTime;
|
||||||
_time_this_iteration += temp_time;
|
_time_this_iteration += temp_time;
|
||||||
time[_funcNum] += temp_time;
|
time[_funcNum] += temp_time;
|
||||||
}
|
}
|
||||||
@ -105,7 +105,7 @@ void AP_PerfMon::ClearAll()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// reset start time to now
|
// reset start time to now
|
||||||
allStartTime = hal.scheduler->micros();
|
allStartTime = AP_HAL::micros();
|
||||||
allEndTime = 0;
|
allEndTime = 0;
|
||||||
|
|
||||||
// reset start times of any active counters
|
// reset start times of any active counters
|
||||||
@ -129,7 +129,7 @@ void AP_PerfMon::DisplayResults()
|
|||||||
|
|
||||||
// record end time
|
// record end time
|
||||||
if( allEndTime == 0 ) {
|
if( allEndTime == 0 ) {
|
||||||
allEndTime = hal.scheduler->micros();
|
allEndTime = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
// turn off any time recording
|
// turn off any time recording
|
||||||
@ -207,7 +207,7 @@ void AP_PerfMon::DisplayResults()
|
|||||||
// DisplayAndClear - will display results after this many milliseconds. should be called regularly
|
// DisplayAndClear - will display results after this many milliseconds. should be called regularly
|
||||||
void AP_PerfMon::DisplayAndClear(uint32_t display_after_seconds)
|
void AP_PerfMon::DisplayAndClear(uint32_t display_after_seconds)
|
||||||
{
|
{
|
||||||
if( (hal.scheduler->micros() - allStartTime) > (uint32_t)(display_after_seconds * 1000000) ) {
|
if( (AP_HAL::micros() - allStartTime) > (uint32_t)(display_after_seconds * 1000000) ) {
|
||||||
DisplayResults();
|
DisplayResults();
|
||||||
ClearAll();
|
ClearAll();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user