Browse Source

AP_HAL_ChibiOS: don't timeout after 11 bits on serial irqs

zr-v5.1
Andy Piper 4 years ago committed by Andrew Tridgell
parent
commit
e9ea360a99
  1. 5
      libraries/AP_HAL_ChibiOS/RCOutput.cpp

5
libraries/AP_HAL_ChibiOS/RCOutput.cpp

@ -1444,11 +1444,6 @@ void RCOutput::serial_bit_irq(void) @@ -1444,11 +1444,6 @@ void RCOutput::serial_bit_irq(void)
irq.nbits = 1;
irq.byte_start_tick = now;
irq.bitmask = 0;
// setup a timeout for 11 bits width, so we aren't left
// waiting at the end of bytes
chSysLockFromISR();
chVTSetI(&irq.serial_timeout, irq.bit_time_tick*11, serial_byte_timeout, irq.waiter);
chSysUnlockFromISR();
}
} else {
systime_t dt = now - irq.byte_start_tick;

Loading…
Cancel
Save