diff --git a/libraries/AP_HAL/UARTDriver.cpp b/libraries/AP_HAL/UARTDriver.cpp index 40819c9900..b3d06c4f45 100644 --- a/libraries/AP_HAL/UARTDriver.cpp +++ b/libraries/AP_HAL/UARTDriver.cpp @@ -152,3 +152,14 @@ bool AP_HAL::UARTDriver::discard_input() } return _discard_input(); } + +/* + default implementation of receive_time_constraint_us() will be used + for subclasses that don't implement the call (eg. network + sockets). Best we can do is to use the current timestamp as we don't + know the transport delay + */ +uint64_t AP_HAL::UARTDriver::receive_time_constraint_us(uint16_t nbytes) +{ + return AP_HAL::micros64(); +} diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index b3e890b719..a7e0c61ef2 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -137,10 +137,8 @@ public: 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) { return 0; } + virtual uint64_t receive_time_constraint_us(uint16_t nbytes); virtual uint32_t bw_in_bytes_per_second() const { return 5760;