Set blackbox file handler to NULL after closing file
[inav.git] / lib / main / STM32H7 / Drivers / STM32H7xx_HAL_Driver / Src / stm32h7xx_hal_dma.c
blob399ae0e0b81597e7a0c6509e304932b5bf23db05
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)
150 * @}
152 /* Private macros ------------------------------------------------------------*/
153 /* Private functions ---------------------------------------------------------*/
154 /** @addtogroup DMA_Private_Functions
155 * @{
157 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
158 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma);
159 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma);
160 static void DMA_CalcDMAMUXChannelBaseAndMask(DMA_HandleTypeDef *hdma);
161 static void DMA_CalcDMAMUXRequestGenBaseAndMask(DMA_HandleTypeDef *hdma);
164 * @}
167 /* Exported functions ---------------------------------------------------------*/
168 /** @addtogroup DMA_Exported_Functions
169 * @{
172 /** @addtogroup DMA_Exported_Functions_Group1
174 @verbatim
175 ===============================================================================
176 ##### Initialization and de-initialization functions #####
177 ===============================================================================
178 [..]
179 This section provides functions allowing to initialize the DMA Stream source
180 and destination incrementation and data sizes, transfer direction,
181 circular/normal mode selection, memory-to-memory mode selection and Stream priority value.
182 [..]
183 The HAL_DMA_Init() function follows the DMA configuration procedures as described in
184 reference manual.
185 The HAL_DMA_DeInit function allows to deinitialize the DMA stream.
187 @endverbatim
188 * @{
192 * @brief Initialize the DMA according to the specified
193 * parameters in the DMA_InitTypeDef and create the associated handle.
194 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
195 * the configuration information for the specified DMA Stream.
196 * @retval HAL status
198 HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma)
200 uint32_t registerValue;
201 uint32_t tickstart = HAL_GetTick();
202 DMA_Base_Registers *regs_dma;
203 BDMA_Base_Registers *regs_bdma;
205 /* Check the DMA peripheral handle */
206 if(hdma == NULL)
208 return HAL_ERROR;
211 /* Check the parameters */
212 assert_param(IS_DMA_ALL_INSTANCE(hdma->Instance));
213 assert_param(IS_DMA_DIRECTION(hdma->Init.Direction));
214 assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc));
215 assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc));
216 assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment));
217 assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment));
218 assert_param(IS_DMA_MODE(hdma->Init.Mode));
219 assert_param(IS_DMA_PRIORITY(hdma->Init.Priority));
221 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
223 assert_param(IS_DMA_REQUEST(hdma->Init.Request));
224 assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode));
225 /* Check the memory burst, peripheral burst and FIFO threshold parameters only
226 when FIFO mode is enabled */
227 if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE)
229 assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold));
230 assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst));
231 assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst));
234 /* Allocate lock resource */
235 __HAL_UNLOCK(hdma);
237 /* Change DMA peripheral state */
238 hdma->State = HAL_DMA_STATE_BUSY;
240 /* Disable the peripheral */
241 __HAL_DMA_DISABLE(hdma);
243 /* Check if the DMA Stream is effectively disabled */
244 while((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U)
246 /* Check for the Timeout */
247 if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
249 /* Update error code */
250 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
252 /* Change the DMA state */
253 hdma->State = HAL_DMA_STATE_ERROR;
255 return HAL_ERROR;
259 /* Get the CR register value */
260 registerValue = ((DMA_Stream_TypeDef *)hdma->Instance)->CR;
262 /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */
263 registerValue &= ((uint32_t)~(DMA_SxCR_MBURST | DMA_SxCR_PBURST | \
264 DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \
265 DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \
266 DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM));
268 /* Prepare the DMA Stream configuration */
269 registerValue |= hdma->Init.Direction |
270 hdma->Init.PeriphInc | hdma->Init.MemInc |
271 hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment |
272 hdma->Init.Mode | hdma->Init.Priority;
274 /* the Memory burst and peripheral burst are not used when the FIFO is disabled */
275 if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
277 /* Get memory burst and peripheral burst */
278 registerValue |= hdma->Init.MemBurst | hdma->Init.PeriphBurst;
281 /* Write to DMA Stream CR register */
282 ((DMA_Stream_TypeDef *)hdma->Instance)->CR = registerValue;
284 /* Get the FCR register value */
285 registerValue = ((DMA_Stream_TypeDef *)hdma->Instance)->FCR;
287 /* Clear Direct mode and FIFO threshold bits */
288 registerValue &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH);
290 /* Prepare the DMA Stream FIFO configuration */
291 registerValue |= hdma->Init.FIFOMode;
293 /* the FIFO threshold is not used when the FIFO mode is disabled */
294 if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
296 /* Get the FIFO threshold */
297 registerValue |= hdma->Init.FIFOThreshold;
299 /* Check compatibility between FIFO threshold level and size of the memory burst */
300 /* for INCR4, INCR8, INCR16 */
301 if(hdma->Init.MemBurst != DMA_MBURST_SINGLE)
303 if (DMA_CheckFifoParam(hdma) != HAL_OK)
305 /* Update error code */
306 hdma->ErrorCode = HAL_DMA_ERROR_PARAM;
308 /* Change the DMA state */
309 hdma->State = HAL_DMA_STATE_READY;
311 return HAL_ERROR;
316 /* Write to DMA Stream FCR */
317 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR = registerValue;
319 /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
320 DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
321 regs_dma = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
323 /* Clear all interrupt flags */
324 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
326 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
328 if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
330 /* Check the request parameter */
331 assert_param(IS_BDMA_REQUEST(hdma->Init.Request));
334 /* Allocate lock resource */
335 __HAL_UNLOCK(hdma);
337 /* Change DMA peripheral state */
338 hdma->State = HAL_DMA_STATE_BUSY;
340 /* Get the CR register value */
341 registerValue = ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR;
343 /* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, MEM2MEM, DBM and CT bits */
344 registerValue &= ((uint32_t)~(BDMA_CCR_PL | BDMA_CCR_MSIZE | BDMA_CCR_PSIZE | \
345 BDMA_CCR_MINC | BDMA_CCR_PINC | BDMA_CCR_CIRC | \
346 BDMA_CCR_DIR | BDMA_CCR_MEM2MEM | BDMA_CCR_DBM | \
347 BDMA_CCR_CT));
349 /* Prepare the DMA Channel configuration */
350 registerValue |= DMA_TO_BDMA_DIRECTION(hdma->Init.Direction) |
351 DMA_TO_BDMA_PERIPHERAL_INC(hdma->Init.PeriphInc) |
352 DMA_TO_BDMA_MEMORY_INC(hdma->Init.MemInc) |
353 DMA_TO_BDMA_PDATA_SIZE(hdma->Init.PeriphDataAlignment) |
354 DMA_TO_BDMA_MDATA_SIZE(hdma->Init.MemDataAlignment) |
355 DMA_TO_BDMA_MODE(hdma->Init.Mode) |
356 DMA_TO_BDMA_PRIORITY(hdma->Init.Priority);
358 /* Write to DMA Channel CR register */
359 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR = registerValue;
361 /* calculation of the channel index */
362 hdma->StreamIndex = (((uint32_t)((uint32_t*)hdma->Instance) - (uint32_t)BDMA_Channel0) / ((uint32_t)BDMA_Channel1 - (uint32_t)BDMA_Channel0)) << 2U;
364 /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
365 DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
366 regs_bdma = (BDMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
368 /* Clear all interrupt flags */
369 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
371 else
373 hdma->ErrorCode = HAL_DMA_ERROR_PARAM;
374 hdma->State = HAL_DMA_STATE_ERROR;
376 return HAL_ERROR;
379 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
381 /* Initialize parameters for DMAMUX channel :
382 DMAmuxChannel, DMAmuxChannelStatus and DMAmuxChannelStatusMask
384 DMA_CalcDMAMUXChannelBaseAndMask(hdma);
386 if(hdma->Init.Direction == DMA_MEMORY_TO_MEMORY)
388 /* if memory to memory force the request to 0*/
389 hdma->Init.Request = DMA_REQUEST_MEM2MEM;
392 /* Set peripheral request to DMAMUX channel */
393 hdma->DMAmuxChannel->CCR = (hdma->Init.Request & DMAMUX_CxCR_DMAREQ_ID);
395 /* Clear the DMAMUX synchro overrun flag */
396 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
398 /* Initialize parameters for DMAMUX request generator :
399 if the DMA request is DMA_REQUEST_GENERATOR0 to DMA_REQUEST_GENERATOR7
401 if((hdma->Init.Request >= DMA_REQUEST_GENERATOR0) && (hdma->Init.Request <= DMA_REQUEST_GENERATOR7))
403 /* Initialize parameters for DMAMUX request generator :
404 DMAmuxRequestGen, DMAmuxRequestGenStatus and DMAmuxRequestGenStatusMask */
405 DMA_CalcDMAMUXRequestGenBaseAndMask(hdma);
407 /* Reset the DMAMUX request generator register */
408 hdma->DMAmuxRequestGen->RGCR = 0U;
410 /* Clear the DMAMUX request generator overrun flag */
411 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
413 else
415 hdma->DMAmuxRequestGen = 0U;
416 hdma->DMAmuxRequestGenStatus = 0U;
417 hdma->DMAmuxRequestGenStatusMask = 0U;
421 /* Initialize the error code */
422 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
424 /* Initialize the DMA state */
425 hdma->State = HAL_DMA_STATE_READY;
427 return HAL_OK;
431 * @brief DeInitializes the DMA peripheral
432 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
433 * the configuration information for the specified DMA Stream.
434 * @retval HAL status
436 HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma)
438 DMA_Base_Registers *regs_dma;
439 BDMA_Base_Registers *regs_bdma;
441 /* Check the DMA peripheral handle */
442 if(hdma == NULL)
444 return HAL_ERROR;
447 /* Disable the selected DMA Streamx */
448 __HAL_DMA_DISABLE(hdma);
450 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
452 /* Reset DMA Streamx control register */
453 ((DMA_Stream_TypeDef *)hdma->Instance)->CR = 0U;
455 /* Reset DMA Streamx number of data to transfer register */
456 ((DMA_Stream_TypeDef *)hdma->Instance)->NDTR = 0U;
458 /* Reset DMA Streamx peripheral address register */
459 ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = 0U;
461 /* Reset DMA Streamx memory 0 address register */
462 ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = 0U;
464 /* Reset DMA Streamx memory 1 address register */
465 ((DMA_Stream_TypeDef *)hdma->Instance)->M1AR = 0U;
467 /* Reset DMA Streamx FIFO control register */
468 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR = (uint32_t)0x00000021U;
470 /* Get DMA steam Base Address */
471 regs_dma = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
473 /* Clear all interrupt flags at correct offset within the register */
474 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
476 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
478 /* Reset DMA Channel control register */
479 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR = 0U;
481 /* Reset DMA Channel Number of Data to Transfer register */
482 ((BDMA_Channel_TypeDef *)hdma->Instance)->CNDTR = 0U;
484 /* Reset DMA Channel peripheral address register */
485 ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = 0U;
487 /* Reset DMA Channel memory 0 address register */
488 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = 0U;
490 /* Reset DMA Channel memory 1 address register */
491 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM1AR = 0U;
493 /* Get DMA steam Base Address */
494 regs_bdma = (BDMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
496 /* Clear all interrupt flags at correct offset within the register */
497 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
499 else
501 /* Return error status */
502 return HAL_ERROR;
505 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
507 /* Initialize parameters for DMAMUX channel :
508 DMAmuxChannel, DMAmuxChannelStatus and DMAmuxChannelStatusMask */
509 DMA_CalcDMAMUXChannelBaseAndMask(hdma);
511 if(hdma->DMAmuxChannel != 0U)
513 /* Resett he DMAMUX channel that corresponds to the DMA stream */
514 hdma->DMAmuxChannel->CCR = 0U;
516 /* Clear the DMAMUX synchro overrun flag */
517 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
520 if((hdma->Init.Request >= DMA_REQUEST_GENERATOR0) && (hdma->Init.Request <= DMA_REQUEST_GENERATOR7))
522 /* Initialize parameters for DMAMUX request generator :
523 DMAmuxRequestGen, DMAmuxRequestGenStatus and DMAmuxRequestGenStatusMask */
524 DMA_CalcDMAMUXRequestGenBaseAndMask(hdma);
526 /* Reset the DMAMUX request generator register */
527 hdma->DMAmuxRequestGen->RGCR = 0U;
529 /* Clear the DMAMUX request generator overrun flag */
530 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
533 hdma->DMAmuxRequestGen = 0U;
534 hdma->DMAmuxRequestGenStatus = 0U;
535 hdma->DMAmuxRequestGenStatusMask = 0U;
539 /* Clean callbacks */
540 hdma->XferCpltCallback = NULL;
541 hdma->XferHalfCpltCallback = NULL;
542 hdma->XferM1CpltCallback = NULL;
543 hdma->XferM1HalfCpltCallback = NULL;
544 hdma->XferErrorCallback = NULL;
545 hdma->XferAbortCallback = NULL;
547 /* Initialize the error code */
548 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
550 /* Initialize the DMA state */
551 hdma->State = HAL_DMA_STATE_RESET;
553 /* Release Lock */
554 __HAL_UNLOCK(hdma);
556 return HAL_OK;
560 * @}
563 /** @addtogroup DMA_Exported_Functions_Group2
565 @verbatim
566 ===============================================================================
567 ##### IO operation functions #####
568 ===============================================================================
569 [..] This section provides functions allowing to:
570 (+) Configure the source, destination address and data length and Start DMA transfer
571 (+) Configure the source, destination address and data length and
572 Start DMA transfer with interrupt
573 (+) Register and Unregister DMA callbacks
574 (+) Abort DMA transfer
575 (+) Poll for transfer complete
576 (+) Handle DMA interrupt request
578 @endverbatim
579 * @{
583 * @brief Starts the DMA Transfer.
584 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
585 * the configuration information for the specified DMA Stream.
586 * @param SrcAddress: The source memory Buffer address
587 * @param DstAddress: The destination memory Buffer address
588 * @param DataLength: The length of data to be transferred from source to destination
589 * @retval HAL status
591 HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
593 HAL_StatusTypeDef status = HAL_OK;
595 /* Check the parameters */
596 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
598 /* Check the DMA peripheral handle */
599 if(hdma == NULL)
601 return HAL_ERROR;
604 /* Process locked */
605 __HAL_LOCK(hdma);
607 if(HAL_DMA_STATE_READY == hdma->State)
609 /* Change DMA peripheral state */
610 hdma->State = HAL_DMA_STATE_BUSY;
612 /* Initialize the error code */
613 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
615 /* Disable the peripheral */
616 __HAL_DMA_DISABLE(hdma);
618 /* Configure the source, destination address and the data length */
619 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
621 /* Enable the Peripheral */
622 __HAL_DMA_ENABLE(hdma);
624 else
626 /* Process unlocked */
627 __HAL_UNLOCK(hdma);
629 /* Set the error code to busy */
630 hdma->ErrorCode = HAL_DMA_ERROR_BUSY;
632 /* Return error status */
633 status = HAL_ERROR;
635 return status;
639 * @brief Start the DMA Transfer with interrupt enabled.
640 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
641 * the configuration information for the specified DMA Stream.
642 * @param SrcAddress: The source memory Buffer address
643 * @param DstAddress: The destination memory Buffer address
644 * @param DataLength: The length of data to be transferred from source to destination
645 * @retval HAL status
647 HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
649 HAL_StatusTypeDef status = HAL_OK;
651 /* Check the parameters */
652 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
654 /* Check the DMA peripheral handle */
655 if(hdma == NULL)
657 return HAL_ERROR;
660 /* Process locked */
661 __HAL_LOCK(hdma);
663 if(HAL_DMA_STATE_READY == hdma->State)
665 /* Change DMA peripheral state */
666 hdma->State = HAL_DMA_STATE_BUSY;
668 /* Initialize the error code */
669 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
671 /* Disable the peripheral */
672 __HAL_DMA_DISABLE(hdma);
674 /* Configure the source, destination address and the data length */
675 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
677 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
679 /* Enable Common interrupts*/
680 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));
682 if(hdma->XferHalfCpltCallback != NULL)
684 /* Enable Half Transfer IT if corresponding Callback is set */
685 ((DMA_Stream_TypeDef *)hdma->Instance)->CR |= DMA_IT_HT;
688 else /* BDMA channel */
690 /* Enable Common interrupts */
691 MODIFY_REG(((BDMA_Channel_TypeDef *)hdma->Instance)->CCR, (BDMA_CCR_TCIE | BDMA_CCR_HTIE | BDMA_CCR_TEIE), (BDMA_CCR_TCIE | BDMA_CCR_TEIE));
693 if(hdma->XferHalfCpltCallback != NULL)
695 /*Enable Half Transfer IT if corresponding Callback is set */
696 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR |= BDMA_CCR_HTIE;
700 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
702 /* Check if DMAMUX Synchronization is enabled */
703 if((hdma->DMAmuxChannel->CCR & DMAMUX_CxCR_SE) != 0U)
705 /* Enable DMAMUX sync overrun IT*/
706 hdma->DMAmuxChannel->CCR |= DMAMUX_CxCR_SOIE;
709 if(hdma->DMAmuxRequestGen != 0U)
711 /* if using DMAMUX request generator, enable the DMAMUX request generator overrun IT*/
712 /* enable the request gen overrun IT */
713 hdma->DMAmuxRequestGen->RGCR |= DMAMUX_RGxCR_OIE;
717 /* Enable the Peripheral */
718 __HAL_DMA_ENABLE(hdma);
720 else
722 /* Process unlocked */
723 __HAL_UNLOCK(hdma);
725 /* Set the error code to busy */
726 hdma->ErrorCode = HAL_DMA_ERROR_BUSY;
728 /* Return error status */
729 status = HAL_ERROR;
732 return status;
736 * @brief Aborts the DMA Transfer.
737 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
738 * the configuration information for the specified DMA Stream.
740 * @note After disabling a DMA Stream, a check for wait until the DMA Stream is
741 * effectively disabled is added. If a Stream is disabled
742 * while a data transfer is ongoing, the current data will be transferred
743 * and the Stream will be effectively disabled only after the transfer of
744 * this single data is finished.
745 * @retval HAL status
747 HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma)
749 /* calculate DMA base and stream number */
750 DMA_Base_Registers *regs_dma;
751 BDMA_Base_Registers *regs_bdma;
752 const __IO uint32_t *enableRegister;
754 uint32_t tickstart = HAL_GetTick();
756 /* Check the DMA peripheral handle */
757 if(hdma == NULL)
759 return HAL_ERROR;
762 /* Check the DMA peripheral state */
763 if(hdma->State != HAL_DMA_STATE_BUSY)
765 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
767 /* Process Unlocked */
768 __HAL_UNLOCK(hdma);
770 return HAL_ERROR;
772 else
774 /* Disable all the transfer interrupts */
775 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
777 /* Disable DMA All Interrupts */
778 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME | DMA_IT_HT);
779 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR &= ~(DMA_IT_FE);
781 enableRegister = (__IO uint32_t *)(&(((DMA_Stream_TypeDef *)hdma->Instance)->CR));
783 else /* BDMA channel */
785 /* Disable DMA All Interrupts */
786 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR &= ~(BDMA_CCR_TCIE | BDMA_CCR_HTIE | BDMA_CCR_TEIE);
788 enableRegister = (__IO uint32_t *)(&(((BDMA_Channel_TypeDef *)hdma->Instance)->CCR));
791 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
793 /* disable the DMAMUX sync overrun IT */
794 hdma->DMAmuxChannel->CCR &= ~DMAMUX_CxCR_SOIE;
797 /* Disable the stream */
798 __HAL_DMA_DISABLE(hdma);
800 /* Check if the DMA Stream is effectively disabled */
801 while(((*enableRegister) & DMA_SxCR_EN) != 0U)
803 /* Check for the Timeout */
804 if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
806 /* Update error code */
807 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
809 /* Process Unlocked */
810 __HAL_UNLOCK(hdma);
812 /* Change the DMA state */
813 hdma->State = HAL_DMA_STATE_ERROR;
815 return HAL_ERROR;
819 /* Clear all interrupt flags at correct offset within the register */
820 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
822 regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
823 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
825 else /* BDMA channel */
827 regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
828 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
831 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
833 /* Clear the DMAMUX synchro overrun flag */
834 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
836 if(hdma->DMAmuxRequestGen != 0U)
838 /* if using DMAMUX request generator, disable the DMAMUX request generator overrun IT */
839 /* disable the request gen overrun IT */
840 hdma->DMAmuxRequestGen->RGCR &= ~DMAMUX_RGxCR_OIE;
842 /* Clear the DMAMUX request generator overrun flag */
843 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
847 /* Process Unlocked */
848 __HAL_UNLOCK(hdma);
850 /* Change the DMA state */
851 hdma->State = HAL_DMA_STATE_READY;
854 return HAL_OK;
858 * @brief Aborts the DMA Transfer in Interrupt mode.
859 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
860 * the configuration information for the specified DMA Stream.
861 * @retval HAL status
863 HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma)
865 BDMA_Base_Registers *regs_bdma;
867 /* Check the DMA peripheral handle */
868 if(hdma == NULL)
870 return HAL_ERROR;
873 if(hdma->State != HAL_DMA_STATE_BUSY)
875 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
876 return HAL_ERROR;
878 else
880 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
882 /* Set Abort State */
883 hdma->State = HAL_DMA_STATE_ABORT;
885 /* Disable the stream */
886 __HAL_DMA_DISABLE(hdma);
888 else /* BDMA channel */
890 /* Disable DMA All Interrupts */
891 ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR &= ~(BDMA_CCR_TCIE | BDMA_CCR_HTIE | BDMA_CCR_TEIE);
893 /* Disable the channel */
894 __HAL_DMA_DISABLE(hdma);
896 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
898 /* disable the DMAMUX sync overrun IT */
899 hdma->DMAmuxChannel->CCR &= ~DMAMUX_CxCR_SOIE;
901 /* Clear all flags */
902 regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
903 regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
905 /* Clear the DMAMUX synchro overrun flag */
906 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
908 if(hdma->DMAmuxRequestGen != 0U)
910 /* if using DMAMUX request generator, disable the DMAMUX request generator overrun IT*/
911 /* disable the request gen overrun IT */
912 hdma->DMAmuxRequestGen->RGCR &= ~DMAMUX_RGxCR_OIE;
914 /* Clear the DMAMUX request generator overrun flag */
915 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
919 /* Process Unlocked */
920 __HAL_UNLOCK(hdma);
922 /* Change the DMA state */
923 hdma->State = HAL_DMA_STATE_READY;
925 /* Call User Abort callback */
926 if(hdma->XferAbortCallback != NULL)
928 hdma->XferAbortCallback(hdma);
933 return HAL_OK;
937 * @brief Polling for transfer complete.
938 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
939 * the configuration information for the specified DMA Stream.
940 * @param CompleteLevel: Specifies the DMA level complete.
941 * @note The polling mode is kept in this version for legacy. it is recommanded to use the IT model instead.
942 * This model could be used for debug purpose.
943 * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode).
944 * @param Timeout: Timeout duration.
945 * @retval HAL status
947 HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout)
949 HAL_StatusTypeDef status = HAL_OK;
950 uint32_t cpltlevel_mask;
951 uint32_t tickstart = HAL_GetTick();
953 /* IT status register */
954 __IO uint32_t *isr_reg;
955 /* IT clear flag register */
956 __IO uint32_t *ifcr_reg;
958 /* Check the DMA peripheral handle */
959 if(hdma == NULL)
961 return HAL_ERROR;
964 if(HAL_DMA_STATE_BUSY != hdma->State)
966 /* No transfer ongoing */
967 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
968 __HAL_UNLOCK(hdma);
970 return HAL_ERROR;
973 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
975 /* Polling mode not supported in circular mode and double buffering mode */
976 if ((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) != 0U)
978 hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
979 return HAL_ERROR;
982 /* Get the level transfer complete flag */
983 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
985 /* Transfer Complete flag */
986 cpltlevel_mask = DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU);
988 else
990 /* Half Transfer Complete flag */
991 cpltlevel_mask = DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU);
994 isr_reg = &(((DMA_Base_Registers *)hdma->StreamBaseAddress)->ISR);
995 ifcr_reg = &(((DMA_Base_Registers *)hdma->StreamBaseAddress)->IFCR);
997 else /* BDMA channel */
999 /* Polling mode not supported in circular mode */
1000 if ((((BDMA_Channel_TypeDef *)hdma->Instance)->CCR & BDMA_CCR_CIRC) != 0U)
1002 hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
1003 return HAL_ERROR;
1006 /* Get the level transfer complete flag */
1007 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1009 /* Transfer Complete flag */
1010 cpltlevel_mask = BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU);
1012 else
1014 /* Half Transfer Complete flag */
1015 cpltlevel_mask = BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU);
1018 isr_reg = &(((BDMA_Base_Registers *)hdma->StreamBaseAddress)->ISR);
1019 ifcr_reg = &(((BDMA_Base_Registers *)hdma->StreamBaseAddress)->IFCR);
1022 while(((*isr_reg) & cpltlevel_mask) == 0U)
1024 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1026 if(((*isr_reg) & (DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1028 /* Update error code */
1029 hdma->ErrorCode |= HAL_DMA_ERROR_FE;
1031 /* Clear the FIFO error flag */
1032 (*ifcr_reg) = DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU);
1035 if(((*isr_reg) & (DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1037 /* Update error code */
1038 hdma->ErrorCode |= HAL_DMA_ERROR_DME;
1040 /* Clear the Direct Mode error flag */
1041 (*ifcr_reg) = DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU);
1044 if(((*isr_reg) & (DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1046 /* Update error code */
1047 hdma->ErrorCode |= HAL_DMA_ERROR_TE;
1049 /* Clear the transfer error flag */
1050 (*ifcr_reg) = DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU);
1052 /* Change the DMA state */
1053 hdma->State = HAL_DMA_STATE_READY;
1055 /* Process Unlocked */
1056 __HAL_UNLOCK(hdma);
1058 return HAL_ERROR;
1061 else /* BDMA channel */
1063 if(((*isr_reg) & (BDMA_FLAG_TE0 << (hdma->StreamIndex & 0x1FU))) != 0U)
1065 /* When a DMA transfer error occurs */
1066 /* A hardware clear of its EN bits is performed */
1067 /* Clear all flags */
1068 (*isr_reg) = ((BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU));
1070 /* Update error code */
1071 hdma->ErrorCode = HAL_DMA_ERROR_TE;
1073 /* Change the DMA state */
1074 hdma->State = HAL_DMA_STATE_READY;
1076 /* Process Unlocked */
1077 __HAL_UNLOCK(hdma);
1079 return HAL_ERROR;
1083 /* Check for the Timeout (Not applicable in circular mode)*/
1084 if(Timeout != HAL_MAX_DELAY)
1086 if(((HAL_GetTick() - tickstart ) > Timeout)||(Timeout == 0U))
1088 /* Update error code */
1089 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
1091 /* if timeout then abort the current transfer */
1092 /* No need to check return value: as in this case we will return HAL_ERROR with HAL_DMA_ERROR_TIMEOUT error code */
1093 (void) HAL_DMA_Abort(hdma);
1095 Note that the Abort function will
1096 - Clear the transfer error flags
1097 - Unlock
1098 - Set the State
1101 return HAL_ERROR;
1105 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
1107 /* Check for DMAMUX Request generator (if used) overrun status */
1108 if(hdma->DMAmuxRequestGen != 0U)
1110 /* if using DMAMUX request generator Check for DMAMUX request generator overrun */
1111 if((hdma->DMAmuxRequestGenStatus->RGSR & hdma->DMAmuxRequestGenStatusMask) != 0U)
1113 /* Clear the DMAMUX request generator overrun flag */
1114 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
1116 /* Update error code */
1117 hdma->ErrorCode |= HAL_DMA_ERROR_REQGEN;
1121 /* Check for DMAMUX Synchronization overrun */
1122 if((hdma->DMAmuxChannelStatus->CSR & hdma->DMAmuxChannelStatusMask) != 0U)
1124 /* Clear the DMAMUX synchro overrun flag */
1125 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
1127 /* Update error code */
1128 hdma->ErrorCode |= HAL_DMA_ERROR_SYNC;
1134 /* Get the level transfer complete flag */
1135 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1137 /* Clear the half transfer and transfer complete flags */
1138 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1140 (*ifcr_reg) = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << (hdma->StreamIndex & 0x1FU);
1142 else /* BDMA channel */
1144 (*ifcr_reg) = (BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU));
1147 /* Process Unlocked */
1148 __HAL_UNLOCK(hdma);
1150 hdma->State = HAL_DMA_STATE_READY;
1152 else /*CompleteLevel = HAL_DMA_HALF_TRANSFER*/
1154 /* Clear the half transfer and transfer complete flags */
1155 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1157 (*ifcr_reg) = (DMA_FLAG_HTIF0_4) << (hdma->StreamIndex & 0x1FU);
1159 else /* BDMA channel */
1161 (*ifcr_reg) = (BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU));
1165 return status;
1169 * @brief Handles DMA interrupt request.
1170 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1171 * the configuration information for the specified DMA Stream.
1172 * @retval None
1174 void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma)
1176 uint32_t tmpisr_dma, tmpisr_bdma;
1177 uint32_t ccr_reg;
1178 __IO uint32_t count = 0U;
1179 uint32_t timeout = SystemCoreClock / 9600U;
1181 /* calculate DMA base and stream number */
1182 DMA_Base_Registers *regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
1183 BDMA_Base_Registers *regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
1185 tmpisr_dma = regs_dma->ISR;
1186 tmpisr_bdma = regs_bdma->ISR;
1188 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1190 /* Transfer Error Interrupt management ***************************************/
1191 if ((tmpisr_dma & (DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1193 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != 0U)
1195 /* Disable the transfer error interrupt */
1196 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TE);
1198 /* Clear the transfer error flag */
1199 regs_dma->IFCR = DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU);
1201 /* Update error code */
1202 hdma->ErrorCode |= HAL_DMA_ERROR_TE;
1205 /* FIFO Error Interrupt management ******************************************/
1206 if ((tmpisr_dma & (DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1208 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != 0U)
1210 /* Clear the FIFO error flag */
1211 regs_dma->IFCR = DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU);
1213 /* Update error code */
1214 hdma->ErrorCode |= HAL_DMA_ERROR_FE;
1217 /* Direct Mode Error Interrupt management ***********************************/
1218 if ((tmpisr_dma & (DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1220 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != 0U)
1222 /* Clear the direct mode error flag */
1223 regs_dma->IFCR = DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU);
1225 /* Update error code */
1226 hdma->ErrorCode |= HAL_DMA_ERROR_DME;
1229 /* Half Transfer Complete Interrupt management ******************************/
1230 if ((tmpisr_dma & (DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1232 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != 0U)
1234 /* Clear the half transfer complete flag */
1235 regs_dma->IFCR = DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU);
1237 /* Multi_Buffering mode enabled */
1238 if(((((DMA_Stream_TypeDef *)hdma->Instance)->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0U)
1240 /* Current memory buffer used is Memory 0 */
1241 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CT) == 0U)
1243 if(hdma->XferHalfCpltCallback != NULL)
1245 /* Half transfer callback */
1246 hdma->XferHalfCpltCallback(hdma);
1249 /* Current memory buffer used is Memory 1 */
1250 else
1252 if(hdma->XferM1HalfCpltCallback != NULL)
1254 /* Half transfer callback */
1255 hdma->XferM1HalfCpltCallback(hdma);
1259 else
1261 /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
1262 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) == 0U)
1264 /* Disable the half transfer interrupt */
1265 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_HT);
1268 if(hdma->XferHalfCpltCallback != NULL)
1270 /* Half transfer callback */
1271 hdma->XferHalfCpltCallback(hdma);
1276 /* Transfer Complete Interrupt management ***********************************/
1277 if ((tmpisr_dma & (DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1279 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != 0U)
1281 /* Clear the transfer complete flag */
1282 regs_dma->IFCR = DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU);
1284 if(HAL_DMA_STATE_ABORT == hdma->State)
1286 /* Disable all the transfer interrupts */
1287 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME);
1288 ((DMA_Stream_TypeDef *)hdma->Instance)->FCR &= ~(DMA_IT_FE);
1290 if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL))
1292 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_HT);
1295 /* Clear all interrupt flags at correct offset within the register */
1296 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
1298 /* Process Unlocked */
1299 __HAL_UNLOCK(hdma);
1301 /* Change the DMA state */
1302 hdma->State = HAL_DMA_STATE_READY;
1304 if(hdma->XferAbortCallback != NULL)
1306 hdma->XferAbortCallback(hdma);
1308 return;
1311 if(((((DMA_Stream_TypeDef *)hdma->Instance)->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0U)
1313 /* Current memory buffer used is Memory 0 */
1314 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CT) == 0U)
1316 if(hdma->XferM1CpltCallback != NULL)
1318 /* Transfer complete Callback for memory1 */
1319 hdma->XferM1CpltCallback(hdma);
1322 /* Current memory buffer used is Memory 1 */
1323 else
1325 if(hdma->XferCpltCallback != NULL)
1327 /* Transfer complete Callback for memory0 */
1328 hdma->XferCpltCallback(hdma);
1332 /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */
1333 else
1335 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) == 0U)
1337 /* Disable the transfer complete interrupt */
1338 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC);
1340 /* Process Unlocked */
1341 __HAL_UNLOCK(hdma);
1343 /* Change the DMA state */
1344 hdma->State = HAL_DMA_STATE_READY;
1347 if(hdma->XferCpltCallback != NULL)
1349 /* Transfer complete callback */
1350 hdma->XferCpltCallback(hdma);
1356 /* manage error case */
1357 if(hdma->ErrorCode != HAL_DMA_ERROR_NONE)
1359 if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != 0U)
1361 hdma->State = HAL_DMA_STATE_ABORT;
1363 /* Disable the stream */
1364 __HAL_DMA_DISABLE(hdma);
1368 if (++count > timeout)
1370 break;
1373 while((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U);
1375 /* Process Unlocked */
1376 __HAL_UNLOCK(hdma);
1378 if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U)
1380 /* Change the DMA state to error if DMA disable fails */
1381 hdma->State = HAL_DMA_STATE_ERROR;
1383 else
1385 /* Change the DMA state to Ready if DMA disable success */
1386 hdma->State = HAL_DMA_STATE_READY;
1390 if(hdma->XferErrorCallback != NULL)
1392 /* Transfer error callback */
1393 hdma->XferErrorCallback(hdma);
1397 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
1399 ccr_reg = (((BDMA_Channel_TypeDef *)hdma->Instance)->CCR);
1401 /* Half Transfer Complete Interrupt management ******************************/
1402 if (((tmpisr_bdma & (BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_HTIE) != 0U))
1404 /* Clear the half transfer complete flag */
1405 regs_bdma->IFCR = (BDMA_ISR_HTIF0 << (hdma->StreamIndex & 0x1FU));
1407 /* Disable the transfer complete interrupt if the DMA mode is Double Buffering */
1408 if((ccr_reg & BDMA_CCR_DBM) != 0U)
1410 /* Current memory buffer used is Memory 0 */
1411 if((ccr_reg & BDMA_CCR_CT) == 0U)
1413 if(hdma->XferM1HalfCpltCallback != NULL)
1415 /* Half transfer Callback for Memory 1 */
1416 hdma->XferM1HalfCpltCallback(hdma);
1419 /* Current memory buffer used is Memory 1 */
1420 else
1422 if(hdma->XferHalfCpltCallback != NULL)
1424 /* Half transfer Callback for Memory 0 */
1425 hdma->XferHalfCpltCallback(hdma);
1429 else
1431 if((ccr_reg & BDMA_CCR_CIRC) == 0U)
1433 /* Disable the half transfer interrupt */
1434 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT);
1437 /* DMA peripheral state is not updated in Half Transfer */
1438 /* but in Transfer Complete case */
1440 if(hdma->XferHalfCpltCallback != NULL)
1442 /* Half transfer callback */
1443 hdma->XferHalfCpltCallback(hdma);
1448 /* Transfer Complete Interrupt management ***********************************/
1449 else if (((tmpisr_bdma & (BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_TCIE) != 0U))
1451 /* Clear the transfer complete flag */
1452 regs_bdma->IFCR = (BDMA_ISR_TCIF0) << (hdma->StreamIndex & 0x1FU);
1454 /* Disable the transfer complete interrupt if the DMA mode is Double Buffering */
1455 if((ccr_reg & BDMA_CCR_DBM) != 0U)
1457 /* Current memory buffer used is Memory 0 */
1458 if((ccr_reg & BDMA_CCR_CT) == 0U)
1460 if(hdma->XferM1CpltCallback != NULL)
1462 /* Transfer complete Callback for Memory 1 */
1463 hdma->XferM1CpltCallback(hdma);
1466 /* Current memory buffer used is Memory 1 */
1467 else
1469 if(hdma->XferCpltCallback != NULL)
1471 /* Transfer complete Callback for Memory 0 */
1472 hdma->XferCpltCallback(hdma);
1476 else
1478 if((ccr_reg & BDMA_CCR_CIRC) == 0U)
1480 /* Disable the transfer complete and error interrupt, if the DMA mode is not CIRCULAR */
1481 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_TE | DMA_IT_TC);
1483 /* Process Unlocked */
1484 __HAL_UNLOCK(hdma);
1486 /* Change the DMA state */
1487 hdma->State = HAL_DMA_STATE_READY;
1490 if(hdma->XferCpltCallback != NULL)
1492 /* Transfer complete callback */
1493 hdma->XferCpltCallback(hdma);
1497 /* Transfer Error Interrupt management **************************************/
1498 else if (((tmpisr_bdma & (BDMA_FLAG_TE0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_TEIE) != 0U))
1500 /* When a DMA transfer error occurs */
1501 /* A hardware clear of its EN bits is performed */
1502 /* Disable ALL DMA IT */
1503 __HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE));
1505 /* Clear all flags */
1506 regs_bdma->IFCR = (BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU);
1508 /* Update error code */
1509 hdma->ErrorCode = HAL_DMA_ERROR_TE;
1511 /* Process Unlocked */
1512 __HAL_UNLOCK(hdma);
1514 /* Change the DMA state */
1515 hdma->State = HAL_DMA_STATE_READY;
1517 if (hdma->XferErrorCallback != NULL)
1519 /* Transfer error callback */
1520 hdma->XferErrorCallback(hdma);
1523 else
1525 /* Nothing To Do */
1528 else
1530 /* Nothing To Do */
1535 * @brief Register callbacks
1536 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1537 * the configuration information for the specified DMA Stream.
1538 * @param CallbackID: User Callback identifier
1539 * a DMA_HandleTypeDef structure as parameter.
1540 * @param pCallback: pointer to private callback function which has pointer to
1541 * a DMA_HandleTypeDef structure as parameter.
1542 * @retval HAL status
1544 HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma))
1547 HAL_StatusTypeDef status = HAL_OK;
1549 /* Check the DMA peripheral handle */
1550 if(hdma == NULL)
1552 return HAL_ERROR;
1555 /* Process locked */
1556 __HAL_LOCK(hdma);
1558 if(HAL_DMA_STATE_READY == hdma->State)
1560 switch (CallbackID)
1562 case HAL_DMA_XFER_CPLT_CB_ID:
1563 hdma->XferCpltCallback = pCallback;
1564 break;
1566 case HAL_DMA_XFER_HALFCPLT_CB_ID:
1567 hdma->XferHalfCpltCallback = pCallback;
1568 break;
1570 case HAL_DMA_XFER_M1CPLT_CB_ID:
1571 hdma->XferM1CpltCallback = pCallback;
1572 break;
1574 case HAL_DMA_XFER_M1HALFCPLT_CB_ID:
1575 hdma->XferM1HalfCpltCallback = pCallback;
1576 break;
1578 case HAL_DMA_XFER_ERROR_CB_ID:
1579 hdma->XferErrorCallback = pCallback;
1580 break;
1582 case HAL_DMA_XFER_ABORT_CB_ID:
1583 hdma->XferAbortCallback = pCallback;
1584 break;
1586 default:
1587 break;
1590 else
1592 /* Return error status */
1593 status = HAL_ERROR;
1596 /* Release Lock */
1597 __HAL_UNLOCK(hdma);
1599 return status;
1603 * @brief UnRegister callbacks
1604 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1605 * the configuration information for the specified DMA Stream.
1606 * @param CallbackID: User Callback identifier
1607 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
1608 * @retval HAL status
1610 HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID)
1612 HAL_StatusTypeDef status = HAL_OK;
1614 /* Check the DMA peripheral handle */
1615 if(hdma == NULL)
1617 return HAL_ERROR;
1620 /* Process locked */
1621 __HAL_LOCK(hdma);
1623 if(HAL_DMA_STATE_READY == hdma->State)
1625 switch (CallbackID)
1627 case HAL_DMA_XFER_CPLT_CB_ID:
1628 hdma->XferCpltCallback = NULL;
1629 break;
1631 case HAL_DMA_XFER_HALFCPLT_CB_ID:
1632 hdma->XferHalfCpltCallback = NULL;
1633 break;
1635 case HAL_DMA_XFER_M1CPLT_CB_ID:
1636 hdma->XferM1CpltCallback = NULL;
1637 break;
1639 case HAL_DMA_XFER_M1HALFCPLT_CB_ID:
1640 hdma->XferM1HalfCpltCallback = NULL;
1641 break;
1643 case HAL_DMA_XFER_ERROR_CB_ID:
1644 hdma->XferErrorCallback = NULL;
1645 break;
1647 case HAL_DMA_XFER_ABORT_CB_ID:
1648 hdma->XferAbortCallback = NULL;
1649 break;
1651 case HAL_DMA_XFER_ALL_CB_ID:
1652 hdma->XferCpltCallback = NULL;
1653 hdma->XferHalfCpltCallback = NULL;
1654 hdma->XferM1CpltCallback = NULL;
1655 hdma->XferM1HalfCpltCallback = NULL;
1656 hdma->XferErrorCallback = NULL;
1657 hdma->XferAbortCallback = NULL;
1658 break;
1660 default:
1661 status = HAL_ERROR;
1662 break;
1665 else
1667 status = HAL_ERROR;
1670 /* Release Lock */
1671 __HAL_UNLOCK(hdma);
1673 return status;
1677 * @}
1680 /** @addtogroup DMA_Exported_Functions_Group3
1682 @verbatim
1683 ===============================================================================
1684 ##### State and Errors functions #####
1685 ===============================================================================
1686 [..]
1687 This subsection provides functions allowing to
1688 (+) Check the DMA state
1689 (+) Get error code
1691 @endverbatim
1692 * @{
1696 * @brief Returns the DMA state.
1697 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1698 * the configuration information for the specified DMA Stream.
1699 * @retval HAL state
1701 HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
1703 return hdma->State;
1707 * @brief Return the DMA error code
1708 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
1709 * the configuration information for the specified DMA Stream.
1710 * @retval DMA Error Code
1712 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
1714 return hdma->ErrorCode;
1718 * @}
1722 * @}
1725 /** @addtogroup DMA_Private_Functions
1726 * @{
1730 * @brief Sets the DMA Transfer parameter.
1731 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1732 * the configuration information for the specified DMA Stream.
1733 * @param SrcAddress: The source memory Buffer address
1734 * @param DstAddress: The destination memory Buffer address
1735 * @param DataLength: The length of data to be transferred from source to destination
1736 * @retval None
1738 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
1740 /* calculate DMA base and stream number */
1741 DMA_Base_Registers *regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
1742 BDMA_Base_Registers *regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
1744 if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
1746 /* Clear the DMAMUX synchro overrun flag */
1747 hdma->DMAmuxChannelStatus->CFR = hdma->DMAmuxChannelStatusMask;
1749 if(hdma->DMAmuxRequestGen != 0U)
1751 /* Clear the DMAMUX request generator overrun flag */
1752 hdma->DMAmuxRequestGenStatus->RGCFR = hdma->DMAmuxRequestGenStatusMask;
1756 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1758 /* Clear all interrupt flags at correct offset within the register */
1759 regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
1761 /* Clear DBM bit */
1762 ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= (uint32_t)(~DMA_SxCR_DBM);
1764 /* Configure DMA Stream data length */
1765 ((DMA_Stream_TypeDef *)hdma->Instance)->NDTR = DataLength;
1767 /* Peripheral to Memory */
1768 if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1770 /* Configure DMA Stream destination address */
1771 ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = DstAddress;
1773 /* Configure DMA Stream source address */
1774 ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = SrcAddress;
1776 /* Memory to Peripheral */
1777 else
1779 /* Configure DMA Stream source address */
1780 ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = SrcAddress;
1782 /* Configure DMA Stream destination address */
1783 ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = DstAddress;
1786 else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
1788 /* Clear all flags */
1789 regs_bdma->IFCR = (BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU);
1791 /* Configure DMA Channel data length */
1792 ((BDMA_Channel_TypeDef *)hdma->Instance)->CNDTR = DataLength;
1794 /* Peripheral to Memory */
1795 if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1797 /* Configure DMA Channel destination address */
1798 ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = DstAddress;
1800 /* Configure DMA Channel source address */
1801 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = SrcAddress;
1803 /* Memory to Peripheral */
1804 else
1806 /* Configure DMA Channel source address */
1807 ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = SrcAddress;
1809 /* Configure DMA Channel destination address */
1810 ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = DstAddress;
1813 else
1815 /* Nothing To Do */
1820 * @brief Returns the DMA Stream base address depending on stream number
1821 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1822 * the configuration information for the specified DMA Stream.
1823 * @retval Stream base address
1825 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma)
1827 if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1829 uint32_t stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 16U) / 24U;
1831 /* lookup table for necessary bitshift of flags within status registers */
1832 static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U};
1833 hdma->StreamIndex = flagBitshiftOffset[stream_number & 0x7U];
1835 if (stream_number > 3U)
1837 /* return pointer to HISR and HIFCR */
1838 hdma->StreamBaseAddress = (((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0x3FFU)) + 4U);
1840 else
1842 /* return pointer to LISR and LIFCR */
1843 hdma->StreamBaseAddress = ((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0x3FFU));
1846 else /* BDMA instance(s) */
1848 /* return pointer to ISR and IFCR */
1849 hdma->StreamBaseAddress = ((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0xFFU));
1852 return hdma->StreamBaseAddress;
1856 * @brief Check compatibility between FIFO threshold level and size of the memory burst
1857 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1858 * the configuration information for the specified DMA Stream.
1859 * @retval HAL status
1861 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma)
1863 HAL_StatusTypeDef status = HAL_OK;
1865 /* Memory Data size equal to Byte */
1866 if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE)
1868 switch (hdma->Init.FIFOThreshold)
1870 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1871 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1873 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1875 status = HAL_ERROR;
1877 break;
1879 case DMA_FIFO_THRESHOLD_HALFFULL:
1880 if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1882 status = HAL_ERROR;
1884 break;
1886 case DMA_FIFO_THRESHOLD_FULL:
1887 break;
1889 default:
1890 break;
1894 /* Memory Data size equal to Half-Word */
1895 else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1897 switch (hdma->Init.FIFOThreshold)
1899 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1900 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1901 status = HAL_ERROR;
1902 break;
1904 case DMA_FIFO_THRESHOLD_HALFFULL:
1905 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1907 status = HAL_ERROR;
1909 break;
1911 case DMA_FIFO_THRESHOLD_FULL:
1912 if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1914 status = HAL_ERROR;
1916 break;
1918 default:
1919 break;
1923 /* Memory Data size equal to Word */
1924 else
1926 switch (hdma->Init.FIFOThreshold)
1928 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1929 case DMA_FIFO_THRESHOLD_HALFFULL:
1930 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1931 status = HAL_ERROR;
1932 break;
1934 case DMA_FIFO_THRESHOLD_FULL:
1935 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1937 status = HAL_ERROR;
1939 break;
1941 default:
1942 break;
1946 return status;
1950 * @brief Updates the DMA handle with the DMAMUX channel and status mask depending on stream number
1951 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1952 * the configuration information for the specified DMA Stream.
1953 * @retval HAL status
1955 static void DMA_CalcDMAMUXChannelBaseAndMask(DMA_HandleTypeDef *hdma)
1957 uint32_t stream_number;
1958 uint32_t stream_baseaddress = (uint32_t)((uint32_t*)hdma->Instance);
1960 if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
1962 /* BDMA Channels are connected to DMAMUX2 channels */
1963 stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 8U) / 20U;
1964 hdma->DMAmuxChannel = (DMAMUX_Channel_TypeDef *)((uint32_t)(((uint32_t)DMAMUX2_Channel0) + (stream_number * 4U)));
1965 hdma->DMAmuxChannelStatus = DMAMUX2_ChannelStatus;
1966 hdma->DMAmuxChannelStatusMask = 1UL << (stream_number & 0x1FU);
1968 else
1970 /* DMA1/DMA2 Streams are connected to DMAMUX1 channels */
1971 stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 16U) / 24U;
1973 if((stream_baseaddress <= ((uint32_t)DMA2_Stream7) ) && \
1974 (stream_baseaddress >= ((uint32_t)DMA2_Stream0)))
1976 stream_number += 8U;
1978 hdma->DMAmuxChannel = (DMAMUX_Channel_TypeDef *)((uint32_t)(((uint32_t)DMAMUX1_Channel0) + (stream_number * 4U)));
1979 hdma->DMAmuxChannelStatus = DMAMUX1_ChannelStatus;
1980 hdma->DMAmuxChannelStatusMask = 1UL << (stream_number & 0x1FU);
1985 * @brief Updates the DMA handle with the DMAMUX request generator params
1986 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1987 * the configuration information for the specified DMA Stream.
1988 * @retval HAL status
1990 static void DMA_CalcDMAMUXRequestGenBaseAndMask(DMA_HandleTypeDef *hdma)
1992 uint32_t request = hdma->Init.Request & DMAMUX_CxCR_DMAREQ_ID;
1994 if((request >= DMA_REQUEST_GENERATOR0) && (request <= DMA_REQUEST_GENERATOR7))
1996 if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
1998 /* BDMA Channels are connected to DMAMUX2 request generator blocks */
1999 hdma->DMAmuxRequestGen = (DMAMUX_RequestGen_TypeDef *)((uint32_t)(((uint32_t)DMAMUX2_RequestGenerator0) + ((request - 1U) * 4U)));
2001 hdma->DMAmuxRequestGenStatus = DMAMUX2_RequestGenStatus;
2003 else
2005 /* DMA1 and DMA2 Streams use DMAMUX1 request generator blocks */
2006 hdma->DMAmuxRequestGen = (DMAMUX_RequestGen_TypeDef *)((uint32_t)(((uint32_t)DMAMUX1_RequestGenerator0) + ((request - 1U) * 4U)));
2008 hdma->DMAmuxRequestGenStatus = DMAMUX1_RequestGenStatus;
2011 hdma->DMAmuxRequestGenStatusMask = 1UL << (request - 1U);
2016 * @}
2019 #endif /* HAL_DMA_MODULE_ENABLED */
2021 * @}
2025 * @}
2028 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/