From 78dac16520d0f4fe57eaa8dd60735d1727a40e19 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 30 Nov 2022 07:59:21 +1100 Subject: [PATCH] SITL: make serial buffer size configurable we need a larger buffer size for NMEA GPS modules --- libraries/SITL/SIM_GPS.cpp | 2 +- libraries/SITL/SIM_SerialDevice.cpp | 6 +++--- libraries/SITL/SIM_SerialDevice.h | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 1c23225405..5e5b732b5f 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -36,7 +36,7 @@ extern const AP_HAL::HAL& hal; using namespace SITL; GPS::GPS(uint8_t _instance) : - SerialDevice(), + SerialDevice(8192, 2048), instance{_instance} { diff --git a/libraries/SITL/SIM_SerialDevice.cpp b/libraries/SITL/SIM_SerialDevice.cpp index 9f7a2538ce..64eb1edb87 100644 --- a/libraries/SITL/SIM_SerialDevice.cpp +++ b/libraries/SITL/SIM_SerialDevice.cpp @@ -27,10 +27,10 @@ using namespace SITL; -SerialDevice::SerialDevice() +SerialDevice::SerialDevice(uint16_t tx_bufsize, uint16_t rx_bufsize) { - to_autopilot = new ByteBuffer{512}; - from_autopilot = new ByteBuffer{512}; + to_autopilot = new ByteBuffer{tx_bufsize}; + from_autopilot = new ByteBuffer{rx_bufsize}; } bool SerialDevice::init_sitl_pointer() diff --git a/libraries/SITL/SIM_SerialDevice.h b/libraries/SITL/SIM_SerialDevice.h index b6d24d77c6..2a36497345 100644 --- a/libraries/SITL/SIM_SerialDevice.h +++ b/libraries/SITL/SIM_SerialDevice.h @@ -26,7 +26,7 @@ namespace SITL { class SerialDevice { public: - SerialDevice(); + SerialDevice(uint16_t tx_bufsize=512, uint16_t rx_bufsize=512); // methods for autopilot to use to talk to device: