mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
HAL_ChibiOS: implement get_statistics()
This commit is contained in:
parent
05a6c0d026
commit
bfff5548ef
@ -154,17 +154,11 @@ class ChibiOS::CANIface : public AP_HAL::CANIface
|
||||
bool _detected_bus_off;
|
||||
Timings timings, fdtimings;
|
||||
uint32_t _bitrate, _fdbitrate;
|
||||
struct {
|
||||
uint32_t tx_requests;
|
||||
uint32_t tx_rejected;
|
||||
uint32_t tx_overflow;
|
||||
uint32_t tx_success;
|
||||
uint32_t tx_timedout;
|
||||
uint32_t tx_abort;
|
||||
uint32_t rx_received;
|
||||
uint32_t rx_overflow;
|
||||
uint32_t rx_errors;
|
||||
uint32_t num_busoff_err;
|
||||
|
||||
/*
|
||||
additional statistics
|
||||
*/
|
||||
struct bus_stats : public AP_HAL::CANIface::bus_stats_t {
|
||||
uint32_t num_events;
|
||||
uint32_t ecr;
|
||||
uint32_t fdf_tx_requests;
|
||||
@ -239,6 +233,14 @@ public:
|
||||
// fetch stats text and return the size of the same,
|
||||
// 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;
|
||||
}
|
||||
|
||||
#endif
|
||||
/************************************
|
||||
* Methods used inside interrupt *
|
||||
|
@ -141,17 +141,10 @@ class ChibiOS::CANIface : public AP_HAL::CANIface
|
||||
void initOnce(bool enable_irq);
|
||||
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD)
|
||||
struct {
|
||||
uint32_t tx_requests;
|
||||
uint32_t tx_rejected;
|
||||
uint32_t tx_success;
|
||||
uint32_t tx_timedout;
|
||||
uint32_t tx_loopback;
|
||||
uint32_t tx_abort;
|
||||
uint32_t rx_received;
|
||||
uint32_t rx_overflow;
|
||||
uint32_t rx_errors;
|
||||
uint32_t num_busoff_err;
|
||||
/*
|
||||
additional statistics
|
||||
*/
|
||||
struct bus_stats : public AP_HAL::CANIface::bus_stats_t {
|
||||
uint32_t num_events;
|
||||
uint32_t esr;
|
||||
} stats;
|
||||
@ -225,6 +218,13 @@ public:
|
||||
// fetch stats text and return the size of the same,
|
||||
// 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;
|
||||
}
|
||||
#endif
|
||||
/************************************
|
||||
* Methods used inside interrupt *
|
||||
|
@ -487,7 +487,6 @@ void CANIface::handleTxMailboxInterrupt(uint8_t mailbox_index, bool txok, const
|
||||
rx_item.frame = txi.frame;
|
||||
rx_item.timestamp_us = timestamp_us;
|
||||
rx_item.flags = AP_HAL::CANIface::Loopback;
|
||||
PERF_STATS(stats.tx_loopback);
|
||||
add_to_rx_queue(rx_item);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user