ardupilot/libraries/AP_PerfMon/AP_PerfMon.h
Gustavo Jose de Sousa 0900cefba9 AP_PerfMon: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
2015-08-11 16:38:22 +10:00

52 lines
2.0 KiB
C++

#ifndef AP_PERFMON_H
#define AP_PERFMON_H
// macros to make integrating into code easier
#define AP_PERFMON_REGISTER static uint8_t myFunc = AP_PerfMon::recordFunctionName(__func__); AP_PerfMon perfMon(myFunc);
#define AP_PERFMON_REGISTER_NAME(functionName) static uint8_t myFunc = AP_PerfMon::recordFunctionName(functionName); AP_PerfMon perfMon(myFunc);
#define AP_PERFMON_REGISTER_FN(func_name) static uint8_t func_name ## _num = AP_PerfMon::recordFunctionName(#func_name);
#define AP_PERFMON_FUNCTION(func_name) AP_PerfMon perfMon(func_name ## _num);
#define PERFMON_MAX_FUNCTIONS 12
#define PERFMON_FUNCTION_NAME_LENGTH 10
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
class AP_PerfMon
{
public:
// static methods
static uint8_t recordFunctionName(const char funcName[]);
static void DisplayResults();
static void ClearAll();
static void DisplayAndClear(uint32_t display_after_seconds); // will display results after this many milliseconds. should be called regularly
// public methods
AP_PerfMon(uint8_t funcNum); // Constructor - records function start time
~AP_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
private:
// static variables
static uint8_t nextFuncNum;
static char functionNames[PERFMON_MAX_FUNCTIONS][PERFMON_FUNCTION_NAME_LENGTH];
static uint32_t time[PERFMON_MAX_FUNCTIONS];
static uint32_t numCalls[PERFMON_MAX_FUNCTIONS];
static uint32_t maxTime[PERFMON_MAX_FUNCTIONS];
static uint32_t allStartTime;
static uint32_t allEndTime;
static AP_PerfMon* lastCreated;
static bool _enabled;
// instance variables
uint8_t _funcNum;
unsigned long _startTime;
unsigned long _time_this_iteration;
AP_PerfMon* _parent;
};
#endif // AP_PERFMON_H