2 ******************************************************************************
3 * @file stm32f3xx_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 Channel
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 Channel, program the required configuration through the following parameters:
23 Transfer Direction, Source and Destination data formats,
24 Circular or Normal mode, Channel Priority level, Source and Destination Increment mode,
25 using HAL_DMA_Init() function.
27 (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error
30 (#) Use HAL_DMA_Abort() function to abort the current transfer
32 -@- In Memory-to-Memory transfer mode, Circular mode is not allowed.
33 *** Polling mode IO operation ***
34 =================================
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.
41 *** Interrupt mode IO operation ***
42 ===================================
44 (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority()
45 (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ()
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.
48 In this case the DMA interrupt is configured
49 (+) Use HAL_DMA_Channel_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 *** DMA HAL driver macros list ***
55 =============================================
57 Below the list of most used macros in DMA HAL driver.
60 (@) You can refer to the DMA HAL driver header file for more useful macros
63 ******************************************************************************
66 * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
68 * Redistribution and use in source and binary forms, with or without modification,
69 * are permitted provided that the following conditions are met:
70 * 1. Redistributions of source code must retain the above copyright notice,
71 * this list of conditions and the following disclaimer.
72 * 2. Redistributions in binary form must reproduce the above copyright notice,
73 * this list of conditions and the following disclaimer in the documentation
74 * and/or other materials provided with the distribution.
75 * 3. Neither the name of STMicroelectronics nor the names of its contributors
76 * may be used to endorse or promote products derived from this software
77 * without specific prior written permission.
79 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
80 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
81 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
82 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
83 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
84 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
85 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
86 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
87 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
88 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
90 ******************************************************************************
93 /* Includes ------------------------------------------------------------------*/
94 #include "stm32f3xx_hal.h"
96 /** @addtogroup STM32F3xx_HAL_Driver
100 /** @defgroup DMA DMA
101 * @brief DMA HAL module driver
105 #ifdef HAL_DMA_MODULE_ENABLED
107 /* Private typedef -----------------------------------------------------------*/
108 /* Private define ------------------------------------------------------------*/
109 /* Private macro -------------------------------------------------------------*/
110 /* Private variables ---------------------------------------------------------*/
111 /* Private function prototypes -----------------------------------------------*/
112 /** @defgroup DMA_Private_Functions DMA Private Functions
115 static void DMA_SetConfig(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
);
116 static void DMA_CalcBaseAndBitshift(DMA_HandleTypeDef
*hdma
);
121 /* Exported functions ---------------------------------------------------------*/
123 /** @defgroup DMA_Exported_Functions DMA Exported Functions
127 /** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions
128 * @brief Initialization and de-initialization functions
131 ===============================================================================
132 ##### Initialization and de-initialization functions #####
133 ===============================================================================
135 This section provides functions allowing to initialize the DMA Channel source
136 and destination addresses, incrementation and data sizes, transfer direction,
137 circular/normal mode selection, memory-to-memory mode selection and Channel priority value.
139 The HAL_DMA_Init() function follows the DMA configuration procedures as described in
147 * @brief Initialize the DMA according to the specified
148 * parameters in the DMA_InitTypeDef and initialize the associated handle.
149 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
150 * the configuration information for the specified DMA Channel.
153 HAL_StatusTypeDef
HAL_DMA_Init(DMA_HandleTypeDef
*hdma
)
157 /* Check the DMA handle allocation */
163 /* Check the parameters */
164 assert_param(IS_DMA_ALL_INSTANCE(hdma
->Instance
));
165 assert_param(IS_DMA_DIRECTION(hdma
->Init
.Direction
));
166 assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma
->Init
.PeriphInc
));
167 assert_param(IS_DMA_MEMORY_INC_STATE(hdma
->Init
.MemInc
));
168 assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma
->Init
.PeriphDataAlignment
));
169 assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma
->Init
.MemDataAlignment
));
170 assert_param(IS_DMA_MODE(hdma
->Init
.Mode
));
171 assert_param(IS_DMA_PRIORITY(hdma
->Init
.Priority
));
173 /* Change DMA peripheral state */
174 hdma
->State
= HAL_DMA_STATE_BUSY
;
176 /* Get the CR register value */
177 tmp
= hdma
->Instance
->CCR
;
179 /* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR bits */
180 tmp
&= ((uint32_t)~(DMA_CCR_PL
| DMA_CCR_MSIZE
| DMA_CCR_PSIZE
| \
181 DMA_CCR_MINC
| DMA_CCR_PINC
| DMA_CCR_CIRC
| \
184 /* Prepare the DMA Channel configuration */
185 tmp
|= hdma
->Init
.Direction
|
186 hdma
->Init
.PeriphInc
| hdma
->Init
.MemInc
|
187 hdma
->Init
.PeriphDataAlignment
| hdma
->Init
.MemDataAlignment
|
188 hdma
->Init
.Mode
| hdma
->Init
.Priority
;
190 /* Write to DMA Channel CR register */
191 hdma
->Instance
->CCR
= tmp
;
193 /* Initialize DmaBaseAddress and ChannelIndex parameters used
194 by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
195 DMA_CalcBaseAndBitshift(hdma
);
197 /* Clean callbacks */
198 hdma
->XferCpltCallback
= NULL
;
199 hdma
->XferHalfCpltCallback
= NULL
;
200 hdma
->XferErrorCallback
= NULL
;
201 hdma
->XferAbortCallback
= NULL
;
203 /* Initialise the error code */
204 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
206 /* Initialize the DMA state*/
207 hdma
->State
= HAL_DMA_STATE_READY
;
209 /* Allocate lock resource and initialize it */
210 hdma
->Lock
= HAL_UNLOCKED
;
216 * @brief DeInitialize the DMA peripheral
217 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
218 * the configuration information for the specified DMA Channel.
221 HAL_StatusTypeDef
HAL_DMA_DeInit(DMA_HandleTypeDef
*hdma
)
223 /* Check the DMA handle allocation */
229 /* Check the parameters */
230 assert_param(IS_DMA_ALL_INSTANCE(hdma
->Instance
));
232 /* Disable the selected DMA Channelx */
233 hdma
->Instance
->CCR
&= ~DMA_CCR_EN
;
235 /* Reset DMA Channel control register */
236 hdma
->Instance
->CCR
= 0U;
238 /* Reset DMA Channel Number of Data to Transfer register */
239 hdma
->Instance
->CNDTR
= 0U;
241 /* Reset DMA Channel peripheral address register */
242 hdma
->Instance
->CPAR
= 0U;
244 /* Reset DMA Channel memory address register */
245 hdma
->Instance
->CMAR
= 0U;
247 /* Get DMA Base Address */
248 DMA_CalcBaseAndBitshift(hdma
);
250 /* Clear all flags */
251 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_GL1
<< hdma
->ChannelIndex
;
253 /* Initialize the error code */
254 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
256 /* Initialize the DMA state */
257 hdma
->State
= HAL_DMA_STATE_RESET
;
269 /** @defgroup DMA_Exported_Functions_Group2 Input and Output operation functions
270 * @brief I/O operation functions
273 ===============================================================================
274 ##### IO operation functions #####
275 ===============================================================================
276 [..] This section provides functions allowing to:
277 (+) Configure the source, destination address and data length and Start DMA transfer
278 (+) Configure the source, destination address and data length and
279 Start DMA transfer with interrupt
280 (+) Abort DMA transfer
281 (+) Poll for transfer complete
282 (+) Handle DMA interrupt request
289 * @brief Start the DMA Transfer.
290 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
291 * the configuration information for the specified DMA Channel.
292 * @param SrcAddress The source memory Buffer address
293 * @param DstAddress The destination memory Buffer address
294 * @param DataLength The length of data to be transferred from source to destination
297 HAL_StatusTypeDef
HAL_DMA_Start(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
)
299 HAL_StatusTypeDef status
= HAL_OK
;
301 /* Check the parameters */
302 assert_param(IS_DMA_BUFFER_SIZE(DataLength
));
307 if(HAL_DMA_STATE_READY
== hdma
->State
)
309 /* Change DMA peripheral state */
310 hdma
->State
= HAL_DMA_STATE_BUSY
;
312 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
314 /* Disable the peripheral */
315 hdma
->Instance
->CCR
&= ~DMA_CCR_EN
;
317 /* Configure the source, destination address and the data length */
318 DMA_SetConfig(hdma
, SrcAddress
, DstAddress
, DataLength
);
320 /* Enable the Peripheral */
321 hdma
->Instance
->CCR
|= DMA_CCR_EN
;
325 /* Process Unlocked */
336 * @brief Start the DMA Transfer with interrupt enabled.
337 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
338 * the configuration information for the specified DMA Channel.
339 * @param SrcAddress The source memory Buffer address
340 * @param DstAddress The destination memory Buffer address
341 * @param DataLength The length of data to be transferred from source to destination
344 HAL_StatusTypeDef
HAL_DMA_Start_IT(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
)
346 HAL_StatusTypeDef status
= HAL_OK
;
348 /* Check the parameters */
349 assert_param(IS_DMA_BUFFER_SIZE(DataLength
));
354 if(HAL_DMA_STATE_READY
== hdma
->State
)
356 /* Change DMA peripheral state */
357 hdma
->State
= HAL_DMA_STATE_BUSY
;
359 hdma
->ErrorCode
= HAL_DMA_ERROR_NONE
;
361 /* Disable the peripheral */
362 hdma
->Instance
->CCR
&= ~DMA_CCR_EN
;
364 /* Configure the source, destination address and the data length */
365 DMA_SetConfig(hdma
, SrcAddress
, DstAddress
, DataLength
);
367 /* Enable the transfer complete, & transfer error interrupts */
368 /* Half transfer interrupt is optional: enable it only if associated callback is available */
369 if(NULL
!= hdma
->XferHalfCpltCallback
)
371 hdma
->Instance
->CCR
|= (DMA_IT_TC
| DMA_IT_HT
| DMA_IT_TE
);
375 hdma
->Instance
->CCR
|= (DMA_IT_TC
| DMA_IT_TE
);
376 hdma
->Instance
->CCR
&= ~DMA_IT_HT
;
379 /* Enable the Peripheral */
380 hdma
->Instance
->CCR
|= DMA_CCR_EN
;
384 /* Process Unlocked */
395 * @brief Abort the DMA Transfer.
396 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
397 * the configuration information for the specified DMA Channel.
400 HAL_StatusTypeDef
HAL_DMA_Abort(DMA_HandleTypeDef
*hdma
)
403 hdma
->Instance
->CCR
&= ~(DMA_IT_TC
| DMA_IT_HT
| DMA_IT_TE
);
405 /* Disable the channel */
406 hdma
->Instance
->CCR
&= ~DMA_CCR_EN
;
408 /* Clear all flags */
409 hdma
->DmaBaseAddress
->IFCR
= (DMA_FLAG_GL1
<< hdma
->ChannelIndex
);
411 /* Change the DMA state*/
412 hdma
->State
= HAL_DMA_STATE_READY
;
414 /* Process Unlocked */
421 * @brief Abort the DMA Transfer in Interrupt mode.
422 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
423 * the configuration information for the specified DMA Stream.
426 HAL_StatusTypeDef
HAL_DMA_Abort_IT(DMA_HandleTypeDef
*hdma
)
428 HAL_StatusTypeDef status
= HAL_OK
;
430 if(HAL_DMA_STATE_BUSY
!= hdma
->State
)
432 /* no transfer ongoing */
433 hdma
->ErrorCode
= HAL_DMA_ERROR_NO_XFER
;
441 hdma
->Instance
->CCR
&= ~(DMA_IT_TC
| DMA_IT_HT
| DMA_IT_TE
);
443 /* Disable the channel */
444 hdma
->Instance
->CCR
&= ~DMA_CCR_EN
;
446 /* Clear all flags */
447 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_GL1
<< hdma
->ChannelIndex
;
449 /* Change the DMA state */
450 hdma
->State
= HAL_DMA_STATE_READY
;
452 /* Process Unlocked */
455 /* Call User Abort callback */
456 if(hdma
->XferAbortCallback
!= NULL
)
458 hdma
->XferAbortCallback(hdma
);
465 * @brief Polling for transfer complete.
466 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
467 * the configuration information for the specified DMA Channel.
468 * @param CompleteLevel Specifies the DMA level complete.
469 * @param Timeout Timeout duration.
472 HAL_StatusTypeDef
HAL_DMA_PollForTransfer(DMA_HandleTypeDef
*hdma
, uint32_t CompleteLevel
, uint32_t Timeout
)
475 uint32_t tickstart
= 0U;
477 if(HAL_DMA_STATE_BUSY
!= hdma
->State
)
479 /* no transfer ongoing */
480 hdma
->ErrorCode
= HAL_DMA_ERROR_NO_XFER
;
485 /* Polling mode not supported in circular mode */
486 if (RESET
!= (hdma
->Instance
->CCR
& DMA_CCR_CIRC
))
488 hdma
->ErrorCode
= HAL_DMA_ERROR_NOT_SUPPORTED
;
492 /* Get the level transfer complete flag */
493 if(HAL_DMA_FULL_TRANSFER
== CompleteLevel
)
495 /* Transfer Complete flag */
496 temp
= DMA_FLAG_TC1
<< hdma
->ChannelIndex
;
500 /* Half Transfer Complete flag */
501 temp
= DMA_FLAG_HT1
<< hdma
->ChannelIndex
;
505 tickstart
= HAL_GetTick();
507 while(RESET
== (hdma
->DmaBaseAddress
->ISR
& temp
))
509 if(RESET
!= (hdma
->DmaBaseAddress
->ISR
& (DMA_FLAG_TE1
<< hdma
->ChannelIndex
)))
511 /* When a DMA transfer error occurs */
512 /* A hardware clear of its EN bits is performed */
513 /* Clear all flags */
514 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_GL1
<< hdma
->ChannelIndex
;
516 /* Update error code */
517 hdma
->ErrorCode
= HAL_DMA_ERROR_TE
;
519 /* Change the DMA state */
520 hdma
->State
= HAL_DMA_STATE_READY
;
522 /* Process Unlocked */
527 /* Check for the Timeout */
528 if(Timeout
!= HAL_MAX_DELAY
)
530 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
532 /* Update error code */
533 hdma
->ErrorCode
= HAL_DMA_ERROR_TIMEOUT
;
535 /* Change the DMA state */
536 hdma
->State
= HAL_DMA_STATE_READY
;
538 /* Process Unlocked */
546 if(HAL_DMA_FULL_TRANSFER
== CompleteLevel
)
548 /* Clear the transfer complete flag */
549 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_TC1
<< hdma
->ChannelIndex
;
551 /* The selected Channelx EN bit is cleared (DMA is disabled and
552 all transfers are complete) */
553 hdma
->State
= HAL_DMA_STATE_READY
;
557 /* Clear the half transfer complete flag */
558 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_HT1
<< hdma
->ChannelIndex
;
561 /* Process unlocked */
568 * @brief Handle DMA interrupt request.
569 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
570 * the configuration information for the specified DMA Channel.
573 void HAL_DMA_IRQHandler(DMA_HandleTypeDef
*hdma
)
575 uint32_t flag_it
= hdma
->DmaBaseAddress
->ISR
;
576 uint32_t source_it
= hdma
->Instance
->CCR
;
578 /* Half Transfer Complete Interrupt management ******************************/
579 if ((RESET
!= (flag_it
& (DMA_FLAG_HT1
<< hdma
->ChannelIndex
))) && (RESET
!= (source_it
& DMA_IT_HT
)))
581 /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
582 if((hdma
->Instance
->CCR
& DMA_CCR_CIRC
) == 0U)
584 /* Disable the half transfer interrupt */
585 hdma
->Instance
->CCR
&= ~DMA_IT_HT
;
588 /* Clear the half transfer complete flag */
589 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_HT1
<< hdma
->ChannelIndex
;
591 /* DMA peripheral state is not updated in Half Transfer */
592 /* State is updated only in Transfer Complete case */
594 if(hdma
->XferHalfCpltCallback
!= NULL
)
596 /* Half transfer callback */
597 hdma
->XferHalfCpltCallback(hdma
);
601 /* Transfer Complete Interrupt management ***********************************/
602 else if ((RESET
!= (flag_it
& (DMA_FLAG_TC1
<< hdma
->ChannelIndex
))) && (RESET
!= (source_it
& DMA_IT_TC
)))
604 if((hdma
->Instance
->CCR
& DMA_CCR_CIRC
) == 0U)
606 /* Disable the transfer complete & transfer error interrupts */
607 /* if the DMA mode is not CIRCULAR */
608 hdma
->Instance
->CCR
&= ~(DMA_IT_TC
| DMA_IT_TE
);
610 /* Change the DMA state */
611 hdma
->State
= HAL_DMA_STATE_READY
;
614 /* Clear the transfer complete flag */
615 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_TC1
<< hdma
->ChannelIndex
;
617 /* Process Unlocked */
620 if(hdma
->XferCpltCallback
!= NULL
)
622 /* Transfer complete callback */
623 hdma
->XferCpltCallback(hdma
);
627 /* Transfer Error Interrupt management ***************************************/
628 else if (( RESET
!= (flag_it
& (DMA_FLAG_TE1
<< hdma
->ChannelIndex
))) && (RESET
!= (source_it
& DMA_IT_TE
)))
630 /* When a DMA transfer error occurs */
631 /* A hardware clear of its EN bits is performed */
632 /* Then, disable all DMA interrupts */
633 hdma
->Instance
->CCR
&= ~(DMA_IT_TC
| DMA_IT_HT
| DMA_IT_TE
);
635 /* Clear all flags */
636 hdma
->DmaBaseAddress
->IFCR
= DMA_FLAG_GL1
<< hdma
->ChannelIndex
;
638 /* Update error code */
639 hdma
->ErrorCode
= HAL_DMA_ERROR_TE
;
641 /* Change the DMA state */
642 hdma
->State
= HAL_DMA_STATE_READY
;
644 /* Process Unlocked */
647 if(hdma
->XferErrorCallback
!= NULL
)
649 /* Transfer error callback */
650 hdma
->XferErrorCallback(hdma
);
656 * @brief Register callbacks
657 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
658 * the configuration information for the specified DMA Stream.
659 * @param CallbackID User Callback identifer
660 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
661 * @param pCallback pointer to private callback function which has pointer to
662 * a DMA_HandleTypeDef structure as parameter.
665 HAL_StatusTypeDef
HAL_DMA_RegisterCallback(DMA_HandleTypeDef
*hdma
, HAL_DMA_CallbackIDTypeDef CallbackID
, void (* pCallback
)( DMA_HandleTypeDef
* _hdma
))
667 HAL_StatusTypeDef status
= HAL_OK
;
672 if(HAL_DMA_STATE_READY
== hdma
->State
)
676 case HAL_DMA_XFER_CPLT_CB_ID
:
677 hdma
->XferCpltCallback
= pCallback
;
680 case HAL_DMA_XFER_HALFCPLT_CB_ID
:
681 hdma
->XferHalfCpltCallback
= pCallback
;
684 case HAL_DMA_XFER_ERROR_CB_ID
:
685 hdma
->XferErrorCallback
= pCallback
;
688 case HAL_DMA_XFER_ABORT_CB_ID
:
689 hdma
->XferAbortCallback
= pCallback
;
709 * @brief UnRegister callbacks
710 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
711 * the configuration information for the specified DMA Stream.
712 * @param CallbackID User Callback identifer
713 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
716 HAL_StatusTypeDef
HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef
*hdma
, HAL_DMA_CallbackIDTypeDef CallbackID
)
718 HAL_StatusTypeDef status
= HAL_OK
;
723 if(HAL_DMA_STATE_READY
== hdma
->State
)
727 case HAL_DMA_XFER_CPLT_CB_ID
:
728 hdma
->XferCpltCallback
= NULL
;
731 case HAL_DMA_XFER_HALFCPLT_CB_ID
:
732 hdma
->XferHalfCpltCallback
= NULL
;
735 case HAL_DMA_XFER_ERROR_CB_ID
:
736 hdma
->XferErrorCallback
= NULL
;
739 case HAL_DMA_XFER_ABORT_CB_ID
:
740 hdma
->XferAbortCallback
= NULL
;
743 case HAL_DMA_XFER_ALL_CB_ID
:
744 hdma
->XferCpltCallback
= NULL
;
745 hdma
->XferHalfCpltCallback
= NULL
;
746 hdma
->XferErrorCallback
= NULL
;
747 hdma
->XferAbortCallback
= NULL
;
770 /** @defgroup DMA_Exported_Functions_Group3 Peripheral State functions
771 * @brief Peripheral State functions
774 ===============================================================================
775 ##### State and Errors functions #####
776 ===============================================================================
778 This subsection provides functions allowing to
779 (+) Check the DMA state
787 * @brief Returns the DMA state.
788 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
789 * the configuration information for the specified DMA Channel.
792 HAL_DMA_StateTypeDef
HAL_DMA_GetState(DMA_HandleTypeDef
*hdma
)
798 * @brief Return the DMA error code
799 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
800 * the configuration information for the specified DMA Channel.
801 * @retval DMA Error Code
803 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef
*hdma
)
805 return hdma
->ErrorCode
;
816 /** @addtogroup DMA_Private_Functions
821 * @brief Set the DMA Transfer parameters.
822 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
823 * the configuration information for the specified DMA Channel.
824 * @param SrcAddress The source memory Buffer address
825 * @param DstAddress The destination memory Buffer address
826 * @param DataLength The length of data to be transferred from source to destination
829 static void DMA_SetConfig(DMA_HandleTypeDef
*hdma
, uint32_t SrcAddress
, uint32_t DstAddress
, uint32_t DataLength
)
831 /* Clear all flags */
832 hdma
->DmaBaseAddress
->IFCR
= (DMA_FLAG_GL1
<< hdma
->ChannelIndex
);
834 /* Configure DMA Channel data length */
835 hdma
->Instance
->CNDTR
= DataLength
;
837 /* Peripheral to Memory */
838 if((hdma
->Init
.Direction
) == DMA_MEMORY_TO_PERIPH
)
840 /* Configure DMA Channel destination address */
841 hdma
->Instance
->CPAR
= DstAddress
;
843 /* Configure DMA Channel source address */
844 hdma
->Instance
->CMAR
= SrcAddress
;
846 /* Memory to Peripheral */
849 /* Configure DMA Channel source address */
850 hdma
->Instance
->CPAR
= SrcAddress
;
852 /* Configure DMA Channel destination address */
853 hdma
->Instance
->CMAR
= DstAddress
;
858 * @brief Set the DMA base address and channel index depending on DMA instance
859 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
860 * the configuration information for the specified DMA Stream.
863 static void DMA_CalcBaseAndBitshift(DMA_HandleTypeDef
*hdma
)
866 /* calculation of the channel index */
867 if ((uint32_t)(hdma
->Instance
) < (uint32_t)(DMA2_Channel1
))
870 hdma
->ChannelIndex
= (((uint32_t)hdma
->Instance
- (uint32_t)DMA1_Channel1
) / ((uint32_t)DMA1_Channel2
- (uint32_t)DMA1_Channel1
)) << 2U;
871 hdma
->DmaBaseAddress
= DMA1
;
876 hdma
->ChannelIndex
= (((uint32_t)hdma
->Instance
- (uint32_t)DMA2_Channel1
) / ((uint32_t)DMA2_Channel2
- (uint32_t)DMA2_Channel1
)) << 2U;
877 hdma
->DmaBaseAddress
= DMA2
;
880 /* calculation of the channel index */
882 hdma
->ChannelIndex
= (((uint32_t)hdma
->Instance
- (uint32_t)DMA1_Channel1
) / ((uint32_t)DMA1_Channel2
- (uint32_t)DMA1_Channel1
)) << 2U;
883 hdma
->DmaBaseAddress
= DMA1
;
894 #endif /* HAL_DMA_MODULE_ENABLED */
904 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/