stm32f411e_discovery.c
Go to the documentation of this file.
1 
37 /* Includes ------------------------------------------------------------------*/
38 #include "stm32f411e_discovery.h"
39 
68 #define __STM32F411E_DISCO_BSP_VERSION_MAIN (0x01)
69 #define __STM32F411E_DISCO_BSP_VERSION_SUB1 (0x00)
70 #define __STM32F411E_DISCO_BSP_VERSION_SUB2 (0x03)
71 #define __STM32F411E_DISCO_BSP_VERSION_RC (0x00)
72 #define __STM32F411E_DISCO_BSP_VERSION ((__STM32F411E_DISCO_BSP_VERSION_MAIN << 24)\
73  |(__STM32F411E_DISCO_BSP_VERSION_SUB1 << 16)\
74  |(__STM32F411E_DISCO_BSP_VERSION_SUB2 << 8 )\
75  |(__STM32F411E_DISCO_BSP_VERSION_RC))
76 
94 
95 const uint16_t GPIO_PIN[LEDn] = {LED4_PIN,
96  LED3_PIN,
97  LED5_PIN,
98  LED6_PIN};
99 
101 const uint16_t BUTTON_PIN[BUTTONn] = {KEY_BUTTON_PIN};
103 
104 uint32_t I2cxTimeout = I2Cx_TIMEOUT_MAX; /*<! Value of Timeout when I2C communication fails */
105 uint32_t SpixTimeout = SPIx_TIMEOUT_MAX; /*<! Value of Timeout when SPI communication fails */
106 
116 /* I2Cx bus function */
117 static void I2Cx_Init(void);
118 static void I2Cx_WriteData(uint16_t Addr, uint8_t Reg, uint8_t Value);
119 static uint8_t I2Cx_ReadData(uint16_t Addr, uint8_t Reg);
120 static void I2Cx_Error (void);
121 static void I2Cx_MspInit(I2C_HandleTypeDef *hi2c);
122 
123 /* SPIx bus function */
124 static void SPIx_Init(void);
125 static uint8_t SPIx_WriteRead(uint8_t byte);
126 static void SPIx_Error (void);
127 static void SPIx_MspInit(SPI_HandleTypeDef *hspi);
128 
129 /* Link function for GYRO peripheral */
130 void GYRO_IO_Init(void);
131 void GYRO_IO_Write(uint8_t* pBuffer, uint8_t WriteAddr, uint16_t NumByteToWrite);
132 void GYRO_IO_Read(uint8_t* pBuffer, uint8_t ReadAddr, uint16_t NumByteToRead);
133 
134 /* Link functions for AUDIO */
135 void AUDIO_IO_Init(void);
136 void AUDIO_IO_DeInit(void);
137 void AUDIO_IO_Write(uint8_t Addr, uint8_t Reg, uint8_t Value);
138 uint8_t AUDIO_IO_Read(uint8_t Addr, uint8_t Reg);
139 
140 /* Link function for COMPASS / ACCELERO peripheral */
141 void COMPASSACCELERO_IO_Init(void);
142 void COMPASSACCELERO_IO_ITConfig(void);
143 void COMPASSACCELERO_IO_Write(uint16_t DeviceAddr, uint8_t RegisterAddr, uint8_t Value);
144 uint8_t COMPASSACCELERO_IO_Read(uint16_t DeviceAddr, uint8_t RegisterAddr);
157 uint32_t BSP_GetVersion(void)
158 {
160 }
161 
172 {
173  GPIO_InitTypeDef GPIO_InitStruct;
174 
175  /* Enable the GPIO_LED Clock */
177 
178  /* Configure the GPIO_LED pin */
179  GPIO_InitStruct.Pin = GPIO_PIN[Led];
180  GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
181  GPIO_InitStruct.Pull = GPIO_PULLUP;
182  GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
183 
184  HAL_GPIO_Init(GPIO_PORT[Led], &GPIO_InitStruct);
185 
187 }
188 
199 {
201 }
202 
213 {
215 }
216 
227 {
229 }
230 
242 {
243  GPIO_InitTypeDef GPIO_InitStruct;
244 
245  /* Enable the BUTTON Clock */
246  BUTTONx_GPIO_CLK_ENABLE(Button);
247 
248  if(ButtonMode == BUTTON_MODE_GPIO)
249  {
250  /* Configure Button pin as input */
251  GPIO_InitStruct.Pin = BUTTON_PIN[Button];
252  GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
253  GPIO_InitStruct.Pull = GPIO_PULLDOWN;
254  GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
255  HAL_GPIO_Init(BUTTON_PORT[Button], &GPIO_InitStruct);
256  }
257 
258  if(ButtonMode == BUTTON_MODE_EXTI)
259  {
260  /* Configure Button pin as input with External interrupt */
261  GPIO_InitStruct.Pin = BUTTON_PIN[Button];
262  GPIO_InitStruct.Pull = GPIO_NOPULL;
263  GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
264  HAL_GPIO_Init(BUTTON_PORT[Button], &GPIO_InitStruct);
265 
266  /* Enable and set Button EXTI Interrupt to the lowest priority */
267  HAL_NVIC_SetPriority((IRQn_Type)(BUTTON_IRQn[Button]), 0x0F, 0x00);
269  }
270 }
271 
279 {
280  return HAL_GPIO_ReadPin(BUTTON_PORT[Button], BUTTON_PIN[Button]);
281 }
282 
283 /*******************************************************************************
284  BUS OPERATIONS
285 *******************************************************************************/
286 
287 /******************************* I2C Routines *********************************/
288 
292 static void I2Cx_Init(void)
293 {
295  {
297  I2cHandle.Init.OwnAddress1 = 0x43;
302  I2cHandle.Init.OwnAddress2 = 0x00;
305 
306  /* Init the I2C */
309  }
310 }
311 
318 static void I2Cx_WriteData(uint16_t Addr, uint8_t Reg, uint8_t Value)
319 {
320  HAL_StatusTypeDef status = HAL_OK;
321 
322  status = HAL_I2C_Mem_Write(&I2cHandle, Addr, (uint16_t)Reg, I2C_MEMADD_SIZE_8BIT, &Value, 1, I2cxTimeout);
323 
324  /* Check the communication status */
325  if(status != HAL_OK)
326  {
327  /* Execute user timeout callback */
328  I2Cx_Error();
329  }
330 }
331 
338 static uint8_t I2Cx_ReadData(uint16_t Addr, uint8_t Reg)
339 {
340  HAL_StatusTypeDef status = HAL_OK;
341  uint8_t value = 0;
342 
343  status = HAL_I2C_Mem_Read(&I2cHandle, Addr, Reg, I2C_MEMADD_SIZE_8BIT, &value, 1, I2cxTimeout);
344 
345  /* Check the communication status */
346  if(status != HAL_OK)
347  {
348  /* Execute user timeout callback */
349  I2Cx_Error();
350  }
351  return value;
352 }
353 
357 static void I2Cx_Error(void)
358 {
359  /* De-initialize the I2C comunication BUS */
361 
362  /* Re- Initiaize the I2C comunication BUS */
363  I2Cx_Init();
364 }
365 
370 static void I2Cx_MspInit(I2C_HandleTypeDef *hi2c)
371 {
372  GPIO_InitTypeDef GPIO_InitStructure;
373 
374  /* Enable the I2C peripheral */
376 
377  /* Enable SCK and SDA GPIO clocks */
379 
380  /* I2Cx SD1 & SCK pin configuration */
381  GPIO_InitStructure.Pin = DISCOVERY_I2Cx_SDA_PIN | DISCOVERY_I2Cx_SCL_PIN;
382  GPIO_InitStructure.Mode = GPIO_MODE_AF_OD;
383  GPIO_InitStructure.Pull = GPIO_NOPULL;
384  GPIO_InitStructure.Speed = GPIO_SPEED_FAST;
385  GPIO_InitStructure.Alternate = DISCOVERY_I2Cx_AF;
386 
387  HAL_GPIO_Init(DISCOVERY_I2Cx_GPIO_PORT, &GPIO_InitStructure);
388 
389  /* Force the I2C peripheral clock reset */
391 
392  /* Release the I2C peripheral clock reset */
394 
395  /* Enable and set I2Cx Interrupt to the lowest priority */
398 
399  /* Enable and set I2Cx Interrupt to the lowest priority */
402 }
403 
404 /******************************* SPI Routines**********************************/
405 
409 static void SPIx_Init(void)
410 {
412  {
413  /* SPI Configuration */
415  /* SPI baudrate is set to 5.6 MHz (PCLK2/SPI_BaudRatePrescaler = 90/16 = 5.625 MHz)
416  to verify these constraints:
417  ILI9341 LCD SPI interface max baudrate is 10MHz for write and 6.66MHz for read
418  L3GD20 SPI interface max baudrate is 10MHz for write/read
419  PCLK2 frequency is set to 90 MHz
420  */
432 
435  }
436 }
437 
444 static uint8_t SPIx_WriteRead(uint8_t Byte)
445 {
446  uint8_t receivedbyte = 0;
447 
448  /* Send a Byte through the SPI peripheral */
449  /* Read byte from the SPI bus */
450  if(HAL_SPI_TransmitReceive(&SpiHandle, (uint8_t*) &Byte, (uint8_t*) &receivedbyte, 1, SpixTimeout) != HAL_OK)
451  {
452  SPIx_Error();
453  }
454 
455  return receivedbyte;
456 }
457 
461 static void SPIx_Error (void)
462 {
463  /* De-initialize the SPI comunication BUS */
465 
466  /* Re-Initiaize the SPI comunication BUS */
467  SPIx_Init();
468 }
469 
474 static void SPIx_MspInit(SPI_HandleTypeDef *hspi)
475 {
476  GPIO_InitTypeDef GPIO_InitStructure;
477 
478  /* Enable SPIx clock */
480 
481  /* Enable SPIx GPIO clock */
483 
484  /* Configure SPIx SCK, MOSI and MISO */
486  GPIO_InitStructure.Mode = GPIO_MODE_AF_PP;
487  GPIO_InitStructure.Pull = GPIO_PULLDOWN;
488  GPIO_InitStructure.Speed = GPIO_SPEED_MEDIUM;
489  GPIO_InitStructure.Alternate = DISCOVERY_SPIx_AF;
490  HAL_GPIO_Init(DISCOVERY_SPIx_GPIO_PORT, &GPIO_InitStructure);
491 }
492 
493 /*******************************************************************************
494  LINK OPERATIONS
495 *******************************************************************************/
496 
497 /********************************* LINK GYROSCOPE *****************************/
501 void GYRO_IO_Init(void)
502 {
503  GPIO_InitTypeDef GPIO_InitStructure;
504 
505  /* Configure the Gyroscope Control pins ------------------------------------*/
506  /* Enable CS GPIO clock and Configure GPIO PIN for Gyroscope Chip select */
508  GPIO_InitStructure.Pin = GYRO_CS_PIN;
509  GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP;
510  GPIO_InitStructure.Pull = GPIO_NOPULL;
511  GPIO_InitStructure.Speed = GPIO_SPEED_MEDIUM;
512  HAL_GPIO_Init(GYRO_CS_GPIO_PORT, &GPIO_InitStructure);
513 
514  /* Deselect : Chip Select high */
515  GYRO_CS_HIGH();
516 
517  /* Enable INT1, INT2 GPIO clock and Configure GPIO PINs to detect Interrupts */
519  GPIO_InitStructure.Pin = GYRO_INT1_PIN | GYRO_INT2_PIN;
520  GPIO_InitStructure.Mode = GPIO_MODE_INPUT;
521  GPIO_InitStructure.Speed = GPIO_SPEED_FAST;
522  GPIO_InitStructure.Pull= GPIO_NOPULL;
523  HAL_GPIO_Init(GYRO_INT_GPIO_PORT, &GPIO_InitStructure);
524 
525  SPIx_Init();
526 }
527 
534 void GYRO_IO_Write(uint8_t* pBuffer, uint8_t WriteAddr, uint16_t NumByteToWrite)
535 {
536  /* Configure the MS bit:
537  - When 0, the address will remain unchanged in multiple read/write commands.
538  - When 1, the address will be auto incremented in multiple read/write commands.
539  */
540  if(NumByteToWrite > 0x01)
541  {
542  WriteAddr |= (uint8_t)MULTIPLEBYTE_CMD;
543  }
544  /* Set chip select Low at the start of the transmission */
545  GYRO_CS_LOW();
546 
547  /* Send the Address of the indexed register */
548  SPIx_WriteRead(WriteAddr);
549 
550  /* Send the data that will be written into the device (MSB First) */
551  while(NumByteToWrite >= 0x01)
552  {
553  SPIx_WriteRead(*pBuffer);
554  NumByteToWrite--;
555  pBuffer++;
556  }
557 
558  /* Set chip select High at the end of the transmission */
559  GYRO_CS_HIGH();
560 }
561 
568 void GYRO_IO_Read(uint8_t* pBuffer, uint8_t ReadAddr, uint16_t NumByteToRead)
569 {
570  if(NumByteToRead > 0x01)
571  {
572  ReadAddr |= (uint8_t)(READWRITE_CMD | MULTIPLEBYTE_CMD);
573  }
574  else
575  {
576  ReadAddr |= (uint8_t)READWRITE_CMD;
577  }
578 
579  /* Set chip select Low at the start of the transmission */
580  GYRO_CS_LOW();
581 
582  /* Send the Address of the indexed register */
583  SPIx_WriteRead(ReadAddr);
584 
585  /* Receive the data that will be read from the device (MSB First) */
586  while(NumByteToRead > 0x00)
587  {
588  /* Send dummy byte (0x00) to generate the SPI clock to GYRO (Slave device) */
589  *pBuffer = SPIx_WriteRead(DUMMY_BYTE);
590  NumByteToRead--;
591  pBuffer++;
592  }
593 
594  /* Set chip select High at the end of the transmission */
595  GYRO_CS_HIGH();
596 }
597 
598 /********************************* LINK AUDIO *********************************/
599 
603 void AUDIO_IO_Init(void)
604 {
605  GPIO_InitTypeDef GPIO_InitStruct;
606 
607  /* Enable Reset GPIO Clock */
609 
610  /* Audio reset pin configuration -------------------------------------------*/
611  GPIO_InitStruct.Pin = AUDIO_RESET_PIN;
612  GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
613  GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
614  GPIO_InitStruct.Pull = GPIO_NOPULL;
615  HAL_GPIO_Init(AUDIO_RESET_GPIO, &GPIO_InitStruct);
616 
617  I2Cx_Init();
618 
619  /* Power Down the codec */
621 
622  /* Wait for a delay to insure registers erasing */
623  HAL_Delay(5);
624 
625  /* Power on the codec */
627 
628  /* Wait for a delay to insure registers erasing */
629  HAL_Delay(5);
630 }
631 
635 void AUDIO_IO_DeInit(void)
636 {
637 
638 }
639 
646 void AUDIO_IO_Write (uint8_t Addr, uint8_t Reg, uint8_t Value)
647 {
648  I2Cx_WriteData(Addr, Reg, Value);
649 }
650 
657 uint8_t AUDIO_IO_Read (uint8_t Addr, uint8_t Reg)
658 {
659  return I2Cx_ReadData(Addr, Reg);
660 }
661 
662 /****************************** LINK ACCELEROMETER ****************************/
663 
668 {
669  GPIO_InitTypeDef GPIO_InitStructure;
670 
671  /* Enable DRDY clock */
673 
674  /* MEMS DRDY pin configuration */
675  GPIO_InitStructure.Pin = ACCELERO_DRDY_PIN;
676  GPIO_InitStructure.Mode = GPIO_MODE_INPUT;
677  GPIO_InitStructure.Pull = GPIO_NOPULL;
678  GPIO_InitStructure.Speed = GPIO_SPEED_FAST;
679  HAL_GPIO_Init(ACCELERO_DRDY_GPIO_PORT, &GPIO_InitStructure);
680 
681  I2Cx_Init();
682 }
683 
688 {
689  GPIO_InitTypeDef GPIO_InitStructure;
690 
691  /* Enable INT1 and INT2 GPIO clock */
693 
694  /* Configure GPIO PINs to detect Interrupts */
695  GPIO_InitStructure.Pin = ACCELERO_INT1_PIN | ACCELERO_INT2_PIN;
696  GPIO_InitStructure.Mode = GPIO_MODE_IT_RISING;
697  GPIO_InitStructure.Speed = GPIO_SPEED_FAST;
698  GPIO_InitStructure.Pull = GPIO_NOPULL;
699  HAL_GPIO_Init(ACCELERO_INT_GPIO_PORT, &GPIO_InitStructure);
700 
701  /* Enable and set COMPASS / ACCELERO Interrupt to the lowest priority */
704 }
705 
712 void COMPASSACCELERO_IO_Write(uint16_t DeviceAddr, uint8_t RegisterAddr, uint8_t Value)
713 {
714  /* Call I2Cx Read data bus function */
715  I2Cx_WriteData(DeviceAddr, RegisterAddr, Value);
716 }
717 
724 uint8_t COMPASSACCELERO_IO_Read(uint16_t DeviceAddr, uint8_t RegisterAddr)
725 {
726  /* Call I2Cx Read data bus function */
727  return I2Cx_ReadData(DeviceAddr, RegisterAddr);
728 }
729 
746 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
CODEC_AUDIO_POWER_OFF
#define CODEC_AUDIO_POWER_OFF()
Definition: stm32f411e_discovery.h:239
I2Cx_MspInit
static void I2Cx_MspInit(I2C_HandleTypeDef *hi2c)
I2Cx MSP Init.
Definition: stm32f411e_discovery.c:370
HAL_I2C_Init
HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c)
__SPI_HandleTypeDef::Init
SPI_InitTypeDef Init
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:109
GPIO_MODE_AF_PP
#define GPIO_MODE_AF_PP
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:122
HAL_StatusTypeDef
HAL_StatusTypeDef
HAL Status structures definition
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:40
SPI_InitTypeDef::BaudRatePrescaler
uint32_t BaudRatePrescaler
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:68
HAL_I2C_GetState
HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c)
I2C_InitTypeDef::OwnAddress1
uint32_t OwnAddress1
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:56
SPIx_MspInit
static void SPIx_MspInit(SPI_HandleTypeDef *hspi)
SPI MSP Init.
Definition: stm32f411e_discovery.c:474
HAL_NVIC_EnableIRQ
void HAL_NVIC_EnableIRQ(IRQn_Type IRQn)
I2C_InitTypeDef::AddressingMode
uint32_t AddressingMode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:59
SPIx_Error
static void SPIx_Error(void)
SPIx error treatment function.
Definition: stm32f411e_discovery.c:461
SPI_InitTypeDef::CLKPhase
uint32_t CLKPhase
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:61
BUTTON_MODE_GPIO
@ BUTTON_MODE_GPIO
Definition: stm32f4_discovery.h:78
SPI_BAUDRATEPRESCALER_8
#define SPI_BAUDRATEPRESCALER_8
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:265
DISCOVERY_I2Cx_GPIO_PORT
#define DISCOVERY_I2Cx_GPIO_PORT
Definition: stm32f411e_discovery.h:168
SPI_InitTypeDef::NSS
uint32_t NSS
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:64
GPIO_InitTypeDef
GPIO Init structure definition
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:47
DISCOVERY_I2Cx_AF
#define DISCOVERY_I2Cx_AF
Definition: stm32f411e_discovery.h:173
GYRO_IO_Init
void GYRO_IO_Init(void)
Configures the GYRO SPI interface.
Definition: stm32f411e_discovery.c:501
I2Cx_MAX_COMMUNICATION_FREQ
#define I2Cx_MAX_COMMUNICATION_FREQ
Definition: stm32f411e_discovery.h:184
BUTTONx_GPIO_CLK_ENABLE
#define BUTTONx_GPIO_CLK_ENABLE(__INDEX__)
Definition: stm32f4_discovery.h:150
LED6_PIN
#define LED6_PIN
Definition: stm32f4_discovery.h:116
I2C_InitTypeDef::OwnAddress2
uint32_t OwnAddress2
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:65
SPI_MODE_MASTER
#define SPI_MODE_MASTER
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:208
DISCOVERY_I2Cx_SDA_PIN
#define DISCOVERY_I2Cx_SDA_PIN
Definition: stm32f4_discovery.h:195
SPI_PHASE_1EDGE
#define SPI_PHASE_1EDGE
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:244
COMPASSACCELERO_IO_ITConfig
void COMPASSACCELERO_IO_ITConfig(void)
Configures COMPASS / ACCELERO click IT.
Definition: stm32f411e_discovery.c:687
GYRO_CS_LOW
#define GYRO_CS_LOW()
Definition: stm32f411e_discovery.h:212
LEDx_GPIO_CLK_ENABLE
#define LEDx_GPIO_CLK_ENABLE(__INDEX__)
Definition: stm32f4_discovery.h:121
GPIO_InitTypeDef::Alternate
uint32_t Alternate
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:61
COMPASSACCELERO_IO_Read
uint8_t COMPASSACCELERO_IO_Read(uint16_t DeviceAddr, uint8_t RegisterAddr)
Reads a block of data from the COMPASS / ACCELERO.
Definition: stm32f411e_discovery.c:724
__SPI_HandleTypeDef
SPI handle Structure definition.
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:105
DISCOVERY_I2Cx_EV_IRQn
#define DISCOVERY_I2Cx_EV_IRQn
Definition: stm32f4_discovery.h:201
LED4_PIN
#define LED4_PIN
Definition: stm32f4_discovery.h:101
SPI_InitTypeDef::FirstBit
uint32_t FirstBit
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:74
I2C_ADDRESSINGMODE_7BIT
#define I2C_ADDRESSINGMODE_7BIT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:299
__STM32F411E_DISCO_BSP_VERSION
#define __STM32F411E_DISCO_BSP_VERSION
Definition: stm32f411e_discovery.c:72
BSP_PB_GetState
uint32_t BSP_PB_GetState(Button_TypeDef Button)
Returns the selected Button state.
Definition: stm32f411e_discovery.c:278
I2C_InitTypeDef::DualAddressMode
uint32_t DualAddressMode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:62
I2C_NOSTRETCH_DISABLED
#define I2C_NOSTRETCH_DISABLED
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h:830
GPIO_PIN_SET
@ GPIO_PIN_SET
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:71
LED5_PIN
#define LED5_PIN
Definition: stm32f4_discovery.h:111
GYRO_CS_GPIO_PORT
#define GYRO_CS_GPIO_PORT
GYRO SPI Interface pins.
Definition: stm32f411e_discovery.h:218
DISCOVERY_SPIx
#define DISCOVERY_SPIx
Definition: stm32f4_discovery.h:164
HAL_I2C_STATE_RESET
@ HAL_I2C_STATE_RESET
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:109
DISCOVERY_I2Cx
#define DISCOVERY_I2Cx
Definition: stm32f4_discovery.h:189
I2C_DUTYCYCLE_2
#define I2C_DUTYCYCLE_2
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:290
SpixTimeout
uint32_t SpixTimeout
Definition: stm32f411e_discovery.c:105
DISCOVERY_SPIx_SCK_PIN
#define DISCOVERY_SPIx_SCK_PIN
Definition: stm32f4_discovery.h:170
SPI_TIMODE_DISABLED
#define SPI_TIMODE_DISABLED
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h:1106
HAL_I2C_Mem_Write
HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
BSP_LED_Off
void BSP_LED_Off(Led_TypeDef Led)
Turns selected LED Off.
Definition: stm32f411e_discovery.c:212
GYRO_IO_Read
void GYRO_IO_Read(uint8_t *pBuffer, uint8_t ReadAddr, uint16_t NumByteToRead)
Reads a block of data from the GYRO.
Definition: stm32f411e_discovery.c:568
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
BUTTON_MODE_EXTI
@ BUTTON_MODE_EXTI
Definition: stm32f4_discovery.h:79
I2C_InitTypeDef::NoStretchMode
uint32_t NoStretchMode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:71
KEY_BUTTON_GPIO_PORT
#define KEY_BUTTON_GPIO_PORT
Definition: stm32f4_discovery.h:145
AUDIO_RESET_PIN
#define AUDIO_RESET_PIN
Definition: stm32f4_discovery.h:251
HAL_GPIO_ReadPin
GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
__SPI_HandleTypeDef::Instance
SPI_TypeDef * Instance
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:107
ButtonMode_TypeDef
ButtonMode_TypeDef
Definition: stm32f4_discovery.h:76
LED4_GPIO_PORT
#define LED4_GPIO_PORT
Definition: stm32f4_discovery.h:102
GYRO_INT1_PIN
#define GYRO_INT1_PIN
Definition: stm32f411e_discovery.h:226
HAL_OK
@ HAL_OK
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:42
LED3_GPIO_PORT
#define LED3_GPIO_PORT
Definition: stm32f4_discovery.h:107
BSP_GetVersion
uint32_t BSP_GetVersion(void)
This method returns the STM32F411 DISCO BSP Driver revision.
Definition: stm32f411e_discovery.c:157
BUTTON_PIN
const uint16_t BUTTON_PIN[BUTTONn]
Definition: stm32f411e_discovery.c:101
HAL_GPIO_Init
void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init)
DISCOVERY_SPIx_CLOCK_ENABLE
#define DISCOVERY_SPIx_CLOCK_ENABLE()
Definition: stm32f411e_discovery.h:188
GPIO_InitTypeDef::Mode
uint32_t Mode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:52
AUDIO_RESET_GPIO
#define AUDIO_RESET_GPIO
Definition: stm32f4_discovery.h:252
BUTTON_PORT
GPIO_TypeDef * BUTTON_PORT[BUTTONn]
Definition: stm32f411e_discovery.c:100
COMPASSACCELERO_IO_Write
void COMPASSACCELERO_IO_Write(uint16_t DeviceAddr, uint8_t RegisterAddr, uint8_t Value)
Writes one byte to the COMPASS / ACCELERO.
Definition: stm32f411e_discovery.c:712
BSP_LED_Toggle
void BSP_LED_Toggle(Led_TypeDef Led)
Toggles the selected LED.
Definition: stm32f411e_discovery.c:226
I2C_InitTypeDef::DutyCycle
uint32_t DutyCycle
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:53
GPIO_InitTypeDef::Pull
uint32_t Pull
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:55
SPI_DIRECTION_2LINES
#define SPI_DIRECTION_2LINES
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:216
GPIO_NOPULL
#define GPIO_NOPULL
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:154
LED5_GPIO_PORT
#define LED5_GPIO_PORT
Definition: stm32f4_discovery.h:112
READWRITE_CMD
#define READWRITE_CMD
Definition: stm32f4_discovery.h:214
AUDIO_IO_Write
void AUDIO_IO_Write(uint8_t Addr, uint8_t Reg, uint8_t Value)
Writes a single data.
Definition: stm32f411e_discovery.c:646
AUDIO_RESET_GPIO_CLK_ENABLE
#define AUDIO_RESET_GPIO_CLK_ENABLE()
Definition: stm32f4_discovery.h:250
COMPASSACCELERO_IO_Init
void COMPASSACCELERO_IO_Init(void)
Configures COMPASS / ACCELERO I2C interface.
Definition: stm32f411e_discovery.c:667
SPI_InitTypeDef::Mode
uint32_t Mode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:49
IRQn_Type
IRQn_Type
STM32F4XX Interrupt Number Definition, according to the selected device in Library_configuration_sect...
Definition: stm32f407xx.h:66
GYRO_CS_HIGH
#define GYRO_CS_HIGH()
Definition: stm32f411e_discovery.h:213
ACCELERO_INT_GPIO_PORT
#define ACCELERO_INT_GPIO_PORT
Definition: stm32f4_discovery.h:231
BSP_LED_On
void BSP_LED_On(Led_TypeDef Led)
Turns selected LED On.
Definition: stm32f411e_discovery.c:198
GYRO_IO_Write
void GYRO_IO_Write(uint8_t *pBuffer, uint8_t WriteAddr, uint16_t NumByteToWrite)
Writes one byte to the GYRO.
Definition: stm32f411e_discovery.c:534
HAL_SPI_STATE_RESET
@ HAL_SPI_STATE_RESET
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:92
KEY_BUTTON_EXTI_IRQn
#define KEY_BUTTON_EXTI_IRQn
Definition: stm32f4_discovery.h:148
DISCOVERY_I2Cx_FORCE_RESET
#define DISCOVERY_I2Cx_FORCE_RESET()
Definition: stm32f4_discovery.h:197
GPIO_InitTypeDef::Speed
uint32_t Speed
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:58
SPI_FIRSTBIT_MSB
#define SPI_FIRSTBIT_MSB
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:278
DISCOVERY_I2Cx_GPIO_CLK_ENABLE
#define DISCOVERY_I2Cx_GPIO_CLK_ENABLE()
Definition: stm32f411e_discovery.h:171
I2C_MEMADD_SIZE_8BIT
#define I2C_MEMADD_SIZE_8BIT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:335
DISCOVERY_I2Cx_ER_IRQn
#define DISCOVERY_I2Cx_ER_IRQn
Definition: stm32f4_discovery.h:202
GPIO_PULLUP
#define GPIO_PULLUP
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:155
SPI_CRCCALCULATION_DISABLED
#define SPI_CRCCALCULATION_DISABLED
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h:1109
LED3_PIN
#define LED3_PIN
Definition: stm32f4_discovery.h:106
GPIO_PIN_RESET
@ GPIO_PIN_RESET
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:70
SPI_POLARITY_LOW
#define SPI_POLARITY_LOW
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:235
HAL_SPI_GetState
HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi)
DISCOVERY_I2Cx_SCL_PIN
#define DISCOVERY_I2Cx_SCL_PIN
Definition: stm32f4_discovery.h:194
I2Cx_ReadData
static uint8_t I2Cx_ReadData(uint16_t Addr, uint8_t Reg)
Reads a register of the device through BUS.
Definition: stm32f411e_discovery.c:338
KEY_BUTTON_PIN
#define KEY_BUTTON_PIN
Wakeup push-button.
Definition: stm32f4_discovery.h:144
I2C_InitTypeDef::GeneralCallMode
uint32_t GeneralCallMode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:68
AUDIO_IO_DeInit
void AUDIO_IO_DeInit(void)
DeInitializes Audio low level.
Definition: stm32f411e_discovery.c:635
Button_TypeDef
Button_TypeDef
Definition: stm32f4_discovery.h:71
DISCOVERY_I2Cx_RELEASE_RESET
#define DISCOVERY_I2Cx_RELEASE_RESET()
Definition: stm32f4_discovery.h:198
I2Cx_WriteData
static void I2Cx_WriteData(uint16_t Addr, uint8_t Reg, uint8_t Value)
Writes a value in a register of the device through BUS.
Definition: stm32f411e_discovery.c:318
SPI_InitTypeDef::CLKPolarity
uint32_t CLKPolarity
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:58
DISCOVERY_SPIx_GPIO_PORT
#define DISCOVERY_SPIx_GPIO_PORT
Definition: stm32f4_discovery.h:166
GPIO_TypeDef
General Purpose I/O.
Definition: stm32f407xx.h:527
GYRO_INT_GPIO_CLK_ENABLE
#define GYRO_INT_GPIO_CLK_ENABLE()
Definition: stm32f411e_discovery.h:224
DISCOVERY_I2Cx_CLOCK_ENABLE
#define DISCOVERY_I2Cx_CLOCK_ENABLE()
Definition: stm32f411e_discovery.h:167
I2C_HandleTypeDef::Init
I2C_InitTypeDef Init
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:193
LED6_GPIO_PORT
#define LED6_GPIO_PORT
Definition: stm32f4_discovery.h:117
DISCOVERY_SPIx_GPIO_CLK_ENABLE
#define DISCOVERY_SPIx_GPIO_CLK_ENABLE()
Definition: stm32f4_discovery.h:168
GPIO_MODE_AF_OD
#define GPIO_MODE_AF_OD
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:123
I2Cx_TIMEOUT_MAX
#define I2Cx_TIMEOUT_MAX
Definition: stm32f4_discovery.h:209
I2C_GENERALCALL_DISABLED
#define I2C_GENERALCALL_DISABLED
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h:828
CODEC_AUDIO_POWER_ON
#define CODEC_AUDIO_POWER_ON()
Definition: stm32f411e_discovery.h:240
BUTTON_IRQn
const uint8_t BUTTON_IRQn[BUTTONn]
Definition: stm32f411e_discovery.c:102
SPI_NSS_SOFT
#define SPI_NSS_SOFT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:253
Led_TypeDef
Led_TypeDef
Definition: stm32f4_discovery.h:63
GPIO_MODE_IT_RISING
#define GPIO_MODE_IT_RISING
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:127
BUTTONn
@ BUTTONn
Definition: stm32h747i_discovery.h:75
SPI_InitTypeDef::CRCPolynomial
uint32_t CRCPolynomial
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:83
I2C_HandleTypeDef
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:188
SpiHandle
static SPI_HandleTypeDef SpiHandle
Definition: stm32f411e_discovery.c:108
GPIO_PULLDOWN
#define GPIO_PULLDOWN
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:156
GPIO_PIN
const uint16_t GPIO_PIN[LEDn]
Definition: stm32f411e_discovery.c:95
BSP_LED_Init
void BSP_LED_Init(Led_TypeDef Led)
Configures LED GPIO.
Definition: stm32f411e_discovery.c:171
ACCELERO_DRDY_GPIO_PORT
#define ACCELERO_DRDY_GPIO_PORT
ACCELERO I2C1 Interface pins.
Definition: stm32f411e_discovery.h:254
SPI_DATASIZE_8BIT
#define SPI_DATASIZE_8BIT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:226
ACCELERO_INT2_PIN
#define ACCELERO_INT2_PIN
Definition: stm32f4_discovery.h:236
GPIO_PORT
GPIO_TypeDef * GPIO_PORT[LEDn]
Definition: stm32f411e_discovery.c:90
ACCELERO_INT1_EXTI_IRQn
#define ACCELERO_INT1_EXTI_IRQn
Definition: stm32f4_discovery.h:235
HAL_NVIC_SetPriority
void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
MULTIPLEBYTE_CMD
#define MULTIPLEBYTE_CMD
Definition: stm32f4_discovery.h:216
I2C_InitTypeDef::ClockSpeed
uint32_t ClockSpeed
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:50
SPI_InitTypeDef::DataSize
uint32_t DataSize
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:55
I2Cx_Error
static void I2Cx_Error(void)
I2Cx error treatment function.
Definition: stm32f411e_discovery.c:357
DUMMY_BYTE
#define DUMMY_BYTE
Definition: stm32f4_discovery.h:218
GYRO_INT2_PIN
#define GYRO_INT2_PIN
Definition: stm32f411e_discovery.h:228
GPIO_MODE_OUTPUT_PP
#define GPIO_MODE_OUTPUT_PP
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:120
HAL_I2C_Mem_Read
HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
HAL_GPIO_TogglePin
void HAL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
SPI_InitTypeDef::TIMode
uint32_t TIMode
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:77
BSP_PB_Init
void BSP_PB_Init(Button_TypeDef Button, ButtonMode_TypeDef ButtonMode)
Configures Button GPIO and EXTI Line.
Definition: stm32f411e_discovery.c:241
I2C_HandleTypeDef::Instance
I2C_TypeDef * Instance
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h:191
stm32f411e_discovery.h
This file contains definitions for STM32F401-Discovery Kit's Leds and push-button hardware resources.
GYRO_INT_GPIO_PORT
#define GYRO_INT_GPIO_PORT
Definition: stm32f411e_discovery.h:223
DISCOVERY_SPIx_AF
#define DISCOVERY_SPIx_AF
Definition: stm32f4_discovery.h:167
GYRO_CS_GPIO_CLK_ENABLE
#define GYRO_CS_GPIO_CLK_ENABLE()
Definition: stm32f411e_discovery.h:219
DISCOVERY_SPIx_MOSI_PIN
#define DISCOVERY_SPIx_MOSI_PIN
Definition: stm32f4_discovery.h:172
ACCELERO_DRDY_PIN
#define ACCELERO_DRDY_PIN
Definition: stm32f411e_discovery.h:257
I2C_DUALADDRESS_DISABLED
#define I2C_DUALADDRESS_DISABLED
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h:826
ACCELERO_INT_GPIO_CLK_ENABLE
#define ACCELERO_INT_GPIO_CLK_ENABLE()
Definition: stm32f4_discovery.h:232
GPIO_MODE_INPUT
#define GPIO_MODE_INPUT
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:119
HAL_SPI_DeInit
HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi)
ACCELERO_DRDY_GPIO_CLK_ENABLE
#define ACCELERO_DRDY_GPIO_CLK_ENABLE()
Definition: stm32f411e_discovery.h:255
SPI_InitTypeDef::Direction
uint32_t Direction
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:52
SPI_InitTypeDef::CRCCalculation
uint32_t CRCCalculation
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h:80
AUDIO_IO_Init
void AUDIO_IO_Init(void)
Initializes Audio low level.
Definition: stm32f411e_discovery.c:603
HAL_SPI_TransmitReceive
HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout)
AUDIO_IO_Read
uint8_t AUDIO_IO_Read(uint8_t Addr, uint8_t Reg)
Reads a single data.
Definition: stm32f411e_discovery.c:657
DISCOVERY_SPIx_MISO_PIN
#define DISCOVERY_SPIx_MISO_PIN
Definition: stm32f4_discovery.h:171
I2cHandle
static I2C_HandleTypeDef I2cHandle
Definition: stm32f411e_discovery.c:107
LEDn
@ LEDn
Definition: stm32h747i_discovery.h:69
SPIx_WriteRead
static uint8_t SPIx_WriteRead(uint8_t byte)
Sends a Byte through the SPI interface and return the Byte received from the SPI bus.
Definition: stm32f411e_discovery.c:444
ACCELERO_INT1_PIN
#define ACCELERO_INT1_PIN
Definition: stm32f4_discovery.h:234
HAL_I2C_DeInit
HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c)
I2Cx_Init
static void I2Cx_Init(void)
I2Cx Bus initialization.
Definition: stm32f411e_discovery.c:292
HAL_GPIO_WritePin
void HAL_GPIO_WritePin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState)
GYRO_CS_PIN
#define GYRO_CS_PIN
Definition: stm32f411e_discovery.h:221
SPIx_Init
static void SPIx_Init(void)
SPIx Bus initialization.
Definition: stm32f411e_discovery.c:409
SPIx_TIMEOUT_MAX
#define SPIx_TIMEOUT_MAX
Definition: stm32f4_discovery.h:179
I2cxTimeout
uint32_t I2cxTimeout
Definition: stm32f411e_discovery.c:104
GPIO_InitTypeDef::Pin
uint32_t Pin
Definition: stm32f407/stm32f407g-disc1/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h:49
HAL_SPI_Init
HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi)


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