AP_HAL_ChibiOS: added last_transmit_us to CAN stats

This commit is contained in:
Andrew Tridgell 2023-09-01 14:42:23 +10:00
parent d40320b1c2
commit d5fbce0547
2 changed files with 2 additions and 0 deletions

View File

@ -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++;
}

View File

@ -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;
}
}