mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL: ensure all UARTDriver implementations have receive_time_constraint_us
this fixes NMEA over network ports
This commit is contained in:
parent
85537c2e97
commit
d1fcb76c9f
@ -152,3 +152,14 @@ bool AP_HAL::UARTDriver::discard_input()
|
|||||||
}
|
}
|
||||||
return _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();
|
||||||
|
}
|
||||||
|
@ -137,10 +137,8 @@ public:
|
|||||||
This takes account of the baudrate of the link. For transports
|
This takes account of the baudrate of the link. For transports
|
||||||
that have no baudrate (such as USB) the time estimate may be
|
that have no baudrate (such as USB) the time estimate may be
|
||||||
less accurate.
|
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 {
|
virtual uint32_t bw_in_bytes_per_second() const {
|
||||||
return 5760;
|
return 5760;
|
||||||
|
Loading…
Reference in New Issue
Block a user