AP_HAL_ChibiOS: use buffered writes for CRSF telemetry

This commit is contained in:
Andy Piper 2021-01-26 19:19:44 +00:00 committed by Andrew Tridgell
parent 8d38a627a9
commit 881fd4f37c
2 changed files with 0 additions and 2 deletions

View File

@ -266,7 +266,6 @@ void AP_RCProtocol::check_added_uart(void)
added.uart->configure_parity(0);
added.uart->set_stop_bits(1);
added.uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
added.uart->set_unbuffered_writes(true);
added.uart->set_blocking_writes(false);
added.uart->set_options(added.uart->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV);
break;

View File

@ -370,7 +370,6 @@ void AP_RCProtocol_CRSF::start_uart()
_uart->configure_parity(0);
_uart->set_stop_bits(1);
_uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
_uart->set_unbuffered_writes(true);
_uart->set_blocking_writes(false);
_uart->set_options(_uart->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV);
_uart->begin(CRSF_BAUDRATE, 128, 128);