From b761060c9b979f372d019cec389930a2c7765552 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 14 Apr 2020 13:51:57 -0400 Subject: [PATCH] perf counters fix perf free and cleanup naming --- src/modules/mavlink/mavlink_main.cpp | 7 ++----- src/modules/mavlink/mavlink_main.h | 8 ++++---- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 6a8424770fb3..695a7c97f02e 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -187,11 +187,6 @@ Mavlink::Mavlink() : Mavlink::~Mavlink() { - perf_free(_loop_perf); - perf_free(_loop_interval_perf); - perf_free(_send_byte_error_perf); - perf_free(_send_start_tx_buf_low); - if (_task_running) { /* task wakes up every 10ms or so at the longest */ _task_should_exit = true; @@ -214,6 +209,8 @@ Mavlink::~Mavlink() perf_free(_loop_perf); perf_free(_loop_interval_perf); + perf_free(_send_byte_error_perf); + perf_free(_send_start_tx_buf_low); } void diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 9e0b700bb13c..09f60d570e20 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -665,10 +665,10 @@ class Mavlink : public ModuleParams (ParamInt) _param_sys_hitl ) - perf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, "mavlink_el")}; /**< loop performance counter */ - perf_counter_t _loop_interval_perf{perf_alloc(PC_INTERVAL, "mavlink_int")}; /**< loop interval performance counter */ - perf_counter_t _send_byte_error_perf{perf_alloc(PC_COUNT, "mavlink_send_bytes_error")}; /**< send bytes error count */ - perf_counter_t _send_start_tx_buf_low{perf_alloc(PC_COUNT, "mavlink_tx_buf_low")}; /**< available tx buffer smaller than message */ + perf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": tx run elapsed")}; /**< loop performance counter */ + perf_counter_t _loop_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": tx run interval")}; /**< loop interval performance counter */ + perf_counter_t _send_byte_error_perf{perf_alloc(PC_COUNT, MODULE_NAME": send_bytes error")}; /**< send bytes error count */ + perf_counter_t _send_start_tx_buf_low{perf_alloc(PC_COUNT, MODULE_NAME": send_start tx buffer full")}; /**< available tx buffer smaller than message */ void mavlink_update_parameters();