From 21b4a19c6f78deff475b1003c406c933f71519f9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Dec 2022 13:35:59 +1100 Subject: [PATCH] HAL_SITL: implement CAN get_statistics() --- libraries/AP_HAL_SITL/CANSocketIface.cpp | 6 +++--- libraries/AP_HAL_SITL/CANSocketIface.h | 18 +++++++++++------- 2 files changed, 14 insertions(+), 10 deletions(-) diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index 02501a9486..84c6147509 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -322,7 +322,7 @@ void CANIface::_pollWrite() stats.tx_full++; break; // Leaving the loop, the frame remains enqueued for the next retry } else { // Transmission error - stats.tx_write_fail++; + stats.tx_rejected++; } } else { // hal.console->printf("TDEAD: %lu CURRT: %lu DEL: %lu\n", tx.deadline, curr_time, curr_time-tx.deadline); @@ -702,7 +702,7 @@ bool CANIface::CANSocketEventSource::wait(uint64_t duration, AP_HAL::EventHandle void CANIface::get_stats(ExpandingString &str) { str.printf("tx_requests: %u\n" - "tx_write_fail: %u\n" + "tx_rejected: %u\n" "tx_full: %u\n" "tx_confirmed: %u\n" "tx_success: %u\n" @@ -716,7 +716,7 @@ void CANIface::get_stats(ExpandingString &str) "num_poll_tx_events: %u\n" "num_poll_rx_events: %u\n", stats.tx_requests, - stats.tx_write_fail, + stats.tx_rejected, stats.tx_full, stats.tx_confirmed, stats.tx_success, diff --git a/libraries/AP_HAL_SITL/CANSocketIface.h b/libraries/AP_HAL_SITL/CANSocketIface.h index a9e9ac486c..37dd3fd584 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.h +++ b/libraries/AP_HAL_SITL/CANSocketIface.h @@ -118,6 +118,13 @@ public: // results available via @SYS/can0_stats.txt or @SYS/can1_stats.txt void get_stats(ExpandingString &str) override; + /* + return statistics structure + */ + const bus_stats_t *get_statistics(void) const override { + return &stats; + } + class CANSocketEventSource : public AP_HAL::EventSource { friend class CANIface; CANIface *_ifaces[HAL_NUM_CAN_IFACES]; @@ -179,15 +186,12 @@ private: std::unordered_multiset _pending_loopback_ids; std::vector _hw_filters_container; - struct { - uint32_t tx_requests; + /* + additional statistics + */ + struct bus_stats : public AP_HAL::CANIface::bus_stats_t { uint32_t tx_full; uint32_t tx_confirmed; - uint32_t tx_write_fail; - uint32_t tx_success; - uint32_t tx_timedout; - uint32_t rx_received; - uint32_t rx_errors; uint32_t num_downs; uint32_t num_rx_poll_req; uint32_t num_tx_poll_req;