mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: added last_transmit_us to CAN stats
This commit is contained in:
parent
aaa2746bff
commit
9afc30671f
|
@ -145,6 +145,7 @@ void CANIface::_pollWrite()
|
|||
bool ok = transport->send(tx.frame);
|
||||
if (ok) {
|
||||
stats.tx_success++;
|
||||
stats.last_transmit_us = curr_time;
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue