mavlink: add detailed stats about rx messages

This commit is contained in:
Julian Oes 2021-04-21 15:45:21 +02:00 committed by Daniel Agar
parent 370d9ee409
commit 5784f1d951
3 changed files with 23 additions and 0 deletions

View File

@ -2814,6 +2814,7 @@ Mavlink::display_status()
printf("\t tx rate max: %i B/s\n", _datarate);
printf("\t rx: %.1f B/s\n", (double)_tstatus.rx_rate_avg);
printf("\t rx loss: %.1f%%\n", (double)_tstatus.rx_message_lost_rate);
_receiver.print_detailed_rx_stats();
if (_mavlink_ulog) {
printf("\tULog rate: %.1f%% of max %.1f%%\n", (double)_mavlink_ulog->current_data_rate() * 100.,

View File

@ -3151,6 +3151,26 @@ void MavlinkReceiver::update_rx_stats(const mavlink_message_t &message)
}
}
void MavlinkReceiver::print_detailed_rx_stats() const
{
const uint32_t now_ms = hrt_absolute_time() / 1000;
// TODO: add mutex around shared data.
for (unsigned i = 0; i < MAX_REMOTE_COMPONENTS; ++i) {
if (_component_states[i].received_messages > 0) {
printf("\t received from %u/%u: %lu, lost: %lu, last %lu ms ago\n",
_component_states[i].system_id,
_component_states[i].component_id,
_component_states[i].received_messages,
_component_states[i].missed_messages,
now_ms - _component_states[i].last_time_received_ms);
} else {
break;
}
}
}
void MavlinkReceiver::start()
{
pthread_attr_t receiveloop_attr;

View File

@ -124,6 +124,8 @@ public:
void start();
void stop();
void print_detailed_rx_stats() const;
private:
static void *start_trampoline(void *context);
void run();