From 6b003ae5518bc0fa363367038d3681afe67d4fe5 Mon Sep 17 00:00:00 2001 From: Mike McCauley Date: Thu, 3 Oct 2013 21:48:30 +1000 Subject: [PATCH] AP_HAL_FLYMAPLE: Fixed problem with tx buffer that caused slow parameter delivery --- libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp b/libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp index 273130429e..a1ddb8a340 100644 --- a/libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp +++ b/libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp @@ -28,6 +28,8 @@ using namespace AP_HAL_FLYMAPLE_NS; +extern const AP_HAL::HAL& hal; + FLYMAPLEUARTDriver::FLYMAPLEUARTDriver(HardwareSerial* hws): _hws(hws), _txBuf(NULL), @@ -37,6 +39,8 @@ FLYMAPLEUARTDriver::FLYMAPLEUARTDriver(HardwareSerial* hws): void FLYMAPLEUARTDriver::begin(uint32_t b) { _hws->begin(b); + if (_txBuf) + rb_init(_hws->c_dev()->rb, _txBufSize, _txBuf); // Get the ring buffer size we want } void FLYMAPLEUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)