mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed CAN statistics on F4/L4/F3/F7
This commit is contained in:
parent
273b9ea354
commit
ebffc8fc65
|
@ -218,7 +218,9 @@ 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;
|
||||
#endif
|
||||
|
||||
#if !defined(HAL_BOOTLOADER_BUILD)
|
||||
/*
|
||||
return statistics structure
|
||||
*/
|
||||
|
@ -226,6 +228,7 @@ public:
|
|||
return &stats;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************
|
||||
* Methods used inside interrupt *
|
||||
************************************/
|
||||
|
|
|
@ -292,6 +292,7 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline,
|
|||
if (frame.isErrorFrame() || frame.dlc > 8) {
|
||||
return -1;
|
||||
}
|
||||
PERF_STATS(stats.tx_requests);
|
||||
|
||||
/*
|
||||
* Normally we should perform the same check as in @ref canAcceptNewTxFrame(), because
|
||||
|
@ -323,7 +324,7 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline,
|
|||
} else if ((can_->TSR & bxcan::TSR_TME2) == bxcan::TSR_TME2) {
|
||||
txmailbox = 2;
|
||||
} else {
|
||||
PERF_STATS(stats.tx_rejected);
|
||||
PERF_STATS(stats.tx_overflow);
|
||||
return 0; // No transmission for you.
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue