Increment eeprom version
[betaflight.git] / lib / main / STM32F1 / Drivers / STM32F1xx_HAL_Driver / Src / stm32f1xx_hal_dma.c
blobff60573d7d2c2ddb026c6530c79e40cb86981595
1 /**
2 ******************************************************************************
3 * @file stm32f1xx_hal_dma.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 12-May-2017
7 * @brief DMA HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Direct Memory Access (DMA) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral State and errors functions
13 @verbatim
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
17 [..]
18 (#) Enable and configure the peripheral to be connected to the DMA Channel
19 (except for internal SRAM / FLASH memories: no initialization is
20 necessary). Please refer to the Reference manual for connection between peripherals
21 and DMA requests.
23 (#) For a given Channel, program the required configuration through the following parameters:
24 Channel request, Transfer Direction, Source and Destination data formats,
25 Circular or Normal mode, Channel Priority level, Source and Destination Increment mode
26 using HAL_DMA_Init() function.
28 (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error
29 detection.
31 (#) Use HAL_DMA_Abort() function to abort the current transfer
33 -@- In Memory-to-Memory transfer mode, Circular mode is not allowed.
34 *** Polling mode IO operation ***
35 =================================
36 [..]
37 (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source
38 address and destination address and the Length of data to be transferred
39 (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this
40 case a fixed Timeout can be configured by User depending from his application.
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.
49 In this 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).
55 *** DMA HAL driver macros list ***
56 =============================================
57 [..]
58 Below the list of most used macros in DMA HAL driver.
60 (+) __HAL_DMA_ENABLE: Enable the specified DMA Channel.
61 (+) __HAL_DMA_DISABLE: Disable the specified DMA Channel.
62 (+) __HAL_DMA_GET_FLAG: Get the DMA Channel pending flags.
63 (+) __HAL_DMA_CLEAR_FLAG: Clear the DMA Channel pending flags.
64 (+) __HAL_DMA_ENABLE_IT: Enable the specified DMA Channel interrupts.
65 (+) __HAL_DMA_DISABLE_IT: Disable the specified DMA Channel interrupts.
66 (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Channel interrupt has occurred or not.
68 [..]
69 (@) You can refer to the DMA HAL driver header file for more useful macros
71 @endverbatim
72 ******************************************************************************
73 * @attention
75 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
77 * Redistribution and use in source and binary forms, with or without modification,
78 * are permitted provided that the following conditions are met:
79 * 1. Redistributions of source code must retain the above copyright notice,
80 * this list of conditions and the following disclaimer.
81 * 2. Redistributions in binary form must reproduce the above copyright notice,
82 * this list of conditions and the following disclaimer in the documentation
83 * and/or other materials provided with the distribution.
84 * 3. Neither the name of STMicroelectronics nor the names of its contributors
85 * may be used to endorse or promote products derived from this software
86 * without specific prior written permission.
88 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
89 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
90 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
91 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
92 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
93 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
94 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
95 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
96 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
97 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
99 ******************************************************************************
102 /* Includes ------------------------------------------------------------------*/
103 #include "stm32f1xx_hal.h"
105 /** @addtogroup STM32F1xx_HAL_Driver
106 * @{
109 /** @defgroup DMA DMA
110 * @brief DMA HAL module driver
111 * @{
114 #ifdef HAL_DMA_MODULE_ENABLED
116 /* Private typedef -----------------------------------------------------------*/
117 /* Private define ------------------------------------------------------------*/
118 /* Private macro -------------------------------------------------------------*/
119 /* Private variables ---------------------------------------------------------*/
120 /* Private function prototypes -----------------------------------------------*/
121 /** @defgroup DMA_Private_Functions DMA Private Functions
122 * @{
124 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
126 * @}
129 /* Exported functions ---------------------------------------------------------*/
131 /** @defgroup DMA_Exported_Functions DMA Exported Functions
132 * @{
135 /** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions
136 * @brief Initialization and de-initialization functions
138 @verbatim
139 ===============================================================================
140 ##### Initialization and de-initialization functions #####
141 ===============================================================================
142 [..]
143 This section provides functions allowing to initialize the DMA Channel source
144 and destination addresses, incrementation and data sizes, transfer direction,
145 circular/normal mode selection, memory-to-memory mode selection and Channel priority value.
146 [..]
147 The HAL_DMA_Init() function follows the DMA configuration procedures as described in
148 reference manual.
150 @endverbatim
151 * @{
155 * @brief Initialize the DMA according to the specified
156 * parameters in the DMA_InitTypeDef and initialize the associated handle.
157 * @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
158 * the configuration information for the specified DMA Channel.
159 * @retval HAL status
161 HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma)
163 uint32_t tmp = 0U;
165 /* Check the DMA handle allocation */
166 if(hdma == NULL)
168 return HAL_ERROR;
171 /* Check the parameters */
172 assert_param(IS_DMA_ALL_INSTANCE(hdma->Instance));
173 assert_param(IS_DMA_DIRECTION(hdma->Init.Direction));
174 assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc));
175 assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc));
176 assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment));
177 assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment));
178 assert_param(IS_DMA_MODE(hdma->Init.Mode));
179 assert_param(IS_DMA_PRIORITY(hdma->Init.Priority));
181 #if defined (STM32F101xE) || defined (STM32F101xG) || defined (STM32F103xE) || defined (STM32F103xG) || defined (STM32F100xE) || defined (STM32F105xC) || defined (STM32F107xC)
182 /* calculation of the channel index */
183 if ((uint32_t)(hdma->Instance) < (uint32_t)(DMA2_Channel1))
185 /* DMA1 */
186 hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2;
187 hdma->DmaBaseAddress = DMA1;
189 else
191 /* DMA2 */
192 hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA2_Channel1) / ((uint32_t)DMA2_Channel2 - (uint32_t)DMA2_Channel1)) << 2;
193 hdma->DmaBaseAddress = DMA2;
195 #else
196 /* DMA1 */
197 hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2;
198 hdma->DmaBaseAddress = DMA1;
199 #endif /* STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG || STM32F100xE || STM32F105xC || STM32F107xC */
201 /* Change DMA peripheral state */
202 hdma->State = HAL_DMA_STATE_BUSY;
204 /* Get the CR register value */
205 tmp = hdma->Instance->CCR;
207 /* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
208 tmp &= ((uint32_t)~(DMA_CCR_PL | DMA_CCR_MSIZE | DMA_CCR_PSIZE | \
209 DMA_CCR_MINC | DMA_CCR_PINC | DMA_CCR_CIRC | \
210 DMA_CCR_DIR));
212 /* Prepare the DMA Channel configuration */
213 tmp |= hdma->Init.Direction |
214 hdma->Init.PeriphInc | hdma->Init.MemInc |
215 hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment |
216 hdma->Init.Mode | hdma->Init.Priority;
218 /* Write to DMA Channel CR register */
219 hdma->Instance->CCR = tmp;
222 /* Clean callbacks */
223 hdma->XferCpltCallback = NULL;
224 hdma->XferHalfCpltCallback = NULL;
225 hdma->XferErrorCallback = NULL;
226 hdma->XferAbortCallback = NULL;
228 /* Initialise the error code */
229 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
231 /* Initialize the DMA state*/
232 hdma->State = HAL_DMA_STATE_READY;
233 /* Allocate lock resource and initialize it */
234 hdma->Lock = HAL_UNLOCKED;
236 return HAL_OK;
240 * @brief DeInitialize the DMA peripheral.
241 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
242 * the configuration information for the specified DMA Channel.
243 * @retval HAL status
245 HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma)
247 /* Check the DMA handle allocation */
248 if(hdma == NULL)
250 return HAL_ERROR;
253 /* Check the parameters */
254 assert_param(IS_DMA_ALL_INSTANCE(hdma->Instance));
256 /* Disable the selected DMA Channelx */
257 __HAL_DMA_DISABLE(hdma);
259 /* Reset DMA Channel control register */
260 hdma->Instance->CCR = 0U;
262 /* Reset DMA Channel Number of Data to Transfer register */
263 hdma->Instance->CNDTR = 0U;
265 /* Reset DMA Channel peripheral address register */
266 hdma->Instance->CPAR = 0U;
268 /* Reset DMA Channel memory address register */
269 hdma->Instance->CMAR = 0U;
271 #if defined (STM32F101xE) || defined (STM32F101xG) || defined (STM32F103xE) || defined (STM32F103xG) || defined (STM32F100xE) || defined (STM32F105xC) || defined (STM32F107xC)
272 /* calculation of the channel index */
273 if ((uint32_t)(hdma->Instance) < (uint32_t)(DMA2_Channel1))
275 /* DMA1 */
276 hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2;
277 hdma->DmaBaseAddress = DMA1;
279 else
281 /* DMA2 */
282 hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA2_Channel1) / ((uint32_t)DMA2_Channel2 - (uint32_t)DMA2_Channel1)) << 2;
283 hdma->DmaBaseAddress = DMA2;
285 #else
286 /* DMA1 */
287 hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2;
288 hdma->DmaBaseAddress = DMA1;
289 #endif /* STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG || STM32F100xE || STM32F105xC || STM32F107xC */
291 /* Clear all flags */
292 hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex));
294 /* Initialize the error code */
295 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
297 /* Initialize the DMA state */
298 hdma->State = HAL_DMA_STATE_RESET;
300 /* Release Lock */
301 __HAL_UNLOCK(hdma);
303 return HAL_OK;
307 * @}
310 /** @defgroup DMA_Exported_Functions_Group2 Input and Output operation functions
311 * @brief Input and Output operation functions
313 @verbatim
314 ===============================================================================
315 ##### IO operation functions #####
316 ===============================================================================
317 [..] This section provides functions allowing to:
318 (+) Configure the source, destination address and data length and Start DMA transfer
319 (+) Configure the source, destination address and data length and
320 Start DMA transfer with interrupt
321 (+) Abort DMA transfer
322 (+) Poll for transfer complete
323 (+) Handle DMA interrupt request
325 @endverbatim
326 * @{
330 * @brief Start the DMA Transfer.
331 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
332 * the configuration information for the specified DMA Channel.
333 * @param SrcAddress: The source memory Buffer address
334 * @param DstAddress: The destination memory Buffer address
335 * @param DataLength: The length of data to be transferred from source to destination
336 * @retval HAL status
338 HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
340 HAL_StatusTypeDef status = HAL_OK;
342 /* Check the parameters */
343 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
345 /* Process locked */
346 __HAL_LOCK(hdma);
348 if(HAL_DMA_STATE_READY == hdma->State)
350 /* Change DMA peripheral state */
351 hdma->State = HAL_DMA_STATE_BUSY;
352 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
354 /* Disable the peripheral */
355 __HAL_DMA_DISABLE(hdma);
357 /* Configure the source, destination address and the data length & clear flags*/
358 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
360 /* Enable the Peripheral */
361 __HAL_DMA_ENABLE(hdma);
363 else
365 /* Process Unlocked */
366 __HAL_UNLOCK(hdma);
367 status = HAL_BUSY;
369 return status;
373 * @brief Start the DMA Transfer with interrupt enabled.
374 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
375 * the configuration information for the specified DMA Channel.
376 * @param SrcAddress: The source memory Buffer address
377 * @param DstAddress: The destination memory Buffer address
378 * @param DataLength: The length of data to be transferred from source to destination
379 * @retval HAL status
381 HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
383 HAL_StatusTypeDef status = HAL_OK;
385 /* Check the parameters */
386 assert_param(IS_DMA_BUFFER_SIZE(DataLength));
388 /* Process locked */
389 __HAL_LOCK(hdma);
391 if(HAL_DMA_STATE_READY == hdma->State)
393 /* Change DMA peripheral state */
394 hdma->State = HAL_DMA_STATE_BUSY;
395 hdma->ErrorCode = HAL_DMA_ERROR_NONE;
397 /* Disable the peripheral */
398 __HAL_DMA_DISABLE(hdma);
400 /* Configure the source, destination address and the data length & clear flags*/
401 DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
403 /* Enable the transfer complete interrupt */
404 /* Enable the transfer Error interrupt */
405 if(NULL != hdma->XferHalfCpltCallback)
407 /* Enable the Half transfer complete interrupt as well */
408 __HAL_DMA_ENABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE));
410 else
412 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT);
413 __HAL_DMA_ENABLE_IT(hdma, (DMA_IT_TC | DMA_IT_TE));
415 /* Enable the Peripheral */
416 __HAL_DMA_ENABLE(hdma);
418 else
420 /* Process Unlocked */
421 __HAL_UNLOCK(hdma);
423 /* Remain BUSY */
424 status = HAL_BUSY;
426 return status;
430 * @brief Abort the DMA Transfer.
431 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
432 * the configuration information for the specified DMA Channel.
433 * @retval HAL status
435 HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma)
437 HAL_StatusTypeDef status = HAL_OK;
439 /* Disable DMA IT */
440 __HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE));
442 /* Disable the channel */
443 __HAL_DMA_DISABLE(hdma);
445 /* Clear all flags */
446 hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex);
448 /* Change the DMA state */
449 hdma->State = HAL_DMA_STATE_READY;
451 /* Process Unlocked */
452 __HAL_UNLOCK(hdma);
454 return status;
458 * @brief Aborts the DMA Transfer in Interrupt mode.
459 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
460 * the configuration information for the specified DMA Channel.
461 * @retval HAL status
463 HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma)
465 HAL_StatusTypeDef status = HAL_OK;
467 if(HAL_DMA_STATE_BUSY != hdma->State)
469 /* no transfer ongoing */
470 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
472 status = HAL_ERROR;
474 else
476 /* Disable DMA IT */
477 __HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE));
479 /* Disable the channel */
480 __HAL_DMA_DISABLE(hdma);
482 /* Clear all flags */
483 __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_GI_FLAG_INDEX(hdma));
485 /* Change the DMA state */
486 hdma->State = HAL_DMA_STATE_READY;
488 /* Process Unlocked */
489 __HAL_UNLOCK(hdma);
491 /* Call User Abort callback */
492 if(hdma->XferAbortCallback != NULL)
494 hdma->XferAbortCallback(hdma);
497 return status;
501 * @brief Polling for transfer complete.
502 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
503 * the configuration information for the specified DMA Channel.
504 * @param CompleteLevel: Specifies the DMA level complete.
505 * @param Timeout: Timeout duration.
506 * @retval HAL status
508 HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, uint32_t CompleteLevel, uint32_t Timeout)
510 uint32_t temp;
511 uint32_t tickstart = 0U;
513 if(HAL_DMA_STATE_BUSY != hdma->State)
515 /* no transfer ongoing */
516 hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
517 __HAL_UNLOCK(hdma);
518 return HAL_ERROR;
521 /* Polling mode not supported in circular mode */
522 if (RESET != (hdma->Instance->CCR & DMA_CCR_CIRC))
524 hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
525 return HAL_ERROR;
528 /* Get the level transfer complete flag */
529 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
531 /* Transfer Complete flag */
532 temp = __HAL_DMA_GET_TC_FLAG_INDEX(hdma);
534 else
536 /* Half Transfer Complete flag */
537 temp = __HAL_DMA_GET_HT_FLAG_INDEX(hdma);
540 /* Get tick */
541 tickstart = HAL_GetTick();
543 while(__HAL_DMA_GET_FLAG(hdma, temp) == RESET)
545 if((__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)) != RESET))
547 /* When a DMA transfer error occurs */
548 /* A hardware clear of its EN bits is performed */
549 /* Clear all flags */
550 hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex);
552 /* Update error code */
553 SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TE);
555 /* Change the DMA state */
556 hdma->State= HAL_DMA_STATE_READY;
558 /* Process Unlocked */
559 __HAL_UNLOCK(hdma);
561 return HAL_ERROR;
563 /* Check for the Timeout */
564 if(Timeout != HAL_MAX_DELAY)
566 if((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
568 /* Update error code */
569 SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TIMEOUT);
571 /* Change the DMA state */
572 hdma->State = HAL_DMA_STATE_READY;
574 /* Process Unlocked */
575 __HAL_UNLOCK(hdma);
577 return HAL_ERROR;
582 if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
584 /* Clear the transfer complete flag */
585 __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma));
587 /* The selected Channelx EN bit is cleared (DMA is disabled and
588 all transfers are complete) */
589 hdma->State = HAL_DMA_STATE_READY;
591 else
593 /* Clear the half transfer complete flag */
594 __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma));
597 /* Process unlocked */
598 __HAL_UNLOCK(hdma);
600 return HAL_OK;
604 * @brief Handles DMA interrupt request.
605 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
606 * the configuration information for the specified DMA Channel.
607 * @retval None
609 void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma)
611 uint32_t flag_it = hdma->DmaBaseAddress->ISR;
612 uint32_t source_it = hdma->Instance->CCR;
614 /* Half Transfer Complete Interrupt management ******************************/
615 if (((flag_it & (DMA_FLAG_HT1 << hdma->ChannelIndex)) != RESET) && ((source_it & DMA_IT_HT) != RESET))
617 /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
618 if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U)
620 /* Disable the half transfer interrupt */
621 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT);
623 /* Clear the half transfer complete flag */
624 __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma));
626 /* DMA peripheral state is not updated in Half Transfer */
627 /* but in Transfer Complete case */
629 if(hdma->XferHalfCpltCallback != NULL)
631 /* Half transfer callback */
632 hdma->XferHalfCpltCallback(hdma);
636 /* Transfer Complete Interrupt management ***********************************/
637 else if (((flag_it & (DMA_FLAG_TC1 << hdma->ChannelIndex)) != RESET) && ((source_it & DMA_IT_TC) != RESET))
639 if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U)
641 /* Disable the transfer complete and error interrupt */
642 __HAL_DMA_DISABLE_IT(hdma, DMA_IT_TE | DMA_IT_TC);
644 /* Change the DMA state */
645 hdma->State = HAL_DMA_STATE_READY;
647 /* Clear the transfer complete flag */
648 __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma));
650 /* Process Unlocked */
651 __HAL_UNLOCK(hdma);
653 if(hdma->XferCpltCallback != NULL)
655 /* Transfer complete callback */
656 hdma->XferCpltCallback(hdma);
660 /* Transfer Error Interrupt management **************************************/
661 else if (( RESET != (flag_it & (DMA_FLAG_TE1 << hdma->ChannelIndex))) && (RESET != (source_it & DMA_IT_TE)))
663 /* When a DMA transfer error occurs */
664 /* A hardware clear of its EN bits is performed */
665 /* Disable ALL DMA IT */
666 __HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE));
668 /* Clear all flags */
669 hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex);
671 /* Update error code */
672 hdma->ErrorCode = HAL_DMA_ERROR_TE;
674 /* Change the DMA state */
675 hdma->State = HAL_DMA_STATE_READY;
677 /* Process Unlocked */
678 __HAL_UNLOCK(hdma);
680 if (hdma->XferErrorCallback != NULL)
682 /* Transfer error callback */
683 hdma->XferErrorCallback(hdma);
686 return;
690 * @brief Register callbacks
691 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
692 * the configuration information for the specified DMA Channel.
693 * @param CallbackID: User Callback identifer
694 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
695 * @param pCallback: pointer to private callbacsk function which has pointer to
696 * a DMA_HandleTypeDef structure as parameter.
697 * @retval HAL status
699 HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)( DMA_HandleTypeDef * _hdma))
701 HAL_StatusTypeDef status = HAL_OK;
703 /* Process locked */
704 __HAL_LOCK(hdma);
706 if(HAL_DMA_STATE_READY == hdma->State)
708 switch (CallbackID)
710 case HAL_DMA_XFER_CPLT_CB_ID:
711 hdma->XferCpltCallback = pCallback;
712 break;
714 case HAL_DMA_XFER_HALFCPLT_CB_ID:
715 hdma->XferHalfCpltCallback = pCallback;
716 break;
718 case HAL_DMA_XFER_ERROR_CB_ID:
719 hdma->XferErrorCallback = pCallback;
720 break;
722 case HAL_DMA_XFER_ABORT_CB_ID:
723 hdma->XferAbortCallback = pCallback;
724 break;
726 default:
727 status = HAL_ERROR;
728 break;
731 else
733 status = HAL_ERROR;
736 /* Release Lock */
737 __HAL_UNLOCK(hdma);
739 return status;
743 * @brief UnRegister callbacks
744 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
745 * the configuration information for the specified DMA Channel.
746 * @param CallbackID: User Callback identifer
747 * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
748 * @retval HAL status
750 HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID)
752 HAL_StatusTypeDef status = HAL_OK;
754 /* Process locked */
755 __HAL_LOCK(hdma);
757 if(HAL_DMA_STATE_READY == hdma->State)
759 switch (CallbackID)
761 case HAL_DMA_XFER_CPLT_CB_ID:
762 hdma->XferCpltCallback = NULL;
763 break;
765 case HAL_DMA_XFER_HALFCPLT_CB_ID:
766 hdma->XferHalfCpltCallback = NULL;
767 break;
769 case HAL_DMA_XFER_ERROR_CB_ID:
770 hdma->XferErrorCallback = NULL;
771 break;
773 case HAL_DMA_XFER_ABORT_CB_ID:
774 hdma->XferAbortCallback = NULL;
775 break;
777 case HAL_DMA_XFER_ALL_CB_ID:
778 hdma->XferCpltCallback = NULL;
779 hdma->XferHalfCpltCallback = NULL;
780 hdma->XferErrorCallback = NULL;
781 hdma->XferAbortCallback = NULL;
782 break;
784 default:
785 status = HAL_ERROR;
786 break;
789 else
791 status = HAL_ERROR;
794 /* Release Lock */
795 __HAL_UNLOCK(hdma);
797 return status;
801 * @}
804 /** @defgroup DMA_Exported_Functions_Group3 Peripheral State and Errors functions
805 * @brief Peripheral State and Errors functions
807 @verbatim
808 ===============================================================================
809 ##### Peripheral State and Errors functions #####
810 ===============================================================================
811 [..]
812 This subsection provides functions allowing to
813 (+) Check the DMA state
814 (+) Get error code
816 @endverbatim
817 * @{
821 * @brief Return the DMA hande state.
822 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
823 * the configuration information for the specified DMA Channel.
824 * @retval HAL state
826 HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
828 /* Return DMA handle state */
829 return hdma->State;
833 * @brief Return the DMA error code.
834 * @param hdma : pointer to a DMA_HandleTypeDef structure that contains
835 * the configuration information for the specified DMA Channel.
836 * @retval DMA Error Code
838 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
840 return hdma->ErrorCode;
844 * @}
848 * @}
851 /** @addtogroup DMA_Private_Functions
852 * @{
856 * @brief Sets the DMA Transfer parameter.
857 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
858 * the configuration information for the specified DMA Channel.
859 * @param SrcAddress: The source memory Buffer address
860 * @param DstAddress: The destination memory Buffer address
861 * @param DataLength: The length of data to be transferred from source to destination
862 * @retval HAL status
864 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
866 /* Clear all flags */
867 hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex);
869 /* Configure DMA Channel data length */
870 hdma->Instance->CNDTR = DataLength;
872 /* Memory to Peripheral */
873 if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
875 /* Configure DMA Channel destination address */
876 hdma->Instance->CPAR = DstAddress;
878 /* Configure DMA Channel source address */
879 hdma->Instance->CMAR = SrcAddress;
881 /* Peripheral to Memory */
882 else
884 /* Configure DMA Channel source address */
885 hdma->Instance->CPAR = SrcAddress;
887 /* Configure DMA Channel destination address */
888 hdma->Instance->CMAR = DstAddress;
893 * @}
896 #endif /* HAL_DMA_MODULE_ENABLED */
898 * @}
902 * @}
905 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/