mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_ChibiOS: increase serial byte timeout
needs 2ms for final ack in verify
This commit is contained in:
parent
202a7dd091
commit
46c76c3d5d
@ -1057,7 +1057,7 @@ void RCOutput::serial_bit_irq(void)
|
||||
*/
|
||||
bool RCOutput::serial_read_byte(uint8_t &b)
|
||||
{
|
||||
bool timed_out = ((chEvtWaitAnyTimeout(serial_event_mask, MS2ST(1)) & serial_event_mask) == 0);
|
||||
bool timed_out = ((chEvtWaitAnyTimeout(serial_event_mask, MS2ST(2)) & serial_event_mask) == 0);
|
||||
|
||||
uint16_t byteval = irq.byteval;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user