stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c
Go to the documentation of this file.
1 
35 /* Includes ------------------------------------------------------------------*/
36 #include "stm32f4xx_hal.h"
37 
47 /* Private typedef -----------------------------------------------------------*/
48 /* Private define ------------------------------------------------------------*/
55 #define __STM32F4xx_HAL_VERSION_MAIN (0x01U)
56 #define __STM32F4xx_HAL_VERSION_SUB1 (0x07U)
57 #define __STM32F4xx_HAL_VERSION_SUB2 (0x0AU)
58 #define __STM32F4xx_HAL_VERSION_RC (0x00U)
59 #define __STM32F4xx_HAL_VERSION ((__STM32F4xx_HAL_VERSION_MAIN << 24U)\
60  |(__STM32F4xx_HAL_VERSION_SUB1 << 16U)\
61  |(__STM32F4xx_HAL_VERSION_SUB2 << 8U )\
62  |(__STM32F4xx_HAL_VERSION_RC))
63 
64 #define IDCODE_DEVID_MASK 0x00000FFFU
65 
66 /* ------------ RCC registers bit address in the alias region ----------- */
67 #define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE)
68 /* --- MEMRMP Register ---*/
69 /* Alias word address of UFB_MODE bit */
70 #define MEMRMP_OFFSET SYSCFG_OFFSET
71 #define UFB_MODE_BIT_NUMBER SYSCFG_MEMRMP_UFB_MODE_Pos
72 #define UFB_MODE_BB (uint32_t)(PERIPH_BB_BASE + (MEMRMP_OFFSET * 32U) + (UFB_MODE_BIT_NUMBER * 4U))
73 
74 /* --- CMPCR Register ---*/
75 /* Alias word address of CMP_PD bit */
76 #define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20U)
77 #define CMP_PD_BIT_NUMBER SYSCFG_CMPCR_CMP_PD_Pos
78 #define CMPCR_CMP_PD_BB (uint32_t)(PERIPH_BB_BASE + (CMPCR_OFFSET * 32U) + (CMP_PD_BIT_NUMBER * 4U))
79 
80 /* --- MCHDLYCR Register ---*/
81 /* Alias word address of BSCKSEL bit */
82 #define MCHDLYCR_OFFSET (SYSCFG_OFFSET + 0x30U)
83 #define BSCKSEL_BIT_NUMBER SYSCFG_MCHDLYCR_BSCKSEL_Pos
84 #define MCHDLYCR_BSCKSEL_BB (uint32_t)(PERIPH_BB_BASE + (MCHDLYCR_OFFSET * 32U) + (BSCKSEL_BIT_NUMBER * 4U))
85 
89 /* Private macro -------------------------------------------------------------*/
90 /* Private variables ---------------------------------------------------------*/
94 __IO uint32_t uwTick;
95 uint32_t uwTickPrio = (1UL << __NVIC_PRIO_BITS); /* Invalid PRIO */
100 /* Private function prototypes -----------------------------------------------*/
101 /* Private functions ---------------------------------------------------------*/
102 
158 {
159  /* Configure Flash prefetch, Instruction cache, Data cache */
160 #if (INSTRUCTION_CACHE_ENABLE != 0U)
162 #endif /* INSTRUCTION_CACHE_ENABLE */
163 
164 #if (DATA_CACHE_ENABLE != 0U)
166 #endif /* DATA_CACHE_ENABLE */
167 
168 #if (PREFETCH_ENABLE != 0U)
170 #endif /* PREFETCH_ENABLE */
171 
172  /* Set Interrupt Group Priority */
174 
175  /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */
177 
178  /* Init the low level hardware */
179  HAL_MspInit();
180 
181  /* Return function status */
182  return HAL_OK;
183 }
184 
191 {
192  /* Reset of all peripherals */
195 
198 
201 
204 
207 
208  /* De-Init the low level hardware */
209  HAL_MspDeInit();
210 
211  /* Return function status */
212  return HAL_OK;
213 }
214 
219 __weak void HAL_MspInit(void)
220 {
221  /* NOTE : This function should not be modified, when the callback is needed,
222  the HAL_MspInit could be implemented in the user file
223  */
224 }
225 
230 __weak void HAL_MspDeInit(void)
231 {
232  /* NOTE : This function should not be modified, when the callback is needed,
233  the HAL_MspDeInit could be implemented in the user file
234  */
235 }
236 
253 __weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
254 {
255  /* Configure the SysTick to have interrupt in 1ms time basis*/
256  if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U)
257  {
258  return HAL_ERROR;
259  }
260 
261  /* Configure the SysTick IRQ priority */
262  if (TickPriority < (1UL << __NVIC_PRIO_BITS))
263  {
264  HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U);
265  uwTickPrio = TickPriority;
266  }
267  else
268  {
269  return HAL_ERROR;
270  }
271 
272  /* Return function status */
273  return HAL_OK;
274 }
275 
312 __weak void HAL_IncTick(void)
313 {
314  uwTick += uwTickFreq;
315 }
316 
323 __weak uint32_t HAL_GetTick(void)
324 {
325  return uwTick;
326 }
327 
332 uint32_t HAL_GetTickPrio(void)
333 {
334  return uwTickPrio;
335 }
336 
342 {
343  HAL_StatusTypeDef status = HAL_OK;
344  HAL_TickFreqTypeDef prevTickFreq;
345 
346  assert_param(IS_TICKFREQ(Freq));
347 
348  if (uwTickFreq != Freq)
349  {
350  /* Back up uwTickFreq frequency */
351  prevTickFreq = uwTickFreq;
352 
353  /* Update uwTickFreq global variable used by HAL_InitTick() */
354  uwTickFreq = Freq;
355 
356  /* Apply the new tick Freq */
357  status = HAL_InitTick(uwTickPrio);
358 
359  if (status != HAL_OK)
360  {
361  /* Restore previous tick frequency */
362  uwTickFreq = prevTickFreq;
363  }
364  }
365 
366  return status;
367 }
368 
374 {
375  return uwTickFreq;
376 }
377 
389 __weak void HAL_Delay(uint32_t Delay)
390 {
391  uint32_t tickstart = HAL_GetTick();
392  uint32_t wait = Delay;
393 
394  /* Add a freq to guarantee minimum wait */
395  if (wait < HAL_MAX_DELAY)
396  {
397  wait += (uint32_t)(uwTickFreq);
398  }
399 
400  while((HAL_GetTick() - tickstart) < wait)
401  {
402  }
403 }
404 
415 __weak void HAL_SuspendTick(void)
416 {
417  /* Disable SysTick Interrupt */
419 }
420 
431 __weak void HAL_ResumeTick(void)
432 {
433  /* Enable SysTick Interrupt */
435 }
436 
441 uint32_t HAL_GetHalVersion(void)
442 {
444 }
445 
450 uint32_t HAL_GetREVID(void)
451 {
452  return((DBGMCU->IDCODE) >> 16U);
453 }
454 
459 uint32_t HAL_GetDEVID(void)
460 {
461  return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK);
462 }
463 
469 {
471 }
472 
478 {
480 }
481 
487 {
489 }
490 
496 {
498 }
499 
505 {
507 }
508 
514 {
516 }
517 
525 {
526  *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)ENABLE;
527 }
528 
536 {
537  *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)DISABLE;
538 }
539 
544 uint32_t HAL_GetUIDw0(void)
545 {
546  return (READ_REG(*((uint32_t *)UID_BASE)));
547 }
548 
553 uint32_t HAL_GetUIDw1(void)
554 {
555  return (READ_REG(*((uint32_t *)(UID_BASE + 4U))));
556 }
557 
562 uint32_t HAL_GetUIDw2(void)
563 {
564  return (READ_REG(*((uint32_t *)(UID_BASE + 8U))));
565 }
566 
567 #if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\
568  defined(STM32F469xx) || defined(STM32F479xx)
569 
579 void HAL_EnableMemorySwappingBank(void)
580 {
581  *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)ENABLE;
582 }
583 
594 void HAL_DisableMemorySwappingBank(void)
595 {
596  *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)DISABLE;
597 }
598 #endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */
599 
615 /************************ (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
DBGMCU_CR_DBG_SLEEP
#define DBGMCU_CR_DBG_SLEEP
Definition: stm32f407xx.h:12721
HAL_DBGMCU_EnableDBGStopMode
void HAL_DBGMCU_EnableDBGStopMode(void)
Enable the Debug Module during STOP mode.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:486
HAL_MspDeInit
void HAL_MspDeInit(void)
DeInitializes the MSP.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:230
__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
__HAL_FLASH_PREFETCH_BUFFER_ENABLE
#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE()
Enable the FLASH prefetch buffer.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h:191
DISABLE
@ DISABLE
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:193
HAL_GetTickPrio
uint32_t HAL_GetTickPrio(void)
This function returns a tick priority.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:332
HAL_GetTickFreq
HAL_TickFreqTypeDef HAL_GetTickFreq(void)
Return tick frequency.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:373
uwTick
__IO uint32_t uwTick
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:94
DBGMCU
#define DBGMCU
Definition: stm32f407xx.h:1140
HAL_DBGMCU_EnableDBGStandbyMode
void HAL_DBGMCU_EnableDBGStandbyMode(void)
Enable the Debug Module during STANDBY mode.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:504
HAL_ERROR
@ HAL_ERROR
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:43
SysTick_IRQn
@ SysTick_IRQn
Definition: MIMXRT1052.h:91
uwTickPrio
uint32_t uwTickPrio
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:95
CLEAR_BIT
#define CLEAR_BIT(REG, BIT)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:214
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
UFB_MODE_BB
#define UFB_MODE_BB
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:72
__HAL_FLASH_INSTRUCTION_CACHE_ENABLE
#define __HAL_FLASH_INSTRUCTION_CACHE_ENABLE()
Enable the FLASH instruction cache.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h:203
__HAL_RCC_AHB2_FORCE_RESET
#define __HAL_RCC_AHB2_FORCE_RESET()
Force or release AHB2 peripheral reset.
Definition: stm32f7xx_hal_rcc_ex.h:1776
wait
void wait(int seconds)
HAL_TICK_FREQ_DEFAULT
@ HAL_TICK_FREQ_DEFAULT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h:55
HAL_Delay
void HAL_Delay(uint32_t Delay)
This function provides minimum delay (in milliseconds) based on variable incremented.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:389
HAL_DBGMCU_DisableDBGStopMode
void HAL_DBGMCU_DisableDBGStopMode(void)
Disable the Debug Module during STOP mode.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:495
ENABLE
@ ENABLE
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:194
HAL_SuspendTick
void HAL_SuspendTick(void)
Suspend Tick increment.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:415
__HAL_RCC_AHB1_RELEASE_RESET
#define __HAL_RCC_AHB1_RELEASE_RESET()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:673
HAL_DBGMCU_EnableDBGSleepMode
void HAL_DBGMCU_EnableDBGSleepMode(void)
Enable the Debug Module during SLEEP mode.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:468
HAL_OK
@ HAL_OK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:42
SysTick_CTRL_TICKINT_Msk
#define SysTick_CTRL_TICKINT_Msk
Definition: imxrt1050/imxrt1050-evkb/CMSIS/core_cm7.h:995
HAL_DeInit
HAL_StatusTypeDef HAL_DeInit(void)
This function de-Initializes common part of the HAL and stops the systick. This function is optional.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:190
HAL_GetUIDw2
uint32_t HAL_GetUIDw2(void)
Returns third word of the unique device identifier (UID based on 96 bits)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:562
HAL_NVIC_SetPriorityGrouping
void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
HAL_GetHalVersion
uint32_t HAL_GetHalVersion(void)
Returns the HAL revision.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:441
HAL_SYSTICK_Config
uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb)
DBGMCU_CR_DBG_STANDBY
#define DBGMCU_CR_DBG_STANDBY
Definition: stm32f407xx.h:12727
__HAL_RCC_AHB2_RELEASE_RESET
#define __HAL_RCC_AHB2_RELEASE_RESET()
Definition: stm32f7xx_hal_rcc_ex.h:1780
uwTickFreq
HAL_TickFreqTypeDef uwTickFreq
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:96
HAL_MspInit
void HAL_MspInit(void)
Initialize the MSP.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:219
HAL_GetREVID
uint32_t HAL_GetREVID(void)
Returns the device revision identifier.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:450
SystemCoreClock
uint32_t SystemCoreClock
Definition: system_MIMXRT1052.c:69
DBGMCU_CR_DBG_STOP
#define DBGMCU_CR_DBG_STOP
Definition: stm32f407xx.h:12724
CMPCR_CMP_PD_BB
#define CMPCR_CMP_PD_BB
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:78
__HAL_RCC_APB1_RELEASE_RESET
#define __HAL_RCC_APB1_RELEASE_RESET()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:697
HAL_DBGMCU_DisableDBGStandbyMode
void HAL_DBGMCU_DisableDBGStandbyMode(void)
Disable the Debug Module during STANDBY mode.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:513
IDCODE_DEVID_MASK
#define IDCODE_DEVID_MASK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:64
HAL_DBGMCU_DisableDBGSleepMode
void HAL_DBGMCU_DisableDBGSleepMode(void)
Disable the Debug Module during SLEEP mode.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:477
HAL_MAX_DELAY
#define HAL_MAX_DELAY
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:61
__HAL_RCC_APB2_RELEASE_RESET
#define __HAL_RCC_APB2_RELEASE_RESET()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:723
__HAL_RCC_APB1_FORCE_RESET
#define __HAL_RCC_APB1_FORCE_RESET()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:688
__HAL_RCC_AHB3_RELEASE_RESET
#define __HAL_RCC_AHB3_RELEASE_RESET()
Definition: stm32f7xx_hal_rcc_ex.h:1814
__HAL_RCC_AHB3_FORCE_RESET
#define __HAL_RCC_AHB3_FORCE_RESET()
Force or release AHB3 peripheral reset.
Definition: stm32f7xx_hal_rcc_ex.h:1810
HAL_IncTick
void HAL_IncTick(void)
This function is called to increment a global variable "uwTick" used as application time base.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:312
HAL_Init
HAL_StatusTypeDef HAL_Init(void)
This function is used to initialize the HAL Library; it must be the first instruction to be executed ...
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:157
HAL_GetDEVID
uint32_t HAL_GetDEVID(void)
Returns the device identifier.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:459
__HAL_FLASH_DATA_CACHE_ENABLE
#define __HAL_FLASH_DATA_CACHE_ENABLE()
Enable the FLASH data cache.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h:215
__HAL_RCC_APB2_FORCE_RESET
#define __HAL_RCC_APB2_FORCE_RESET()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:713
HAL_InitTick
HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
This function configures the source of the time base. The time source is configured to have 1ms time ...
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:253
__STM32F4xx_HAL_VERSION
#define __STM32F4xx_HAL_VERSION
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:59
HAL_ResumeTick
void HAL_ResumeTick(void)
Resume Tick increment.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:431
HAL_GetUIDw1
uint32_t HAL_GetUIDw1(void)
Returns second word of the unique device identifier (UID based on 96 bits)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:553
NVIC_PRIORITYGROUP_4
#define NVIC_PRIORITYGROUP_4
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h:98
HAL_DisableCompensationCell
void HAL_DisableCompensationCell(void)
Power-down the I/O Compensation Cell.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:535
HAL_GetUIDw0
uint32_t HAL_GetUIDw0(void)
Returns first word of the unique device identifier (UID based on 96 bits)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:544
SysTick
#define SysTick
Definition: imxrt1050/imxrt1050-evkb/CMSIS/core_cm7.h:1779
UID_BASE
#define UID_BASE
Definition: stm32f407xx.h:1048
HAL_NVIC_SetPriority
void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
HAL_EnableCompensationCell
void HAL_EnableCompensationCell(void)
Enables the I/O Compensation Cell.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:524
READ_REG
#define READ_REG(REG)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:222
SET_BIT
#define SET_BIT(REG, BIT)
Definition: stm32f407/stm32f407g-disc1/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:212
HAL_TickFreqTypeDef
HAL_TickFreqTypeDef
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h:50
HAL_SetTickFreq
HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq)
Set new tick Freq.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c:341
__HAL_RCC_AHB1_FORCE_RESET
#define __HAL_RCC_AHB1_FORCE_RESET()
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h:665
TICK_INT_PRIORITY
#define TICK_INT_PRIORITY
Definition: stm32f407/stm32f407g-disc1/Inc/stm32f4xx_hal_conf.h:121
__NVIC_PRIO_BITS
#define __NVIC_PRIO_BITS
Definition: MIMXRT1052.h:266
IS_TICKFREQ
#define IS_TICKFREQ(FREQ)
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h:193


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