mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 16:13:56 -03:00
HAL_SITL: take account of available bytes in receive_time_constraint_us
This commit is contained in:
parent
36ebb14b2e
commit
049e3ae02d
@ -518,12 +518,12 @@ void UARTDriver::_timer_tick(void)
|
||||
|
||||
A return value of zero means the HAL does not support this API
|
||||
*/
|
||||
uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) const
|
||||
uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
||||
{
|
||||
uint64_t last_receive_us = _receive_timestamp;
|
||||
if (_uart_baudrate > 0) {
|
||||
// assume 10 bits per byte.
|
||||
uint32_t transport_time_us = (1000000UL * 10UL / _uart_baudrate) * nbytes;
|
||||
uint32_t transport_time_us = (1000000UL * 10UL / _uart_baudrate) * (nbytes+available());
|
||||
last_receive_us -= transport_time_us;
|
||||
}
|
||||
return last_receive_us;
|
||||
|
@ -80,7 +80,7 @@ public:
|
||||
|
||||
A return value of zero means the HAL does not support this API
|
||||
*/
|
||||
uint64_t receive_time_constraint_us(uint16_t nbytes) const override;
|
||||
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
||||
|
||||
private:
|
||||
uint8_t _portNumber;
|
||||
|
Loading…
Reference in New Issue
Block a user