Browse Source

AP_HAL_FLYMAPLE: Fixed problem with tx buffer that caused slow parameter

delivery
mission-4.1.18
Mike McCauley 12 years ago committed by Andrew Tridgell
parent
commit
6b003ae551
  1. 4
      libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp

4
libraries/AP_HAL_FLYMAPLE/UARTDriver.cpp

@ -28,6 +28,8 @@ @@ -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): @@ -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)

Loading…
Cancel
Save