Browse Source

AP_IOMCU: use unbuffered UART writes

this lowers latency for servo outputs to the IOMCU
master
Andrew Tridgell 7 years ago
parent
commit
5ffcff1a79
  1. 1
      libraries/AP_IOMCU/AP_IOMCU.cpp

1
libraries/AP_IOMCU/AP_IOMCU.cpp

@ -145,6 +145,7 @@ void AP_IOMCU::thread_main(void) @@ -145,6 +145,7 @@ void AP_IOMCU::thread_main(void)
// uart runs at 1.5MBit
uart.begin(1500*1000, 256, 256);
uart.set_blocking_writes(false);
uart.set_unbuffered_writes(true);
trigger_event(IOEVENT_INIT);

Loading…
Cancel
Save