mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
HAL_ChibiOS: allow for unbuffered writes without DMA
This commit is contained in:
parent
b8f9f171e0
commit
a7b83b1e26
@ -404,7 +404,7 @@ void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
DMA transmit complettion interrupt handler
|
DMA transmit completion interrupt handler
|
||||||
*/
|
*/
|
||||||
void UARTDriver::tx_complete(void* self, uint32_t flags)
|
void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||||
{
|
{
|
||||||
@ -605,12 +605,19 @@ int16_t UARTDriver::read_locked(uint32_t key)
|
|||||||
return byte;
|
return byte;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Empty implementations of Print virtual methods */
|
/* write one byte to the port */
|
||||||
size_t UARTDriver::write(uint8_t c)
|
size_t UARTDriver::write(uint8_t c)
|
||||||
{
|
{
|
||||||
if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) {
|
if (lock_write_key != 0) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
if (unbuffered_writes && _blocking_writes) {
|
||||||
|
_write_mutex.take_blocking();
|
||||||
|
} else {
|
||||||
|
if (!_write_mutex.take_nonblocking()) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (!_initialised) {
|
if (!_initialised) {
|
||||||
_write_mutex.give();
|
_write_mutex.give();
|
||||||
@ -632,6 +639,7 @@ size_t UARTDriver::write(uint8_t c)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* write a block of bytes to the port */
|
||||||
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
||||||
{
|
{
|
||||||
if (!_initialised || lock_write_key != 0) {
|
if (!_initialised || lock_write_key != 0) {
|
||||||
@ -771,6 +779,7 @@ void UARTDriver::handle_tx_timeout(void *arg)
|
|||||||
*/
|
*/
|
||||||
void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(_write_mutex);
|
||||||
check_dma_tx_completion();
|
check_dma_tx_completion();
|
||||||
|
|
||||||
if (!tx_bounce_buf_ready) {
|
if (!tx_bounce_buf_ready) {
|
||||||
@ -823,6 +832,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|||||||
*/
|
*/
|
||||||
void UARTDriver::write_pending_bytes_NODMA(uint32_t n)
|
void UARTDriver::write_pending_bytes_NODMA(uint32_t n)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(_write_mutex);
|
||||||
|
|
||||||
ByteBuffer::IoVec vec[2];
|
ByteBuffer::IoVec vec[2];
|
||||||
uint16_t nwritten = 0;
|
uint16_t nwritten = 0;
|
||||||
|
|
||||||
@ -937,12 +948,14 @@ void UARTDriver::half_duplex_setup_tx(void)
|
|||||||
#ifdef HAVE_USB_SERIAL
|
#ifdef HAVE_USB_SERIAL
|
||||||
if (!hd_tx_active) {
|
if (!hd_tx_active) {
|
||||||
chEvtGetAndClearFlags(&hd_listener);
|
chEvtGetAndClearFlags(&hd_listener);
|
||||||
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
|
||||||
hd_tx_active = true;
|
hd_tx_active = true;
|
||||||
|
if (_last_options & (OPTION_RXINV | OPTION_TXINV)) {
|
||||||
|
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
||||||
sdStop(sd);
|
sdStop(sd);
|
||||||
sercfg.cr3 &= ~USART_CR3_HDSEL;
|
sercfg.cr3 &= ~USART_CR3_HDSEL;
|
||||||
sdStart(sd, &sercfg);
|
sdStart(sd, &sercfg);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -962,10 +975,12 @@ void UARTDriver::_timer_tick(void)
|
|||||||
half-duplex transmit has finished. We now re-enable the
|
half-duplex transmit has finished. We now re-enable the
|
||||||
HDSEL bit for receive
|
HDSEL bit for receive
|
||||||
*/
|
*/
|
||||||
|
if (_last_options & (OPTION_RXINV | OPTION_TXINV)) {
|
||||||
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
||||||
sdStop(sd);
|
sdStop(sd);
|
||||||
sercfg.cr3 |= USART_CR3_HDSEL;
|
sercfg.cr3 |= USART_CR3_HDSEL;
|
||||||
sdStart(sd, &sercfg);
|
sdStart(sd, &sercfg);
|
||||||
|
}
|
||||||
hd_tx_active = false;
|
hd_tx_active = false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -1065,7 +1080,7 @@ void UARTDriver::_timer_tick(void)
|
|||||||
// provided by the write() call, but if the write is larger
|
// provided by the write() call, but if the write is larger
|
||||||
// than the DMA buffer size then there can be extra bytes to
|
// than the DMA buffer size then there can be extra bytes to
|
||||||
// send here, and they must be sent with the write lock held
|
// send here, and they must be sent with the write lock held
|
||||||
_write_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
_write_mutex.take_blocking();
|
||||||
write_pending_bytes();
|
write_pending_bytes();
|
||||||
_write_mutex.give();
|
_write_mutex.give();
|
||||||
} else {
|
} else {
|
||||||
@ -1159,16 +1174,8 @@ void UARTDriver::update_rts_line(void)
|
|||||||
*/
|
*/
|
||||||
bool UARTDriver::set_unbuffered_writes(bool on)
|
bool UARTDriver::set_unbuffered_writes(bool on)
|
||||||
{
|
{
|
||||||
#ifdef HAL_UART_NODMA
|
|
||||||
return false;
|
|
||||||
#else
|
|
||||||
if (on && !tx_dma_enabled) {
|
|
||||||
// we can't implement low latemcy writes safely without TX DMA
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
unbuffered_writes = on;
|
unbuffered_writes = on;
|
||||||
return true;
|
return true;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -159,7 +159,7 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
ByteBuffer _readbuf{0};
|
ByteBuffer _readbuf{0};
|
||||||
ByteBuffer _writebuf{0};
|
ByteBuffer _writebuf{0};
|
||||||
Semaphore _write_mutex;
|
HAL_Semaphore_Recursive _write_mutex;
|
||||||
#ifndef HAL_UART_NODMA
|
#ifndef HAL_UART_NODMA
|
||||||
const stm32_dma_stream_t* rxdma;
|
const stm32_dma_stream_t* rxdma;
|
||||||
const stm32_dma_stream_t* txdma;
|
const stm32_dma_stream_t* txdma;
|
||||||
|
Loading…
Reference in New Issue
Block a user