Skip to content

Commit

Permalink
perf counters fix perf free and cleanup naming
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar authored and LorenzMeier committed Apr 15, 2020
1 parent dc2254a commit b761060
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 9 deletions.
7 changes: 2 additions & 5 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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
Expand Down
8 changes: 4 additions & 4 deletions src/modules/mavlink/mavlink_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -665,10 +665,10 @@ class Mavlink : public ModuleParams
(ParamInt<px4::params::SYS_HITL>) _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();

Expand Down

0 comments on commit b761060

Please sign in to comment.