From 635a9754861989dd9e906d174faec80f509fb454 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 23 May 2016 23:31:23 +1000 Subject: [PATCH] HAL_SITL: use a smaller buffer for real SITL UARTs better emulation of real hw --- libraries/AP_HAL_SITL/UARTDriver.cpp | 3 +++ libraries/AP_HAL_SITL/UARTDriver.h | 12 ------------ 2 files changed, 3 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 5641f833dc..12c4580ce2 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -307,6 +307,9 @@ void UARTDriver::_uart_start_connection(const char *path, uint32_t baudrate) if (!_connected) { ::printf("Opening %s\n", path); _fd = ::open(path, O_RDWR | O_CLOEXEC); + // use much smaller buffer sizes on real UARTs + _writebuffer.set_size(1024); + _readbuffer.set_size(512); } if (_fd == -1) { diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 7d1c9e9a59..97e251a623 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -83,18 +83,6 @@ private: static bool _select_check(int ); static void _set_nonblocking(int ); - /// default receive buffer size - static const uint16_t _default_rx_buffer_size = 128; - - /// default transmit buffer size - static const uint16_t _default_tx_buffer_size = 16; - - /// maxium tx/rx buffer size - /// @note if we could bring the max size down to 256, the mask and head/tail - /// pointers in the buffer could become uint8_t. - /// - static const uint16_t _max_buffer_size = 512; - SITL_State *_sitlState; };