mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
HAL_F4Light: take account of available bytes in receive_time_constraint_us
This commit is contained in:
parent
89898bae1d
commit
f983c8a906
@ -149,14 +149,14 @@ void UARTDriver::update_timestamp(){ // called from ISR
|
||||
}
|
||||
|
||||
// this is mostly a
|
||||
uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) const {
|
||||
uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) {
|
||||
|
||||
// timestamp is 32 bits so read is atomic, in worst case we get 2nd timestamp
|
||||
uint32_t time_from_last_byte = AP_HAL::micros() - _receive_timestamp[_time_idx];
|
||||
uint32_t transport_time_us = 0;
|
||||
if (_baudrate > 0) {
|
||||
// assume 10 bits per byte
|
||||
transport_time_us = (1000000UL * 10UL / _baudrate) * nbytes;
|
||||
transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
|
||||
}
|
||||
return AP_HAL::micros64() - (time_from_last_byte + transport_time_us);
|
||||
}
|
||||
|
@ -53,7 +53,7 @@ public:
|
||||
|
||||
inline void disable(){ _usart_device = NULL; } // pins used for another needs
|
||||
|
||||
uint64_t receive_time_constraint_us(uint16_t nbytes) const override;
|
||||
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
||||
|
||||
void update_timestamp();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user