2 ******************************************************************************
3 * @file stm32f7xx_hal_dma.c
4 * @author MCD Application Team
5 * @brief DMA HAL module driver.
7 * This file provides firmware functions to manage the following
8 * functionalities of the Direct Memory Access (DMA) peripheral:
9 * + Initialization and de-initialization functions
10 * + IO operation functions
11 * + Peripheral State and errors functions
13 ==============================================================================
14 ##### How to use this driver #####
15 ==============================================================================
17 (#) Enable and configure the peripheral to be connected to the DMA Stream
18 (except for internal SRAM/FLASH memories: no initialization is
19 necessary) please refer to Reference manual for connection between peripherals
22 (#) For a given Stream, program the required configuration through the following parameters:
23 Transfer Direction, Source and Destination data formats,
24 Circular, Normal or peripheral flow control mode, Stream Priority level,
25 Source and Destination Increment mode, FIFO mode and its Threshold (if needed),
26 Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function.
28 -@- Prior to HAL_DMA_Init() the clock must be enabled for DMA through the following macros:
29 __HAL_RCC_DMA1_CLK_ENABLE() or __HAL_RCC_DMA2_CLK_ENABLE().
31 *** Polling mode IO operation ***
32 =================================
34 (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source
35 address and destination address and the Length of data to be transferred.
36 (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this
37 case a fixed Timeout can be configured by User depending from his application.
38 (+) Use HAL_DMA_Abort() function to abort the current transfer.
40 *** Interrupt mode IO operation ***
41 ===================================
43 (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority()
44 (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ()
45 (+) Select Callbacks functions using HAL_DMA_RegisterCallback()
46 (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of
47 Source address and destination address and the Length of data to be transferred. In this
48 case the DMA interrupt is configured
49 (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine
50 (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can
51 add his own function by customization of function pointer XferCpltCallback and
52 XferErrorCallback (i.e a member of DMA handle structure).
54 (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error
57 (#) Use HAL_DMA_Abort_IT() function to abort the current transfer
59 -@- In Memory-to-Memory transfer mode, Circular mode is not allowed.
61 -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is
62 possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set
63 Half-Word data size for the peripheral to access its data register and set Word data size
64 for the Memory to gain in access time. Each two half words will be packed and written in
65 a single access to a Word in the Memory).
67 -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source
68 and Destination. In this case the Peripheral Data Size will be applied to both Source
71 *** DMA HAL driver macros list ***
72 =============================================
74 Below the list of most used macros in DMA HAL driver.
76 (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream.
77 (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream.
78 (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not.
81 (@) You can refer to the DMA HAL driver header file for more useful macros
84 ******************************************************************************
87 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
88 * All rights reserved.</center></h2>
90 * This software component is licensed by ST under BSD 3-Clause license,
91 * the "License"; You may not use this file except in compliance with the
92 * License. You may obtain a copy of the License at:
93 * opensource.org/licenses/BSD-3-Clause
95 ******************************************************************************
98 /* Includes ------------------------------------------------------------------*/
99 #include "stm32f7xx_hal.h"
101 /** @addtogroup STM32F7xx_HAL_Driver
105 /** @defgroup DMA DMA
106 * @brief DMA HAL module driver
110 #ifdef HAL_DMA_MODULE_ENABLED
112 /* Private types -------------------------------------------------------------*/
115 __IO
uint32_t ISR
; /*!< DMA interrupt status register */
116 __IO
uint32_t Reserved0
;
117 __IO
uint32_t IFCR
; /*!< DMA interrupt flag clear register */
118 } DMA_Base_Registers
;
120 /* Private variables ---------------------------------------------------------*/
121 /* Private constants ---------------------------------------------------------*/
122 /** @addtogroup DMA_Private_Constants
125 #define HAL_TIMEOUT_DMA_ABORT ((uint32_t)5) /* 5 ms */
129 /* Private macros ------------------------------------------------------------*/
130 /* Private functions ---------------------------------------------------------*/
131 /** @addtogroup DMA_Private_Functions
134 static void DMA_SetConfig(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
);
135 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef
*hdma
);
136 static HAL_StatusTypeDef
DMA_CheckFifoParam(DMA_HandleTypeDef
*hdma
);
142 /* Exported functions ---------------------------------------------------------*/
143 /** @addtogroup DMA_Exported_Functions
147 /** @addtogroup DMA_Exported_Functions_Group1
150 ===============================================================================
151 ##### Initialization and de-initialization functions #####
152 ===============================================================================
154 This section provides functions allowing to initialize the DMA Stream source
155 and destination addresses, incrementation and data sizes, transfer direction,
156 circular/normal mode selection, memory-to-memory mode selection and Stream priority value.
158 The HAL_DMA_Init() function follows the DMA configuration procedures as described in
166 * @brief Initialize the DMA according to the specified
167 * parameters in the DMA_InitTypeDef and create the associated handle.
168 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
169 * the configuration information for the specified DMA Stream.
172 HAL_StatusTypeDef
HAL_DMA_Init(DMA_HandleTypeDef
*hdma
)
175 uint32_t tickstart
= HAL_GetTick();
176 DMA_Base_Registers
*regs
;
178 /* Check the DMA peripheral state */
184 /* Check the parameters */
185 assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma
->Instance
));
186 assert_param(IS_DMA_CHANNEL(hdma
->Init
.Channel
));
187 assert_param(IS_DMA_DIRECTION(hdma
->Init
.Direction
));
188 assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma
->Init
.PeriphInc
));
189 assert_param(IS_DMA_MEMORY_INC_STATE(hdma
->Init
.MemInc
));
190 assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma
->Init
.PeriphDataAlignment
));
191 assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma
->Init
.MemDataAlignment
));
192 assert_param(IS_DMA_MODE(hdma
->Init
.Mode
));
193 assert_param(IS_DMA_PRIORITY(hdma
->Init
.Priority
));
194 assert_param(IS_DMA_FIFO_MODE_STATE(hdma
->Init
.FIFOMode
));
195 /* Check the memory burst, peripheral burst and FIFO threshold parameters only
196 when FIFO mode is enabled */
197 if(hdma
->Init
.FIFOMode
!= DMA_FIFOMODE_DISABLE
)
199 assert_param(IS_DMA_FIFO_THRESHOLD(hdma
->Init
.FIFOThreshold
));
200 assert_param(IS_DMA_MEMORY_BURST(hdma
->Init
.MemBurst
));
201 assert_param(IS_DMA_PERIPHERAL_BURST(hdma
->Init
.PeriphBurst
));
204 /* Allocate lock resource */
207 /* Change DMA peripheral state */
208 hdma
->State
= HAL_DMA_STATE_BUSY
;
210 /* Disable the peripheral */
211 __HAL_DMA_DISABLE(hdma
);
213 /* Check if the DMA Stream is effectively disabled */
214 while((hdma
->Instance
->CR
& DMA_SxCR_EN
) != RESET
)
216 /* Check for the Timeout */
217 if((HAL_GetTick() - tickstart
) > HAL_TIMEOUT_DMA_ABORT
)
219 /* Update error code */
220 hdma
->ErrorCode
= HAL_DMA_ERROR_TIMEOUT
;
222 /* Change the DMA state */
223 hdma
->State
= HAL_DMA_STATE_TIMEOUT
;
229 /* Get the CR register value */
230 tmp
= hdma
->Instance
->CR
;
232 /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */
233 tmp
&= ((uint32_t)~(DMA_SxCR_CHSEL
| DMA_SxCR_MBURST
| DMA_SxCR_PBURST
| \
234 DMA_SxCR_PL
| DMA_SxCR_MSIZE
| DMA_SxCR_PSIZE
| \
235 DMA_SxCR_MINC
| DMA_SxCR_PINC
| DMA_SxCR_CIRC
| \
236 DMA_SxCR_DIR
| DMA_SxCR_CT
| DMA_SxCR_DBM
));
238 /* Prepare the DMA Stream configuration */
239 tmp
|= hdma
->Init
.Channel
| hdma
->Init
.Direction
|
240 hdma
->Init
.PeriphInc
| hdma
->Init
.MemInc
|
241 hdma
->Init
.PeriphDataAlignment
| hdma
->Init
.MemDataAlignment
|
242 hdma
->Init
.Mode
| hdma
->Init
.Priority
;
244 /* the Memory burst and peripheral burst are not used when the FIFO is disabled */
245 if(hdma
->Init
.FIFOMode
== DMA_FIFOMODE_ENABLE
)
247 /* Get memory burst and peripheral burst */
248 tmp
|= hdma
->Init
.MemBurst
| hdma
->Init
.PeriphBurst
;
251 /* Write to DMA Stream CR register */
252 hdma
->Instance
->CR
= tmp
;
254 /* Get the FCR register value */
255 tmp
= hdma
->Instance
->FCR
;
257 /* Clear Direct mode and FIFO threshold bits */
258 tmp
&= (uint32_t)~(DMA_SxFCR_DMDIS
| DMA_SxFCR_FTH
);
260 /* Prepare the DMA Stream FIFO configuration */
261 tmp
|= hdma
->Init
.FIFOMode
;
263 /* The FIFO threshold is not used when the FIFO mode is disabled */
264 if(hdma
->Init
.FIFOMode
== DMA_FIFOMODE_ENABLE
)
266 /* Get the FIFO threshold */
267 tmp
|= hdma
->Init
.FIFOThreshold
;
269 /* Check compatibility between FIFO threshold level and size of the memory burst */
270 /* for INCR4, INCR8, INCR16 bursts */
271 if (hdma
->Init
.MemBurst
!= DMA_MBURST_SINGLE
)
273 if (DMA_CheckFifoParam(hdma
) != HAL_OK
)
275 /* Update error code */
276 hdma
->ErrorCode
= HAL_DMA_ERROR_PARAM
;
278 /* Change the DMA state */
279 hdma
->State
= HAL_DMA_STATE_READY
;
286 /* Write to DMA Stream FCR */
287 hdma
->Instance
->FCR
= tmp
;
289 /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
290 DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
291 regs
= (DMA_Base_Registers
*)DMA_CalcBaseAndBitshift(hdma
);
293 /* Clear all interrupt flags */
294 regs
->IFCR
= 0x3FU
<< hdma
->StreamIndex
;
296 /* Initialize the error code */
297 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
299 /* Initialize the DMA state */
300 hdma
->State
= HAL_DMA_STATE_READY
;
306 * @brief DeInitializes the DMA peripheral
307 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
308 * the configuration information for the specified DMA Stream.
311 HAL_StatusTypeDef
HAL_DMA_DeInit(DMA_HandleTypeDef
*hdma
)
313 DMA_Base_Registers
*regs
;
315 /* Check the DMA peripheral state */
321 /* Check the DMA peripheral state */
322 if(hdma
->State
== HAL_DMA_STATE_BUSY
)
324 /* Return error status */
328 /* Check the parameters */
329 assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma
->Instance
));
331 /* Disable the selected DMA Streamx */
332 __HAL_DMA_DISABLE(hdma
);
334 /* Reset DMA Streamx control register */
335 hdma
->Instance
->CR
= 0U;
337 /* Reset DMA Streamx number of data to transfer register */
338 hdma
->Instance
->NDTR
= 0U;
340 /* Reset DMA Streamx peripheral address register */
341 hdma
->Instance
->PAR
= 0U;
343 /* Reset DMA Streamx memory 0 address register */
344 hdma
->Instance
->M0AR
= 0U;
346 /* Reset DMA Streamx memory 1 address register */
347 hdma
->Instance
->M1AR
= 0U;
349 /* Reset DMA Streamx FIFO control register */
350 hdma
->Instance
->FCR
= (uint32_t)0x00000021U
;
352 /* Get DMA steam Base Address */
353 regs
= (DMA_Base_Registers
*)DMA_CalcBaseAndBitshift(hdma
);
355 /* Clear all interrupt flags at correct offset within the register */
356 regs
->IFCR
= 0x3FU
<< hdma
->StreamIndex
;
358 /* Clean all callbacks */
359 hdma
->XferCpltCallback
= NULL
;
360 hdma
->XferHalfCpltCallback
= NULL
;
361 hdma
->XferM1CpltCallback
= NULL
;
362 hdma
->XferM1HalfCpltCallback
= NULL
;
363 hdma
->XferErrorCallback
= NULL
;
364 hdma
->XferAbortCallback
= NULL
;
366 /* Reset the error code */
367 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
369 /* Reset the DMA state */
370 hdma
->State
= HAL_DMA_STATE_RESET
;
382 /** @addtogroup DMA_Exported_Functions_Group2
385 ===============================================================================
386 ##### IO operation functions #####
387 ===============================================================================
388 [..] This section provides functions allowing to:
389 (+) Configure the source, destination address and data length and Start DMA transfer
390 (+) Configure the source, destination address and data length and
391 Start DMA transfer with interrupt
392 (+) Abort DMA transfer
393 (+) Poll for transfer complete
394 (+) Handle DMA interrupt request
401 * @brief Starts the DMA Transfer.
402 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
403 * the configuration information for the specified DMA Stream.
404 * @param SrcAddress The source memory Buffer address
405 * @param DstAddress The destination memory Buffer address
406 * @param DataLength The length of data to be transferred from source to destination
409 HAL_StatusTypeDef
HAL_DMA_Start(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
)
411 HAL_StatusTypeDef status
= HAL_OK
;
413 /* Check the parameters */
414 assert_param(IS_DMA_BUFFER_SIZE(DataLength
));
419 if(HAL_DMA_STATE_READY
== hdma
->State
)
421 /* Change DMA peripheral state */
422 hdma
->State
= HAL_DMA_STATE_BUSY
;
424 /* Initialize the error code */
425 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
427 /* Configure the source, destination address and the data length */
428 DMA_SetConfig(hdma
, SrcAddress
, DstAddress
, DataLength
);
430 /* Enable the Peripheral */
431 __HAL_DMA_ENABLE(hdma
);
435 /* Process unlocked */
438 /* Return error status */
445 * @brief Start the DMA Transfer with interrupt enabled.
446 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
447 * the configuration information for the specified DMA Stream.
448 * @param SrcAddress The source memory Buffer address
449 * @param DstAddress The destination memory Buffer address
450 * @param DataLength The length of data to be transferred from source to destination
453 HAL_StatusTypeDef
HAL_DMA_Start_IT(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
)
455 HAL_StatusTypeDef status
= HAL_OK
;
457 /* calculate DMA base and stream number */
458 DMA_Base_Registers
*regs
= (DMA_Base_Registers
*)hdma
->StreamBaseAddress
;
460 /* Check the parameters */
461 assert_param(IS_DMA_BUFFER_SIZE(DataLength
));
466 if(HAL_DMA_STATE_READY
== hdma
->State
)
468 /* Change DMA peripheral state */
469 hdma
->State
= HAL_DMA_STATE_BUSY
;
471 /* Initialize the error code */
472 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
474 /* Configure the source, destination address and the data length */
475 DMA_SetConfig(hdma
, SrcAddress
, DstAddress
, DataLength
);
477 /* Clear all interrupt flags at correct offset within the register */
478 regs
->IFCR
= 0x3FU
<< hdma
->StreamIndex
;
480 /* Enable Common interrupts*/
481 hdma
->Instance
->CR
|= DMA_IT_TC
| DMA_IT_TE
| DMA_IT_DME
;
482 hdma
->Instance
->FCR
|= DMA_IT_FE
;
484 if(hdma
->XferHalfCpltCallback
!= NULL
)
486 hdma
->Instance
->CR
|= DMA_IT_HT
;
489 /* Enable the Peripheral */
490 __HAL_DMA_ENABLE(hdma
);
494 /* Process unlocked */
497 /* Return error status */
505 * @brief Aborts the DMA Transfer.
506 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
507 * the configuration information for the specified DMA Stream.
509 * @note After disabling a DMA Stream, a check for wait until the DMA Stream is
510 * effectively disabled is added. If a Stream is disabled
511 * while a data transfer is ongoing, the current data will be transferred
512 * and the Stream will be effectively disabled only after the transfer of
513 * this single data is finished.
516 HAL_StatusTypeDef
HAL_DMA_Abort(DMA_HandleTypeDef
*hdma
)
518 /* calculate DMA base and stream number */
519 DMA_Base_Registers
*regs
= (DMA_Base_Registers
*)hdma
->StreamBaseAddress
;
521 uint32_t tickstart
= HAL_GetTick();
523 if(hdma
->State
!= HAL_DMA_STATE_BUSY
)
525 hdma
->ErrorCode
= HAL_DMA_ERROR_NO_XFER
;
527 /* Process Unlocked */
534 /* Disable all the transfer interrupts */
535 hdma
->Instance
->CR
&= ~(DMA_IT_TC
| DMA_IT_TE
| DMA_IT_DME
);
536 hdma
->Instance
->FCR
&= ~(DMA_IT_FE
);
538 if((hdma
->XferHalfCpltCallback
!= NULL
) || (hdma
->XferM1HalfCpltCallback
!= NULL
))
540 hdma
->Instance
->CR
&= ~(DMA_IT_HT
);
543 /* Disable the stream */
544 __HAL_DMA_DISABLE(hdma
);
546 /* Check if the DMA Stream is effectively disabled */
547 while((hdma
->Instance
->CR
& DMA_SxCR_EN
) != RESET
)
549 /* Check for the Timeout */
550 if((HAL_GetTick() - tickstart
) > HAL_TIMEOUT_DMA_ABORT
)
552 /* Update error code */
553 hdma
->ErrorCode
= HAL_DMA_ERROR_TIMEOUT
;
555 /* Process Unlocked */
558 /* Change the DMA state */
559 hdma
->State
= HAL_DMA_STATE_TIMEOUT
;
565 /* Clear all interrupt flags at correct offset within the register */
566 regs
->IFCR
= 0x3FU
<< hdma
->StreamIndex
;
568 /* Process Unlocked */
571 /* Change the DMA state*/
572 hdma
->State
= HAL_DMA_STATE_READY
;
578 * @brief Aborts the DMA Transfer in Interrupt mode.
579 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
580 * the configuration information for the specified DMA Stream.
583 HAL_StatusTypeDef
HAL_DMA_Abort_IT(DMA_HandleTypeDef
*hdma
)
585 if(hdma
->State
!= HAL_DMA_STATE_BUSY
)
587 hdma
->ErrorCode
= HAL_DMA_ERROR_NO_XFER
;
592 /* Set Abort State */
593 hdma
->State
= HAL_DMA_STATE_ABORT
;
595 /* Disable the stream */
596 __HAL_DMA_DISABLE(hdma
);
603 * @brief Polling for transfer complete.
604 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
605 * the configuration information for the specified DMA Stream.
606 * @param CompleteLevel Specifies the DMA level complete.
607 * @note The polling mode is kept in this version for legacy. it is recommanded to use the IT model instead.
608 * This model could be used for debug purpose.
609 * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode).
610 * @param Timeout Timeout duration.
613 HAL_StatusTypeDef
HAL_DMA_PollForTransfer(DMA_HandleTypeDef
*hdma
, HAL_DMA_LevelCompleteTypeDef CompleteLevel
, uint32_t Timeout
)
615 HAL_StatusTypeDef status
= HAL_OK
;
616 uint32_t mask_cpltlevel
;
617 uint32_t tickstart
= HAL_GetTick();
620 /* calculate DMA base and stream number */
621 DMA_Base_Registers
*regs
;
623 if(HAL_DMA_STATE_BUSY
!= hdma
->State
)
625 /* No transfer ongoing */
626 hdma
->ErrorCode
= HAL_DMA_ERROR_NO_XFER
;
631 /* Polling mode not supported in circular mode and double buffering mode */
632 if ((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) != RESET
)
634 hdma
->ErrorCode
= HAL_DMA_ERROR_NOT_SUPPORTED
;
638 /* Get the level transfer complete flag */
639 if(CompleteLevel
== HAL_DMA_FULL_TRANSFER
)
641 /* Transfer Complete flag */
642 mask_cpltlevel
= DMA_FLAG_TCIF0_4
<< hdma
->StreamIndex
;
646 /* Half Transfer Complete flag */
647 mask_cpltlevel
= DMA_FLAG_HTIF0_4
<< hdma
->StreamIndex
;
650 regs
= (DMA_Base_Registers
*)hdma
->StreamBaseAddress
;
653 while(((tmpisr
& mask_cpltlevel
) == RESET
) && ((hdma
->ErrorCode
& HAL_DMA_ERROR_TE
) == RESET
))
655 /* Check for the Timeout (Not applicable in circular mode)*/
656 if(Timeout
!= HAL_MAX_DELAY
)
658 if((Timeout
== 0)||((HAL_GetTick() - tickstart
) > Timeout
))
660 /* Update error code */
661 hdma
->ErrorCode
= HAL_DMA_ERROR_TIMEOUT
;
663 /* Process Unlocked */
666 /* Change the DMA state */
667 hdma
->State
= HAL_DMA_STATE_READY
;
673 /* Get the ISR register value */
676 if((tmpisr
& (DMA_FLAG_TEIF0_4
<< hdma
->StreamIndex
)) != RESET
)
678 /* Update error code */
679 hdma
->ErrorCode
|= HAL_DMA_ERROR_TE
;
681 /* Clear the transfer error flag */
682 regs
->IFCR
= DMA_FLAG_TEIF0_4
<< hdma
->StreamIndex
;
685 if((tmpisr
& (DMA_FLAG_FEIF0_4
<< hdma
->StreamIndex
)) != RESET
)
687 /* Update error code */
688 hdma
->ErrorCode
|= HAL_DMA_ERROR_FE
;
690 /* Clear the FIFO error flag */
691 regs
->IFCR
= DMA_FLAG_FEIF0_4
<< hdma
->StreamIndex
;
694 if((tmpisr
& (DMA_FLAG_DMEIF0_4
<< hdma
->StreamIndex
)) != RESET
)
696 /* Update error code */
697 hdma
->ErrorCode
|= HAL_DMA_ERROR_DME
;
699 /* Clear the Direct Mode error flag */
700 regs
->IFCR
= DMA_FLAG_DMEIF0_4
<< hdma
->StreamIndex
;
704 if(hdma
->ErrorCode
!= HAL_DMA_ERROR_NONE
)
706 if((hdma
->ErrorCode
& HAL_DMA_ERROR_TE
) != RESET
)
710 /* Clear the half transfer and transfer complete flags */
711 regs
->IFCR
= (DMA_FLAG_HTIF0_4
| DMA_FLAG_TCIF0_4
) << hdma
->StreamIndex
;
713 /* Process Unlocked */
716 /* Change the DMA state */
717 hdma
->State
= HAL_DMA_STATE_READY
;
723 /* Get the level transfer complete flag */
724 if(CompleteLevel
== HAL_DMA_FULL_TRANSFER
)
726 /* Clear the half transfer and transfer complete flags */
727 regs
->IFCR
= (DMA_FLAG_HTIF0_4
| DMA_FLAG_TCIF0_4
) << hdma
->StreamIndex
;
729 /* Process Unlocked */
732 hdma
->State
= HAL_DMA_STATE_READY
;
736 /* Clear the half transfer flag */
737 regs
->IFCR
= (DMA_FLAG_HTIF0_4
) << hdma
->StreamIndex
;
744 * @brief Handles DMA interrupt request.
745 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
746 * the configuration information for the specified DMA Stream.
749 void HAL_DMA_IRQHandler(DMA_HandleTypeDef
*hdma
)
752 __IO
uint32_t count
= 0;
753 uint32_t timeout
= SystemCoreClock
/ 9600;
755 /* calculate DMA base and stream number */
756 DMA_Base_Registers
*regs
= (DMA_Base_Registers
*)hdma
->StreamBaseAddress
;
760 /* Transfer Error Interrupt management ***************************************/
761 if ((tmpisr
& (DMA_FLAG_TEIF0_4
<< hdma
->StreamIndex
)) != RESET
)
763 if(__HAL_DMA_GET_IT_SOURCE(hdma
, DMA_IT_TE
) != RESET
)
765 /* Disable the transfer error interrupt */
766 hdma
->Instance
->CR
&= ~(DMA_IT_TE
);
768 /* Clear the transfer error flag */
769 regs
->IFCR
= DMA_FLAG_TEIF0_4
<< hdma
->StreamIndex
;
771 /* Update error code */
772 hdma
->ErrorCode
|= HAL_DMA_ERROR_TE
;
775 /* FIFO Error Interrupt management ******************************************/
776 if ((tmpisr
& (DMA_FLAG_FEIF0_4
<< hdma
->StreamIndex
)) != RESET
)
778 if(__HAL_DMA_GET_IT_SOURCE(hdma
, DMA_IT_FE
) != RESET
)
780 /* Clear the FIFO error flag */
781 regs
->IFCR
= DMA_FLAG_FEIF0_4
<< hdma
->StreamIndex
;
783 /* Update error code */
784 hdma
->ErrorCode
|= HAL_DMA_ERROR_FE
;
787 /* Direct Mode Error Interrupt management ***********************************/
788 if ((tmpisr
& (DMA_FLAG_DMEIF0_4
<< hdma
->StreamIndex
)) != RESET
)
790 if(__HAL_DMA_GET_IT_SOURCE(hdma
, DMA_IT_DME
) != RESET
)
792 /* Clear the direct mode error flag */
793 regs
->IFCR
= DMA_FLAG_DMEIF0_4
<< hdma
->StreamIndex
;
795 /* Update error code */
796 hdma
->ErrorCode
|= HAL_DMA_ERROR_DME
;
799 /* Half Transfer Complete Interrupt management ******************************/
800 if ((tmpisr
& (DMA_FLAG_HTIF0_4
<< hdma
->StreamIndex
)) != RESET
)
802 if(__HAL_DMA_GET_IT_SOURCE(hdma
, DMA_IT_HT
) != RESET
)
804 /* Clear the half transfer complete flag */
805 regs
->IFCR
= DMA_FLAG_HTIF0_4
<< hdma
->StreamIndex
;
807 /* Multi_Buffering mode enabled */
808 if(((hdma
->Instance
->CR
) & (uint32_t)(DMA_SxCR_DBM
)) != RESET
)
810 /* Current memory buffer used is Memory 0 */
811 if((hdma
->Instance
->CR
& DMA_SxCR_CT
) == RESET
)
813 if(hdma
->XferHalfCpltCallback
!= NULL
)
815 /* Half transfer callback */
816 hdma
->XferHalfCpltCallback(hdma
);
819 /* Current memory buffer used is Memory 1 */
822 if(hdma
->XferM1HalfCpltCallback
!= NULL
)
824 /* Half transfer callback */
825 hdma
->XferM1HalfCpltCallback(hdma
);
831 /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
832 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == RESET
)
834 /* Disable the half transfer interrupt */
835 hdma
->Instance
->CR
&= ~(DMA_IT_HT
);
838 if(hdma
->XferHalfCpltCallback
!= NULL
)
840 /* Half transfer callback */
841 hdma
->XferHalfCpltCallback(hdma
);
846 /* Transfer Complete Interrupt management ***********************************/
847 if ((tmpisr
& (DMA_FLAG_TCIF0_4
<< hdma
->StreamIndex
)) != RESET
)
849 if(__HAL_DMA_GET_IT_SOURCE(hdma
, DMA_IT_TC
) != RESET
)
851 /* Clear the transfer complete flag */
852 regs
->IFCR
= DMA_FLAG_TCIF0_4
<< hdma
->StreamIndex
;
854 if(HAL_DMA_STATE_ABORT
== hdma
->State
)
856 /* Disable all the transfer interrupts */
857 hdma
->Instance
->CR
&= ~(DMA_IT_TC
| DMA_IT_TE
| DMA_IT_DME
);
858 hdma
->Instance
->FCR
&= ~(DMA_IT_FE
);
860 if((hdma
->XferHalfCpltCallback
!= NULL
) || (hdma
->XferM1HalfCpltCallback
!= NULL
))
862 hdma
->Instance
->CR
&= ~(DMA_IT_HT
);
865 /* Clear all interrupt flags at correct offset within the register */
866 regs
->IFCR
= 0x3FU
<< hdma
->StreamIndex
;
868 /* Process Unlocked */
871 /* Change the DMA state */
872 hdma
->State
= HAL_DMA_STATE_READY
;
874 if(hdma
->XferAbortCallback
!= NULL
)
876 hdma
->XferAbortCallback(hdma
);
881 if(((hdma
->Instance
->CR
) & (uint32_t)(DMA_SxCR_DBM
)) != RESET
)
883 /* Current memory buffer used is Memory 0 */
884 if((hdma
->Instance
->CR
& DMA_SxCR_CT
) == RESET
)
886 if(hdma
->XferM1CpltCallback
!= NULL
)
888 /* Transfer complete Callback for memory1 */
889 hdma
->XferM1CpltCallback(hdma
);
892 /* Current memory buffer used is Memory 1 */
895 if(hdma
->XferCpltCallback
!= NULL
)
897 /* Transfer complete Callback for memory0 */
898 hdma
->XferCpltCallback(hdma
);
902 /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */
905 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == RESET
)
907 /* Disable the transfer complete interrupt */
908 hdma
->Instance
->CR
&= ~(DMA_IT_TC
);
910 /* Process Unlocked */
913 /* Change the DMA state */
914 hdma
->State
= HAL_DMA_STATE_READY
;
917 if(hdma
->XferCpltCallback
!= NULL
)
919 /* Transfer complete callback */
920 hdma
->XferCpltCallback(hdma
);
926 /* manage error case */
927 if(hdma
->ErrorCode
!= HAL_DMA_ERROR_NONE
)
929 if((hdma
->ErrorCode
& HAL_DMA_ERROR_TE
) != RESET
)
931 hdma
->State
= HAL_DMA_STATE_ABORT
;
933 /* Disable the stream */
934 __HAL_DMA_DISABLE(hdma
);
938 if (++count
> timeout
)
943 while((hdma
->Instance
->CR
& DMA_SxCR_EN
) != RESET
);
945 /* Process Unlocked */
948 /* Change the DMA state */
949 hdma
->State
= HAL_DMA_STATE_READY
;
952 if(hdma
->XferErrorCallback
!= NULL
)
954 /* Transfer error callback */
955 hdma
->XferErrorCallback(hdma
);
961 * @brief Register callbacks
962 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
963 * the configuration information for the specified DMA Stream.
964 * @param CallbackID User Callback identifer
965 * a DMA_HandleTypeDef structure as parameter.
966 * @param pCallback pointer to private callbacsk function which has pointer to
967 * a DMA_HandleTypeDef structure as parameter.
970 HAL_StatusTypeDef
HAL_DMA_RegisterCallback(DMA_HandleTypeDef
*hdma
, HAL_DMA_CallbackIDTypeDef CallbackID
, void (* pCallback
)(DMA_HandleTypeDef
*_hdma
))
973 HAL_StatusTypeDef status
= HAL_OK
;
978 if(HAL_DMA_STATE_READY
== hdma
->State
)
982 case HAL_DMA_XFER_CPLT_CB_ID
:
983 hdma
->XferCpltCallback
= pCallback
;
986 case HAL_DMA_XFER_HALFCPLT_CB_ID
:
987 hdma
->XferHalfCpltCallback
= pCallback
;
990 case HAL_DMA_XFER_M1CPLT_CB_ID
:
991 hdma
->XferM1CpltCallback
= pCallback
;
994 case HAL_DMA_XFER_M1HALFCPLT_CB_ID
:
995 hdma
->XferM1HalfCpltCallback
= pCallback
;
998 case HAL_DMA_XFER_ERROR_CB_ID
:
999 hdma
->XferErrorCallback
= pCallback
;
1002 case HAL_DMA_XFER_ABORT_CB_ID
:
1003 hdma
->XferAbortCallback
= pCallback
;
1012 /* Return error status */
1023 * @brief UnRegister callbacks
1024 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1025 * the configuration information for the specified DMA Stream.
1026 * @param CallbackID User Callback identifer
1027 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
1028 * @retval HAL status
1030 HAL_StatusTypeDef
HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef
*hdma
, HAL_DMA_CallbackIDTypeDef CallbackID
)
1032 HAL_StatusTypeDef status
= HAL_OK
;
1034 /* Process locked */
1037 if(HAL_DMA_STATE_READY
== hdma
->State
)
1041 case HAL_DMA_XFER_CPLT_CB_ID
:
1042 hdma
->XferCpltCallback
= NULL
;
1045 case HAL_DMA_XFER_HALFCPLT_CB_ID
:
1046 hdma
->XferHalfCpltCallback
= NULL
;
1049 case HAL_DMA_XFER_M1CPLT_CB_ID
:
1050 hdma
->XferM1CpltCallback
= NULL
;
1053 case HAL_DMA_XFER_M1HALFCPLT_CB_ID
:
1054 hdma
->XferM1HalfCpltCallback
= NULL
;
1057 case HAL_DMA_XFER_ERROR_CB_ID
:
1058 hdma
->XferErrorCallback
= NULL
;
1061 case HAL_DMA_XFER_ABORT_CB_ID
:
1062 hdma
->XferAbortCallback
= NULL
;
1065 case HAL_DMA_XFER_ALL_CB_ID
:
1066 hdma
->XferCpltCallback
= NULL
;
1067 hdma
->XferHalfCpltCallback
= NULL
;
1068 hdma
->XferM1CpltCallback
= NULL
;
1069 hdma
->XferM1HalfCpltCallback
= NULL
;
1070 hdma
->XferErrorCallback
= NULL
;
1071 hdma
->XferAbortCallback
= NULL
;
1094 /** @addtogroup DMA_Exported_Functions_Group3
1097 ===============================================================================
1098 ##### State and Errors functions #####
1099 ===============================================================================
1101 This subsection provides functions allowing to
1102 (+) Check the DMA state
1110 * @brief Returns the DMA state.
1111 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1112 * the configuration information for the specified DMA Stream.
1115 HAL_DMA_StateTypeDef
HAL_DMA_GetState(DMA_HandleTypeDef
*hdma
)
1121 * @brief Return the DMA error code
1122 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1123 * the configuration information for the specified DMA Stream.
1124 * @retval DMA Error Code
1126 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef
*hdma
)
1128 return hdma
->ErrorCode
;
1139 /** @addtogroup DMA_Private_Functions
1144 * @brief Sets the DMA Transfer parameter.
1145 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1146 * the configuration information for the specified DMA Stream.
1147 * @param SrcAddress The source memory Buffer address
1148 * @param DstAddress The destination memory Buffer address
1149 * @param DataLength The length of data to be transferred from source to destination
1150 * @retval HAL status
1152 static void DMA_SetConfig(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
)
1155 hdma
->Instance
->CR
&= (uint32_t)(~DMA_SxCR_DBM
);
1157 /* Configure DMA Stream data length */
1158 hdma
->Instance
->NDTR
= DataLength
;
1160 /* Memory to Peripheral */
1161 if((hdma
->Init
.Direction
) == DMA_MEMORY_TO_PERIPH
)
1163 /* Configure DMA Stream destination address */
1164 hdma
->Instance
->PAR
= DstAddress
;
1166 /* Configure DMA Stream source address */
1167 hdma
->Instance
->M0AR
= SrcAddress
;
1169 /* Peripheral to Memory */
1172 /* Configure DMA Stream source address */
1173 hdma
->Instance
->PAR
= SrcAddress
;
1175 /* Configure DMA Stream destination address */
1176 hdma
->Instance
->M0AR
= DstAddress
;
1181 * @brief Returns the DMA Stream base address depending on stream number
1182 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1183 * the configuration information for the specified DMA Stream.
1184 * @retval Stream base address
1186 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef
*hdma
)
1188 uint32_t stream_number
= (((uint32_t)hdma
->Instance
& 0xFFU
) - 16U) / 24U;
1190 /* lookup table for necessary bitshift of flags within status registers */
1191 static const uint8_t flagBitshiftOffset
[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U};
1192 hdma
->StreamIndex
= flagBitshiftOffset
[stream_number
];
1194 if (stream_number
> 3U)
1196 /* return pointer to HISR and HIFCR */
1197 hdma
->StreamBaseAddress
= (((uint32_t)hdma
->Instance
& (uint32_t)(~0x3FFU
)) + 4U);
1201 /* return pointer to LISR and LIFCR */
1202 hdma
->StreamBaseAddress
= ((uint32_t)hdma
->Instance
& (uint32_t)(~0x3FFU
));
1205 return hdma
->StreamBaseAddress
;
1209 * @brief Check compatibility between FIFO threshold level and size of the memory burst
1210 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
1211 * the configuration information for the specified DMA Stream.
1212 * @retval HAL status
1214 static HAL_StatusTypeDef
DMA_CheckFifoParam(DMA_HandleTypeDef
*hdma
)
1216 HAL_StatusTypeDef status
= HAL_OK
;
1217 uint32_t tmp
= hdma
->Init
.FIFOThreshold
;
1219 /* Memory Data size equal to Byte */
1220 if(hdma
->Init
.MemDataAlignment
== DMA_MDATAALIGN_BYTE
)
1224 case DMA_FIFO_THRESHOLD_1QUARTERFULL
:
1225 case DMA_FIFO_THRESHOLD_3QUARTERSFULL
:
1226 if ((hdma
->Init
.MemBurst
& DMA_SxCR_MBURST_1
) == DMA_SxCR_MBURST_1
)
1231 case DMA_FIFO_THRESHOLD_HALFFULL
:
1232 if (hdma
->Init
.MemBurst
== DMA_MBURST_INC16
)
1237 case DMA_FIFO_THRESHOLD_FULL
:
1244 /* Memory Data size equal to Half-Word */
1245 else if (hdma
->Init
.MemDataAlignment
== DMA_MDATAALIGN_HALFWORD
)
1249 case DMA_FIFO_THRESHOLD_1QUARTERFULL
:
1250 case DMA_FIFO_THRESHOLD_3QUARTERSFULL
:
1253 case DMA_FIFO_THRESHOLD_HALFFULL
:
1254 if ((hdma
->Init
.MemBurst
& DMA_SxCR_MBURST_1
) == DMA_SxCR_MBURST_1
)
1259 case DMA_FIFO_THRESHOLD_FULL
:
1260 if (hdma
->Init
.MemBurst
== DMA_MBURST_INC16
)
1270 /* Memory Data size equal to Word */
1275 case DMA_FIFO_THRESHOLD_1QUARTERFULL
:
1276 case DMA_FIFO_THRESHOLD_HALFFULL
:
1277 case DMA_FIFO_THRESHOLD_3QUARTERSFULL
:
1280 case DMA_FIFO_THRESHOLD_FULL
:
1281 if ((hdma
->Init
.MemBurst
& DMA_SxCR_MBURST_1
) == DMA_SxCR_MBURST_1
)
1298 #endif /* HAL_DMA_MODULE_ENABLED */
1307 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/