|
|
|
@ -210,9 +210,11 @@ void UARTDriver::dma_tx_deallocate(void)
@@ -210,9 +210,11 @@ void UARTDriver::dma_tx_deallocate(void)
|
|
|
|
|
void UARTDriver::tx_complete(void* self, uint32_t flags) |
|
|
|
|
{ |
|
|
|
|
UARTDriver* uart_drv = (UARTDriver*)self; |
|
|
|
|
uart_drv->dma_handle->unlock_from_IRQ(); |
|
|
|
|
uart_drv->_last_write_completed_us = AP_HAL::micros(); |
|
|
|
|
uart_drv->tx_bounce_buf_ready = true; |
|
|
|
|
if (!uart_drv->tx_bounce_buf_ready) { |
|
|
|
|
uart_drv->dma_handle->unlock_from_IRQ(); |
|
|
|
|
uart_drv->_last_write_completed_us = AP_HAL::micros(); |
|
|
|
|
uart_drv->tx_bounce_buf_ready = true; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -401,6 +403,9 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
@@ -401,6 +403,9 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
|
|
|
|
|
|
|
|
|
size_t ret = _writebuf.write(buffer, size); |
|
|
|
|
if (unbuffered_writes) { |
|
|
|
|
if (ret != size) { |
|
|
|
|
hal.console->printf("ret=%d size=%d\n", (int)ret, (int)size); |
|
|
|
|
} |
|
|
|
|
write_pending_bytes(); |
|
|
|
|
} |
|
|
|
|
chMtxUnlock(&_write_mutex); |
|
|
|
@ -431,6 +436,9 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
@@ -431,6 +436,9 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|
|
|
|
if (!tx_bounce_buf_ready && txdma) { |
|
|
|
|
if (!(txdma->stream->CR & STM32_DMA_CR_EN)) { |
|
|
|
|
if (txdma->stream->NDTR == 0) { |
|
|
|
|
hal.console->printf("ISR complete %u took %u\n", |
|
|
|
|
AP_HAL::millis(), |
|
|
|
|
AP_HAL::micros() - _last_write_started_us); |
|
|
|
|
tx_bounce_buf_ready = true; |
|
|
|
|
_last_write_completed_us = AP_HAL::micros(); |
|
|
|
|
dma_handle->unlock(); |
|
|
|
@ -459,6 +467,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
@@ -459,6 +467,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
|
|
|
|
dmamode |= STM32_DMA_CR_PL(0); |
|
|
|
|
dmaStreamSetMode(txdma, dmamode | STM32_DMA_CR_DIR_M2P | |
|
|
|
|
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); |
|
|
|
|
_last_write_started_us = AP_HAL::micros(); |
|
|
|
|
dmaStreamEnable(txdma); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -608,10 +617,16 @@ void UARTDriver::_timer_tick(void)
@@ -608,10 +617,16 @@ void UARTDriver::_timer_tick(void)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!unbuffered_writes) { |
|
|
|
|
if (unbuffered_writes) { |
|
|
|
|
// now send pending bytes. If we are doing "unbuffered" writes
|
|
|
|
|
// then the send happens as soon as the bytes are provided by
|
|
|
|
|
// the write() call, and no writes are done in the timer tick
|
|
|
|
|
// then the send normally happens as soon as the bytes are
|
|
|
|
|
// 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
|
|
|
|
|
chMtxLock(&_write_mutex); |
|
|
|
|
write_pending_bytes(); |
|
|
|
|
chMtxUnlock(&_write_mutex); |
|
|
|
|
} else { |
|
|
|
|
write_pending_bytes(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|