mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_HAL: added generic perf counter
simple wrapper around PX4 API, but ready for use by other HALs
This commit is contained in:
parent
3f9d62d6b4
commit
28fa05c965
@ -84,6 +84,20 @@ public:
|
|||||||
/* Support for an imu heating system */
|
/* Support for an imu heating system */
|
||||||
virtual void set_imu_temp(float current) {}
|
virtual void set_imu_temp(float current) {}
|
||||||
|
|
||||||
|
/*
|
||||||
|
performance counter calls - wrapper around original PX4 interface
|
||||||
|
*/
|
||||||
|
enum perf_counter_type {
|
||||||
|
PC_COUNT, /**< count the number of times an event occurs */
|
||||||
|
PC_ELAPSED, /**< measure the time elapsed performing an event */
|
||||||
|
PC_INTERVAL /**< measure the interval between instances of an event */
|
||||||
|
};
|
||||||
|
typedef void *perf_counter_t;
|
||||||
|
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; }
|
||||||
|
virtual void perf_begin(perf_counter_t h) {}
|
||||||
|
virtual void perf_end(perf_counter_t h) {}
|
||||||
|
virtual void perf_count(perf_counter_t h) {}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// we start soft_armed false, so that actuators don't send any
|
// we start soft_armed false, so that actuators don't send any
|
||||||
// values until the vehicle code has fully started
|
// values until the vehicle code has fully started
|
||||||
|
Loading…
Reference in New Issue
Block a user