mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
HAL_PX4: take account of available bytes in receive_time_constraint_us
This commit is contained in:
parent
b396b2a2e0
commit
36ebb14b2e
@ -542,12 +542,12 @@ void PX4UARTDriver::_timer_tick(void)
|
||||
|
||||
A return value of zero means the HAL does not support this API
|
||||
*/
|
||||
uint64_t PX4UARTDriver::receive_time_constraint_us(uint16_t nbytes) const
|
||||
uint64_t PX4UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
||||
{
|
||||
uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
|
||||
if (_baudrate > 0 && !_is_usb) {
|
||||
// assume 10 bits per byte. For USB we assume zero transport delay
|
||||
uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * nbytes;
|
||||
uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
|
||||
last_receive_us -= transport_time_us;
|
||||
}
|
||||
return last_receive_us;
|
||||
|
@ -57,7 +57,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:
|
||||
const char *_devpath;
|
||||
|
Loading…
Reference in New Issue
Block a user