Merge pull request #10558 from iNavFlight/MrD_Correct-comments-on-OSD-symbols
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_dma.c
blob1adfab150ce1157f370487d295ac9505c76ea5cd
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_dma.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief DMA HAL module driver.
8 *
9 * This file provides firmware functions to manage the following
10 * functionalities of the Direct Memory Access (DMA) peripheral:
11 * + Initialization and de-initialization functions
12 * + IO operation functions
13 * + Peripheral State and errors functions
14 @verbatim
15 ==============================================================================
16 ##### How to use this driver #####
17 ==============================================================================
18 [..]
19 (#) Enable and configure the peripheral to be connected to the DMA Stream
20 (except for internal SRAM/FLASH memories: no initialization is
21 necessary) please refer to Reference manual for connection between peripherals
22 and DMA requests.
24 (#) For a given Stream, program the required configuration through the following parameters:
25 Transfer Direction, Source and Destination data formats,
26 Circular, Normal or peripheral flow control mode, Stream Priority level,
27 Source and Destination Increment mode, FIFO mode and its Threshold (if needed),
28 Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function.
30 -@- Prior to HAL_DMA_Init() the clock must be enabled for DMA through the following macros:
31 __HAL_RCC_DMA1_CLK_ENABLE() or __HAL_RCC_DMA2_CLK_ENABLE().
33 *** Polling mode IO operation ***
34 =================================
35 [..]
36 (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source
37 address and destination address and the Length of data to be transferred.
38 (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this
39 case a fixed Timeout can be configured by User depending from his application.
40 (+) Use HAL_DMA_Abort() function to abort the current transfer.
42 *** Interrupt mode IO operation ***
43 ===================================
44 [..]
45 (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority()
46 (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ()
47 (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of
48 Source address and destination address and the Length of data to be transferred. In this
49 case the DMA interrupt is configured
50 (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine
51 (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can
52 add his own function by customization of function pointer XferCpltCallback and
53 XferErrorCallback (i.e a member of DMA handle structure).
54 [..]
55 (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error
56 detection.
58 (#) Use HAL_DMA_Abort_IT() function to abort the current transfer
60 -@- In Memory-to-Memory transfer mode, Circular mode is not allowed.
62 -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is
63 possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set
64 Half-Word data size for the peripheral to access its data register and set Word data size
65 for the Memory to gain in access time. Each two half words will be packed and written in
66 a single access to a Word in the Memory).
68 -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source
69 and Destination. In this case the Peripheral Data Size will be applied to both Source
70 and Destination.
72 *** DMA HAL driver macros list ***
73 =============================================
74 [..]
75 Below the list of most used macros in DMA HAL driver.
77 (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream.
78 (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream.
79 (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not.
81 [..]
82 (@) You can refer to the DMA HAL driver header file for more useful macros
84 @endverbatim
85 ******************************************************************************
86 * @attention
88 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
90 * Redistribution and use in source and binary forms, with or without modification,
91 * are permitted provided that the following conditions are met:
92 * 1. Redistributions of source code must retain the above copyright notice,
93 * this list of conditions and the following disclaimer.
94 * 2. Redistributions in binary form must reproduce the above copyright notice,
95 * this list of conditions and the following disclaimer in the documentation
96 * and/or other materials provided with the distribution.
97 * 3. Neither the name of STMicroelectronics nor the names of its contributors
98 * may be used to endorse or promote products derived from this software
99 * without specific prior written permission.
101 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
102 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
103 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
104 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
105 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
106 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
107 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
108 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
109 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
110 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
112 ******************************************************************************
115 /* Includes ------------------------------------------------------------------*/
116 #include "stm32f7xx_hal.h"
118 /** @addtogroup STM32F7xx_HAL_Driver
119 * @{
122 /** @defgroup DMA DMA
123 * @brief DMA HAL module driver
124 * @{
127 #ifdef HAL_DMA_MODULE_ENABLED
129 /* Private types -------------------------------------------------------------*/
130 typedef struct
132 __IO uint32_t ISR; /*!< DMA interrupt status register */
133 __IO uint32_t Reserved0;
134 __IO uint32_t IFCR; /*!< DMA interrupt flag clear register */
135 } DMA_Base_Registers;
137 /* Private variables ---------------------------------------------------------*/
138 /* Private constants ---------------------------------------------------------*/
139 /** @addtogroup DMA_Private_Constants
140 * @{
142 #define HAL_TIMEOUT_DMA_ABORT ((uint32_t)5) /* 5 ms */
144 * @}
146 /* Private macros ------------------------------------------------------------*/
147 /* Private functions ---------------------------------------------------------*/
148 /** @addtogroup DMA_Private_Functions
149 * @{
151 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
152 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma);
153 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma);
156 * @}
159 /* Exported functions ---------------------------------------------------------*/
160 /** @addtogroup DMA_Exported_Functions
161 * @{
164 /** @addtogroup DMA_Exported_Functions_Group1
166 @verbatim
167 ===============================================================================
168 ##### Initialization and de-initialization functions #####
169 ===============================================================================
170 [..]
171 This section provides functions allowing to initialize the DMA Stream source
172 and destination addresses, incrementation and data sizes, transfer direction,
173 circular/normal mode selection, memory-to-memory mode selection and Stream priority value.
174 [..]
175 The HAL_DMA_Init() function follows the DMA configuration procedures as described in
176 reference manual.
178 @endverbatim
179 * @{
183 * @brief Initialize the DMA according to the specified
184 * parameters in the DMA_InitTypeDef and create the associated handle.
185 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
186 * the configuration information for the specified DMA Stream.
187 * @retval HAL status
189 HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma)
191 uint32_t tmp = 0U;
192 uint32_t tickstart = HAL_GetTick();
193 DMA_Base_Registers *regs;
195 /* Check the DMA peripheral state */
196 if(hdma == NULL)
198 return HAL_ERROR;
201 /* Check the parameters */
202 assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance));
203 assert_param(IS_DMA_CHANNEL(hdma->Init.Channel));
204 assert_param(IS_DMA_DIRECTION(hdma->Init.Direction));
205 assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc));
206 assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc));
207 assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment));
208 assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment));
209 assert_param(IS_DMA_MODE(hdma->Init.Mode));
210 assert_param(IS_DMA_PRIORITY(hdma->Init.Priority));
211 assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode));
212 /* Check the memory burst, peripheral burst and FIFO threshold parameters only
213 when FIFO mode is enabled */
214 if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE)
216 assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold));
217 assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst));
218 assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst));
221 /* Allocate lock resource */
222 __HAL_UNLOCK(hdma);
224 /* Change DMA peripheral state */
225 hdma->State = HAL_DMA_STATE_BUSY;
227 /* Disable the peripheral */
228 __HAL_DMA_DISABLE(hdma);
230 /* Check if the DMA Stream is effectively disabled */
231 while((hdma->Instance->CR & DMA_SxCR_EN) != RESET)
233 /* Check for the Timeout */
234 if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
236 /* Update error code */
237 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
239 /* Change the DMA state */
240 hdma->State = HAL_DMA_STATE_TIMEOUT;
242 return HAL_TIMEOUT;
246 /* Get the CR register value */
247 tmp = hdma->Instance->CR;
249 /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */
250 tmp &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \
251 DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \
252 DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \
253 DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM));
255 /* Prepare the DMA Stream configuration */
256 tmp |= hdma->Init.Channel | hdma->Init.Direction |
257 hdma->Init.PeriphInc | hdma->Init.MemInc |
258 hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment |
259 hdma->Init.Mode | hdma->Init.Priority;
261 /* the Memory burst and peripheral burst are not used when the FIFO is disabled */
262 if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
264 /* Get memory burst and peripheral burst */
265 tmp |= hdma->Init.MemBurst | hdma->Init.PeriphBurst;
268 /* Write to DMA Stream CR register */
269 hdma->Instance->CR = tmp;
271 /* Get the FCR register value */
272 tmp = hdma->Instance->FCR;
274 /* Clear Direct mode and FIFO threshold bits */
275 tmp &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH);
277 /* Prepare the DMA Stream FIFO configuration */
278 tmp |= hdma->Init.FIFOMode;
280 /* The FIFO threshold is not used when the FIFO mode is disabled */
281 if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
283 /* Get the FIFO threshold */
284 tmp |= hdma->Init.FIFOThreshold;
286 /* Check compatibility between FIFO threshold level and size of the memory burst */
287 /* for INCR4, INCR8, INCR16 bursts */
288 if (hdma->Init.MemBurst != DMA_MBURST_SINGLE)
290 if (DMA_CheckFifoParam(hdma) != HAL_OK)
292 /* Update error code */
293 hdma->ErrorCode = HAL_DMA_ERROR_PARAM;
295 /* Change the DMA state */
296 hdma->State = HAL_DMA_STATE_READY;
298 return HAL_ERROR;
303 /* Write to DMA Stream FCR */
304 hdma->Instance->FCR = tmp;
306 /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
307 DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
308 regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
310 /* Clear all interrupt flags */
311 regs->IFCR = 0x3FU << hdma->StreamIndex;
313 /* Initialize the error code */
314 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
316 /* Initialize the DMA state */
317 hdma->State = HAL_DMA_STATE_READY;
319 return HAL_OK;
323 * @brief DeInitializes the DMA peripheral
324 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
325 * the configuration information for the specified DMA Stream.
326 * @retval HAL status
328 HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma)
330 DMA_Base_Registers *regs;
332 /* Check the DMA peripheral state */
333 if(hdma == NULL)
335 return HAL_ERROR;
338 /* Check the DMA peripheral state */
339 if(hdma->State == HAL_DMA_STATE_BUSY)
341 /* Return error status */
342 return HAL_BUSY;
345 /* Check the parameters */
346 assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance));
348 /* Disable the selected DMA Streamx */
349 __HAL_DMA_DISABLE(hdma);
351 /* Reset DMA Streamx control register */
352 hdma->Instance->CR = 0U;
354 /* Reset DMA Streamx number of data to transfer register */
355 hdma->Instance->NDTR = 0U;
357 /* Reset DMA Streamx peripheral address register */
358 hdma->Instance->PAR = 0U;
360 /* Reset DMA Streamx memory 0 address register */
361 hdma->Instance->M0AR = 0U;
363 /* Reset DMA Streamx memory 1 address register */
364 hdma->Instance->M1AR = 0U;
366 /* Reset DMA Streamx FIFO control register */
367 hdma->Instance->FCR = (uint32_t)0x00000021U;
369 /* Get DMA steam Base Address */
370 regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
372 /* Clear all interrupt flags at correct offset within the register */
373 regs->IFCR = 0x3FU << hdma->StreamIndex;
375 /* Initialize the error code */
376 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
378 /* Initialize the DMA state */
379 hdma->State = HAL_DMA_STATE_RESET;
381 /* Release Lock */
382 __HAL_UNLOCK(hdma);
384 return HAL_OK;
388 * @}
391 /** @addtogroup DMA_Exported_Functions_Group2
393 @verbatim
394 ===============================================================================
395 ##### IO operation functions #####
396 ===============================================================================
397 [..] This section provides functions allowing to:
398 (+) Configure the source, destination address and data length and Start DMA transfer
399 (+) Configure the source, destination address and data length and
400 Start DMA transfer with interrupt
401 (+) Abort DMA transfer
402 (+) Poll for transfer complete
403 (+) Handle DMA interrupt request
405 @endverbatim
406 * @{
410 * @brief Starts the DMA Transfer.
411 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
412 * the configuration information for the specified DMA Stream.
413 * @param SrcAddress: The source memory Buffer address
414 * @param DstAddress: The destination memory Buffer address
415 * @param DataLength: The length of data to be transferred from source to destination
416 * @retval HAL status
418 HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
420 HAL_StatusTypeDef status = HAL_OK;
422 /* Check the parameters */
423 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
425 /* Process locked */
426 __HAL_LOCK(hdma);
428 if(HAL_DMA_STATE_READY == hdma->State)
430 /* Change DMA peripheral state */
431 hdma->State = HAL_DMA_STATE_BUSY;
433 /* Initialize the error code */
434 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
436 /* Configure the source, destination address and the data length */
437 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
439 /* Enable the Peripheral */
440 __HAL_DMA_ENABLE(hdma);
442 else
444 /* Process unlocked */
445 __HAL_UNLOCK(hdma);
447 /* Return error status */
448 status = HAL_BUSY;
450 return status;
454 * @brief Start the DMA Transfer with interrupt enabled.
455 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
456 * the configuration information for the specified DMA Stream.
457 * @param SrcAddress: The source memory Buffer address
458 * @param DstAddress: The destination memory Buffer address
459 * @param DataLength: The length of data to be transferred from source to destination
460 * @retval HAL status
462 HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
464 HAL_StatusTypeDef status = HAL_OK;
466 /* calculate DMA base and stream number */
467 DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress;
469 /* Check the parameters */
470 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
472 /* Process locked */
473 __HAL_LOCK(hdma);
475 if(HAL_DMA_STATE_READY == hdma->State)
477 /* Change DMA peripheral state */
478 hdma->State = HAL_DMA_STATE_BUSY;
480 /* Initialize the error code */
481 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
483 /* Configure the source, destination address and the data length */
484 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
486 /* Clear all interrupt flags at correct offset within the register */
487 regs->IFCR = 0x3FU << hdma->StreamIndex;
489 /* Enable Common interrupts*/
490 hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME;
491 hdma->Instance->FCR |= DMA_IT_FE;
493 if(hdma->XferHalfCpltCallback != NULL)
495 hdma->Instance->CR |= DMA_IT_HT;
498 /* Enable the Peripheral */
499 __HAL_DMA_ENABLE(hdma);
501 else
503 /* Process unlocked */
504 __HAL_UNLOCK(hdma);
506 /* Return error status */
507 status = HAL_BUSY;
510 return status;
514 * @brief Aborts the DMA Transfer.
515 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
516 * the configuration information for the specified DMA Stream.
518 * @note After disabling a DMA Stream, a check for wait until the DMA Stream is
519 * effectively disabled is added. If a Stream is disabled
520 * while a data transfer is ongoing, the current data will be transferred
521 * and the Stream will be effectively disabled only after the transfer of
522 * this single data is finished.
523 * @retval HAL status
525 HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma)
527 /* calculate DMA base and stream number */
528 DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress;
530 uint32_t tickstart = HAL_GetTick();
532 if(hdma->State != HAL_DMA_STATE_BUSY)
534 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
536 /* Process Unlocked */
537 __HAL_UNLOCK(hdma);
539 return HAL_ERROR;
541 else
543 /* Disable all the transfer interrupts */
544 hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME);
545 hdma->Instance->FCR &= ~(DMA_IT_FE);
547 if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL))
549 hdma->Instance->CR &= ~(DMA_IT_HT);
552 /* Disable the stream */
553 __HAL_DMA_DISABLE(hdma);
555 /* Check if the DMA Stream is effectively disabled */
556 while((hdma->Instance->CR & DMA_SxCR_EN) != RESET)
558 /* Check for the Timeout */
559 if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
561 /* Update error code */
562 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
564 /* Process Unlocked */
565 __HAL_UNLOCK(hdma);
567 /* Change the DMA state */
568 hdma->State = HAL_DMA_STATE_TIMEOUT;
570 return HAL_TIMEOUT;
574 /* Clear all interrupt flags at correct offset within the register */
575 regs->IFCR = 0x3FU << hdma->StreamIndex;
577 /* Process Unlocked */
578 __HAL_UNLOCK(hdma);
580 /* Change the DMA state*/
581 hdma->State = HAL_DMA_STATE_READY;
583 return HAL_OK;
587 * @brief Aborts the DMA Transfer in Interrupt mode.
588 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
589 * the configuration information for the specified DMA Stream.
590 * @retval HAL status
592 HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma)
594 if(hdma->State != HAL_DMA_STATE_BUSY)
596 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
597 return HAL_ERROR;
599 else
601 /* Set Abort State */
602 hdma->State = HAL_DMA_STATE_ABORT;
604 /* Disable the stream */
605 __HAL_DMA_DISABLE(hdma);
608 return HAL_OK;
612 * @brief Polling for transfer complete.
613 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
614 * the configuration information for the specified DMA Stream.
615 * @param CompleteLevel: Specifies the DMA level complete.
616 * @note The polling mode is kept in this version for legacy. it is recommanded to use the IT model instead.
617 * This model could be used for debug purpose.
618 * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode).
619 * @param Timeout: Timeout duration.
620 * @retval HAL status
622 HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout)
624 HAL_StatusTypeDef status = HAL_OK;
625 uint32_t mask_cpltlevel;
626 uint32_t tickstart = HAL_GetTick();
627 uint32_t tmpisr;
629 /* calculate DMA base and stream number */
630 DMA_Base_Registers *regs;
632 if(HAL_DMA_STATE_BUSY != hdma->State)
634 /* No transfer ongoing */
635 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
636 __HAL_UNLOCK(hdma);
637 return HAL_ERROR;
640 /* Polling mode not supported in circular mode and double buffering mode */
641 if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET)
643 hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
644 return HAL_ERROR;
647 /* Get the level transfer complete flag */
648 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
650 /* Transfer Complete flag */
651 mask_cpltlevel = DMA_FLAG_TCIF0_4 << hdma->StreamIndex;
653 else
655 /* Half Transfer Complete flag */
656 mask_cpltlevel = DMA_FLAG_HTIF0_4 << hdma->StreamIndex;
659 regs = (DMA_Base_Registers *)hdma->StreamBaseAddress;
660 tmpisr = regs->ISR;
662 while(((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET))
664 /* Check for the Timeout (Not applicable in circular mode)*/
665 if(Timeout != HAL_MAX_DELAY)
667 if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
669 /* Update error code */
670 hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT;
672 /* Process Unlocked */
673 __HAL_UNLOCK(hdma);
675 /* Change the DMA state */
676 hdma->State = HAL_DMA_STATE_READY;
678 return HAL_TIMEOUT;
682 /* Get the ISR register value */
683 tmpisr = regs->ISR;
685 if((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET)
687 /* Update error code */
688 hdma->ErrorCode |= HAL_DMA_ERROR_TE;
690 /* Clear the transfer error flag */
691 regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex;
694 if((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET)
696 /* Update error code */
697 hdma->ErrorCode |= HAL_DMA_ERROR_FE;
699 /* Clear the FIFO error flag */
700 regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex;
703 if((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET)
705 /* Update error code */
706 hdma->ErrorCode |= HAL_DMA_ERROR_DME;
708 /* Clear the Direct Mode error flag */
709 regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex;
713 if(hdma->ErrorCode != HAL_DMA_ERROR_NONE)
715 if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET)
717 HAL_DMA_Abort(hdma);
719 /* Clear the half transfer and transfer complete flags */
720 regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex;
722 /* Process Unlocked */
723 __HAL_UNLOCK(hdma);
725 /* Change the DMA state */
726 hdma->State= HAL_DMA_STATE_READY;
728 return HAL_ERROR;
732 /* Get the level transfer complete flag */
733 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
735 /* Clear the half transfer and transfer complete flags */
736 regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex;
738 /* Process Unlocked */
739 __HAL_UNLOCK(hdma);
741 hdma->State = HAL_DMA_STATE_READY;
743 else
745 /* Clear the half transfer and transfer complete flags */
746 regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex;
749 return status;
753 * @brief Handles DMA interrupt request.
754 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
755 * the configuration information for the specified DMA Stream.
756 * @retval None
758 void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma)
760 uint32_t tmpisr;
761 __IO uint32_t count = 0;
762 uint32_t timeout = SystemCoreClock / 9600;
764 /* calculate DMA base and stream number */
765 DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress;
767 tmpisr = regs->ISR;
769 /* Transfer Error Interrupt management ***************************************/
770 if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET)
772 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET)
774 /* Disable the transfer error interrupt */
775 hdma->Instance->CR &= ~(DMA_IT_TE);
777 /* Clear the transfer error flag */
778 regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex;
780 /* Update error code */
781 hdma->ErrorCode |= HAL_DMA_ERROR_TE;
784 /* FIFO Error Interrupt management ******************************************/
785 if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET)
787 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != RESET)
789 /* Clear the FIFO error flag */
790 regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex;
792 /* Update error code */
793 hdma->ErrorCode |= HAL_DMA_ERROR_FE;
796 /* Direct Mode Error Interrupt management ***********************************/
797 if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET)
799 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != RESET)
801 /* Clear the direct mode error flag */
802 regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex;
804 /* Update error code */
805 hdma->ErrorCode |= HAL_DMA_ERROR_DME;
808 /* Half Transfer Complete Interrupt management ******************************/
809 if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET)
811 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET)
813 /* Clear the half transfer complete flag */
814 regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex;
816 /* Multi_Buffering mode enabled */
817 if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET)
819 /* Current memory buffer used is Memory 0 */
820 if((hdma->Instance->CR & DMA_SxCR_CT) == RESET)
822 if(hdma->XferHalfCpltCallback != NULL)
824 /* Half transfer callback */
825 hdma->XferHalfCpltCallback(hdma);
828 /* Current memory buffer used is Memory 1 */
829 else
831 if(hdma->XferM1HalfCpltCallback != NULL)
833 /* Half transfer callback */
834 hdma->XferM1HalfCpltCallback(hdma);
838 else
840 /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
841 if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET)
843 /* Disable the half transfer interrupt */
844 hdma->Instance->CR &= ~(DMA_IT_HT);
847 if(hdma->XferHalfCpltCallback != NULL)
849 /* Half transfer callback */
850 hdma->XferHalfCpltCallback(hdma);
855 /* Transfer Complete Interrupt management ***********************************/
856 if ((tmpisr & (DMA_FLAG_TCIF0_4 << hdma->StreamIndex)) != RESET)
858 if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET)
860 /* Clear the transfer complete flag */
861 regs->IFCR = DMA_FLAG_TCIF0_4 << hdma->StreamIndex;
863 if(HAL_DMA_STATE_ABORT == hdma->State)
865 /* Disable all the transfer interrupts */
866 hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME);
867 hdma->Instance->FCR &= ~(DMA_IT_FE);
869 if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL))
871 hdma->Instance->CR &= ~(DMA_IT_HT);
874 /* Clear all interrupt flags at correct offset within the register */
875 regs->IFCR = 0x3FU << hdma->StreamIndex;
877 /* Process Unlocked */
878 __HAL_UNLOCK(hdma);
880 /* Change the DMA state */
881 hdma->State = HAL_DMA_STATE_READY;
883 if(hdma->XferAbortCallback != NULL)
885 hdma->XferAbortCallback(hdma);
887 return;
890 if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET)
892 /* Current memory buffer used is Memory 0 */
893 if((hdma->Instance->CR & DMA_SxCR_CT) == RESET)
895 if(hdma->XferM1CpltCallback != NULL)
897 /* Transfer complete Callback for memory1 */
898 hdma->XferM1CpltCallback(hdma);
901 /* Current memory buffer used is Memory 1 */
902 else
904 if(hdma->XferCpltCallback != NULL)
906 /* Transfer complete Callback for memory0 */
907 hdma->XferCpltCallback(hdma);
911 /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */
912 else
914 if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET)
916 /* Disable the transfer complete interrupt */
917 hdma->Instance->CR &= ~(DMA_IT_TC);
919 /* Process Unlocked */
920 __HAL_UNLOCK(hdma);
922 /* Change the DMA state */
923 hdma->State = HAL_DMA_STATE_READY;
926 if(hdma->XferCpltCallback != NULL)
928 /* Transfer complete callback */
929 hdma->XferCpltCallback(hdma);
935 /* manage error case */
936 if(hdma->ErrorCode != HAL_DMA_ERROR_NONE)
938 if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET)
940 hdma->State = HAL_DMA_STATE_ABORT;
942 /* Disable the stream */
943 __HAL_DMA_DISABLE(hdma);
947 if (++count > timeout)
949 break;
952 while((hdma->Instance->CR & DMA_SxCR_EN) != RESET);
954 /* Process Unlocked */
955 __HAL_UNLOCK(hdma);
957 /* Change the DMA state */
958 hdma->State = HAL_DMA_STATE_READY;
961 if(hdma->XferErrorCallback != NULL)
963 /* Transfer error callback */
964 hdma->XferErrorCallback(hdma);
970 * @brief Register callbacks
971 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
972 * the configuration information for the specified DMA Stream.
973 * @param CallbackID: User Callback identifer
974 * a DMA_HandleTypeDef structure as parameter.
975 * @param pCallback: pointer to private callbacsk function which has pointer to
976 * a DMA_HandleTypeDef structure as parameter.
977 * @retval HAL status
979 HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma))
982 HAL_StatusTypeDef status = HAL_OK;
984 /* Process locked */
985 __HAL_LOCK(hdma);
987 if(HAL_DMA_STATE_READY == hdma->State)
989 switch (CallbackID)
991 case HAL_DMA_XFER_CPLT_CB_ID:
992 hdma->XferCpltCallback = pCallback;
993 break;
995 case HAL_DMA_XFER_HALFCPLT_CB_ID:
996 hdma->XferHalfCpltCallback = pCallback;
997 break;
999 case HAL_DMA_XFER_M1CPLT_CB_ID:
1000 hdma->XferM1CpltCallback = pCallback;
1001 break;
1003 case HAL_DMA_XFER_M1HALFCPLT_CB_ID:
1004 hdma->XferM1HalfCpltCallback = pCallback;
1005 break;
1007 case HAL_DMA_XFER_ERROR_CB_ID:
1008 hdma->XferErrorCallback = pCallback;
1009 break;
1011 case HAL_DMA_XFER_ABORT_CB_ID:
1012 hdma->XferAbortCallback = pCallback;
1013 break;
1015 default:
1016 break;
1019 else
1021 /* Return error status */
1022 status = HAL_ERROR;
1025 /* Release Lock */
1026 __HAL_UNLOCK(hdma);
1028 return status;
1032 * @brief UnRegister callbacks
1033 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1034 * the configuration information for the specified DMA Stream.
1035 * @param CallbackID: User Callback identifer
1036 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
1037 * @retval HAL status
1039 HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID)
1041 HAL_StatusTypeDef status = HAL_OK;
1043 /* Process locked */
1044 __HAL_LOCK(hdma);
1046 if(HAL_DMA_STATE_READY == hdma->State)
1048 switch (CallbackID)
1050 case HAL_DMA_XFER_CPLT_CB_ID:
1051 hdma->XferCpltCallback = NULL;
1052 break;
1054 case HAL_DMA_XFER_HALFCPLT_CB_ID:
1055 hdma->XferHalfCpltCallback = NULL;
1056 break;
1058 case HAL_DMA_XFER_M1CPLT_CB_ID:
1059 hdma->XferM1CpltCallback = NULL;
1060 break;
1062 case HAL_DMA_XFER_M1HALFCPLT_CB_ID:
1063 hdma->XferM1HalfCpltCallback = NULL;
1064 break;
1066 case HAL_DMA_XFER_ERROR_CB_ID:
1067 hdma->XferErrorCallback = NULL;
1068 break;
1070 case HAL_DMA_XFER_ABORT_CB_ID:
1071 hdma->XferAbortCallback = NULL;
1072 break;
1074 case HAL_DMA_XFER_ALL_CB_ID:
1075 hdma->XferCpltCallback = NULL;
1076 hdma->XferHalfCpltCallback = NULL;
1077 hdma->XferM1CpltCallback = NULL;
1078 hdma->XferM1HalfCpltCallback = NULL;
1079 hdma->XferErrorCallback = NULL;
1080 hdma->XferAbortCallback = NULL;
1081 break;
1083 default:
1084 status = HAL_ERROR;
1085 break;
1088 else
1090 status = HAL_ERROR;
1093 /* Release Lock */
1094 __HAL_UNLOCK(hdma);
1096 return status;
1100 * @}
1103 /** @addtogroup DMA_Exported_Functions_Group3
1105 @verbatim
1106 ===============================================================================
1107 ##### State and Errors functions #####
1108 ===============================================================================
1109 [..]
1110 This subsection provides functions allowing to
1111 (+) Check the DMA state
1112 (+) Get error code
1114 @endverbatim
1115 * @{
1119 * @brief Returns the DMA state.
1120 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1121 * the configuration information for the specified DMA Stream.
1122 * @retval HAL state
1124 HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
1126 return hdma->State;
1130 * @brief Return the DMA error code
1131 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
1132 * the configuration information for the specified DMA Stream.
1133 * @retval DMA Error Code
1135 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
1137 return hdma->ErrorCode;
1141 * @}
1145 * @}
1148 /** @addtogroup DMA_Private_Functions
1149 * @{
1153 * @brief Sets the DMA Transfer parameter.
1154 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1155 * the configuration information for the specified DMA Stream.
1156 * @param SrcAddress: The source memory Buffer address
1157 * @param DstAddress: The destination memory Buffer address
1158 * @param DataLength: The length of data to be transferred from source to destination
1159 * @retval HAL status
1161 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
1163 /* Clear DBM bit */
1164 hdma->Instance->CR &= (uint32_t)(~DMA_SxCR_DBM);
1166 /* Configure DMA Stream data length */
1167 hdma->Instance->NDTR = DataLength;
1169 /* Peripheral to Memory */
1170 if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1172 /* Configure DMA Stream destination address */
1173 hdma->Instance->PAR = DstAddress;
1175 /* Configure DMA Stream source address */
1176 hdma->Instance->M0AR = SrcAddress;
1178 /* Memory to Peripheral */
1179 else
1181 /* Configure DMA Stream source address */
1182 hdma->Instance->PAR = SrcAddress;
1184 /* Configure DMA Stream destination address */
1185 hdma->Instance->M0AR = DstAddress;
1190 * @brief Returns the DMA Stream base address depending on stream number
1191 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1192 * the configuration information for the specified DMA Stream.
1193 * @retval Stream base address
1195 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma)
1197 uint32_t stream_number = (((uint32_t)hdma->Instance & 0xFFU) - 16U) / 24U;
1199 /* lookup table for necessary bitshift of flags within status registers */
1200 static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U};
1201 hdma->StreamIndex = flagBitshiftOffset[stream_number];
1203 if (stream_number > 3U)
1205 /* return pointer to HISR and HIFCR */
1206 hdma->StreamBaseAddress = (((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)) + 4U);
1208 else
1210 /* return pointer to LISR and LIFCR */
1211 hdma->StreamBaseAddress = ((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU));
1214 return hdma->StreamBaseAddress;
1218 * @brief Check compatibility between FIFO threshold level and size of the memory burst
1219 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1220 * the configuration information for the specified DMA Stream.
1221 * @retval HAL status
1223 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma)
1225 HAL_StatusTypeDef status = HAL_OK;
1226 uint32_t tmp = hdma->Init.FIFOThreshold;
1228 /* Memory Data size equal to Byte */
1229 if(hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE)
1231 switch (tmp)
1233 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1234 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1235 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1237 status = HAL_ERROR;
1239 break;
1240 case DMA_FIFO_THRESHOLD_HALFFULL:
1241 if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1243 status = HAL_ERROR;
1245 break;
1246 case DMA_FIFO_THRESHOLD_FULL:
1247 break;
1248 default:
1249 break;
1253 /* Memory Data size equal to Half-Word */
1254 else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1256 switch (tmp)
1258 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1259 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1260 status = HAL_ERROR;
1261 break;
1262 case DMA_FIFO_THRESHOLD_HALFFULL:
1263 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1265 status = HAL_ERROR;
1267 break;
1268 case DMA_FIFO_THRESHOLD_FULL:
1269 if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1271 status = HAL_ERROR;
1273 break;
1274 default:
1275 break;
1279 /* Memory Data size equal to Word */
1280 else
1282 switch (tmp)
1284 case DMA_FIFO_THRESHOLD_1QUARTERFULL:
1285 case DMA_FIFO_THRESHOLD_HALFFULL:
1286 case DMA_FIFO_THRESHOLD_3QUARTERSFULL:
1287 status = HAL_ERROR;
1288 break;
1289 case DMA_FIFO_THRESHOLD_FULL:
1290 if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1)
1292 status = HAL_ERROR;
1294 break;
1295 default:
1296 break;
1300 return status;
1304 * @}
1307 #endif /* HAL_DMA_MODULE_ENABLED */
1309 * @}
1313 * @}
1316 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/