GCS_MAVLink: fix non static perf counter

Commit b9877e0d38
(GCS_MAVLink: make per channel perf counter non-static) made the
perf counters to be available per instance but missed the fact that
the perf infra doesn't copy the string.

Fix this by maintaining a the string inside the object.
This commit is contained in:
Lucas De Marchi 2017-09-12 10:24:13 -07:00
parent 406f4a9ca7
commit 58dec08b29
2 changed files with 6 additions and 6 deletions

View File

@ -363,6 +363,8 @@ private:
// perf counters
AP_HAL::Util::perf_counter_t _perf_packet;
AP_HAL::Util::perf_counter_t _perf_update;
char _perf_packet_name[16];
char _perf_update_name[16];
// deferred message handling. We size the deferred_message
// ringbuffer so we can defer every message type

View File

@ -59,13 +59,11 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
initialised = true;
_queued_parameter = nullptr;
char perf_name[16];
snprintf(_perf_packet_name, sizeof(_perf_packet_name), "GCS_Packet_%u", chan);
_perf_packet = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_packet_name);
snprintf(perf_name, sizeof(perf_name), "GCS_Packet_%u", chan);
_perf_packet = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, perf_name);
snprintf(perf_name, sizeof(perf_name), "GCS_Update_%u", chan);
_perf_update = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, perf_name);
snprintf(_perf_update_name, sizeof(_perf_update_name), "GCS_Update_%u", chan);
_perf_update = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_update_name);
}