mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
HAL_ChibiOS: make sure the UART bounce buffers are DMA safe
This commit is contained in:
parent
eec4a12cc2
commit
0fade4eb9e
@ -54,7 +54,6 @@ uint32_t UARTDriver::last_thread_run_us;
|
||||
#define EVT_DATA EVENT_MASK(0)
|
||||
|
||||
UARTDriver::UARTDriver(uint8_t _serial_num) :
|
||||
tx_bounce_buf_ready(true),
|
||||
serial_num(_serial_num),
|
||||
sdef(_serial_tab[_serial_num]),
|
||||
_baudrate(57600),
|
||||
@ -165,6 +164,14 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
_baudrate = b;
|
||||
}
|
||||
|
||||
if (rx_bounce_buf == nullptr) {
|
||||
rx_bounce_buf = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
}
|
||||
if (tx_bounce_buf == nullptr) {
|
||||
tx_bounce_buf = (uint8_t *)hal.util->malloc_type(TX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
tx_bounce_buf_ready = true;
|
||||
}
|
||||
|
||||
/*
|
||||
allocate the write buffer
|
||||
*/
|
||||
|
@ -131,8 +131,8 @@ private:
|
||||
|
||||
// we use in-task ring buffers to reduce the system call cost
|
||||
// of ::read() and ::write() in the main loop
|
||||
uint8_t rx_bounce_buf[RX_BOUNCE_BUFSIZE];
|
||||
uint8_t tx_bounce_buf[TX_BOUNCE_BUFSIZE];
|
||||
uint8_t *rx_bounce_buf;
|
||||
uint8_t *tx_bounce_buf;
|
||||
ByteBuffer _readbuf{0};
|
||||
ByteBuffer _writebuf{0};
|
||||
Semaphore _write_mutex;
|
||||
|
Loading…
Reference in New Issue
Block a user