mavlink_ulog: update ulog_stream message lost errors to perf counter

This commit is contained in:
Igor Mišić 2021-07-16 19:55:51 +02:00 committed by Daniel Agar
parent cfef0c5d5a
commit 54c91002cd
2 changed files with 10 additions and 2 deletions

View File

@ -66,6 +66,11 @@ MavlinkULog::MavlinkULog(int datarate, float max_rate_factor, uint8_t target_sys
_next_rate_check = _last_sent_time + _rate_calculation_delta_t * 1.e6f;
}
MavlinkULog::~MavlinkULog()
{
perf_free(_msg_missed_ulog_stream_perf);
}
void MavlinkULog::start_ack_received()
{
if (_waiting_for_initial_ack) {
@ -134,7 +139,7 @@ int MavlinkULog::handle_update(mavlink_channel_t channel)
_ulog_stream_sub.update();
if (_ulog_stream_sub.get_last_generation() != last_generation + 1) {
PX4_ERR("ulog_stream lost, generation %d -> %d", last_generation, _ulog_stream_sub.get_last_generation());
perf_count(_msg_missed_ulog_stream_perf);
}
const ulog_stream_s &ulog_data = _ulog_stream_sub.get();

View File

@ -45,6 +45,7 @@
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/sem.h>
#include <drivers/drv_hrt.h>
#include <lib/perf/perf_counter.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
@ -102,7 +103,7 @@ private:
MavlinkULog(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component);
~MavlinkULog() = default;
~MavlinkULog();
static void lock()
{
@ -137,6 +138,8 @@ private:
int _current_num_msgs = 0; ///< number of messages sent within the current time interval
hrt_abstime _next_rate_check; ///< next timestamp at which to update the rate
perf_counter_t _msg_missed_ulog_stream_perf{perf_alloc(PC_COUNT, MODULE_NAME": ulog_stream messages missed")};
/* do not allow copying this class */
MavlinkULog(const MavlinkULog &) = delete;
MavlinkULog operator=(const MavlinkULog &) = delete;