|
|
|
@ -404,7 +404,7 @@ void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
@@ -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) |
|
|
|
|
{ |
|
|
|
@ -605,12 +605,19 @@ int16_t UARTDriver::read_locked(uint32_t key)
@@ -605,12 +605,19 @@ int16_t UARTDriver::read_locked(uint32_t key)
|
|
|
|
|
return byte; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* Empty implementations of Print virtual methods */ |
|
|
|
|
/* write one byte to the port */ |
|
|
|
|
size_t UARTDriver::write(uint8_t c) |
|
|
|
|
{ |
|
|
|
|
if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) { |
|
|
|
|
if (lock_write_key != 0) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
if (unbuffered_writes && _blocking_writes) { |
|
|
|
|
_write_mutex.take_blocking(); |
|
|
|
|
} else { |
|
|
|
|
if (!_write_mutex.take_nonblocking()) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!_initialised) { |
|
|
|
|
_write_mutex.give(); |
|
|
|
@ -632,6 +639,7 @@ size_t UARTDriver::write(uint8_t c)
@@ -632,6 +639,7 @@ size_t UARTDriver::write(uint8_t c)
|
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* write a block of bytes to the port */ |
|
|
|
|
size_t UARTDriver::write(const uint8_t *buffer, size_t size) |
|
|
|
|
{ |
|
|
|
|
if (!_initialised || lock_write_key != 0) { |
|
|
|
@ -771,6 +779,7 @@ void UARTDriver::handle_tx_timeout(void *arg)
@@ -771,6 +779,7 @@ void UARTDriver::handle_tx_timeout(void *arg)
|
|
|
|
|
*/ |
|
|
|
|
void UARTDriver::write_pending_bytes_DMA(uint32_t n) |
|
|
|
|
{ |
|
|
|
|
WITH_SEMAPHORE(_write_mutex); |
|
|
|
|
check_dma_tx_completion(); |
|
|
|
|
|
|
|
|
|
if (!tx_bounce_buf_ready) { |
|
|
|
@ -823,6 +832,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
@@ -823,6 +832,8 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|
|
|
|
*/ |
|
|
|
|
void UARTDriver::write_pending_bytes_NODMA(uint32_t n) |
|
|
|
|
{ |
|
|
|
|
WITH_SEMAPHORE(_write_mutex); |
|
|
|
|
|
|
|
|
|
ByteBuffer::IoVec vec[2]; |
|
|
|
|
uint16_t nwritten = 0; |
|
|
|
|
|
|
|
|
@ -937,11 +948,13 @@ void UARTDriver::half_duplex_setup_tx(void)
@@ -937,11 +948,13 @@ void UARTDriver::half_duplex_setup_tx(void)
|
|
|
|
|
#ifdef HAVE_USB_SERIAL |
|
|
|
|
if (!hd_tx_active) { |
|
|
|
|
chEvtGetAndClearFlags(&hd_listener); |
|
|
|
|
SerialDriver *sd = (SerialDriver*)(sdef.serial); |
|
|
|
|
hd_tx_active = true; |
|
|
|
|
sdStop(sd); |
|
|
|
|
sercfg.cr3 &= ~USART_CR3_HDSEL; |
|
|
|
|
sdStart(sd, &sercfg); |
|
|
|
|
if (_last_options & (OPTION_RXINV | OPTION_TXINV)) { |
|
|
|
|
SerialDriver *sd = (SerialDriver*)(sdef.serial); |
|
|
|
|
sdStop(sd); |
|
|
|
|
sercfg.cr3 &= ~USART_CR3_HDSEL; |
|
|
|
|
sdStart(sd, &sercfg); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
@ -962,10 +975,12 @@ void UARTDriver::_timer_tick(void)
@@ -962,10 +975,12 @@ void UARTDriver::_timer_tick(void)
|
|
|
|
|
half-duplex transmit has finished. We now re-enable the |
|
|
|
|
HDSEL bit for receive |
|
|
|
|
*/ |
|
|
|
|
SerialDriver *sd = (SerialDriver*)(sdef.serial); |
|
|
|
|
sdStop(sd); |
|
|
|
|
sercfg.cr3 |= USART_CR3_HDSEL; |
|
|
|
|
sdStart(sd, &sercfg); |
|
|
|
|
if (_last_options & (OPTION_RXINV | OPTION_TXINV)) { |
|
|
|
|
SerialDriver *sd = (SerialDriver*)(sdef.serial); |
|
|
|
|
sdStop(sd); |
|
|
|
|
sercfg.cr3 |= USART_CR3_HDSEL; |
|
|
|
|
sdStart(sd, &sercfg); |
|
|
|
|
} |
|
|
|
|
hd_tx_active = false; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
@ -1065,7 +1080,7 @@ void UARTDriver::_timer_tick(void)
@@ -1065,7 +1080,7 @@ void UARTDriver::_timer_tick(void)
|
|
|
|
|
// provided by the write() call, but if the write is larger
|
|
|
|
|
// than the DMA buffer size then there can be extra bytes to
|
|
|
|
|
// 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_mutex.give(); |
|
|
|
|
} else { |
|
|
|
@ -1159,16 +1174,8 @@ void UARTDriver::update_rts_line(void)
@@ -1159,16 +1174,8 @@ void UARTDriver::update_rts_line(void)
|
|
|
|
|
*/ |
|
|
|
|
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; |
|
|
|
|
return true; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|