Browse Source

AP_HAL: added function for last receive timestamp on uarts

this is used for mavlink vision time estimates
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
f7a239d833
  1. 15
      libraries/AP_HAL/UARTDriver.h

15
libraries/AP_HAL/UARTDriver.h

@ -70,4 +70,19 @@ public: @@ -70,4 +70,19 @@ public:
* can implement it if their HAL layer requires.
*/
virtual void _timer_tick(void) { }
/*
return timestamp estimate in microseconds for when the start of
a nbytes packet arrived on the uart. This should be treated as a
time constraint, not an exact time. It is guaranteed that the
packet did not start being received after this time, but it
could have been in a system buffer before the returned time.
This takes account of the baudrate of the link. For transports
that have no baudrate (such as USB) the time estimate may be
less accurate.
A return value of zero means the HAL does not support this API
*/
virtual uint64_t receive_time_constraint_us(uint16_t nbytes) const { return 0; }
};

Loading…
Cancel
Save