mirror of https://github.com/ArduPilot/ardupilot
SITL: make serial buffer size configurable
we need a larger buffer size for NMEA GPS modules
This commit is contained in:
parent
29f1c31854
commit
78dac16520
|
@ -36,7 +36,7 @@ extern const AP_HAL::HAL& hal;
|
|||
using namespace SITL;
|
||||
|
||||
GPS::GPS(uint8_t _instance) :
|
||||
SerialDevice(),
|
||||
SerialDevice(8192, 2048),
|
||||
instance{_instance}
|
||||
{
|
||||
|
||||
|
|
|
@ -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()
|
||||
|
|
|
@ -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:
|
||||
|
|
Loading…
Reference in New Issue