AP_HAL: removed perf counters

This commit is contained in:
Andrew Tridgell 2021-06-07 09:59:07 +10:00
parent 684e32068b
commit 7c5c805381
3 changed files with 0 additions and 22 deletions

View File

@ -139,20 +139,6 @@ public:
/* Support for an imu heating system */
virtual void set_imu_target_temp(int8_t *target) {}
/*
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 nullptr; }
virtual void perf_begin(perf_counter_t h) {}
virtual void perf_end(perf_counter_t h) {}
virtual void perf_count(perf_counter_t h) {}
// allocate and free DMA-capable memory if possible. Otherwise return normal memory
enum Memory_Type {
MEM_DMA_SAFE,

View File

@ -347,8 +347,6 @@ bool RCOutput_Tap::_uart_open()
void RCOutput_Tap::init()
{
_perf_rcout = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "APM_rcout");
if (!_uart_open()) {
AP_HAL::panic("Unable to open " HAL_RCOUTPUT_TAP_DEVICE);
return;
@ -498,8 +496,6 @@ void RCOutput_Tap::push()
{
_corking = false;
hal.util->perf_begin(_perf_rcout);
uint16_t out[TAP_ESC_MAX_MOTOR_NUM];
uint8_t motor_cnt = _channels_count;
@ -573,8 +569,6 @@ void RCOutput_Tap::push()
if (ret < 1) {
debug("TX ERROR: ret: %d, errno: %d", ret, errno);
}
hal.util->perf_end(_perf_rcout);
}
#endif

View File

@ -85,8 +85,6 @@ private:
bool _uart_set_speed(int speed);
void _uart_close();
AP_HAL::Util::perf_counter_t _perf_rcout;
uint8_t _enabled_channels;
bool _corking;
bool _led_on;