stm32h747/stm32h747i-disco/CM7/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_dma.c
Go to the documentation of this file.
1 
95 /* Includes ------------------------------------------------------------------*/
96 #include "stm32h7xx_hal.h"
97 
107 #ifdef HAL_DMA_MODULE_ENABLED
108 
109 /* Private types -------------------------------------------------------------*/
110 typedef struct
111 {
112  __IO uint32_t ISR;
113  __IO uint32_t Reserved0;
114  __IO uint32_t IFCR;
115 } DMA_Base_Registers;
116 
117 typedef struct
118 {
119  __IO uint32_t ISR;
120  __IO uint32_t IFCR;
121 } BDMA_Base_Registers;
122 
123 /* Private variables ---------------------------------------------------------*/
124 /* Private constants ---------------------------------------------------------*/
128 #define HAL_TIMEOUT_DMA_ABORT (5U) /* 5 ms */
129 
130 #define BDMA_PERIPH_TO_MEMORY (0x00000000U)
131 #define BDMA_MEMORY_TO_PERIPH ((uint32_t)BDMA_CCR_DIR)
132 #define BDMA_MEMORY_TO_MEMORY ((uint32_t)BDMA_CCR_MEM2MEM)
134 /* DMA to BDMA conversion */
135 #define DMA_TO_BDMA_DIRECTION(__DMA_DIRECTION__) (((__DMA_DIRECTION__) == DMA_MEMORY_TO_PERIPH)? BDMA_MEMORY_TO_PERIPH: \
136  ((__DMA_DIRECTION__) == DMA_MEMORY_TO_MEMORY)? BDMA_MEMORY_TO_MEMORY: \
137  BDMA_PERIPH_TO_MEMORY)
138 
139 #define DMA_TO_BDMA_PERIPHERAL_INC(__DMA_PERIPHERAL_INC__) ((__DMA_PERIPHERAL_INC__) >> 3U)
140 #define DMA_TO_BDMA_MEMORY_INC(__DMA_MEMORY_INC__) ((__DMA_MEMORY_INC__) >> 3U)
141 
142 #define DMA_TO_BDMA_PDATA_SIZE(__DMA_PDATA_SIZE__) ((__DMA_PDATA_SIZE__) >> 3U)
143 #define DMA_TO_BDMA_MDATA_SIZE(__DMA_MDATA_SIZE__) ((__DMA_MDATA_SIZE__) >> 3U)
144 
145 #define DMA_TO_BDMA_MODE(__DMA_MODE__) ((__DMA_MODE__) >> 3U)
146 
147 #define DMA_TO_BDMA_PRIORITY(__DMA_PRIORITY__) ((__DMA_PRIORITY__) >> 4U)
148 
149 #if defined(UART9)
150 #define IS_DMA_UART_USART_REQUEST(__REQUEST__) ((((__REQUEST__) >= DMA_REQUEST_USART1_RX) && ((__REQUEST__) <= DMA_REQUEST_USART3_TX)) || \
151  (((__REQUEST__) >= DMA_REQUEST_UART4_RX) && ((__REQUEST__) <= DMA_REQUEST_UART5_TX )) || \
152  (((__REQUEST__) >= DMA_REQUEST_USART6_RX) && ((__REQUEST__) <= DMA_REQUEST_USART6_TX)) || \
153  (((__REQUEST__) >= DMA_REQUEST_UART7_RX) && ((__REQUEST__) <= DMA_REQUEST_UART8_TX )) || \
154  (((__REQUEST__) >= DMA_REQUEST_UART9_RX) && ((__REQUEST__) <= DMA_REQUEST_USART10_TX )))
155 #else
156 #define IS_DMA_UART_USART_REQUEST(__REQUEST__) ((((__REQUEST__) >= DMA_REQUEST_USART1_RX) && ((__REQUEST__) <= DMA_REQUEST_USART3_TX)) || \
157  (((__REQUEST__) >= DMA_REQUEST_UART4_RX) && ((__REQUEST__) <= DMA_REQUEST_UART5_TX )) || \
158  (((__REQUEST__) >= DMA_REQUEST_USART6_RX) && ((__REQUEST__) <= DMA_REQUEST_USART6_TX)) || \
159  (((__REQUEST__) >= DMA_REQUEST_UART7_RX) && ((__REQUEST__) <= DMA_REQUEST_UART8_TX )))
160 
161 #endif
162 
165 /* Private macros ------------------------------------------------------------*/
166 /* Private functions ---------------------------------------------------------*/
170 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
171 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma);
172 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma);
173 static void DMA_CalcDMAMUXChannelBaseAndMask(DMA_HandleTypeDef *hdma);
174 static void DMA_CalcDMAMUXRequestGenBaseAndMask(DMA_HandleTypeDef *hdma);
175 
180 /* Exported functions ---------------------------------------------------------*/
212 {
213  uint32_t registerValue;
214  uint32_t tickstart = HAL_GetTick();
215  DMA_Base_Registers *regs_dma;
216  BDMA_Base_Registers *regs_bdma;
217 
218  /* Check the DMA peripheral handle */
219  if(hdma == NULL)
220  {
221  return HAL_ERROR;
222  }
223 
224  /* Check the parameters */
233 
234  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
235  {
238  /* Check the memory burst, peripheral burst and FIFO threshold parameters only
239  when FIFO mode is enabled */
240  if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE)
241  {
245  }
246 
247  /* Allocate lock resource */
248  __HAL_UNLOCK(hdma);
249 
250  /* Change DMA peripheral state */
251  hdma->State = HAL_DMA_STATE_BUSY;
252 
253  /* Disable the peripheral */
254  __HAL_DMA_DISABLE(hdma);
255 
256  /* Check if the DMA Stream is effectively disabled */
257  while((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U)
258  {
259  /* Check for the Timeout */
260  if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
261  {
262  /* Update error code */
264 
265  /* Change the DMA state */
266  hdma->State = HAL_DMA_STATE_ERROR;
267 
268  return HAL_ERROR;
269  }
270  }
271 
272  /* Get the CR register value */
273  registerValue = ((DMA_Stream_TypeDef *)hdma->Instance)->CR;
274 
275  /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */
276  registerValue &= ((uint32_t)~(DMA_SxCR_MBURST | DMA_SxCR_PBURST | \
280 
281  /* Prepare the DMA Stream configuration */
282  registerValue |= hdma->Init.Direction |
283  hdma->Init.PeriphInc | hdma->Init.MemInc |
285  hdma->Init.Mode | hdma->Init.Priority;
286 
287  /* the Memory burst and peripheral burst are not used when the FIFO is disabled */
288  if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
289  {
290  /* Get memory burst and peripheral burst */
291  registerValue |= hdma->Init.MemBurst | hdma->Init.PeriphBurst;
292  }
293 
294  /* Work around for Errata 2.22: UART/USART- DMA transfer lock: DMA stream could be
295  lock when transfering data to/from USART/UART */
296 #if (STM32H7_DEV_ID == 0x450UL)
297  if((DBGMCU->IDCODE & 0xFFFF0000U) >= 0x20000000U)
298  {
299 #endif /* STM32H7_DEV_ID == 0x450UL */
300  if(IS_DMA_UART_USART_REQUEST(hdma->Init.Request) != 0U)
301  {
302  registerValue |= DMA_SxCR_TRBUFF;
303  }
304 #if (STM32H7_DEV_ID == 0x450UL)
305  }
306 #endif /* STM32H7_DEV_ID == 0x450UL */
307 
308  /* Write to DMA Stream CR register */
309  ((DMA_Stream_TypeDef *)hdma->Instance)->CR = registerValue;
310 
311  /* Get the FCR register value */
312  registerValue = ((DMA_Stream_TypeDef *)hdma->Instance)->FCR;
313 
314  /* Clear Direct mode and FIFO threshold bits */
315  registerValue &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH);
316 
317  /* Prepare the DMA Stream FIFO configuration */
318  registerValue |= hdma->Init.FIFOMode;
319 
320  /* the FIFO threshold is not used when the FIFO mode is disabled */
321  if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE)
322  {
323  /* Get the FIFO threshold */
324  registerValue |= hdma->Init.FIFOThreshold;
325 
326  /* Check compatibility between FIFO threshold level and size of the memory burst */
327  /* for INCR4, INCR8, INCR16 */
328  if(hdma->Init.MemBurst != DMA_MBURST_SINGLE)
329  {
330  if (DMA_CheckFifoParam(hdma) != HAL_OK)
331  {
332  /* Update error code */
334 
335  /* Change the DMA state */
336  hdma->State = HAL_DMA_STATE_READY;
337 
338  return HAL_ERROR;
339  }
340  }
341  }
342 
343  /* Write to DMA Stream FCR */
344  ((DMA_Stream_TypeDef *)hdma->Instance)->FCR = registerValue;
345 
346  /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
347  DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
348  regs_dma = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
349 
350  /* Clear all interrupt flags */
351  regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
352  }
353  else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
354  {
356  {
357  /* Check the request parameter */
359  }
360 
361  /* Allocate lock resource */
362  __HAL_UNLOCK(hdma);
363 
364  /* Change DMA peripheral state */
365  hdma->State = HAL_DMA_STATE_BUSY;
366 
367  /* Get the CR register value */
368  registerValue = ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR;
369 
370  /* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, MEM2MEM, DBM and CT bits */
371  registerValue &= ((uint32_t)~(BDMA_CCR_PL | BDMA_CCR_MSIZE | BDMA_CCR_PSIZE | \
374  BDMA_CCR_CT));
375 
376  /* Prepare the DMA Channel configuration */
377  registerValue |= DMA_TO_BDMA_DIRECTION(hdma->Init.Direction) |
378  DMA_TO_BDMA_PERIPHERAL_INC(hdma->Init.PeriphInc) |
379  DMA_TO_BDMA_MEMORY_INC(hdma->Init.MemInc) |
380  DMA_TO_BDMA_PDATA_SIZE(hdma->Init.PeriphDataAlignment) |
381  DMA_TO_BDMA_MDATA_SIZE(hdma->Init.MemDataAlignment) |
382  DMA_TO_BDMA_MODE(hdma->Init.Mode) |
383  DMA_TO_BDMA_PRIORITY(hdma->Init.Priority);
384 
385  /* Write to DMA Channel CR register */
386  ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR = registerValue;
387 
388  /* calculation of the channel index */
389  hdma->StreamIndex = (((uint32_t)((uint32_t*)hdma->Instance) - (uint32_t)BDMA_Channel0) / ((uint32_t)BDMA_Channel1 - (uint32_t)BDMA_Channel0)) << 2U;
390 
391  /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate
392  DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
393  regs_bdma = (BDMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
394 
395  /* Clear all interrupt flags */
396  regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
397  }
398  else
399  {
401  hdma->State = HAL_DMA_STATE_ERROR;
402 
403  return HAL_ERROR;
404  }
405 
406  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
407  {
408  /* Initialize parameters for DMAMUX channel :
409  DMAmuxChannel, DMAmuxChannelStatus and DMAmuxChannelStatusMask
410  */
411  DMA_CalcDMAMUXChannelBaseAndMask(hdma);
412 
413  if(hdma->Init.Direction == DMA_MEMORY_TO_MEMORY)
414  {
415  /* if memory to memory force the request to 0*/
417  }
418 
419  /* Set peripheral request to DMAMUX channel */
421 
422  /* Clear the DMAMUX synchro overrun flag */
424 
425  /* Initialize parameters for DMAMUX request generator :
426  if the DMA request is DMA_REQUEST_GENERATOR0 to DMA_REQUEST_GENERATOR7
427  */
429  {
430  /* Initialize parameters for DMAMUX request generator :
431  DMAmuxRequestGen, DMAmuxRequestGenStatus and DMAmuxRequestGenStatusMask */
432  DMA_CalcDMAMUXRequestGenBaseAndMask(hdma);
433 
434  /* Reset the DMAMUX request generator register */
435  hdma->DMAmuxRequestGen->RGCR = 0U;
436 
437  /* Clear the DMAMUX request generator overrun flag */
439  }
440  else
441  {
442  hdma->DMAmuxRequestGen = 0U;
443  hdma->DMAmuxRequestGenStatus = 0U;
444  hdma->DMAmuxRequestGenStatusMask = 0U;
445  }
446  }
447 
448  /* Initialize the error code */
450 
451  /* Initialize the DMA state */
452  hdma->State = HAL_DMA_STATE_READY;
453 
454  return HAL_OK;
455 }
456 
464 {
465  DMA_Base_Registers *regs_dma;
466  BDMA_Base_Registers *regs_bdma;
467 
468  /* Check the DMA peripheral handle */
469  if(hdma == NULL)
470  {
471  return HAL_ERROR;
472  }
473 
474  /* Disable the selected DMA Streamx */
475  __HAL_DMA_DISABLE(hdma);
476 
477  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
478  {
479  /* Reset DMA Streamx control register */
480  ((DMA_Stream_TypeDef *)hdma->Instance)->CR = 0U;
481 
482  /* Reset DMA Streamx number of data to transfer register */
483  ((DMA_Stream_TypeDef *)hdma->Instance)->NDTR = 0U;
484 
485  /* Reset DMA Streamx peripheral address register */
486  ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = 0U;
487 
488  /* Reset DMA Streamx memory 0 address register */
489  ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = 0U;
490 
491  /* Reset DMA Streamx memory 1 address register */
492  ((DMA_Stream_TypeDef *)hdma->Instance)->M1AR = 0U;
493 
494  /* Reset DMA Streamx FIFO control register */
495  ((DMA_Stream_TypeDef *)hdma->Instance)->FCR = (uint32_t)0x00000021U;
496 
497  /* Get DMA steam Base Address */
498  regs_dma = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
499 
500  /* Clear all interrupt flags at correct offset within the register */
501  regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
502  }
503  else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
504  {
505  /* Reset DMA Channel control register */
506  ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR = 0U;
507 
508  /* Reset DMA Channel Number of Data to Transfer register */
509  ((BDMA_Channel_TypeDef *)hdma->Instance)->CNDTR = 0U;
510 
511  /* Reset DMA Channel peripheral address register */
512  ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = 0U;
513 
514  /* Reset DMA Channel memory 0 address register */
515  ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = 0U;
516 
517  /* Reset DMA Channel memory 1 address register */
518  ((BDMA_Channel_TypeDef *)hdma->Instance)->CM1AR = 0U;
519 
520  /* Get DMA steam Base Address */
521  regs_bdma = (BDMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma);
522 
523  /* Clear all interrupt flags at correct offset within the register */
524  regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
525  }
526  else
527  {
528  /* Return error status */
529  return HAL_ERROR;
530  }
531 
532 #if defined (BDMA1) /* No DMAMUX available for BDMA1 available on STM32H7Ax/Bx devices only */
533  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
534 #endif /* BDMA1 */
535  {
536  /* Initialize parameters for DMAMUX channel :
537  DMAmuxChannel, DMAmuxChannelStatus and DMAmuxChannelStatusMask */
538  DMA_CalcDMAMUXChannelBaseAndMask(hdma);
539 
540  if(hdma->DMAmuxChannel != 0U)
541  {
542  /* Resett he DMAMUX channel that corresponds to the DMA stream */
543  hdma->DMAmuxChannel->CCR = 0U;
544 
545  /* Clear the DMAMUX synchro overrun flag */
547  }
548 
550  {
551  /* Initialize parameters for DMAMUX request generator :
552  DMAmuxRequestGen, DMAmuxRequestGenStatus and DMAmuxRequestGenStatusMask */
553  DMA_CalcDMAMUXRequestGenBaseAndMask(hdma);
554 
555  /* Reset the DMAMUX request generator register */
556  hdma->DMAmuxRequestGen->RGCR = 0U;
557 
558  /* Clear the DMAMUX request generator overrun flag */
560  }
561 
562  hdma->DMAmuxRequestGen = 0U;
563  hdma->DMAmuxRequestGenStatus = 0U;
564  hdma->DMAmuxRequestGenStatusMask = 0U;
565  }
566 
567 
568  /* Clean callbacks */
569  hdma->XferCpltCallback = NULL;
570  hdma->XferHalfCpltCallback = NULL;
571  hdma->XferM1CpltCallback = NULL;
573  hdma->XferErrorCallback = NULL;
574  hdma->XferAbortCallback = NULL;
575 
576  /* Initialize the error code */
578 
579  /* Initialize the DMA state */
580  hdma->State = HAL_DMA_STATE_RESET;
581 
582  /* Release Lock */
583  __HAL_UNLOCK(hdma);
584 
585  return HAL_OK;
586 }
587 
620 HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
621 {
622  HAL_StatusTypeDef status = HAL_OK;
623 
624  /* Check the parameters */
625  assert_param(IS_DMA_BUFFER_SIZE(DataLength));
626 
627  /* Check the DMA peripheral handle */
628  if(hdma == NULL)
629  {
630  return HAL_ERROR;
631  }
632 
633  /* Process locked */
634  __HAL_LOCK(hdma);
635 
636  if(HAL_DMA_STATE_READY == hdma->State)
637  {
638  /* Change DMA peripheral state */
639  hdma->State = HAL_DMA_STATE_BUSY;
640 
641  /* Initialize the error code */
643 
644  /* Disable the peripheral */
645  __HAL_DMA_DISABLE(hdma);
646 
647  /* Configure the source, destination address and the data length */
648  DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
649 
650  /* Enable the Peripheral */
651  __HAL_DMA_ENABLE(hdma);
652  }
653  else
654  {
655  /* Process unlocked */
656  __HAL_UNLOCK(hdma);
657 
658  /* Set the error code to busy */
660 
661  /* Return error status */
662  status = HAL_ERROR;
663  }
664  return status;
665 }
666 
676 HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
677 {
678  HAL_StatusTypeDef status = HAL_OK;
679 
680  /* Check the parameters */
681  assert_param(IS_DMA_BUFFER_SIZE(DataLength));
682 
683  /* Check the DMA peripheral handle */
684  if(hdma == NULL)
685  {
686  return HAL_ERROR;
687  }
688 
689  /* Process locked */
690  __HAL_LOCK(hdma);
691 
692  if(HAL_DMA_STATE_READY == hdma->State)
693  {
694  /* Change DMA peripheral state */
695  hdma->State = HAL_DMA_STATE_BUSY;
696 
697  /* Initialize the error code */
699 
700  /* Disable the peripheral */
701  __HAL_DMA_DISABLE(hdma);
702 
703  /* Configure the source, destination address and the data length */
704  DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
705 
706  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
707  {
708  /* Enable Common interrupts*/
710 
711  if(hdma->XferHalfCpltCallback != NULL)
712  {
713  /* Enable Half Transfer IT if corresponding Callback is set */
714  ((DMA_Stream_TypeDef *)hdma->Instance)->CR |= DMA_IT_HT;
715  }
716  }
717  else /* BDMA channel */
718  {
719  /* Enable Common interrupts */
721 
722  if(hdma->XferHalfCpltCallback != NULL)
723  {
724  /*Enable Half Transfer IT if corresponding Callback is set */
725  ((BDMA_Channel_TypeDef *)hdma->Instance)->CCR |= BDMA_CCR_HTIE;
726  }
727  }
728 
729  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
730  {
731  /* Check if DMAMUX Synchronization is enabled */
732  if((hdma->DMAmuxChannel->CCR & DMAMUX_CxCR_SE) != 0U)
733  {
734  /* Enable DMAMUX sync overrun IT*/
736  }
737 
738  if(hdma->DMAmuxRequestGen != 0U)
739  {
740  /* if using DMAMUX request generator, enable the DMAMUX request generator overrun IT*/
741  /* enable the request gen overrun IT */
743  }
744  }
745 
746  /* Enable the Peripheral */
747  __HAL_DMA_ENABLE(hdma);
748  }
749  else
750  {
751  /* Process unlocked */
752  __HAL_UNLOCK(hdma);
753 
754  /* Set the error code to busy */
756 
757  /* Return error status */
758  status = HAL_ERROR;
759  }
760 
761  return status;
762 }
763 
777 {
778  /* calculate DMA base and stream number */
779  DMA_Base_Registers *regs_dma;
780  BDMA_Base_Registers *regs_bdma;
781  const __IO uint32_t *enableRegister;
782 
783  uint32_t tickstart = HAL_GetTick();
784 
785  /* Check the DMA peripheral handle */
786  if(hdma == NULL)
787  {
788  return HAL_ERROR;
789  }
790 
791  /* Check the DMA peripheral state */
792  if(hdma->State != HAL_DMA_STATE_BUSY)
793  {
795 
796  /* Process Unlocked */
797  __HAL_UNLOCK(hdma);
798 
799  return HAL_ERROR;
800  }
801  else
802  {
803  /* Disable all the transfer interrupts */
804  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
805  {
806  /* Disable DMA All Interrupts */
808  ((DMA_Stream_TypeDef *)hdma->Instance)->FCR &= ~(DMA_IT_FE);
809 
810  enableRegister = (__IO uint32_t *)(&(((DMA_Stream_TypeDef *)hdma->Instance)->CR));
811  }
812  else /* BDMA channel */
813  {
814  /* Disable DMA All Interrupts */
816 
817  enableRegister = (__IO uint32_t *)(&(((BDMA_Channel_TypeDef *)hdma->Instance)->CCR));
818  }
819 
820  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
821  {
822  /* disable the DMAMUX sync overrun IT */
824  }
825 
826  /* Disable the stream */
827  __HAL_DMA_DISABLE(hdma);
828 
829  /* Check if the DMA Stream is effectively disabled */
830  while(((*enableRegister) & DMA_SxCR_EN) != 0U)
831  {
832  /* Check for the Timeout */
833  if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
834  {
835  /* Update error code */
837 
838  /* Process Unlocked */
839  __HAL_UNLOCK(hdma);
840 
841  /* Change the DMA state */
842  hdma->State = HAL_DMA_STATE_ERROR;
843 
844  return HAL_ERROR;
845  }
846  }
847 
848  /* Clear all interrupt flags at correct offset within the register */
849  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
850  {
851  regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
852  regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
853  }
854  else /* BDMA channel */
855  {
856  regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
857  regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
858  }
859 
860  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
861  {
862  /* Clear the DMAMUX synchro overrun flag */
864 
865  if(hdma->DMAmuxRequestGen != 0U)
866  {
867  /* if using DMAMUX request generator, disable the DMAMUX request generator overrun IT */
868  /* disable the request gen overrun IT */
870 
871  /* Clear the DMAMUX request generator overrun flag */
873  }
874  }
875 
876  /* Process Unlocked */
877  __HAL_UNLOCK(hdma);
878 
879  /* Change the DMA state */
880  hdma->State = HAL_DMA_STATE_READY;
881  }
882 
883  return HAL_OK;
884 }
885 
893 {
894  BDMA_Base_Registers *regs_bdma;
895 
896  /* Check the DMA peripheral handle */
897  if(hdma == NULL)
898  {
899  return HAL_ERROR;
900  }
901 
902  if(hdma->State != HAL_DMA_STATE_BUSY)
903  {
905  return HAL_ERROR;
906  }
907  else
908  {
909  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
910  {
911  /* Set Abort State */
912  hdma->State = HAL_DMA_STATE_ABORT;
913 
914  /* Disable the stream */
915  __HAL_DMA_DISABLE(hdma);
916  }
917  else /* BDMA channel */
918  {
919  /* Disable DMA All Interrupts */
921 
922  /* Disable the channel */
923  __HAL_DMA_DISABLE(hdma);
924 
925  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
926  {
927  /* disable the DMAMUX sync overrun IT */
929 
930  /* Clear all flags */
931  regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
932  regs_bdma->IFCR = ((BDMA_IFCR_CGIF0) << (hdma->StreamIndex & 0x1FU));
933 
934  /* Clear the DMAMUX synchro overrun flag */
936 
937  if(hdma->DMAmuxRequestGen != 0U)
938  {
939  /* if using DMAMUX request generator, disable the DMAMUX request generator overrun IT*/
940  /* disable the request gen overrun IT */
942 
943  /* Clear the DMAMUX request generator overrun flag */
945  }
946  }
947 
948  /* Process Unlocked */
949  __HAL_UNLOCK(hdma);
950 
951  /* Change the DMA state */
952  hdma->State = HAL_DMA_STATE_READY;
953 
954  /* Call User Abort callback */
955  if(hdma->XferAbortCallback != NULL)
956  {
957  hdma->XferAbortCallback(hdma);
958  }
959  }
960  }
961 
962  return HAL_OK;
963 }
964 
977 {
978  HAL_StatusTypeDef status = HAL_OK;
979  uint32_t cpltlevel_mask;
980  uint32_t tickstart = HAL_GetTick();
981 
982  /* IT status register */
983  __IO uint32_t *isr_reg;
984  /* IT clear flag register */
985  __IO uint32_t *ifcr_reg;
986 
987  /* Check the DMA peripheral handle */
988  if(hdma == NULL)
989  {
990  return HAL_ERROR;
991  }
992 
993  if(HAL_DMA_STATE_BUSY != hdma->State)
994  {
995  /* No transfer ongoing */
997  __HAL_UNLOCK(hdma);
998 
999  return HAL_ERROR;
1000  }
1001 
1002  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1003  {
1004  /* Polling mode not supported in circular mode and double buffering mode */
1005  if ((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) != 0U)
1006  {
1008  return HAL_ERROR;
1009  }
1010 
1011  /* Get the level transfer complete flag */
1012  if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1013  {
1014  /* Transfer Complete flag */
1015  cpltlevel_mask = DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU);
1016  }
1017  else
1018  {
1019  /* Half Transfer Complete flag */
1020  cpltlevel_mask = DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU);
1021  }
1022 
1023  isr_reg = &(((DMA_Base_Registers *)hdma->StreamBaseAddress)->ISR);
1024  ifcr_reg = &(((DMA_Base_Registers *)hdma->StreamBaseAddress)->IFCR);
1025  }
1026  else /* BDMA channel */
1027  {
1028  /* Polling mode not supported in circular mode */
1029  if ((((BDMA_Channel_TypeDef *)hdma->Instance)->CCR & BDMA_CCR_CIRC) != 0U)
1030  {
1032  return HAL_ERROR;
1033  }
1034 
1035  /* Get the level transfer complete flag */
1036  if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1037  {
1038  /* Transfer Complete flag */
1039  cpltlevel_mask = BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU);
1040  }
1041  else
1042  {
1043  /* Half Transfer Complete flag */
1044  cpltlevel_mask = BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU);
1045  }
1046 
1047  isr_reg = &(((BDMA_Base_Registers *)hdma->StreamBaseAddress)->ISR);
1048  ifcr_reg = &(((BDMA_Base_Registers *)hdma->StreamBaseAddress)->IFCR);
1049  }
1050 
1051  while(((*isr_reg) & cpltlevel_mask) == 0U)
1052  {
1053  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1054  {
1055  if(((*isr_reg) & (DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1056  {
1057  /* Update error code */
1058  hdma->ErrorCode |= HAL_DMA_ERROR_FE;
1059 
1060  /* Clear the FIFO error flag */
1061  (*ifcr_reg) = DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU);
1062  }
1063 
1064  if(((*isr_reg) & (DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1065  {
1066  /* Update error code */
1067  hdma->ErrorCode |= HAL_DMA_ERROR_DME;
1068 
1069  /* Clear the Direct Mode error flag */
1070  (*ifcr_reg) = DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU);
1071  }
1072 
1073  if(((*isr_reg) & (DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1074  {
1075  /* Update error code */
1076  hdma->ErrorCode |= HAL_DMA_ERROR_TE;
1077 
1078  /* Clear the transfer error flag */
1079  (*ifcr_reg) = DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU);
1080 
1081  /* Change the DMA state */
1082  hdma->State = HAL_DMA_STATE_READY;
1083 
1084  /* Process Unlocked */
1085  __HAL_UNLOCK(hdma);
1086 
1087  return HAL_ERROR;
1088  }
1089  }
1090  else /* BDMA channel */
1091  {
1092  if(((*isr_reg) & (BDMA_FLAG_TE0 << (hdma->StreamIndex & 0x1FU))) != 0U)
1093  {
1094  /* When a DMA transfer error occurs */
1095  /* A hardware clear of its EN bits is performed */
1096  /* Clear all flags */
1097  (*isr_reg) = ((BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU));
1098 
1099  /* Update error code */
1100  hdma->ErrorCode = HAL_DMA_ERROR_TE;
1101 
1102  /* Change the DMA state */
1103  hdma->State = HAL_DMA_STATE_READY;
1104 
1105  /* Process Unlocked */
1106  __HAL_UNLOCK(hdma);
1107 
1108  return HAL_ERROR;
1109  }
1110  }
1111 
1112  /* Check for the Timeout (Not applicable in circular mode)*/
1113  if(Timeout != HAL_MAX_DELAY)
1114  {
1115  if(((HAL_GetTick() - tickstart ) > Timeout)||(Timeout == 0U))
1116  {
1117  /* Update error code */
1119 
1120  /* if timeout then abort the current transfer */
1121  /* No need to check return value: as in this case we will return HAL_ERROR with HAL_DMA_ERROR_TIMEOUT error code */
1122  (void) HAL_DMA_Abort(hdma);
1123  /*
1124  Note that the Abort function will
1125  - Clear the transfer error flags
1126  - Unlock
1127  - Set the State
1128  */
1129 
1130  return HAL_ERROR;
1131  }
1132  }
1133 
1134  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
1135  {
1136  /* Check for DMAMUX Request generator (if used) overrun status */
1137  if(hdma->DMAmuxRequestGen != 0U)
1138  {
1139  /* if using DMAMUX request generator Check for DMAMUX request generator overrun */
1140  if((hdma->DMAmuxRequestGenStatus->RGSR & hdma->DMAmuxRequestGenStatusMask) != 0U)
1141  {
1142  /* Clear the DMAMUX request generator overrun flag */
1144 
1145  /* Update error code */
1147  }
1148  }
1149 
1150  /* Check for DMAMUX Synchronization overrun */
1151  if((hdma->DMAmuxChannelStatus->CSR & hdma->DMAmuxChannelStatusMask) != 0U)
1152  {
1153  /* Clear the DMAMUX synchro overrun flag */
1155 
1156  /* Update error code */
1157  hdma->ErrorCode |= HAL_DMA_ERROR_SYNC;
1158  }
1159  }
1160  }
1161 
1162 
1163  /* Get the level transfer complete flag */
1164  if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
1165  {
1166  /* Clear the half transfer and transfer complete flags */
1167  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1168  {
1169  (*ifcr_reg) = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << (hdma->StreamIndex & 0x1FU);
1170  }
1171  else /* BDMA channel */
1172  {
1173  (*ifcr_reg) = (BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU));
1174  }
1175 
1176  /* Process Unlocked */
1177  __HAL_UNLOCK(hdma);
1178 
1179  hdma->State = HAL_DMA_STATE_READY;
1180  }
1181  else /*CompleteLevel = HAL_DMA_HALF_TRANSFER*/
1182  {
1183  /* Clear the half transfer and transfer complete flags */
1184  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1185  {
1186  (*ifcr_reg) = (DMA_FLAG_HTIF0_4) << (hdma->StreamIndex & 0x1FU);
1187  }
1188  else /* BDMA channel */
1189  {
1190  (*ifcr_reg) = (BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU));
1191  }
1192  }
1193 
1194  return status;
1195 }
1196 
1204 {
1205  uint32_t tmpisr_dma, tmpisr_bdma;
1206  uint32_t ccr_reg;
1207  __IO uint32_t count = 0U;
1208  uint32_t timeout = SystemCoreClock / 9600U;
1209 
1210  /* calculate DMA base and stream number */
1211  DMA_Base_Registers *regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
1212  BDMA_Base_Registers *regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
1213 
1214  tmpisr_dma = regs_dma->ISR;
1215  tmpisr_bdma = regs_bdma->ISR;
1216 
1217  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1218  {
1219  /* Transfer Error Interrupt management ***************************************/
1220  if ((tmpisr_dma & (DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1221  {
1222  if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != 0U)
1223  {
1224  /* Disable the transfer error interrupt */
1225  ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TE);
1226 
1227  /* Clear the transfer error flag */
1228  regs_dma->IFCR = DMA_FLAG_TEIF0_4 << (hdma->StreamIndex & 0x1FU);
1229 
1230  /* Update error code */
1231  hdma->ErrorCode |= HAL_DMA_ERROR_TE;
1232  }
1233  }
1234  /* FIFO Error Interrupt management ******************************************/
1235  if ((tmpisr_dma & (DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1236  {
1237  if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != 0U)
1238  {
1239  /* Clear the FIFO error flag */
1240  regs_dma->IFCR = DMA_FLAG_FEIF0_4 << (hdma->StreamIndex & 0x1FU);
1241 
1242  /* Update error code */
1243  hdma->ErrorCode |= HAL_DMA_ERROR_FE;
1244  }
1245  }
1246  /* Direct Mode Error Interrupt management ***********************************/
1247  if ((tmpisr_dma & (DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1248  {
1249  if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != 0U)
1250  {
1251  /* Clear the direct mode error flag */
1252  regs_dma->IFCR = DMA_FLAG_DMEIF0_4 << (hdma->StreamIndex & 0x1FU);
1253 
1254  /* Update error code */
1255  hdma->ErrorCode |= HAL_DMA_ERROR_DME;
1256  }
1257  }
1258  /* Half Transfer Complete Interrupt management ******************************/
1259  if ((tmpisr_dma & (DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1260  {
1261  if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != 0U)
1262  {
1263  /* Clear the half transfer complete flag */
1264  regs_dma->IFCR = DMA_FLAG_HTIF0_4 << (hdma->StreamIndex & 0x1FU);
1265 
1266  /* Multi_Buffering mode enabled */
1267  if(((((DMA_Stream_TypeDef *)hdma->Instance)->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0U)
1268  {
1269  /* Current memory buffer used is Memory 0 */
1270  if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CT) == 0U)
1271  {
1272  if(hdma->XferHalfCpltCallback != NULL)
1273  {
1274  /* Half transfer callback */
1275  hdma->XferHalfCpltCallback(hdma);
1276  }
1277  }
1278  /* Current memory buffer used is Memory 1 */
1279  else
1280  {
1281  if(hdma->XferM1HalfCpltCallback != NULL)
1282  {
1283  /* Half transfer callback */
1284  hdma->XferM1HalfCpltCallback(hdma);
1285  }
1286  }
1287  }
1288  else
1289  {
1290  /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
1291  if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) == 0U)
1292  {
1293  /* Disable the half transfer interrupt */
1294  ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_HT);
1295  }
1296 
1297  if(hdma->XferHalfCpltCallback != NULL)
1298  {
1299  /* Half transfer callback */
1300  hdma->XferHalfCpltCallback(hdma);
1301  }
1302  }
1303  }
1304  }
1305  /* Transfer Complete Interrupt management ***********************************/
1306  if ((tmpisr_dma & (DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU))) != 0U)
1307  {
1308  if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != 0U)
1309  {
1310  /* Clear the transfer complete flag */
1311  regs_dma->IFCR = DMA_FLAG_TCIF0_4 << (hdma->StreamIndex & 0x1FU);
1312 
1313  if(HAL_DMA_STATE_ABORT == hdma->State)
1314  {
1315  /* Disable all the transfer interrupts */
1316  ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME);
1317  ((DMA_Stream_TypeDef *)hdma->Instance)->FCR &= ~(DMA_IT_FE);
1318 
1319  if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL))
1320  {
1321  ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_HT);
1322  }
1323 
1324  /* Clear all interrupt flags at correct offset within the register */
1325  regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
1326 
1327  /* Process Unlocked */
1328  __HAL_UNLOCK(hdma);
1329 
1330  /* Change the DMA state */
1331  hdma->State = HAL_DMA_STATE_READY;
1332 
1333  if(hdma->XferAbortCallback != NULL)
1334  {
1335  hdma->XferAbortCallback(hdma);
1336  }
1337  return;
1338  }
1339 
1340  if(((((DMA_Stream_TypeDef *)hdma->Instance)->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0U)
1341  {
1342  /* Current memory buffer used is Memory 0 */
1343  if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CT) == 0U)
1344  {
1345  if(hdma->XferM1CpltCallback != NULL)
1346  {
1347  /* Transfer complete Callback for memory1 */
1348  hdma->XferM1CpltCallback(hdma);
1349  }
1350  }
1351  /* Current memory buffer used is Memory 1 */
1352  else
1353  {
1354  if(hdma->XferCpltCallback != NULL)
1355  {
1356  /* Transfer complete Callback for memory0 */
1357  hdma->XferCpltCallback(hdma);
1358  }
1359  }
1360  }
1361  /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */
1362  else
1363  {
1364  if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_CIRC) == 0U)
1365  {
1366  /* Disable the transfer complete interrupt */
1367  ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= ~(DMA_IT_TC);
1368 
1369  /* Process Unlocked */
1370  __HAL_UNLOCK(hdma);
1371 
1372  /* Change the DMA state */
1373  hdma->State = HAL_DMA_STATE_READY;
1374  }
1375 
1376  if(hdma->XferCpltCallback != NULL)
1377  {
1378  /* Transfer complete callback */
1379  hdma->XferCpltCallback(hdma);
1380  }
1381  }
1382  }
1383  }
1384 
1385  /* manage error case */
1386  if(hdma->ErrorCode != HAL_DMA_ERROR_NONE)
1387  {
1388  if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != 0U)
1389  {
1390  hdma->State = HAL_DMA_STATE_ABORT;
1391 
1392  /* Disable the stream */
1393  __HAL_DMA_DISABLE(hdma);
1394 
1395  do
1396  {
1397  if (++count > timeout)
1398  {
1399  break;
1400  }
1401  }
1402  while((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U);
1403 
1404  /* Process Unlocked */
1405  __HAL_UNLOCK(hdma);
1406 
1407  if((((DMA_Stream_TypeDef *)hdma->Instance)->CR & DMA_SxCR_EN) != 0U)
1408  {
1409  /* Change the DMA state to error if DMA disable fails */
1410  hdma->State = HAL_DMA_STATE_ERROR;
1411  }
1412  else
1413  {
1414  /* Change the DMA state to Ready if DMA disable success */
1415  hdma->State = HAL_DMA_STATE_READY;
1416  }
1417  }
1418 
1419  if(hdma->XferErrorCallback != NULL)
1420  {
1421  /* Transfer error callback */
1422  hdma->XferErrorCallback(hdma);
1423  }
1424  }
1425  }
1426  else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
1427  {
1428  ccr_reg = (((BDMA_Channel_TypeDef *)hdma->Instance)->CCR);
1429 
1430  /* Half Transfer Complete Interrupt management ******************************/
1431  if (((tmpisr_bdma & (BDMA_FLAG_HT0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_HTIE) != 0U))
1432  {
1433  /* Clear the half transfer complete flag */
1434  regs_bdma->IFCR = (BDMA_ISR_HTIF0 << (hdma->StreamIndex & 0x1FU));
1435 
1436  /* Disable the transfer complete interrupt if the DMA mode is Double Buffering */
1437  if((ccr_reg & BDMA_CCR_DBM) != 0U)
1438  {
1439  /* Current memory buffer used is Memory 0 */
1440  if((ccr_reg & BDMA_CCR_CT) == 0U)
1441  {
1442  if(hdma->XferM1HalfCpltCallback != NULL)
1443  {
1444  /* Half transfer Callback for Memory 1 */
1445  hdma->XferM1HalfCpltCallback(hdma);
1446  }
1447  }
1448  /* Current memory buffer used is Memory 1 */
1449  else
1450  {
1451  if(hdma->XferHalfCpltCallback != NULL)
1452  {
1453  /* Half transfer Callback for Memory 0 */
1454  hdma->XferHalfCpltCallback(hdma);
1455  }
1456  }
1457  }
1458  else
1459  {
1460  if((ccr_reg & BDMA_CCR_CIRC) == 0U)
1461  {
1462  /* Disable the half transfer interrupt */
1464  }
1465 
1466  /* DMA peripheral state is not updated in Half Transfer */
1467  /* but in Transfer Complete case */
1468 
1469  if(hdma->XferHalfCpltCallback != NULL)
1470  {
1471  /* Half transfer callback */
1472  hdma->XferHalfCpltCallback(hdma);
1473  }
1474  }
1475  }
1476 
1477  /* Transfer Complete Interrupt management ***********************************/
1478  else if (((tmpisr_bdma & (BDMA_FLAG_TC0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_TCIE) != 0U))
1479  {
1480  /* Clear the transfer complete flag */
1481  regs_bdma->IFCR = (BDMA_ISR_TCIF0) << (hdma->StreamIndex & 0x1FU);
1482 
1483  /* Disable the transfer complete interrupt if the DMA mode is Double Buffering */
1484  if((ccr_reg & BDMA_CCR_DBM) != 0U)
1485  {
1486  /* Current memory buffer used is Memory 0 */
1487  if((ccr_reg & BDMA_CCR_CT) == 0U)
1488  {
1489  if(hdma->XferM1CpltCallback != NULL)
1490  {
1491  /* Transfer complete Callback for Memory 1 */
1492  hdma->XferM1CpltCallback(hdma);
1493  }
1494  }
1495  /* Current memory buffer used is Memory 1 */
1496  else
1497  {
1498  if(hdma->XferCpltCallback != NULL)
1499  {
1500  /* Transfer complete Callback for Memory 0 */
1501  hdma->XferCpltCallback(hdma);
1502  }
1503  }
1504  }
1505  else
1506  {
1507  if((ccr_reg & BDMA_CCR_CIRC) == 0U)
1508  {
1509  /* Disable the transfer complete and error interrupt, if the DMA mode is not CIRCULAR */
1511 
1512  /* Process Unlocked */
1513  __HAL_UNLOCK(hdma);
1514 
1515  /* Change the DMA state */
1516  hdma->State = HAL_DMA_STATE_READY;
1517  }
1518 
1519  if(hdma->XferCpltCallback != NULL)
1520  {
1521  /* Transfer complete callback */
1522  hdma->XferCpltCallback(hdma);
1523  }
1524  }
1525  }
1526  /* Transfer Error Interrupt management **************************************/
1527  else if (((tmpisr_bdma & (BDMA_FLAG_TE0 << (hdma->StreamIndex & 0x1FU))) != 0U) && ((ccr_reg & BDMA_CCR_TEIE) != 0U))
1528  {
1529  /* When a DMA transfer error occurs */
1530  /* A hardware clear of its EN bits is performed */
1531  /* Disable ALL DMA IT */
1533 
1534  /* Clear all flags */
1535  regs_bdma->IFCR = (BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU);
1536 
1537  /* Update error code */
1538  hdma->ErrorCode = HAL_DMA_ERROR_TE;
1539 
1540  /* Process Unlocked */
1541  __HAL_UNLOCK(hdma);
1542 
1543  /* Change the DMA state */
1544  hdma->State = HAL_DMA_STATE_READY;
1545 
1546  if (hdma->XferErrorCallback != NULL)
1547  {
1548  /* Transfer error callback */
1549  hdma->XferErrorCallback(hdma);
1550  }
1551  }
1552  else
1553  {
1554  /* Nothing To Do */
1555  }
1556  }
1557  else
1558  {
1559  /* Nothing To Do */
1560  }
1561 }
1562 
1574 {
1575 
1576  HAL_StatusTypeDef status = HAL_OK;
1577 
1578  /* Check the DMA peripheral handle */
1579  if(hdma == NULL)
1580  {
1581  return HAL_ERROR;
1582  }
1583 
1584  /* Process locked */
1585  __HAL_LOCK(hdma);
1586 
1587  if(HAL_DMA_STATE_READY == hdma->State)
1588  {
1589  switch (CallbackID)
1590  {
1592  hdma->XferCpltCallback = pCallback;
1593  break;
1594 
1596  hdma->XferHalfCpltCallback = pCallback;
1597  break;
1598 
1600  hdma->XferM1CpltCallback = pCallback;
1601  break;
1602 
1604  hdma->XferM1HalfCpltCallback = pCallback;
1605  break;
1606 
1608  hdma->XferErrorCallback = pCallback;
1609  break;
1610 
1612  hdma->XferAbortCallback = pCallback;
1613  break;
1614 
1615  default:
1616  break;
1617  }
1618  }
1619  else
1620  {
1621  /* Return error status */
1622  status = HAL_ERROR;
1623  }
1624 
1625  /* Release Lock */
1626  __HAL_UNLOCK(hdma);
1627 
1628  return status;
1629 }
1630 
1640 {
1641  HAL_StatusTypeDef status = HAL_OK;
1642 
1643  /* Check the DMA peripheral handle */
1644  if(hdma == NULL)
1645  {
1646  return HAL_ERROR;
1647  }
1648 
1649  /* Process locked */
1650  __HAL_LOCK(hdma);
1651 
1652  if(HAL_DMA_STATE_READY == hdma->State)
1653  {
1654  switch (CallbackID)
1655  {
1657  hdma->XferCpltCallback = NULL;
1658  break;
1659 
1661  hdma->XferHalfCpltCallback = NULL;
1662  break;
1663 
1665  hdma->XferM1CpltCallback = NULL;
1666  break;
1667 
1669  hdma->XferM1HalfCpltCallback = NULL;
1670  break;
1671 
1673  hdma->XferErrorCallback = NULL;
1674  break;
1675 
1677  hdma->XferAbortCallback = NULL;
1678  break;
1679 
1681  hdma->XferCpltCallback = NULL;
1682  hdma->XferHalfCpltCallback = NULL;
1683  hdma->XferM1CpltCallback = NULL;
1684  hdma->XferM1HalfCpltCallback = NULL;
1685  hdma->XferErrorCallback = NULL;
1686  hdma->XferAbortCallback = NULL;
1687  break;
1688 
1689  default:
1690  status = HAL_ERROR;
1691  break;
1692  }
1693  }
1694  else
1695  {
1696  status = HAL_ERROR;
1697  }
1698 
1699  /* Release Lock */
1700  __HAL_UNLOCK(hdma);
1701 
1702  return status;
1703 }
1704 
1731 {
1732  return hdma->State;
1733 }
1734 
1741 uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
1742 {
1743  return hdma->ErrorCode;
1744 }
1745 
1767 static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
1768 {
1769  /* calculate DMA base and stream number */
1770  DMA_Base_Registers *regs_dma = (DMA_Base_Registers *)hdma->StreamBaseAddress;
1771  BDMA_Base_Registers *regs_bdma = (BDMA_Base_Registers *)hdma->StreamBaseAddress;
1772 
1773  if(IS_DMA_DMAMUX_ALL_INSTANCE(hdma->Instance) != 0U) /* No DMAMUX available for BDMA1 */
1774  {
1775  /* Clear the DMAMUX synchro overrun flag */
1777 
1778  if(hdma->DMAmuxRequestGen != 0U)
1779  {
1780  /* Clear the DMAMUX request generator overrun flag */
1782  }
1783  }
1784 
1785  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1786  {
1787  /* Clear all interrupt flags at correct offset within the register */
1788  regs_dma->IFCR = 0x3FUL << (hdma->StreamIndex & 0x1FU);
1789 
1790  /* Clear DBM bit */
1791  ((DMA_Stream_TypeDef *)hdma->Instance)->CR &= (uint32_t)(~DMA_SxCR_DBM);
1792 
1793  /* Configure DMA Stream data length */
1794  ((DMA_Stream_TypeDef *)hdma->Instance)->NDTR = DataLength;
1795 
1796  /* Peripheral to Memory */
1797  if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1798  {
1799  /* Configure DMA Stream destination address */
1800  ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = DstAddress;
1801 
1802  /* Configure DMA Stream source address */
1803  ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = SrcAddress;
1804  }
1805  /* Memory to Peripheral */
1806  else
1807  {
1808  /* Configure DMA Stream source address */
1809  ((DMA_Stream_TypeDef *)hdma->Instance)->PAR = SrcAddress;
1810 
1811  /* Configure DMA Stream destination address */
1812  ((DMA_Stream_TypeDef *)hdma->Instance)->M0AR = DstAddress;
1813  }
1814  }
1815  else if(IS_BDMA_CHANNEL_INSTANCE(hdma->Instance) != 0U) /* BDMA instance(s) */
1816  {
1817  /* Clear all flags */
1818  regs_bdma->IFCR = (BDMA_ISR_GIF0) << (hdma->StreamIndex & 0x1FU);
1819 
1820  /* Configure DMA Channel data length */
1821  ((BDMA_Channel_TypeDef *)hdma->Instance)->CNDTR = DataLength;
1822 
1823  /* Peripheral to Memory */
1824  if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
1825  {
1826  /* Configure DMA Channel destination address */
1827  ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = DstAddress;
1828 
1829  /* Configure DMA Channel source address */
1830  ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = SrcAddress;
1831  }
1832  /* Memory to Peripheral */
1833  else
1834  {
1835  /* Configure DMA Channel source address */
1836  ((BDMA_Channel_TypeDef *)hdma->Instance)->CPAR = SrcAddress;
1837 
1838  /* Configure DMA Channel destination address */
1839  ((BDMA_Channel_TypeDef *)hdma->Instance)->CM0AR = DstAddress;
1840  }
1841  }
1842  else
1843  {
1844  /* Nothing To Do */
1845  }
1846 }
1847 
1854 static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma)
1855 {
1856  if(IS_DMA_STREAM_INSTANCE(hdma->Instance) != 0U) /* DMA1 or DMA2 instance */
1857  {
1858  uint32_t stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 16U) / 24U;
1859 
1860  /* lookup table for necessary bitshift of flags within status registers */
1861  static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U};
1862  hdma->StreamIndex = flagBitshiftOffset[stream_number & 0x7U];
1863 
1864  if (stream_number > 3U)
1865  {
1866  /* return pointer to HISR and HIFCR */
1867  hdma->StreamBaseAddress = (((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0x3FFU)) + 4U);
1868  }
1869  else
1870  {
1871  /* return pointer to LISR and LIFCR */
1872  hdma->StreamBaseAddress = ((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0x3FFU));
1873  }
1874  }
1875  else /* BDMA instance(s) */
1876  {
1877  /* return pointer to ISR and IFCR */
1878  hdma->StreamBaseAddress = ((uint32_t)((uint32_t*)hdma->Instance) & (uint32_t)(~0xFFU));
1879  }
1880 
1881  return hdma->StreamBaseAddress;
1882 }
1883 
1890 static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma)
1891 {
1892  HAL_StatusTypeDef status = HAL_OK;
1893 
1894  /* Memory Data size equal to Byte */
1896  {
1897  switch (hdma->Init.FIFOThreshold)
1898  {
1901 
1903  {
1904  status = HAL_ERROR;
1905  }
1906  break;
1907 
1909  if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1910  {
1911  status = HAL_ERROR;
1912  }
1913  break;
1914 
1916  break;
1917 
1918  default:
1919  break;
1920  }
1921  }
1922 
1923  /* Memory Data size equal to Half-Word */
1924  else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1925  {
1926  switch (hdma->Init.FIFOThreshold)
1927  {
1930  status = HAL_ERROR;
1931  break;
1932 
1935  {
1936  status = HAL_ERROR;
1937  }
1938  break;
1939 
1941  if (hdma->Init.MemBurst == DMA_MBURST_INC16)
1942  {
1943  status = HAL_ERROR;
1944  }
1945  break;
1946 
1947  default:
1948  break;
1949  }
1950  }
1951 
1952  /* Memory Data size equal to Word */
1953  else
1954  {
1955  switch (hdma->Init.FIFOThreshold)
1956  {
1960  status = HAL_ERROR;
1961  break;
1962 
1965  {
1966  status = HAL_ERROR;
1967  }
1968  break;
1969 
1970  default:
1971  break;
1972  }
1973  }
1974 
1975  return status;
1976 }
1977 
1984 static void DMA_CalcDMAMUXChannelBaseAndMask(DMA_HandleTypeDef *hdma)
1985 {
1986  uint32_t stream_number;
1987  uint32_t stream_baseaddress = (uint32_t)((uint32_t*)hdma->Instance);
1988 
1989  if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
1990  {
1991  /* BDMA Channels are connected to DMAMUX2 channels */
1992  stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 8U) / 20U;
1993  hdma->DMAmuxChannel = (DMAMUX_Channel_TypeDef *)((uint32_t)(((uint32_t)DMAMUX2_Channel0) + (stream_number * 4U)));
1995  hdma->DMAmuxChannelStatusMask = 1UL << (stream_number & 0x1FU);
1996  }
1997  else
1998  {
1999  /* DMA1/DMA2 Streams are connected to DMAMUX1 channels */
2000  stream_number = (((uint32_t)((uint32_t*)hdma->Instance) & 0xFFU) - 16U) / 24U;
2001 
2002  if((stream_baseaddress <= ((uint32_t)DMA2_Stream7) ) && \
2003  (stream_baseaddress >= ((uint32_t)DMA2_Stream0)))
2004  {
2005  stream_number += 8U;
2006  }
2007  hdma->DMAmuxChannel = (DMAMUX_Channel_TypeDef *)((uint32_t)(((uint32_t)DMAMUX1_Channel0) + (stream_number * 4U)));
2009  hdma->DMAmuxChannelStatusMask = 1UL << (stream_number & 0x1FU);
2010  }
2011 }
2012 
2019 static void DMA_CalcDMAMUXRequestGenBaseAndMask(DMA_HandleTypeDef *hdma)
2020 {
2021  uint32_t request = hdma->Init.Request & DMAMUX_CxCR_DMAREQ_ID;
2022 
2023  if((request >= DMA_REQUEST_GENERATOR0) && (request <= DMA_REQUEST_GENERATOR7))
2024  {
2025  if(IS_BDMA_CHANNEL_DMAMUX_INSTANCE(hdma->Instance) != 0U)
2026  {
2027  /* BDMA Channels are connected to DMAMUX2 request generator blocks */
2028  hdma->DMAmuxRequestGen = (DMAMUX_RequestGen_TypeDef *)((uint32_t)(((uint32_t)DMAMUX2_RequestGenerator0) + ((request - 1U) * 4U)));
2029 
2031  }
2032  else
2033  {
2034  /* DMA1 and DMA2 Streams use DMAMUX1 request generator blocks */
2035  hdma->DMAmuxRequestGen = (DMAMUX_RequestGen_TypeDef *)((uint32_t)(((uint32_t)DMAMUX1_RequestGenerator0) + ((request - 1U) * 4U)));
2036 
2038  }
2039 
2040  hdma->DMAmuxRequestGenStatusMask = 1UL << (request - 1U);
2041  }
2042 }
2043 
2048 #endif /* HAL_DMA_MODULE_ENABLED */
2049 
2057 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
assert_param
#define assert_param(expr)
Include module's header file.
Definition: stm32f407/stm32f407g-disc1/Inc/stm32f4xx_hal_conf.h:353
DMA_IT_HT
#define DMA_IT_HT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:351
__DMA_HandleTypeDef::DMAmuxChannelStatusMask
uint32_t DMAmuxChannelStatusMask
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:171
__DMA_HandleTypeDef::DMAmuxChannelStatus
DMAMUX_ChannelStatus_TypeDef * DMAmuxChannelStatus
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:169
HAL_DMA_STATE_BUSY
@ HAL_DMA_STATE_BUSY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:107
__HAL_DMA_DISABLE
#define __HAL_DMA_DISABLE(__HANDLE__)
Disable the specified DMA Stream.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:425
__IO
#define __IO
Definition: imxrt1050/imxrt1050-evkb/CMSIS/core_cm7.h:237
HAL_StatusTypeDef
HAL_StatusTypeDef
HAL Status structures definition
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:40
IS_DMA_STREAM_INSTANCE
#define IS_DMA_STREAM_INSTANCE(INSTANCE)
Definition: stm32h735xx.h:23880
IS_DMA_PRIORITY
#define IS_DMA_PRIORITY(PRIORITY)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:755
DMAMUX_ChannelStatus_TypeDef::CFR
__IO uint32_t CFR
Definition: stm32h735xx.h:646
HAL_DMA_ERROR_SYNC
#define HAL_DMA_ERROR_SYNC
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:206
HAL_DMA_XFER_ERROR_CB_ID
@ HAL_DMA_XFER_ERROR_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:131
DMA_Stream_TypeDef
DMA Controller.
Definition: stm32f407xx.h:346
DMA_MDATAALIGN_BYTE
#define DMA_MDATAALIGN_BYTE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:270
DMAMUX_CxCR_SE
#define DMAMUX_CxCR_SE
Definition: stm32h735xx.h:9411
__DMA_HandleTypeDef::XferHalfCpltCallback
void(* XferHalfCpltCallback)(struct __DMA_HandleTypeDef *hdma)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:153
__DMA_HandleTypeDef
DMA handle Structure definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:139
NULL
#define NULL
Definition: porcupine/demo/c/dr_libs/tests/external/miniaudio/extras/speex_resampler/thirdparty/resample.c:92
__DMA_HandleTypeDef::StreamIndex
uint32_t StreamIndex
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:167
DMA_FLAG_FEIF0_4
#define DMA_FLAG_FEIF0_4
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:363
DMAMUX1_ChannelStatus
#define DMAMUX1_ChannelStatus
Definition: stm32h735xx.h:2761
BDMA_ISR_TCIF0
#define BDMA_ISR_TCIF0
Definition: stm32h735xx.h:6878
DBGMCU
#define DBGMCU
Definition: stm32f407xx.h:1140
HAL_DMA_ERROR_TIMEOUT
#define HAL_DMA_ERROR_TIMEOUT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:190
DMAMUX1_RequestGenStatus
#define DMAMUX1_RequestGenStatus
Definition: stm32h735xx.h:2762
DMA_InitTypeDef::Priority
uint32_t Priority
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:75
__DMA_HandleTypeDef::StreamBaseAddress
uint32_t StreamBaseAddress
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:165
DMA_InitTypeDef::PeriphInc
uint32_t PeriphInc
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:58
__DMA_HandleTypeDef::ErrorCode
__IO uint32_t ErrorCode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:163
HAL_DMA_Abort_IT
HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma)
__DMA_HandleTypeDef::XferM1CpltCallback
void(* XferM1CpltCallback)(struct __DMA_HandleTypeDef *hdma)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:155
DMA_MEMORY_TO_MEMORY
#define DMA_MEMORY_TO_MEMORY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:230
DMA2_Stream0
#define DMA2_Stream0
Definition: stm32f407xx.h:1125
DMA_IT_TC
#define DMA_IT_TC
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:350
DMA_REQUEST_GENERATOR0
#define DMA_REQUEST_GENERATOR0
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:221
__HAL_DMA_ENABLE
#define __HAL_DMA_ENABLE(__HANDLE__)
Enable the specified DMA Stream.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:418
HAL_DMA_STATE_ERROR
@ HAL_DMA_STATE_ERROR
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:109
IS_DMA_FIFO_THRESHOLD
#define IS_DMA_FIFO_THRESHOLD(THRESHOLD)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:763
__DMA_HandleTypeDef::XferAbortCallback
void(* XferAbortCallback)(struct __DMA_HandleTypeDef *hdma)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:161
HAL_DMA_ERROR_NO_XFER
#define HAL_DMA_ERROR_NO_XFER
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:192
DMA2_Stream7
#define DMA2_Stream7
Definition: stm32f407xx.h:1132
DMAMUX_CxCR_DMAREQ_ID
#define DMAMUX_CxCR_DMAREQ_ID
Definition: stm32h735xx.h:9394
DMA_REQUEST_MEM2MEM
#define DMA_REQUEST_MEM2MEM
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:219
DMAMUX_CxCR_SOIE
#define DMAMUX_CxCR_SOIE
Definition: stm32h735xx.h:9405
DMA_SxCR_TRBUFF
#define DMA_SxCR_TRBUFF
Definition: stm32h735xx.h:9025
BDMA_ISR_GIF0
#define BDMA_ISR_GIF0
Definition: stm32h735xx.h:6875
__DMA_HandleTypeDef::Init
DMA_InitTypeDef Init
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:143
BDMA_CCR_CT
#define BDMA_CCR_CT
Definition: stm32h735xx.h:7120
HAL_ERROR
@ HAL_ERROR
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:43
HAL_DMA_STATE_ABORT
@ HAL_DMA_STATE_ABORT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:110
__DMA_HandleTypeDef::DMAmuxChannel
DMAMUX_Channel_TypeDef * DMAmuxChannel
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:167
BDMA_ISR_HTIF0
#define BDMA_ISR_HTIF0
Definition: stm32h735xx.h:6881
BDMA_CCR_PSIZE
#define BDMA_CCR_PSIZE
Definition: stm32h735xx.h:7096
HAL_GetTick
uint32_t HAL_GetTick(void)
Provides a tick value in millisecond.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:323
DMA_InitTypeDef::FIFOThreshold
uint32_t FIFOThreshold
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:83
DMAMUX_RequestGen_TypeDef::RGCR
__IO uint32_t RGCR
Definition: stm32h735xx.h:651
DMA_InitTypeDef::PeriphDataAlignment
uint32_t PeriphDataAlignment
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:64
__DMA_HandleTypeDef::State
__IO HAL_DMA_StateTypeDef State
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:147
BDMA_CCR_MEM2MEM
#define BDMA_CCR_MEM2MEM
Definition: stm32h735xx.h:7114
BDMA_Channel1
#define BDMA_Channel1
Definition: stm32h735xx.h:2665
IS_BDMA_REQUEST
#define IS_BDMA_REQUEST(REQUEST)
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:1249
DMA_MBURST_SINGLE
#define DMA_MBURST_SINGLE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:326
IS_DMA_DMAMUX_ALL_INSTANCE
#define IS_DMA_DMAMUX_ALL_INSTANCE(INSTANCE)
Definition: stm32h735xx.h:23844
BDMA_CCR_TCIE
#define BDMA_CCR_TCIE
Definition: stm32h735xx.h:7074
HAL_OK
@ HAL_OK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:42
DMA_SxFCR_DMDIS
#define DMA_SxFCR_DMDIS
Definition: stm32f407xx.h:5915
DMA_SxCR_MBURST_1
#define DMA_SxCR_MBURST_1
Definition: stm32f407xx.h:5814
HAL_DMA_XFER_ABORT_CB_ID
@ HAL_DMA_XFER_ABORT_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:132
DMAMUX2_RequestGenerator0
#define DMAMUX2_RequestGenerator0
Definition: stm32h735xx.h:2701
DMAMUX2_ChannelStatus
#define DMAMUX2_ChannelStatus
Definition: stm32h735xx.h:2710
IS_BDMA_CHANNEL_INSTANCE
#define IS_BDMA_CHANNEL_INSTANCE(INSTANCE)
Definition: stm32h735xx.h:23834
HAL_DMA_XFER_M1HALFCPLT_CB_ID
@ HAL_DMA_XFER_M1HALFCPLT_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:130
DMA_SxCR_PINC
#define DMA_SxCR_PINC
Definition: stm32f407xx.h:5849
BDMA_CCR_MINC
#define BDMA_CCR_MINC
Definition: stm32h735xx.h:7092
DMAMUX2_RequestGenStatus
#define DMAMUX2_RequestGenStatus
Definition: stm32h735xx.h:2711
IS_DMA_REQUEST
#define IS_DMA_REQUEST(REQUEST)
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:1243
IS_DMA_FIFO_MODE_STATE
#define IS_DMA_FIFO_MODE_STATE(STATE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:760
HAL_DMA_ERROR_BUSY
#define HAL_DMA_ERROR_BUSY
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:208
DMAMUX_ChannelStatus_TypeDef::CSR
__IO uint32_t CSR
Definition: stm32h735xx.h:645
DMA_SxCR_PBURST
#define DMA_SxCR_PBURST
Definition: stm32f407xx.h:5817
BDMA_CCR_HTIE
#define BDMA_CCR_HTIE
Definition: stm32h735xx.h:7077
DMA_SxCR_EN
#define DMA_SxCR_EN
Definition: stm32f407xx.h:5875
DMA_InitTypeDef::MemInc
uint32_t MemInc
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:61
DMA_SxCR_CT
#define DMA_SxCR_CT
Definition: stm32f407xx.h:5822
BDMA_CCR_PINC
#define BDMA_CCR_PINC
Definition: stm32h735xx.h:7089
BDMA_Channel_TypeDef
Definition: stm32h735xx.h:623
IS_DMA_MEMORY_INC_STATE
#define IS_DMA_MEMORY_INC_STATE(STATE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:740
HAL_DMA_FULL_TRANSFER
@ HAL_DMA_FULL_TRANSFER
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:118
HAL_DMA_UnRegisterCallback
HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID)
HAL_DMA_XFER_ALL_CB_ID
@ HAL_DMA_XFER_ALL_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:133
HAL_DMA_PollForTransfer
HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout)
__HAL_DMA_GET_IT_SOURCE
#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__)
Check whether the specified DMA Stream interrupt is enabled or disabled.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:607
IS_DMA_MODE
#define IS_DMA_MODE(MODE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:751
DMA_IT_DME
#define DMA_IT_DME
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:353
DMA_InitTypeDef::PeriphBurst
uint32_t PeriphBurst
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:92
IS_DMA_ALL_INSTANCE
#define IS_DMA_ALL_INSTANCE(INSTANCE)
Definition: stm32h735xx.h:23808
__HAL_LOCK
#define __HAL_LOCK(__HANDLE__)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:93
DMA_MDATAALIGN_HALFWORD
#define DMA_MDATAALIGN_HALFWORD
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:271
DMA_MBURST_INC16
#define DMA_MBURST_INC16
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:329
HAL_DMA_GetState
HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
__DMA_HandleTypeDef::Instance
DMA_Stream_TypeDef * Instance
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:141
SystemCoreClock
uint32_t SystemCoreClock
Definition: system_MIMXRT1052.c:69
DMA_FLAG_TCIF0_4
#define DMA_FLAG_TCIF0_4
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:367
IS_DMA_PERIPHERAL_BURST
#define IS_DMA_PERIPHERAL_BURST(BURST)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:773
MODIFY_REG
#define MODIFY_REG(REG, CLEARMASK, SETMASK)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:224
BDMA_FLAG_TC0
#define BDMA_FLAG_TC0
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:628
DMA_InitTypeDef::MemDataAlignment
uint32_t MemDataAlignment
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:67
DMA_SxCR_DIR
#define DMA_SxCR_DIR
Definition: stm32f407xx.h:5855
HAL_DMA_CallbackIDTypeDef
HAL_DMA_CallbackIDTypeDef
HAL DMA Error Code structure definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:125
count
size_t count
Definition: porcupine/demo/c/dr_libs/tests/external/miniaudio/tests/test_common/ma_test_common.c:31
BDMA_CCR_CIRC
#define BDMA_CCR_CIRC
Definition: stm32h735xx.h:7086
HAL_DMA_Start_IT
HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
DMA_SxCR_PL
#define DMA_SxCR_PL
Definition: stm32f407xx.h:5828
DMA_SxCR_MSIZE
#define DMA_SxCR_MSIZE
Definition: stm32f407xx.h:5836
HAL_DMA_XFER_M1CPLT_CB_ID
@ HAL_DMA_XFER_M1CPLT_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:129
DMA_IT_FE
#define DMA_IT_FE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:354
DMA_SxCR_DBM
#define DMA_SxCR_DBM
Definition: stm32f407xx.h:5825
DMAMUX1_RequestGenerator0
#define DMAMUX1_RequestGenerator0
Definition: stm32h735xx.h:2752
DMA_FLAG_HTIF0_4
#define DMA_FLAG_HTIF0_4
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:366
BDMA_FLAG_HT0
#define BDMA_FLAG_HT0
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:629
DMA_FIFO_THRESHOLD_3QUARTERSFULL
#define DMA_FIFO_THRESHOLD_3QUARTERSFULL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:316
IS_DMA_BUFFER_SIZE
#define IS_DMA_BUFFER_SIZE(SIZE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:735
__HAL_UNLOCK
#define __HAL_UNLOCK(__HANDLE__)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:105
HAL_MAX_DELAY
#define HAL_MAX_DELAY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:61
DMA_SxCR_PSIZE
#define DMA_SxCR_PSIZE
Definition: stm32f407xx.h:5841
HAL_DMA_Abort
HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma)
BDMA_Channel0
#define BDMA_Channel0
Definition: stm32h735xx.h:2664
DMAMUX_RequestGenStatus_TypeDef::RGSR
__IO uint32_t RGSR
Definition: stm32h735xx.h:656
DMA_FIFO_THRESHOLD_1QUARTERFULL
#define DMA_FIFO_THRESHOLD_1QUARTERFULL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:314
HAL_DMA_ERROR_REQGEN
#define HAL_DMA_ERROR_REQGEN
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:207
DMAMUX_RequestGen_TypeDef
Definition: stm32h735xx.h:649
DMA_SxFCR_FTH
#define DMA_SxFCR_FTH
Definition: stm32f407xx.h:5918
IS_DMA_DIRECTION
#define IS_DMA_DIRECTION(DIRECTION)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:731
HAL_DMA_XFER_CPLT_CB_ID
@ HAL_DMA_XFER_CPLT_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:127
DMA_InitTypeDef::MemBurst
uint32_t MemBurst
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:86
__DMA_HandleTypeDef::DMAmuxRequestGenStatusMask
uint32_t DMAmuxRequestGenStatusMask
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:178
__DMA_HandleTypeDef::DMAmuxRequestGen
DMAMUX_RequestGen_TypeDef * DMAmuxRequestGen
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:174
HAL_DMA_ERROR_DME
#define HAL_DMA_ERROR_DME
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:189
__HAL_DMA_DISABLE_IT
#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__)
Disable the specified DMA Stream interrupts.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:592
DMAMUX1_Channel0
#define DMAMUX1_Channel0
Definition: stm32h735xx.h:2735
DMAMUX_RGxCR_OIE
#define DMAMUX_RGxCR_OIE
Definition: stm32h735xx.h:9545
DMA_FIFOMODE_ENABLE
#define DMA_FIFOMODE_ENABLE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:305
HAL_DMA_STATE_RESET
@ HAL_DMA_STATE_RESET
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:105
DMA_InitTypeDef::FIFOMode
uint32_t FIFOMode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:78
HAL_DMA_ERROR_NOT_SUPPORTED
#define HAL_DMA_ERROR_NOT_SUPPORTED
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:193
DMA_FIFOMODE_DISABLE
#define DMA_FIFOMODE_DISABLE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:304
DMAMUX_RequestGenStatus_TypeDef::RGCFR
__IO uint32_t RGCFR
Definition: stm32h735xx.h:657
__DMA_HandleTypeDef::XferCpltCallback
void(* XferCpltCallback)(struct __DMA_HandleTypeDef *hdma)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:151
IS_DMA_MEMORY_DATA_SIZE
#define IS_DMA_MEMORY_DATA_SIZE(SIZE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:747
BDMA_FLAG_TE0
#define BDMA_FLAG_TE0
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:630
DMA_FLAG_TEIF0_4
#define DMA_FLAG_TEIF0_4
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:365
DMA_MEMORY_TO_PERIPH
#define DMA_MEMORY_TO_PERIPH
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:229
IS_DMA_MEMORY_BURST
#define IS_DMA_MEMORY_BURST(BURST)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:768
HAL_DMA_Init
HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma)
BDMA_CCR_MSIZE
#define BDMA_CCR_MSIZE
Definition: stm32h735xx.h:7102
DMA_FLAG_DMEIF0_4
#define DMA_FLAG_DMEIF0_4
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:364
IS_DMA_PERIPHERAL_INC_STATE
#define IS_DMA_PERIPHERAL_INC_STATE(STATE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:737
DMA_REQUEST_GENERATOR7
#define DMA_REQUEST_GENERATOR7
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:228
DMA_InitTypeDef::Direction
uint32_t Direction
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:54
BDMA_CCR_DIR
#define BDMA_CCR_DIR
Definition: stm32h735xx.h:7083
HAL_DMA_DeInit
HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma)
IS_DMA_PERIPHERAL_DATA_SIZE
#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:743
HAL_DMA_ERROR_TE
#define HAL_DMA_ERROR_TE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:187
HAL_DMA_XFER_HALFCPLT_CB_ID
@ HAL_DMA_XFER_HALFCPLT_CB_ID
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:128
DMA_SxCR_MINC
#define DMA_SxCR_MINC
Definition: stm32f407xx.h:5846
BDMA_IFCR_CGIF0
#define BDMA_IFCR_CGIF0
Definition: stm32h735xx.h:6973
__DMA_HandleTypeDef::XferM1HalfCpltCallback
void(* XferM1HalfCpltCallback)(struct __DMA_HandleTypeDef *hdma)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:157
BDMA_CCR_PL
#define BDMA_CCR_PL
Definition: stm32h735xx.h:7108
HAL_DMA_GetError
uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
HAL_DMA_ERROR_PARAM
#define HAL_DMA_ERROR_PARAM
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:191
DMAMUX_Channel_TypeDef::CCR
__IO uint32_t CCR
Definition: stm32h735xx.h:640
DMA_InitTypeDef::Mode
uint32_t Mode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:70
HAL_DMA_Start
HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
HAL_DMA_ERROR_NONE
#define HAL_DMA_ERROR_NONE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:186
HAL_DMA_StateTypeDef
HAL_DMA_StateTypeDef
HAL DMA State structures definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:103
HAL_DMA_LevelCompleteTypeDef
HAL_DMA_LevelCompleteTypeDef
HAL DMA Error Code structure definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:116
HAL_DMA_ERROR_FE
#define HAL_DMA_ERROR_FE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:188
DMA_FIFO_THRESHOLD_FULL
#define DMA_FIFO_THRESHOLD_FULL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:317
DMA_SxCR_CIRC
#define DMA_SxCR_CIRC
Definition: stm32f407xx.h:5852
BDMA_CCR_TEIE
#define BDMA_CCR_TEIE
Definition: stm32h735xx.h:7080
BDMA_CCR_DBM
#define BDMA_CCR_DBM
Definition: stm32h735xx.h:7117
DMAMUX2_Channel0
#define DMAMUX2_Channel0
Definition: stm32h735xx.h:2691
DMA_IT_TE
#define DMA_IT_TE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:352
DMAMUX_Channel_TypeDef
Definition: stm32h735xx.h:638
HAL_DMA_IRQHandler
void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma)
__DMA_HandleTypeDef::DMAmuxRequestGenStatus
DMAMUX_RequestGenStatus_TypeDef * DMAmuxRequestGenStatus
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:176
__DMA_HandleTypeDef::XferErrorCallback
void(* XferErrorCallback)(struct __DMA_HandleTypeDef *hdma)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:159
DMA_InitTypeDef::Request
uint32_t Request
Definition: stm32h735/stm32h735g-dk/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_dma.h:51
DMA_SxCR_MBURST
#define DMA_SxCR_MBURST
Definition: stm32f407xx.h:5812
HAL_DMA_RegisterCallback
HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void(*pCallback)(DMA_HandleTypeDef *_hdma))
IS_BDMA_CHANNEL_DMAMUX_INSTANCE
#define IS_BDMA_CHANNEL_DMAMUX_INSTANCE(INSTANCE)
Definition: stm32h735xx.h:23870
HAL_DMA_STATE_READY
@ HAL_DMA_STATE_READY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:106
DMA_FIFO_THRESHOLD_HALFFULL
#define DMA_FIFO_THRESHOLD_HALFFULL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h:315


picovoice_driver
Author(s):
autogenerated on Fri Apr 1 2022 02:14:54