mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: fixed unbuffered UART writes in SITL
this was causing PPP to slow down by about 1000x due to duplicate writes
This commit is contained in:
parent
0a8faa83d9
commit
cfa28c5246
|
@ -787,6 +787,7 @@ uint16_t UARTDriver::read_from_async_csv(uint8_t *buffer, uint16_t space)
|
|||
|
||||
void UARTDriver::handle_writing_from_writebuffer_to_device()
|
||||
{
|
||||
WITH_SEMAPHORE(write_mtx);
|
||||
if (!_connected) {
|
||||
_check_reconnect();
|
||||
return;
|
||||
|
|
|
@ -110,6 +110,8 @@ private:
|
|||
uint32_t last_read_tick_us;
|
||||
uint32_t last_write_tick_us;
|
||||
|
||||
HAL_Semaphore write_mtx;
|
||||
|
||||
SITL::SerialDevice *_sim_serial_device;
|
||||
|
||||
struct {
|
||||
|
|
Loading…
Reference in New Issue