HAL_ChibiOS: increase serial byte timeout

needs 2ms for final ack in verify
This commit is contained in:
Andrew Tridgell 2018-03-26 08:31:58 +11:00
parent 202a7dd091
commit 46c76c3d5d

View File

@ -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;