AP_HAL_ChibiOS: added last_transmit_us to CAN stats
This commit is contained in:
parent
d40320b1c2
commit
d5fbce0547
@ -796,6 +796,7 @@ void CANIface::handleTxCompleteInterrupt(const uint64_t timestamp_us)
|
||||
|
||||
if (!pending_tx_[i].pushed) {
|
||||
stats.tx_success++;
|
||||
stats.last_transmit_us = timestamp_us;
|
||||
if (pending_tx_[i].canfd_frame) {
|
||||
stats.fdf_tx_success++;
|
||||
}
|
||||
|
@ -496,6 +496,7 @@ void CANIface::handleTxMailboxInterrupt(uint8_t mailbox_index, bool txok, const
|
||||
if (txok && !txi.pushed) {
|
||||
txi.pushed = true;
|
||||
PERF_STATS(stats.tx_success);
|
||||
stats.last_transmit_us = timestamp_us;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user