mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_HAL_FLYMAPLE: Fixed problem with tx buffer that caused slow parameter
delivery
This commit is contained in:
parent
c90c1b9998
commit
6b003ae551
@ -28,6 +28,8 @@
|
|||||||
|
|
||||||
using namespace AP_HAL_FLYMAPLE_NS;
|
using namespace AP_HAL_FLYMAPLE_NS;
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
FLYMAPLEUARTDriver::FLYMAPLEUARTDriver(HardwareSerial* hws):
|
FLYMAPLEUARTDriver::FLYMAPLEUARTDriver(HardwareSerial* hws):
|
||||||
_hws(hws),
|
_hws(hws),
|
||||||
_txBuf(NULL),
|
_txBuf(NULL),
|
||||||
@ -37,6 +39,8 @@ FLYMAPLEUARTDriver::FLYMAPLEUARTDriver(HardwareSerial* hws):
|
|||||||
void FLYMAPLEUARTDriver::begin(uint32_t b)
|
void FLYMAPLEUARTDriver::begin(uint32_t b)
|
||||||
{
|
{
|
||||||
_hws->begin(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)
|
void FLYMAPLEUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||||
|
Loading…
Reference in New Issue
Block a user