mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
HAL_ChibiOS: fixed a bug in wait_timeout() on UARTs
wait_timeout() could return true on a read of less bytes than are expected.
This commit is contained in:
parent
eb9e5df0dd
commit
afc8a70ce4
@ -647,14 +647,18 @@ size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key
|
|||||||
*/
|
*/
|
||||||
bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
|
bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
|
||||||
{
|
{
|
||||||
chEvtGetAndClearEvents(EVT_DATA);
|
uint32_t t0 = AP_HAL::millis();
|
||||||
if (available() >= n) {
|
while (available() < n) {
|
||||||
return true;
|
chEvtGetAndClearEvents(EVT_DATA);
|
||||||
|
_wait.n = n;
|
||||||
|
_wait.thread_ctx = chThdGetSelfX();
|
||||||
|
uint32_t now = AP_HAL::millis();
|
||||||
|
if (now - t0 >= timeout_ms) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
chEvtWaitAnyTimeout(EVT_DATA, chTimeMS2I(timeout_ms - (now - t0)));
|
||||||
}
|
}
|
||||||
_wait.n = n;
|
return available() >= n;
|
||||||
_wait.thread_ctx = chThdGetSelfX();
|
|
||||||
eventmask_t mask = chEvtWaitAnyTimeout(EVT_DATA, chTimeMS2I(timeout_ms));
|
|
||||||
return (mask & EVT_DATA) != 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user