forked from Archive/PX4-Autopilot
Update STM32 F1 DMA to parity with F2/F4
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5509 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
7609c9a192
commit
b26d1e1453
|
@ -79,8 +79,8 @@
|
|||
|
||||
#if SERIAL_HAVE_DMA
|
||||
|
||||
/* Verify that DMA has been enabled an the DMA channel has been defined.
|
||||
* NOTE: These assignments may only be true for the F4.
|
||||
# if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
|
||||
/* Verify that DMA has been enabled and the DMA channel has been defined.
|
||||
*/
|
||||
|
||||
# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART6_RXDMA)
|
||||
|
@ -138,6 +138,30 @@
|
|||
# error "USART6 DMA channel not defined (DMAMAP_USART6_RX)"
|
||||
# endif
|
||||
|
||||
# elif defined(CONFIG_STM32_STM32F10XX)
|
||||
|
||||
# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \
|
||||
defined(CONFIG_USART3_RXDMA)
|
||||
# ifndef CONFIG_STM32_DMA1
|
||||
# error STM32 USART1/2/3 receive DMA requires CONFIG_STM32_DMA1
|
||||
# endif
|
||||
# endif
|
||||
|
||||
# if defined(CONFIG_UART4_RXDMA)
|
||||
# ifndef CONFIG_STM32_DMA2
|
||||
# error STM32 USART4 receive DMA requires CONFIG_STM32_DMA2
|
||||
# endif
|
||||
# endif
|
||||
|
||||
/* There are no optional DMA channel assignments for the F1 */
|
||||
|
||||
# define DMAMAP_USART1_RX DMACHAN_USART1_RX
|
||||
# define DMAMAP_USART2_RX DMACHAN_USART2_RX
|
||||
# define DMAMAP_USART3_RX DMACHAN_USART3_RX
|
||||
# define DMAMAP_UART4_RX DMACHAN_USART4_RX
|
||||
|
||||
# endif
|
||||
|
||||
/* The DMA buffer size when using RX DMA to emulate a FIFO.
|
||||
*
|
||||
* When streaming data, the generic serial layer will be called
|
||||
|
@ -169,6 +193,27 @@
|
|||
# error "Unknown STM32 DMA"
|
||||
# endif
|
||||
|
||||
/* DMA control word */
|
||||
|
||||
# if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
|
||||
# define SERIAL_DMA_CONTROL_WORD \
|
||||
(DMA_SCR_DIR_P2M | \
|
||||
DMA_SCR_CIRC | \
|
||||
DMA_SCR_MINC | \
|
||||
DMA_SCR_PSIZE_8BITS | \
|
||||
DMA_SCR_MSIZE_8BITS | \
|
||||
CONFIG_USART_DMAPRIO | \
|
||||
DMA_SCR_PBURST_SINGLE | \
|
||||
DMA_SCR_MBURST_SINGLE)
|
||||
# else
|
||||
# define SERIAL_DMA_CONTROL_WORD \
|
||||
(DMA_CCR_CIRC | \
|
||||
DMA_CCR_MINC | \
|
||||
DMA_CCR_PSIZE_8BITS | \
|
||||
DMA_CCR_MSIZE_8BITS | \
|
||||
CONFIG_USART_DMAPRIO)
|
||||
# endif
|
||||
|
||||
#endif
|
||||
|
||||
/* Power management definitions */
|
||||
|
@ -1056,13 +1101,16 @@ static int up_dma_setup(struct uart_dev_s *dev)
|
|||
int result;
|
||||
uint32_t regval;
|
||||
|
||||
/* Do the basic UART setup first */
|
||||
/* Do the basic UART setup first, unless we are the console */
|
||||
|
||||
if (!dev->isconsole)
|
||||
{
|
||||
result = up_setup(dev);
|
||||
if (result != OK)
|
||||
{
|
||||
return result;
|
||||
}
|
||||
}
|
||||
|
||||
/* Acquire the DMA channel. This should always succeed. */
|
||||
|
||||
|
@ -1074,14 +1122,7 @@ static int up_dma_setup(struct uart_dev_s *dev)
|
|||
priv->usartbase + STM32_USART_DR_OFFSET,
|
||||
(uint32_t)priv->rxfifo,
|
||||
RXDMA_BUFFER_SIZE,
|
||||
DMA_SCR_DIR_P2M |
|
||||
DMA_SCR_CIRC |
|
||||
DMA_SCR_MINC |
|
||||
DMA_SCR_PSIZE_8BITS |
|
||||
DMA_SCR_MSIZE_8BITS |
|
||||
CONFIG_USART_DMAPRIO |
|
||||
DMA_SCR_PBURST_SINGLE |
|
||||
DMA_SCR_MBURST_SINGLE);
|
||||
SERIAL_DMA_CONTROL_WORD);
|
||||
|
||||
/* Reset our DMA shadow pointer to match the address just
|
||||
* programmed above.
|
||||
|
|
|
@ -140,12 +140,9 @@
|
|||
# undef HAVE_CONSOLE
|
||||
#endif
|
||||
|
||||
/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration.
|
||||
* Furthermore, DMA support is currently only implemented for the F4 (but could be
|
||||
* extended to the F1 and F2 with a little effort in the DMA code.
|
||||
*/
|
||||
/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration */
|
||||
|
||||
#if !defined(HAVE_UART) || !defined(CONFIG_ARCH_DMA) || !defined(CONFIG_STM32_STM32F40XX)
|
||||
#if !defined(HAVE_UART) || !defined(CONFIG_ARCH_DMA)
|
||||
# undef CONFIG_USART1_RXDMA
|
||||
# undef CONFIG_USART2_RXDMA
|
||||
# undef CONFIG_USART3_RXDMA
|
||||
|
|
|
@ -303,13 +303,13 @@ static int stm32_dmainterrupt(int irq, void *context)
|
|||
}
|
||||
dmach = &g_dma[chndx];
|
||||
|
||||
/* Get the interrupt status (for this channel only) -- not currently used */
|
||||
/* Get the interrupt status (for this channel only) */
|
||||
|
||||
isr = dmabase_getreg(dmach, STM32_DMA_ISR_OFFSET) & DMA_ISR_CHAN_MASK(dmach->chan);
|
||||
|
||||
/* Disable the DMA channel */
|
||||
/* Clear the interrupts we are handling */
|
||||
|
||||
stm32_dmachandisable(dmach);
|
||||
dmabase_putreg(dmach, STM32_DMA_IFCR_OFFSET, isr);
|
||||
|
||||
/* Invoke the callback */
|
||||
|
||||
|
@ -528,6 +528,12 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
|
|||
ccr = dmachan_getreg(dmach, STM32_DMACHAN_CCR_OFFSET);
|
||||
ccr |= DMA_CCR_EN;
|
||||
|
||||
/* In normal mode, interrupt at either half or full completion. In circular mode,
|
||||
* always interrupt on buffer wrap, and optionally interrupt at the halfway point.
|
||||
*/
|
||||
|
||||
if ((ccr & DMA_CCR_CIRC) == 0)
|
||||
{
|
||||
/* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
|
||||
* set and an interrupt is generated if the Half-Transfer Interrupt Enable
|
||||
* bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag
|
||||
|
@ -536,6 +542,20 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
|
|||
*/
|
||||
|
||||
ccr |= (half ? (DMA_CCR_HTIE|DMA_CCR_TEIE) : (DMA_CCR_TCIE|DMA_CCR_TEIE));
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
/* In nonstop mode, when the transfer completes it immediately resets
|
||||
* and starts again. The transfer-complete interrupt is thus always
|
||||
* enabled, and the half-complete interrupt can be used in circular
|
||||
* mode to determine when the buffer is half-full, or in double-buffered
|
||||
* mode to determine when one of the two buffers is full.
|
||||
*/
|
||||
|
||||
ccr |= (half ? DMA_CCR_HTIE : 0) | DMA_CCR_TCIE | DMA_CCR_TEIE;
|
||||
}
|
||||
|
||||
dmachan_putreg(dmach, STM32_DMACHAN_CCR_OFFSET, ccr);
|
||||
}
|
||||
|
||||
|
@ -558,6 +578,24 @@ void stm32_dmastop(DMA_HANDLE handle)
|
|||
stm32_dmachandisable(dmach);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmaresidual
|
||||
*
|
||||
* Description:
|
||||
* Returns the number of bytes remaining to be transferred
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by stm32_dmachannel()
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
size_t stm32_dmaresidual(DMA_HANDLE handle)
|
||||
{
|
||||
struct stm32_dma_s *dmach = (struct stm32_dma_s *)handle;
|
||||
|
||||
return dmachan_getreg(dmach, STM32_DMACHAN_CNDTR_OFFSET);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmasample
|
||||
*
|
||||
|
|
|
@ -94,7 +94,6 @@ struct stm32_dma_s
|
|||
uint8_t irq; /* DMA stream IRQ number */
|
||||
uint8_t shift; /* ISR/IFCR bit shift value */
|
||||
uint8_t channel; /* DMA channel number (0-7) */
|
||||
bool nonstop; /* Stream is configured in a non-stopping mode. */
|
||||
sem_t sem; /* Used to wait for DMA channel to become available */
|
||||
uint32_t base; /* DMA register channel base address */
|
||||
dma_callback_t callback; /* Callback invoked when the DMA completes */
|
||||
|
@ -728,7 +727,6 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
|
|||
DMA_SCR_DBM|DMA_SCR_CIRC|
|
||||
DMA_SCR_PBURST_MASK|DMA_SCR_MBURST_MASK);
|
||||
regval |= scr;
|
||||
dmast->nonstop = (scr & (DMA_SCR_DBM|DMA_SCR_CIRC)) != 0;
|
||||
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
|
||||
}
|
||||
|
||||
|
@ -764,7 +762,12 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
|
|||
scr = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
|
||||
scr |= DMA_SCR_EN;
|
||||
|
||||
if (!dmast->nonstop)
|
||||
/* In normal mode, interrupt at either half or full completion. In circular
|
||||
* and double-buffered modes, always interrupt on buffer wrap, and optionally
|
||||
* interrupt at the halfway point.
|
||||
*/
|
||||
|
||||
if ((scr & (DMA_SCR_DBM|DMA_SCR_CIRC)) == 0)
|
||||
{
|
||||
/* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
|
||||
* set and an interrupt is generated if the Half-Transfer Interrupt Enable
|
||||
|
@ -777,7 +780,7 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
|
|||
}
|
||||
else
|
||||
{
|
||||
/* In nonstop mode, when the transfer completes it immediately resets
|
||||
/* In non-stop modes, when the transfer completes it immediately resets
|
||||
* and starts again. The transfer-complete interrupt is thus always
|
||||
* enabled, and the half-complete interrupt can be used in circular
|
||||
* mode to determine when the buffer is half-full, or in double-buffered
|
||||
|
|
Loading…
Reference in New Issue