HAL_SITL: use a smaller buffer for real SITL UARTs

better emulation of real hw
This commit is contained in:
Andrew Tridgell 2016-05-23 23:31:23 +10:00
parent 595d5c0002
commit 635a975486
2 changed files with 3 additions and 12 deletions

View File

@ -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) {

View File

@ -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;
};