Merge pull request #11494 from haslinghuis/dshot_gpio
[betaflight.git] / lib / main / STM32H7 / Drivers / STM32H7xx_HAL_Driver / Src / stm32h7xx_hal_dma.c
blob6a8bce56e2e9f2383f236805e2aacb892623c279
1 /**
2 ******************************************************************************
3 * @file stm32h7xx_hal_dma.c
4 * @author MCD Application Team
5 * @brief DMA HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Direct Memory Access (DMA) peripheral:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral State and errors functions
11 @verbatim
12 ==============================================================================
13 ##### How to use this driver #####
14 ==============================================================================
15 [..]
16 (#) Enable and configure the peripheral to be connected to the DMA Stream
17 (except for internal SRAM/FLASH memories: no initialization is
18 necessary) please refer to Reference manual for connection between peripherals
19 and DMA requests .
21 (#) For a given Stream, program the required configuration through the following parameters:
22 Transfer Direction, Source and Destination data formats,
23 Circular, Normal or peripheral flow control mode, Stream Priority level,
24 Source and Destination Increment mode, FIFO mode and its Threshold (if needed),
25 Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function.
27 *** Polling mode IO operation ***
28 =================================
29 [..]
30 (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source
31 address and destination address and the Length of data to be transferred
32 (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this
33 case a fixed Timeout can be configured by User depending from his application.
35 *** Interrupt mode IO operation ***
36 ===================================
37 [..]
38 (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority()
39 (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ()
40 (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of
41 Source address and destination address and the Length of data to be transferred. In this
42 case the DMA interrupt is configured
43 (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine
44 (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can
45 add his own function by customization of function pointer XferCpltCallback and
46 XferErrorCallback (i.e a member of DMA handle structure).
47 [..]
48 (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error
49 detection.
51 (#) Use HAL_DMA_Abort() function to abort the current transfer
53 -@- In Memory-to-Memory transfer mode, Circular mode is not allowed.
55 -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is
56 possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set
57 Half-Word data size for the peripheral to access its data register and set Word data size
58 for the Memory to gain in access time. Each two half words will be packed and written in
59 a single access to a Word in the Memory).
61 -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source
62 and Destination. In this case the Peripheral Data Size will be applied to both Source
63 and Destination.
65 *** DMA HAL driver macros list ***
66 =============================================
67 [..]
68 Below the list of most used macros in DMA HAL driver.
70 (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream.
71 (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream.
72 (+) __HAL_DMA_GET_FS: Return the current DMA Stream FIFO filled level.
73 (+) __HAL_DMA_ENABLE_IT: Enable the specified DMA Stream interrupts.
74 (+) __HAL_DMA_DISABLE_IT: Disable the specified DMA Stream interrupts.
75 (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not.
77 [..]
78 (@) You can refer to the DMA HAL driver header file for more useful macros.
80 @endverbatim
81 ******************************************************************************
82 * @attention
84 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics.
85 * All rights reserved.</center></h2>
87 * This software component is licensed by ST under BSD 3-Clause license,
88 * the "License"; You may not use this file except in compliance with the
89 * License. You may obtain a copy of the License at:
90 * opensource.org/licenses/BSD-3-Clause
92 ******************************************************************************
95 /* Includes ------------------------------------------------------------------*/
96 #include "stm32h7xx_hal.h"
98 /** @addtogroup STM32H7xx_HAL_Driver
99 * @{
102 /** @defgroup DMA DMA
103 * @brief DMA HAL module driver
104 * @{
107 #ifdef HAL_DMA_MODULE_ENABLED
109 /* Private types -------------------------------------------------------------*/
110 typedef struct
112 __IO uint32_t ISR; /*!< DMA interrupt status register */
113 __IO uint32_t Reserved0;
114 __IO uint32_t IFCR; /*!< DMA interrupt flag clear register */
115 } DMA_Base_Registers;
117 typedef struct
119 __IO uint32_t ISR; /*!< BDMA interrupt status register */
120 __IO uint32_t IFCR; /*!< BDMA interrupt flag clear register */
121 } BDMA_Base_Registers;
123 /* Private variables ---------------------------------------------------------*/
124 /* Private constants ---------------------------------------------------------*/
125 /** @addtogroup DMA_Private_Constants
126 * @{
128 #define HAL_TIMEOUT_DMA_ABORT (5U) /* 5 ms */
130 #define BDMA_PERIPH_TO_MEMORY (0x00000000U) /*!< Peripheral to memory direction */
131 #define BDMA_MEMORY_TO_PERIPH ((uint32_t)BDMA_CCR_DIR) /*!< Memory to peripheral direction */
132 #define BDMA_MEMORY_TO_MEMORY ((uint32_t)BDMA_CCR_MEM2MEM) /*!< Memory to memory direction */
134 /* DMA to BDMA conversion */
135 #define DMA_TO_BDMA_DIRECTION(__DMA_DIRECTION__) (((__DMA_DIRECTION__) == DMA_MEMORY_TO_PERIPH)? BDMA_MEMORY_TO_PERIPH: \
136 ((__DMA_DIRECTION__) == DMA_MEMORY_TO_MEMORY)? BDMA_MEMORY_TO_MEMORY: \
137 BDMA_PERIPH_TO_MEMORY)
139 #define DMA_TO_BDMA_PERIPHERAL_INC(__DMA_PERIPHERAL_INC__) ((__DMA_PERIPHERAL_INC__) >> 3U)
140 #define DMA_TO_BDMA_MEMORY_INC(__DMA_MEMORY_INC__) ((__DMA_MEMORY_INC__) >> 3U)
142 #define DMA_TO_BDMA_PDATA_SIZE(__DMA_PDATA_SIZE__) ((__DMA_PDATA_SIZE__) >> 3U)
143 #define DMA_TO_BDMA_MDATA_SIZE(__DMA_MDATA_SIZE__) ((__DMA_MDATA_SIZE__) >> 3U)
145 #define DMA_TO_BDMA_MODE(__DMA_MODE__) ((__DMA_MODE__) >> 3U)
147 #define DMA_TO_BDMA_PRIORITY(__DMA_PRIORITY__) ((__DMA_PRIORITY__) >> 4U)
149 #if defined(UART9)
150 #define IS_DMA_UART_USART_REQUEST(__REQUEST__) ((((__REQUEST__) >= DMA_REQUEST_USART1_RX) && ((__REQUEST__) <= DMA_REQUEST_USART3_TX)) || \
151 (((__REQUEST__) >= DMA_REQUEST_UART4_RX) && ((__REQUEST__) <= DMA_REQUEST_UART5_TX )) || \
152 (((__REQUEST__) >= DMA_REQUEST_USART6_RX) && ((__REQUEST__) <= DMA_REQUEST_USART6_TX)) || \
153 (((__REQUEST__) >= DMA_REQUEST_UART7_RX) && ((__REQUEST__) <= DMA_REQUEST_UART8_TX )) || \
154 (((__REQUEST__) >= DMA_REQUEST_UART9_RX) && ((__REQUEST__) <= DMA_REQUEST_USART10_TX )))
155 #else
156 #define IS_DMA_UART_USART_REQUEST(__REQUEST__) ((((__REQUEST__) >= DMA_REQUEST_USART1_RX) && ((__REQUEST__) <= DMA_REQUEST_USART3_TX)) || \
157 (((__REQUEST__) >= DMA_REQUEST_UART4_RX) && ((__REQUEST__) <= DMA_REQUEST_UART5_TX )) || \
158 (((__REQUEST__) >= DMA_REQUEST_USART6_RX) && ((__REQUEST__) <= DMA_REQUEST_USART6_TX)) || \
159 (((__REQUEST__) >= DMA_REQUEST_UART7_RX) && ((__REQUEST__) <= DMA_REQUEST_UART8_TX )))
161 #endif
163 * @}
165 /* Private macros ------------------------------------------------------------*/
166 /* Private functions ---------------------------------------------------------*/
167 /** @addtogroup DMA_Private_Functions
168 * @{
170 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
171 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma);
172 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma);
173 static void DMA_CalcDMAMUXChannelBaseAndMask(DMA_HandleTypeDef *hdma);
174 static void DMA_CalcDMAMUXRequestGenBaseAndMask(DMA_HandleTypeDef *hdma);
177 * @}
180 /* Exported functions ---------------------------------------------------------*/
181 /** @addtogroup DMA_Exported_Functions
182 * @{
185 /** @addtogroup DMA_Exported_Functions_Group1
187 @verbatim
188 ===============================================================================
189 ##### Initialization and de-initialization functions #####
190 ===============================================================================
191 [..]
192 This section provides functions allowing to initialize the DMA Stream source
193 and destination incrementation and data sizes, transfer direction,
194 circular/normal mode selection, memory-to-memory mode selection and Stream priority value.
195 [..]
196 The HAL_DMA_Init() function follows the DMA configuration procedures as described in
197 reference manual.
198 The HAL_DMA_DeInit function allows to deinitialize the DMA stream.
200 @endverbatim
201 * @{
205 * @brief Initialize the DMA according to the specified
206 * parameters in the DMA_InitTypeDef and create the associated handle.
207 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
208 * the configuration information for the specified DMA Stream.
209 * @retval HAL status
211 HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma)
213 uint32_t registerValue;
214 uint32_t tickstart = HAL_GetTick();
215 DMA_Base_Registers *regs_dma;
216 BDMA_Base_Registers *regs_bdma;
218 /* Check the DMA peripheral handle */
219 if(hdma == NULL)
221 return HAL_ERROR;
224 /* Check the parameters */
225 assert_param(IS_DMA_ALL_INSTANCE(hdma->Instance));
226 assert_param(IS_DMA_DIRECTION(hdma->Init.Direction));
227 assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc));
228 assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc));
229 assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment));
230 assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment));
231 assert_param(IS_DMA_MODE(hdma->Init.Mode));
232 assert_param(IS_DMA_PRIORITY(hdma->Init.Priority));
234 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
236 assert_param(IS_DMA_REQUEST(hdma->Init.Request));
237 assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode));
238 /* Check the memory burst, peripheral burst and FIFO threshold parameters only
239 when FIFO mode is enabled */
240 if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE)
242 assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold));
243 assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst));
244 assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst));
247 /* Allocate lock resource */
248 __HAL_UNLOCK(hdma);
250 /* Change DMA peripheral state */
251 hdma->State = HAL_DMA_STATE_BUSY;
253 /* Disable the peripheral */
254 __HAL_DMA_DISABLE(hdma);
256 /* Check if the DMA Stream is effectively disabled */
257 while((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U)
259 /* Check for the Timeout */
260 if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
262 /* Update error code */
263 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
265 /* Change the DMA state */
266 hdma->State = HAL_DMA_STATE_ERROR;
268 return HAL_ERROR;
272 /* Get the CR register value */
273 registerValue = ((DMA_Stream_TypeDef *)hdma->Instance)->CR;
275 /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */
276 registerValue &= ((uint32_t)~(DMA_SxCR_MBURST | DMA_SxCR_PBURST | \
277 DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \
278 DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \
279 DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM));
281 /* Prepare the DMA Stream configuration */
282 registerValue |= hdma->Init.Direction |
283 hdma->Init.PeriphInc | hdma->Init.MemInc |
284 hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment |
285 hdma->Init.Mode | hdma->Init.Priority;
287 /* the Memory burst and peripheral burst are not used when the FIFO is disabled */
288 if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
290 /* Get memory burst and peripheral burst */
291 registerValue |= hdma->Init.MemBurst | hdma->Init.PeriphBurst;
294 /* Work around for Errata 2.22: UART/USART- DMA transfer lock: DMA stream could be
295 lock when transfering data to/from USART/UART */
296 #if (STM32H7_DEV_ID == 0x450UL)
297 if((DBGMCU->IDCODE & 0xFFFF0000U) >= 0x20000000U)
299 #endif /* STM32H7_DEV_ID == 0x450UL */
300 if(IS_DMA_UART_USART_REQUEST(hdma->Init.Request) != 0U)
302 registerValue |= DMA_SxCR_TRBUFF;
304 #if (STM32H7_DEV_ID == 0x450UL)
306 #endif /* STM32H7_DEV_ID == 0x450UL */
308 /* Write to DMA Stream CR register */
309 ((DMA_Stream_TypeDef *)hdma->Instance)->CR = registerValue;
311 /* Get the FCR register value */
312 registerValue = ((DMA_Stream_TypeDef *)hdma->Instance)->FCR;
314 /* Clear Direct mode and FIFO threshold bits */
315 registerValue &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH);
317 /* Prepare the DMA Stream FIFO configuration */
318 registerValue |= hdma->Init.FIFOMode;
320 /* the FIFO threshold is not used when the FIFO mode is disabled */
321 if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
323 /* Get the FIFO threshold */
324 registerValue |= hdma->Init.FIFOThreshold;
326 /* Check compatibility between FIFO threshold level and size of the memory burst */
327 /* for INCR4, INCR8, INCR16 */
328 if(hdma->Init.MemBurst != DMA_MBURST_SINGLE)
330 if (DMA_CheckFifoParam(hdma) != HAL_OK)
332 /* Update error code */
333 hdma->ErrorCode = HAL_DMA_ERROR_PARAM;
335 /* Change the DMA state */
336 hdma->State = HAL_DMA_STATE_READY;
338 return HAL_ERROR;
343 /* Write to DMA Stream FCR */
344 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR = registerValue;
346 /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
347 DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
348 regs_dma = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
350 /* Clear all interrupt flags */
351 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
353 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
355 if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
357 /* Check the request parameter */
358 assert_param(IS_BDMA_REQUEST(hdma->Init.Request));
361 /* Allocate lock resource */
362 __HAL_UNLOCK(hdma);
364 /* Change DMA peripheral state */
365 hdma->State = HAL_DMA_STATE_BUSY;
367 /* Get the CR register value */
368 registerValue = ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR;
370 /* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, MEM2MEM, DBM and CT bits */
371 registerValue &= ((uint32_t)~(BDMA_CCR_PL | BDMA_CCR_MSIZE | BDMA_CCR_PSIZE | \
372 BDMA_CCR_MINC | BDMA_CCR_PINC | BDMA_CCR_CIRC | \
373 BDMA_CCR_DIR | BDMA_CCR_MEM2MEM | BDMA_CCR_DBM | \
374 BDMA_CCR_CT));
376 /* Prepare the DMA Channel configuration */
377 registerValue |= DMA_TO_BDMA_DIRECTION(hdma->Init.Direction) |
378 DMA_TO_BDMA_PERIPHERAL_INC(hdma->Init.PeriphInc) |
379 DMA_TO_BDMA_MEMORY_INC(hdma->Init.MemInc) |
380 DMA_TO_BDMA_PDATA_SIZE(hdma->Init.PeriphDataAlignment) |
381 DMA_TO_BDMA_MDATA_SIZE(hdma->Init.MemDataAlignment) |
382 DMA_TO_BDMA_MODE(hdma->Init.Mode) |
383 DMA_TO_BDMA_PRIORITY(hdma->Init.Priority);
385 /* Write to DMA Channel CR register */
386 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR = registerValue;
388 /* calculation of the channel index */
389 hdma->StreamIndex = (((uint32_t)((uint32_t*)hdma->Instance) - (uint32_t)BDMA_Channel0) / ((uint32_t)BDMA_Channel1 - (uint32_t)BDMA_Channel0)) << 2U;
391 /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
392 DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
393 regs_bdma = (BDMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
395 /* Clear all interrupt flags */
396 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
398 else
400 hdma->ErrorCode = HAL_DMA_ERROR_PARAM;
401 hdma->State = HAL_DMA_STATE_ERROR;
403 return HAL_ERROR;
406 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
408 /* Initialize parameters for DMAMUX channel :
409 DMAmuxChannel, DMAmuxChannelStatus and DMAmuxChannelStatusMask
411 DMA_CalcDMAMUXChannelBaseAndMask(hdma);
413 if(hdma->Init.Direction == DMA_MEMORY_TO_MEMORY)
415 /* if memory to memory force the request to 0*/
416 hdma->Init.Request = DMA_REQUEST_MEM2MEM;
419 /* Set peripheral request to DMAMUX channel */
420 hdma->DMAmuxChannel->CCR = (hdma->Init.Request & DMAMUX_CxCR_DMAREQ_ID);
422 /* Clear the DMAMUX synchro overrun flag */
423 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
425 /* Initialize parameters for DMAMUX request generator :
426 if the DMA request is DMA_REQUEST_GENERATOR0 to DMA_REQUEST_GENERATOR7
428 if((hdma->Init.Request >= DMA_REQUEST_GENERATOR0) && (hdma->Init.Request <= DMA_REQUEST_GENERATOR7))
430 /* Initialize parameters for DMAMUX request generator :
431 DMAmuxRequestGen, DMAmuxRequestGenStatus and DMAmuxRequestGenStatusMask */
432 DMA_CalcDMAMUXRequestGenBaseAndMask(hdma);
434 /* Reset the DMAMUX request generator register */
435 hdma->DMAmuxRequestGen->RGCR = 0U;
437 /* Clear the DMAMUX request generator overrun flag */
438 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
440 else
442 hdma->DMAmuxRequestGen = 0U;
443 hdma->DMAmuxRequestGenStatus = 0U;
444 hdma->DMAmuxRequestGenStatusMask = 0U;
448 /* Initialize the error code */
449 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
451 /* Initialize the DMA state */
452 hdma->State = HAL_DMA_STATE_READY;
454 return HAL_OK;
458 * @brief DeInitializes the DMA peripheral
459 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
460 * the configuration information for the specified DMA Stream.
461 * @retval HAL status
463 HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma)
465 DMA_Base_Registers *regs_dma;
466 BDMA_Base_Registers *regs_bdma;
468 /* Check the DMA peripheral handle */
469 if(hdma == NULL)
471 return HAL_ERROR;
474 /* Disable the selected DMA Streamx */
475 __HAL_DMA_DISABLE(hdma);
477 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
479 /* Reset DMA Streamx control register */
480 ((DMA_Stream_TypeDef *)hdma->Instance)->CR = 0U;
482 /* Reset DMA Streamx number of data to transfer register */
483 ((DMA_Stream_TypeDef *)hdma->Instance)->NDTR = 0U;
485 /* Reset DMA Streamx peripheral address register */
486 ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = 0U;
488 /* Reset DMA Streamx memory 0 address register */
489 ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = 0U;
491 /* Reset DMA Streamx memory 1 address register */
492 ((DMA_Stream_TypeDef *)hdma->Instance)->M1AR = 0U;
494 /* Reset DMA Streamx FIFO control register */
495 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR = (uint32_t)0x00000021U;
497 /* Get DMA steam Base Address */
498 regs_dma = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
500 /* Clear all interrupt flags at correct offset within the register */
501 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
503 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
505 /* Reset DMA Channel control register */
506 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR = 0U;
508 /* Reset DMA Channel Number of Data to Transfer register */
509 ((BDMA_Channel_TypeDef *)hdma->Instance)->CNDTR = 0U;
511 /* Reset DMA Channel peripheral address register */
512 ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = 0U;
514 /* Reset DMA Channel memory 0 address register */
515 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = 0U;
517 /* Reset DMA Channel memory 1 address register */
518 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM1AR = 0U;
520 /* Get DMA steam Base Address */
521 regs_bdma = (BDMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
523 /* Clear all interrupt flags at correct offset within the register */
524 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
526 else
528 /* Return error status */
529 return HAL_ERROR;
532 #if defined (BDMA1) /* No DMAMUX available for BDMA1 available on STM32H7Ax/Bx devices only */
533 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
534 #endif /* BDMA1 */
536 /* Initialize parameters for DMAMUX channel :
537 DMAmuxChannel, DMAmuxChannelStatus and DMAmuxChannelStatusMask */
538 DMA_CalcDMAMUXChannelBaseAndMask(hdma);
540 if(hdma->DMAmuxChannel != 0U)
542 /* Resett he DMAMUX channel that corresponds to the DMA stream */
543 hdma->DMAmuxChannel->CCR = 0U;
545 /* Clear the DMAMUX synchro overrun flag */
546 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
549 if((hdma->Init.Request >= DMA_REQUEST_GENERATOR0) && (hdma->Init.Request <= DMA_REQUEST_GENERATOR7))
551 /* Initialize parameters for DMAMUX request generator :
552 DMAmuxRequestGen, DMAmuxRequestGenStatus and DMAmuxRequestGenStatusMask */
553 DMA_CalcDMAMUXRequestGenBaseAndMask(hdma);
555 /* Reset the DMAMUX request generator register */
556 hdma->DMAmuxRequestGen->RGCR = 0U;
558 /* Clear the DMAMUX request generator overrun flag */
559 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
562 hdma->DMAmuxRequestGen = 0U;
563 hdma->DMAmuxRequestGenStatus = 0U;
564 hdma->DMAmuxRequestGenStatusMask = 0U;
568 /* Clean callbacks */
569 hdma->XferCpltCallback = NULL;
570 hdma->XferHalfCpltCallback = NULL;
571 hdma->XferM1CpltCallback = NULL;
572 hdma->XferM1HalfCpltCallback = NULL;
573 hdma->XferErrorCallback = NULL;
574 hdma->XferAbortCallback = NULL;
576 /* Initialize the error code */
577 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
579 /* Initialize the DMA state */
580 hdma->State = HAL_DMA_STATE_RESET;
582 /* Release Lock */
583 __HAL_UNLOCK(hdma);
585 return HAL_OK;
589 * @}
592 /** @addtogroup DMA_Exported_Functions_Group2
594 @verbatim
595 ===============================================================================
596 ##### IO operation functions #####
597 ===============================================================================
598 [..] This section provides functions allowing to:
599 (+) Configure the source, destination address and data length and Start DMA transfer
600 (+) Configure the source, destination address and data length and
601 Start DMA transfer with interrupt
602 (+) Register and Unregister DMA callbacks
603 (+) Abort DMA transfer
604 (+) Poll for transfer complete
605 (+) Handle DMA interrupt request
607 @endverbatim
608 * @{
612 * @brief Starts the DMA Transfer.
613 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
614 * the configuration information for the specified DMA Stream.
615 * @param SrcAddress: The source memory Buffer address
616 * @param DstAddress: The destination memory Buffer address
617 * @param DataLength: The length of data to be transferred from source to destination
618 * @retval HAL status
620 HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
622 HAL_StatusTypeDef status = HAL_OK;
624 /* Check the parameters */
625 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
627 /* Check the DMA peripheral handle */
628 if(hdma == NULL)
630 return HAL_ERROR;
633 /* Process locked */
634 __HAL_LOCK(hdma);
636 if(HAL_DMA_STATE_READY == hdma->State)
638 /* Change DMA peripheral state */
639 hdma->State = HAL_DMA_STATE_BUSY;
641 /* Initialize the error code */
642 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
644 /* Disable the peripheral */
645 __HAL_DMA_DISABLE(hdma);
647 /* Configure the source, destination address and the data length */
648 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
650 /* Enable the Peripheral */
651 __HAL_DMA_ENABLE(hdma);
653 else
655 /* Process unlocked */
656 __HAL_UNLOCK(hdma);
658 /* Set the error code to busy */
659 hdma->ErrorCode = HAL_DMA_ERROR_BUSY;
661 /* Return error status */
662 status = HAL_ERROR;
664 return status;
668 * @brief Start the DMA Transfer with interrupt enabled.
669 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
670 * the configuration information for the specified DMA Stream.
671 * @param SrcAddress: The source memory Buffer address
672 * @param DstAddress: The destination memory Buffer address
673 * @param DataLength: The length of data to be transferred from source to destination
674 * @retval HAL status
676 HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
678 HAL_StatusTypeDef status = HAL_OK;
680 /* Check the parameters */
681 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
683 /* Check the DMA peripheral handle */
684 if(hdma == NULL)
686 return HAL_ERROR;
689 /* Process locked */
690 __HAL_LOCK(hdma);
692 if(HAL_DMA_STATE_READY == hdma->State)
694 /* Change DMA peripheral state */
695 hdma->State = HAL_DMA_STATE_BUSY;
697 /* Initialize the error code */
698 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
700 /* Disable the peripheral */
701 __HAL_DMA_DISABLE(hdma);
703 /* Configure the source, destination address and the data length */
704 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
706 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
708 /* Enable Common interrupts*/
709 MODIFY_REG(((DMA_Stream_TypeDef *)hdma->Instance)->CR, (DMA_IT_TC | DMA_IT_TE | DMA_IT_DME | DMA_IT_HT), (DMA_IT_TC | DMA_IT_TE | DMA_IT_DME));
711 if(hdma->XferHalfCpltCallback != NULL)
713 /* Enable Half Transfer IT if corresponding Callback is set */
714 ((DMA_Stream_TypeDef *)hdma->Instance)->CR |= DMA_IT_HT;
717 else /* BDMA channel */
719 /* Enable Common interrupts */
720 MODIFY_REG(((BDMA_Channel_TypeDef *)hdma->Instance)->CCR, (BDMA_CCR_TCIE | BDMA_CCR_HTIE | BDMA_CCR_TEIE), (BDMA_CCR_TCIE | BDMA_CCR_TEIE));
722 if(hdma->XferHalfCpltCallback != NULL)
724 /*Enable Half Transfer IT if corresponding Callback is set */
725 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR |= BDMA_CCR_HTIE;
729 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
731 /* Check if DMAMUX Synchronization is enabled */
732 if((hdma->DMAmuxChannel->CCR & DMAMUX_CxCR_SE) != 0U)
734 /* Enable DMAMUX sync overrun IT*/
735 hdma->DMAmuxChannel->CCR |= DMAMUX_CxCR_SOIE;
738 if(hdma->DMAmuxRequestGen != 0U)
740 /* if using DMAMUX request generator, enable the DMAMUX request generator overrun IT*/
741 /* enable the request gen overrun IT */
742 hdma->DMAmuxRequestGen->RGCR |= DMAMUX_RGxCR_OIE;
746 /* Enable the Peripheral */
747 __HAL_DMA_ENABLE(hdma);
749 else
751 /* Process unlocked */
752 __HAL_UNLOCK(hdma);
754 /* Set the error code to busy */
755 hdma->ErrorCode = HAL_DMA_ERROR_BUSY;
757 /* Return error status */
758 status = HAL_ERROR;
761 return status;
765 * @brief Aborts the DMA Transfer.
766 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
767 * the configuration information for the specified DMA Stream.
769 * @note After disabling a DMA Stream, a check for wait until the DMA Stream is
770 * effectively disabled is added. If a Stream is disabled
771 * while a data transfer is ongoing, the current data will be transferred
772 * and the Stream will be effectively disabled only after the transfer of
773 * this single data is finished.
774 * @retval HAL status
776 HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma)
778 /* calculate DMA base and stream number */
779 DMA_Base_Registers *regs_dma;
780 BDMA_Base_Registers *regs_bdma;
781 const __IO uint32_t *enableRegister;
783 uint32_t tickstart = HAL_GetTick();
785 /* Check the DMA peripheral handle */
786 if(hdma == NULL)
788 return HAL_ERROR;
791 /* Check the DMA peripheral state */
792 if(hdma->State != HAL_DMA_STATE_BUSY)
794 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
796 /* Process Unlocked */
797 __HAL_UNLOCK(hdma);
799 return HAL_ERROR;
801 else
803 /* Disable all the transfer interrupts */
804 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
806 /* Disable DMA All Interrupts */
807 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME | DMA_IT_HT);
808 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR &= ~(DMA_IT_FE);
810 enableRegister = (__IO uint32_t *)(&(((DMA_Stream_TypeDef *)hdma->Instance)->CR));
812 else /* BDMA channel */
814 /* Disable DMA All Interrupts */
815 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR &= ~(BDMA_CCR_TCIE | BDMA_CCR_HTIE | BDMA_CCR_TEIE);
817 enableRegister = (__IO uint32_t *)(&(((BDMA_Channel_TypeDef *)hdma->Instance)->CCR));
820 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
822 /* disable the DMAMUX sync overrun IT */
823 hdma->DMAmuxChannel->CCR &= ~DMAMUX_CxCR_SOIE;
826 /* Disable the stream */
827 __HAL_DMA_DISABLE(hdma);
829 /* Check if the DMA Stream is effectively disabled */
830 while(((*enableRegister) & DMA_SxCR_EN) != 0U)
832 /* Check for the Timeout */
833 if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
835 /* Update error code */
836 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
838 /* Process Unlocked */
839 __HAL_UNLOCK(hdma);
841 /* Change the DMA state */
842 hdma->State = HAL_DMA_STATE_ERROR;
844 return HAL_ERROR;
848 /* Clear all interrupt flags at correct offset within the register */
849 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
851 regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
852 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
854 else /* BDMA channel */
856 regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
857 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
860 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
862 /* Clear the DMAMUX synchro overrun flag */
863 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
865 if(hdma->DMAmuxRequestGen != 0U)
867 /* if using DMAMUX request generator, disable the DMAMUX request generator overrun IT */
868 /* disable the request gen overrun IT */
869 hdma->DMAmuxRequestGen->RGCR &= ~DMAMUX_RGxCR_OIE;
871 /* Clear the DMAMUX request generator overrun flag */
872 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
876 /* Process Unlocked */
877 __HAL_UNLOCK(hdma);
879 /* Change the DMA state */
880 hdma->State = HAL_DMA_STATE_READY;
883 return HAL_OK;
887 * @brief Aborts the DMA Transfer in Interrupt mode.
888 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
889 * the configuration information for the specified DMA Stream.
890 * @retval HAL status
892 HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma)
894 BDMA_Base_Registers *regs_bdma;
896 /* Check the DMA peripheral handle */
897 if(hdma == NULL)
899 return HAL_ERROR;
902 if(hdma->State != HAL_DMA_STATE_BUSY)
904 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
905 return HAL_ERROR;
907 else
909 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
911 /* Set Abort State */
912 hdma->State = HAL_DMA_STATE_ABORT;
914 /* Disable the stream */
915 __HAL_DMA_DISABLE(hdma);
917 else /* BDMA channel */
919 /* Disable DMA All Interrupts */
920 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR &= ~(BDMA_CCR_TCIE | BDMA_CCR_HTIE | BDMA_CCR_TEIE);
922 /* Disable the channel */
923 __HAL_DMA_DISABLE(hdma);
925 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
927 /* disable the DMAMUX sync overrun IT */
928 hdma->DMAmuxChannel->CCR &= ~DMAMUX_CxCR_SOIE;
930 /* Clear all flags */
931 regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
932 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
934 /* Clear the DMAMUX synchro overrun flag */
935 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
937 if(hdma->DMAmuxRequestGen != 0U)
939 /* if using DMAMUX request generator, disable the DMAMUX request generator overrun IT*/
940 /* disable the request gen overrun IT */
941 hdma->DMAmuxRequestGen->RGCR &= ~DMAMUX_RGxCR_OIE;
943 /* Clear the DMAMUX request generator overrun flag */
944 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
948 /* Process Unlocked */
949 __HAL_UNLOCK(hdma);
951 /* Change the DMA state */
952 hdma->State = HAL_DMA_STATE_READY;
954 /* Call User Abort callback */
955 if(hdma->XferAbortCallback != NULL)
957 hdma->XferAbortCallback(hdma);
962 return HAL_OK;
966 * @brief Polling for transfer complete.
967 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
968 * the configuration information for the specified DMA Stream.
969 * @param CompleteLevel: Specifies the DMA level complete.
970 * @note The polling mode is kept in this version for legacy. it is recommanded to use the IT model instead.
971 * This model could be used for debug purpose.
972 * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode).
973 * @param Timeout: Timeout duration.
974 * @retval HAL status
976 HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout)
978 HAL_StatusTypeDef status = HAL_OK;
979 uint32_t cpltlevel_mask;
980 uint32_t tickstart = HAL_GetTick();
982 /* IT status register */
983 __IO uint32_t *isr_reg;
984 /* IT clear flag register */
985 __IO uint32_t *ifcr_reg;
987 /* Check the DMA peripheral handle */
988 if(hdma == NULL)
990 return HAL_ERROR;
993 if(HAL_DMA_STATE_BUSY != hdma->State)
995 /* No transfer ongoing */
996 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
997 __HAL_UNLOCK(hdma);
999 return HAL_ERROR;
1002 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1004 /* Polling mode not supported in circular mode and double buffering mode */
1005 if ((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) != 0U)
1007 hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
1008 return HAL_ERROR;
1011 /* Get the level transfer complete flag */
1012 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1014 /* Transfer Complete flag */
1015 cpltlevel_mask = DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU);
1017 else
1019 /* Half Transfer Complete flag */
1020 cpltlevel_mask = DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU);
1023 isr_reg = &(((DMA_Base_Registers *)hdma->StreamBaseAddress)->ISR);
1024 ifcr_reg = &(((DMA_Base_Registers *)hdma->StreamBaseAddress)->IFCR);
1026 else /* BDMA channel */
1028 /* Polling mode not supported in circular mode */
1029 if ((((BDMA_Channel_TypeDef *)hdma->Instance)->CCR & BDMA_CCR_CIRC) != 0U)
1031 hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
1032 return HAL_ERROR;
1035 /* Get the level transfer complete flag */
1036 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1038 /* Transfer Complete flag */
1039 cpltlevel_mask = BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU);
1041 else
1043 /* Half Transfer Complete flag */
1044 cpltlevel_mask = BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU);
1047 isr_reg = &(((BDMA_Base_Registers *)hdma->StreamBaseAddress)->ISR);
1048 ifcr_reg = &(((BDMA_Base_Registers *)hdma->StreamBaseAddress)->IFCR);
1051 while(((*isr_reg) & cpltlevel_mask) == 0U)
1053 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1055 if(((*isr_reg) & (DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1057 /* Update error code */
1058 hdma->ErrorCode |= HAL_DMA_ERROR_FE;
1060 /* Clear the FIFO error flag */
1061 (*ifcr_reg) = DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU);
1064 if(((*isr_reg) & (DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1066 /* Update error code */
1067 hdma->ErrorCode |= HAL_DMA_ERROR_DME;
1069 /* Clear the Direct Mode error flag */
1070 (*ifcr_reg) = DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU);
1073 if(((*isr_reg) & (DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1075 /* Update error code */
1076 hdma->ErrorCode |= HAL_DMA_ERROR_TE;
1078 /* Clear the transfer error flag */
1079 (*ifcr_reg) = DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU);
1081 /* Change the DMA state */
1082 hdma->State = HAL_DMA_STATE_READY;
1084 /* Process Unlocked */
1085 __HAL_UNLOCK(hdma);
1087 return HAL_ERROR;
1090 else /* BDMA channel */
1092 if(((*isr_reg) & (BDMA_FLAG_TE0 << (hdma->StreamIndex & 0x1FU))) != 0U)
1094 /* When a DMA transfer error occurs */
1095 /* A hardware clear of its EN bits is performed */
1096 /* Clear all flags */
1097 (*isr_reg) = ((BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU));
1099 /* Update error code */
1100 hdma->ErrorCode = HAL_DMA_ERROR_TE;
1102 /* Change the DMA state */
1103 hdma->State = HAL_DMA_STATE_READY;
1105 /* Process Unlocked */
1106 __HAL_UNLOCK(hdma);
1108 return HAL_ERROR;
1112 /* Check for the Timeout (Not applicable in circular mode)*/
1113 if(Timeout != HAL_MAX_DELAY)
1115 if(((HAL_GetTick() - tickstart ) > Timeout)||(Timeout == 0U))
1117 /* Update error code */
1118 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
1120 /* if timeout then abort the current transfer */
1121 /* No need to check return value: as in this case we will return HAL_ERROR with HAL_DMA_ERROR_TIMEOUT error code */
1122 (void) HAL_DMA_Abort(hdma);
1124 Note that the Abort function will
1125 - Clear the transfer error flags
1126 - Unlock
1127 - Set the State
1130 return HAL_ERROR;
1134 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
1136 /* Check for DMAMUX Request generator (if used) overrun status */
1137 if(hdma->DMAmuxRequestGen != 0U)
1139 /* if using DMAMUX request generator Check for DMAMUX request generator overrun */
1140 if((hdma->DMAmuxRequestGenStatus->RGSR & hdma->DMAmuxRequestGenStatusMask) != 0U)
1142 /* Clear the DMAMUX request generator overrun flag */
1143 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
1145 /* Update error code */
1146 hdma->ErrorCode |= HAL_DMA_ERROR_REQGEN;
1150 /* Check for DMAMUX Synchronization overrun */
1151 if((hdma->DMAmuxChannelStatus->CSR & hdma->DMAmuxChannelStatusMask) != 0U)
1153 /* Clear the DMAMUX synchro overrun flag */
1154 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
1156 /* Update error code */
1157 hdma->ErrorCode |= HAL_DMA_ERROR_SYNC;
1163 /* Get the level transfer complete flag */
1164 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1166 /* Clear the half transfer and transfer complete flags */
1167 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1169 (*ifcr_reg) = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << (hdma->StreamIndex & 0x1FU);
1171 else /* BDMA channel */
1173 (*ifcr_reg) = (BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU));
1176 /* Process Unlocked */
1177 __HAL_UNLOCK(hdma);
1179 hdma->State = HAL_DMA_STATE_READY;
1181 else /*CompleteLevel = HAL_DMA_HALF_TRANSFER*/
1183 /* Clear the half transfer and transfer complete flags */
1184 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1186 (*ifcr_reg) = (DMA_FLAG_HTIF0_4) << (hdma->StreamIndex & 0x1FU);
1188 else /* BDMA channel */
1190 (*ifcr_reg) = (BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU));
1194 return status;
1198 * @brief Handles DMA interrupt request.
1199 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1200 * the configuration information for the specified DMA Stream.
1201 * @retval None
1203 void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma)
1205 uint32_t tmpisr_dma, tmpisr_bdma;
1206 uint32_t ccr_reg;
1207 __IO uint32_t count = 0U;
1208 uint32_t timeout = SystemCoreClock / 9600U;
1210 /* calculate DMA base and stream number */
1211 DMA_Base_Registers *regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
1212 BDMA_Base_Registers *regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
1214 tmpisr_dma = regs_dma->ISR;
1215 tmpisr_bdma = regs_bdma->ISR;
1217 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1219 /* Transfer Error Interrupt management ***************************************/
1220 if ((tmpisr_dma & (DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1222 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != 0U)
1224 /* Disable the transfer error interrupt */
1225 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TE);
1227 /* Clear the transfer error flag */
1228 regs_dma->IFCR = DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU);
1230 /* Update error code */
1231 hdma->ErrorCode |= HAL_DMA_ERROR_TE;
1234 /* FIFO Error Interrupt management ******************************************/
1235 if ((tmpisr_dma & (DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1237 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != 0U)
1239 /* Clear the FIFO error flag */
1240 regs_dma->IFCR = DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU);
1242 /* Update error code */
1243 hdma->ErrorCode |= HAL_DMA_ERROR_FE;
1246 /* Direct Mode Error Interrupt management ***********************************/
1247 if ((tmpisr_dma & (DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1249 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != 0U)
1251 /* Clear the direct mode error flag */
1252 regs_dma->IFCR = DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU);
1254 /* Update error code */
1255 hdma->ErrorCode |= HAL_DMA_ERROR_DME;
1258 /* Half Transfer Complete Interrupt management ******************************/
1259 if ((tmpisr_dma & (DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1261 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != 0U)
1263 /* Clear the half transfer complete flag */
1264 regs_dma->IFCR = DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU);
1266 /* Multi_Buffering mode enabled */
1267 if(((((DMA_Stream_TypeDef *)hdma->Instance)->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0U)
1269 /* Current memory buffer used is Memory 0 */
1270 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CT) == 0U)
1272 if(hdma->XferHalfCpltCallback != NULL)
1274 /* Half transfer callback */
1275 hdma->XferHalfCpltCallback(hdma);
1278 /* Current memory buffer used is Memory 1 */
1279 else
1281 if(hdma->XferM1HalfCpltCallback != NULL)
1283 /* Half transfer callback */
1284 hdma->XferM1HalfCpltCallback(hdma);
1288 else
1290 /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
1291 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) == 0U)
1293 /* Disable the half transfer interrupt */
1294 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_HT);
1297 if(hdma->XferHalfCpltCallback != NULL)
1299 /* Half transfer callback */
1300 hdma->XferHalfCpltCallback(hdma);
1305 /* Transfer Complete Interrupt management ***********************************/
1306 if ((tmpisr_dma & (DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1308 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != 0U)
1310 /* Clear the transfer complete flag */
1311 regs_dma->IFCR = DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU);
1313 if(HAL_DMA_STATE_ABORT == hdma->State)
1315 /* Disable all the transfer interrupts */
1316 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME);
1317 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR &= ~(DMA_IT_FE);
1319 if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL))
1321 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_HT);
1324 /* Clear all interrupt flags at correct offset within the register */
1325 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
1327 /* Process Unlocked */
1328 __HAL_UNLOCK(hdma);
1330 /* Change the DMA state */
1331 hdma->State = HAL_DMA_STATE_READY;
1333 if(hdma->XferAbortCallback != NULL)
1335 hdma->XferAbortCallback(hdma);
1337 return;
1340 if(((((DMA_Stream_TypeDef *)hdma->Instance)->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0U)
1342 /* Current memory buffer used is Memory 0 */
1343 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CT) == 0U)
1345 if(hdma->XferM1CpltCallback != NULL)
1347 /* Transfer complete Callback for memory1 */
1348 hdma->XferM1CpltCallback(hdma);
1351 /* Current memory buffer used is Memory 1 */
1352 else
1354 if(hdma->XferCpltCallback != NULL)
1356 /* Transfer complete Callback for memory0 */
1357 hdma->XferCpltCallback(hdma);
1361 /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */
1362 else
1364 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) == 0U)
1366 /* Disable the transfer complete interrupt */
1367 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC);
1369 /* Process Unlocked */
1370 __HAL_UNLOCK(hdma);
1372 /* Change the DMA state */
1373 hdma->State = HAL_DMA_STATE_READY;
1376 if(hdma->XferCpltCallback != NULL)
1378 /* Transfer complete callback */
1379 hdma->XferCpltCallback(hdma);
1385 /* manage error case */
1386 if(hdma->ErrorCode != HAL_DMA_ERROR_NONE)
1388 if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != 0U)
1390 hdma->State = HAL_DMA_STATE_ABORT;
1392 /* Disable the stream */
1393 __HAL_DMA_DISABLE(hdma);
1397 if (++count > timeout)
1399 break;
1402 while((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U);
1404 /* Process Unlocked */
1405 __HAL_UNLOCK(hdma);
1407 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U)
1409 /* Change the DMA state to error if DMA disable fails */
1410 hdma->State = HAL_DMA_STATE_ERROR;
1412 else
1414 /* Change the DMA state to Ready if DMA disable success */
1415 hdma->State = HAL_DMA_STATE_READY;
1419 if(hdma->XferErrorCallback != NULL)
1421 /* Transfer error callback */
1422 hdma->XferErrorCallback(hdma);
1426 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
1428 ccr_reg = (((BDMA_Channel_TypeDef *)hdma->Instance)->CCR);
1430 /* Half Transfer Complete Interrupt management ******************************/
1431 if (((tmpisr_bdma & (BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_HTIE) != 0U))
1433 /* Clear the half transfer complete flag */
1434 regs_bdma->IFCR = (BDMA_ISR_HTIF0 << (hdma->StreamIndex & 0x1FU));
1436 /* Disable the transfer complete interrupt if the DMA mode is Double Buffering */
1437 if((ccr_reg & BDMA_CCR_DBM) != 0U)
1439 /* Current memory buffer used is Memory 0 */
1440 if((ccr_reg & BDMA_CCR_CT) == 0U)
1442 if(hdma->XferM1HalfCpltCallback != NULL)
1444 /* Half transfer Callback for Memory 1 */
1445 hdma->XferM1HalfCpltCallback(hdma);
1448 /* Current memory buffer used is Memory 1 */
1449 else
1451 if(hdma->XferHalfCpltCallback != NULL)
1453 /* Half transfer Callback for Memory 0 */
1454 hdma->XferHalfCpltCallback(hdma);
1458 else
1460 if((ccr_reg & BDMA_CCR_CIRC) == 0U)
1462 /* Disable the half transfer interrupt */
1463 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT);
1466 /* DMA peripheral state is not updated in Half Transfer */
1467 /* but in Transfer Complete case */
1469 if(hdma->XferHalfCpltCallback != NULL)
1471 /* Half transfer callback */
1472 hdma->XferHalfCpltCallback(hdma);
1477 /* Transfer Complete Interrupt management ***********************************/
1478 else if (((tmpisr_bdma & (BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_TCIE) != 0U))
1480 /* Clear the transfer complete flag */
1481 regs_bdma->IFCR = (BDMA_ISR_TCIF0) << (hdma->StreamIndex & 0x1FU);
1483 /* Disable the transfer complete interrupt if the DMA mode is Double Buffering */
1484 if((ccr_reg & BDMA_CCR_DBM) != 0U)
1486 /* Current memory buffer used is Memory 0 */
1487 if((ccr_reg & BDMA_CCR_CT) == 0U)
1489 if(hdma->XferM1CpltCallback != NULL)
1491 /* Transfer complete Callback for Memory 1 */
1492 hdma->XferM1CpltCallback(hdma);
1495 /* Current memory buffer used is Memory 1 */
1496 else
1498 if(hdma->XferCpltCallback != NULL)
1500 /* Transfer complete Callback for Memory 0 */
1501 hdma->XferCpltCallback(hdma);
1505 else
1507 if((ccr_reg & BDMA_CCR_CIRC) == 0U)
1509 /* Disable the transfer complete and error interrupt, if the DMA mode is not CIRCULAR */
1510 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_TE | DMA_IT_TC);
1512 /* Process Unlocked */
1513 __HAL_UNLOCK(hdma);
1515 /* Change the DMA state */
1516 hdma->State = HAL_DMA_STATE_READY;
1519 if(hdma->XferCpltCallback != NULL)
1521 /* Transfer complete callback */
1522 hdma->XferCpltCallback(hdma);
1526 /* Transfer Error Interrupt management **************************************/
1527 else if (((tmpisr_bdma & (BDMA_FLAG_TE0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_TEIE) != 0U))
1529 /* When a DMA transfer error occurs */
1530 /* A hardware clear of its EN bits is performed */
1531 /* Disable ALL DMA IT */
1532 __HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE));
1534 /* Clear all flags */
1535 regs_bdma->IFCR = (BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU);
1537 /* Update error code */
1538 hdma->ErrorCode = HAL_DMA_ERROR_TE;
1540 /* Process Unlocked */
1541 __HAL_UNLOCK(hdma);
1543 /* Change the DMA state */
1544 hdma->State = HAL_DMA_STATE_READY;
1546 if (hdma->XferErrorCallback != NULL)
1548 /* Transfer error callback */
1549 hdma->XferErrorCallback(hdma);
1552 else
1554 /* Nothing To Do */
1557 else
1559 /* Nothing To Do */
1564 * @brief Register callbacks
1565 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1566 * the configuration information for the specified DMA Stream.
1567 * @param CallbackID: User Callback identifier
1568 * a DMA_HandleTypeDef structure as parameter.
1569 * @param pCallback: pointer to private callback function which has pointer to
1570 * a DMA_HandleTypeDef structure as parameter.
1571 * @retval HAL status
1573 HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma))
1576 HAL_StatusTypeDef status = HAL_OK;
1578 /* Check the DMA peripheral handle */
1579 if(hdma == NULL)
1581 return HAL_ERROR;
1584 /* Process locked */
1585 __HAL_LOCK(hdma);
1587 if(HAL_DMA_STATE_READY == hdma->State)
1589 switch (CallbackID)
1591 case HAL_DMA_XFER_CPLT_CB_ID:
1592 hdma->XferCpltCallback = pCallback;
1593 break;
1595 case HAL_DMA_XFER_HALFCPLT_CB_ID:
1596 hdma->XferHalfCpltCallback = pCallback;
1597 break;
1599 case HAL_DMA_XFER_M1CPLT_CB_ID:
1600 hdma->XferM1CpltCallback = pCallback;
1601 break;
1603 case HAL_DMA_XFER_M1HALFCPLT_CB_ID:
1604 hdma->XferM1HalfCpltCallback = pCallback;
1605 break;
1607 case HAL_DMA_XFER_ERROR_CB_ID:
1608 hdma->XferErrorCallback = pCallback;
1609 break;
1611 case HAL_DMA_XFER_ABORT_CB_ID:
1612 hdma->XferAbortCallback = pCallback;
1613 break;
1615 default:
1616 break;
1619 else
1621 /* Return error status */
1622 status = HAL_ERROR;
1625 /* Release Lock */
1626 __HAL_UNLOCK(hdma);
1628 return status;
1632 * @brief UnRegister callbacks
1633 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1634 * the configuration information for the specified DMA Stream.
1635 * @param CallbackID: User Callback identifier
1636 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
1637 * @retval HAL status
1639 HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID)
1641 HAL_StatusTypeDef status = HAL_OK;
1643 /* Check the DMA peripheral handle */
1644 if(hdma == NULL)
1646 return HAL_ERROR;
1649 /* Process locked */
1650 __HAL_LOCK(hdma);
1652 if(HAL_DMA_STATE_READY == hdma->State)
1654 switch (CallbackID)
1656 case HAL_DMA_XFER_CPLT_CB_ID:
1657 hdma->XferCpltCallback = NULL;
1658 break;
1660 case HAL_DMA_XFER_HALFCPLT_CB_ID:
1661 hdma->XferHalfCpltCallback = NULL;
1662 break;
1664 case HAL_DMA_XFER_M1CPLT_CB_ID:
1665 hdma->XferM1CpltCallback = NULL;
1666 break;
1668 case HAL_DMA_XFER_M1HALFCPLT_CB_ID:
1669 hdma->XferM1HalfCpltCallback = NULL;
1670 break;
1672 case HAL_DMA_XFER_ERROR_CB_ID:
1673 hdma->XferErrorCallback = NULL;
1674 break;
1676 case HAL_DMA_XFER_ABORT_CB_ID:
1677 hdma->XferAbortCallback = NULL;
1678 break;
1680 case HAL_DMA_XFER_ALL_CB_ID:
1681 hdma->XferCpltCallback = NULL;
1682 hdma->XferHalfCpltCallback = NULL;
1683 hdma->XferM1CpltCallback = NULL;
1684 hdma->XferM1HalfCpltCallback = NULL;
1685 hdma->XferErrorCallback = NULL;
1686 hdma->XferAbortCallback = NULL;
1687 break;
1689 default:
1690 status = HAL_ERROR;
1691 break;
1694 else
1696 status = HAL_ERROR;
1699 /* Release Lock */
1700 __HAL_UNLOCK(hdma);
1702 return status;
1706 * @}
1709 /** @addtogroup DMA_Exported_Functions_Group3
1711 @verbatim
1712 ===============================================================================
1713 ##### State and Errors functions #####
1714 ===============================================================================
1715 [..]
1716 This subsection provides functions allowing to
1717 (+) Check the DMA state
1718 (+) Get error code
1720 @endverbatim
1721 * @{
1725 * @brief Returns the DMA state.
1726 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1727 * the configuration information for the specified DMA Stream.
1728 * @retval HAL state
1730 HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
1732 return hdma->State;
1736 * @brief Return the DMA error code
1737 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
1738 * the configuration information for the specified DMA Stream.
1739 * @retval DMA Error Code
1741 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
1743 return hdma->ErrorCode;
1747 * @}
1751 * @}
1754 /** @addtogroup DMA_Private_Functions
1755 * @{
1759 * @brief Sets the DMA Transfer parameter.
1760 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1761 * the configuration information for the specified DMA Stream.
1762 * @param SrcAddress: The source memory Buffer address
1763 * @param DstAddress: The destination memory Buffer address
1764 * @param DataLength: The length of data to be transferred from source to destination
1765 * @retval None
1767 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
1769 /* calculate DMA base and stream number */
1770 DMA_Base_Registers *regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
1771 BDMA_Base_Registers *regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
1773 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
1775 /* Clear the DMAMUX synchro overrun flag */
1776 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
1778 if(hdma->DMAmuxRequestGen != 0U)
1780 /* Clear the DMAMUX request generator overrun flag */
1781 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
1785 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1787 /* Clear all interrupt flags at correct offset within the register */
1788 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
1790 /* Clear DBM bit */
1791 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= (uint32_t)(~DMA_SxCR_DBM);
1793 /* Configure DMA Stream data length */
1794 ((DMA_Stream_TypeDef *)hdma->Instance)->NDTR = DataLength;
1796 /* Peripheral to Memory */
1797 if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1799 /* Configure DMA Stream destination address */
1800 ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = DstAddress;
1802 /* Configure DMA Stream source address */
1803 ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = SrcAddress;
1805 /* Memory to Peripheral */
1806 else
1808 /* Configure DMA Stream source address */
1809 ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = SrcAddress;
1811 /* Configure DMA Stream destination address */
1812 ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = DstAddress;
1815 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
1817 /* Clear all flags */
1818 regs_bdma->IFCR = (BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU);
1820 /* Configure DMA Channel data length */
1821 ((BDMA_Channel_TypeDef *)hdma->Instance)->CNDTR = DataLength;
1823 /* Peripheral to Memory */
1824 if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1826 /* Configure DMA Channel destination address */
1827 ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = DstAddress;
1829 /* Configure DMA Channel source address */
1830 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = SrcAddress;
1832 /* Memory to Peripheral */
1833 else
1835 /* Configure DMA Channel source address */
1836 ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = SrcAddress;
1838 /* Configure DMA Channel destination address */
1839 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = DstAddress;
1842 else
1844 /* Nothing To Do */
1849 * @brief Returns the DMA Stream base address depending on stream number
1850 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1851 * the configuration information for the specified DMA Stream.
1852 * @retval Stream base address
1854 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma)
1856 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1858 uint32_t stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 16U) / 24U;
1860 /* lookup table for necessary bitshift of flags within status registers */
1861 static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U};
1862 hdma->StreamIndex = flagBitshiftOffset[stream_number & 0x7U];
1864 if (stream_number > 3U)
1866 /* return pointer to HISR and HIFCR */
1867 hdma->StreamBaseAddress = (((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0x3FFU)) + 4U);
1869 else
1871 /* return pointer to LISR and LIFCR */
1872 hdma->StreamBaseAddress = ((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0x3FFU));
1875 else /* BDMA instance(s) */
1877 /* return pointer to ISR and IFCR */
1878 hdma->StreamBaseAddress = ((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0xFFU));
1881 return hdma->StreamBaseAddress;
1885 * @brief Check compatibility between FIFO threshold level and size of the memory burst
1886 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1887 * the configuration information for the specified DMA Stream.
1888 * @retval HAL status
1890 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma)
1892 HAL_StatusTypeDef status = HAL_OK;
1894 /* Memory Data size equal to Byte */
1895 if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE)
1897 switch (hdma->Init.FIFOThreshold)
1899 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1900 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1902 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1904 status = HAL_ERROR;
1906 break;
1908 case DMA_FIFO_THRESHOLD_HALFFULL:
1909 if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1911 status = HAL_ERROR;
1913 break;
1915 case DMA_FIFO_THRESHOLD_FULL:
1916 break;
1918 default:
1919 break;
1923 /* Memory Data size equal to Half-Word */
1924 else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1926 switch (hdma->Init.FIFOThreshold)
1928 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1929 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1930 status = HAL_ERROR;
1931 break;
1933 case DMA_FIFO_THRESHOLD_HALFFULL:
1934 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1936 status = HAL_ERROR;
1938 break;
1940 case DMA_FIFO_THRESHOLD_FULL:
1941 if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1943 status = HAL_ERROR;
1945 break;
1947 default:
1948 break;
1952 /* Memory Data size equal to Word */
1953 else
1955 switch (hdma->Init.FIFOThreshold)
1957 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1958 case DMA_FIFO_THRESHOLD_HALFFULL:
1959 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1960 status = HAL_ERROR;
1961 break;
1963 case DMA_FIFO_THRESHOLD_FULL:
1964 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1966 status = HAL_ERROR;
1968 break;
1970 default:
1971 break;
1975 return status;
1979 * @brief Updates the DMA handle with the DMAMUX channel and status mask depending on stream number
1980 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1981 * the configuration information for the specified DMA Stream.
1982 * @retval HAL status
1984 static void DMA_CalcDMAMUXChannelBaseAndMask(DMA_HandleTypeDef *hdma)
1986 uint32_t stream_number;
1987 uint32_t stream_baseaddress = (uint32_t)((uint32_t*)hdma->Instance);
1989 if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
1991 /* BDMA Channels are connected to DMAMUX2 channels */
1992 stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 8U) / 20U;
1993 hdma->DMAmuxChannel = (DMAMUX_Channel_TypeDef *)((uint32_t)(((uint32_t)DMAMUX2_Channel0) + (stream_number * 4U)));
1994 hdma->DMAmuxChannelStatus = DMAMUX2_ChannelStatus;
1995 hdma->DMAmuxChannelStatusMask = 1UL << (stream_number & 0x1FU);
1997 else
1999 /* DMA1/DMA2 Streams are connected to DMAMUX1 channels */
2000 stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 16U) / 24U;
2002 if((stream_baseaddress <= ((uint32_t)DMA2_Stream7) ) && \
2003 (stream_baseaddress >= ((uint32_t)DMA2_Stream0)))
2005 stream_number += 8U;
2007 hdma->DMAmuxChannel = (DMAMUX_Channel_TypeDef *)((uint32_t)(((uint32_t)DMAMUX1_Channel0) + (stream_number * 4U)));
2008 hdma->DMAmuxChannelStatus = DMAMUX1_ChannelStatus;
2009 hdma->DMAmuxChannelStatusMask = 1UL << (stream_number & 0x1FU);
2014 * @brief Updates the DMA handle with the DMAMUX request generator params
2015 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2016 * the configuration information for the specified DMA Stream.
2017 * @retval HAL status
2019 static void DMA_CalcDMAMUXRequestGenBaseAndMask(DMA_HandleTypeDef *hdma)
2021 uint32_t request = hdma->Init.Request & DMAMUX_CxCR_DMAREQ_ID;
2023 if((request >= DMA_REQUEST_GENERATOR0) && (request <= DMA_REQUEST_GENERATOR7))
2025 if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
2027 /* BDMA Channels are connected to DMAMUX2 request generator blocks */
2028 hdma->DMAmuxRequestGen = (DMAMUX_RequestGen_TypeDef *)((uint32_t)(((uint32_t)DMAMUX2_RequestGenerator0) + ((request - 1U) * 4U)));
2030 hdma->DMAmuxRequestGenStatus = DMAMUX2_RequestGenStatus;
2032 else
2034 /* DMA1 and DMA2 Streams use DMAMUX1 request generator blocks */
2035 hdma->DMAmuxRequestGen = (DMAMUX_RequestGen_TypeDef *)((uint32_t)(((uint32_t)DMAMUX1_RequestGenerator0) + ((request - 1U) * 4U)));
2037 hdma->DMAmuxRequestGenStatus = DMAMUX1_RequestGenStatus;
2040 hdma->DMAmuxRequestGenStatusMask = 1UL << (request - 1U);
2045 * @}
2048 #endif /* HAL_DMA_MODULE_ENABLED */
2050 * @}
2054 * @}
2057 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/