diff --git a/libraries/AP_HAL_Linux/CANSocketIface.cpp b/libraries/AP_HAL_Linux/CANSocketIface.cpp index fc51eb95db..03f3be88da 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.cpp +++ b/libraries/AP_HAL_Linux/CANSocketIface.cpp @@ -281,10 +281,10 @@ void CANIface::_pollWrite() stats.tx_success++; stats.last_transmit_us = curr_time; } else if (res == 0) { // Not transmitted, nor is it an error - stats.tx_full++; + stats.tx_overflow++; 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); @@ -592,8 +592,8 @@ bool CANIface::CANSocketEventSource::wait(uint16_t duration_us, AP_HAL::EventHan void CANIface::get_stats(ExpandingString &str) { str.printf("tx_requests: %u\n" - "tx_write_fail: %u\n" - "tx_full: %u\n" + "tx_rejected: %u\n" + "tx_overflow: %u\n" "tx_confirmed: %u\n" "tx_success: %u\n" "tx_timedout: %u\n" @@ -606,8 +606,8 @@ 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_full, + stats.tx_rejected, + stats.tx_overflow, stats.tx_confirmed, stats.tx_success, stats.tx_timedout, diff --git a/libraries/AP_HAL_Linux/CANSocketIface.h b/libraries/AP_HAL_Linux/CANSocketIface.h index 583faca14f..a7e85f4575 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.h +++ b/libraries/AP_HAL_Linux/CANSocketIface.h @@ -174,15 +174,8 @@ private: std::unordered_multiset _pending_loopback_ids; std::vector _hw_filters_container; - struct { - uint32_t tx_requests; - uint32_t tx_full; + struct bus_stats : public AP_HAL::CANIface::bus_stats_t { 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;