STM32F429I-Discovery BSP User Manual
|
stm32f429i_discovery.c
Go to the documentation of this file.
00001 /** 00002 ****************************************************************************** 00003 * @file stm32f429i_discovery.c 00004 * @author MCD Application Team 00005 * @version V2.1.5 00006 * @date 27-January-2017 00007 * @brief This file provides set of firmware functions to manage Leds and 00008 * push-button available on STM32F429I-Discovery Kit from STMicroelectronics. 00009 ****************************************************************************** 00010 * @attention 00011 * 00012 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2> 00013 * 00014 * Redistribution and use in source and binary forms, with or without modification, 00015 * are permitted provided that the following conditions are met: 00016 * 1. Redistributions of source code must retain the above copyright notice, 00017 * this list of conditions and the following disclaimer. 00018 * 2. Redistributions in binary form must reproduce the above copyright notice, 00019 * this list of conditions and the following disclaimer in the documentation 00020 * and/or other materials provided with the distribution. 00021 * 3. Neither the name of STMicroelectronics nor the names of its contributors 00022 * may be used to endorse or promote products derived from this software 00023 * without specific prior written permission. 00024 * 00025 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00026 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00027 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00028 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00029 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00030 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00031 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00033 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00034 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 ****************************************************************************** 00037 */ 00038 00039 /* Includes ------------------------------------------------------------------*/ 00040 #include "stm32f429i_discovery.h" 00041 00042 /** @defgroup BSP BSP 00043 * @{ 00044 */ 00045 00046 /** @defgroup STM32F429I_DISCOVERY STM32F429I DISCOVERY 00047 * @{ 00048 */ 00049 00050 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL STM32F429I DISCOVERY LOW LEVEL 00051 * @brief This file provides set of firmware functions to manage Leds and push-button 00052 * available on STM32F429I-Discovery Kit from STMicroelectronics. 00053 * @{ 00054 */ 00055 00056 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL_Private_TypesDefinitions STM32F429I DISCOVERY LOW LEVEL Private TypesDefinitions 00057 * @{ 00058 */ 00059 /** 00060 * @} 00061 */ 00062 00063 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL_Private_Defines STM32F429I DISCOVERY LOW LEVEL Private Defines 00064 * @{ 00065 */ 00066 00067 /** 00068 * @brief STM32F429I DISCO BSP Driver version number V2.1.5 00069 */ 00070 #define __STM32F429I_DISCO_BSP_VERSION_MAIN (0x02) /*!< [31:24] main version */ 00071 #define __STM32F429I_DISCO_BSP_VERSION_SUB1 (0x01) /*!< [23:16] sub1 version */ 00072 #define __STM32F429I_DISCO_BSP_VERSION_SUB2 (0x05) /*!< [15:8] sub2 version */ 00073 #define __STM32F429I_DISCO_BSP_VERSION_RC (0x00) /*!< [7:0] release candidate */ 00074 #define __STM32F429I_DISCO_BSP_VERSION ((__STM32F429I_DISCO_BSP_VERSION_MAIN << 24)\ 00075 |(__STM32F429I_DISCO_BSP_VERSION_SUB1 << 16)\ 00076 |(__STM32F429I_DISCO_BSP_VERSION_SUB2 << 8 )\ 00077 |(__STM32F429I_DISCO_BSP_VERSION_RC)) 00078 /** 00079 * @} 00080 */ 00081 00082 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL_Private_Macros STM32F429I DISCOVERY LOW LEVEL Private Macros 00083 * @{ 00084 */ 00085 /** 00086 * @} 00087 */ 00088 00089 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL_Private_Variables STM32F429I DISCOVERY LOW LEVEL Private Variables 00090 * @{ 00091 */ 00092 GPIO_TypeDef* GPIO_PORT[LEDn] = {LED3_GPIO_PORT, 00093 LED4_GPIO_PORT}; 00094 00095 const uint16_t GPIO_PIN[LEDn] = {LED3_PIN, 00096 LED4_PIN}; 00097 00098 GPIO_TypeDef* BUTTON_PORT[BUTTONn] = {KEY_BUTTON_GPIO_PORT}; 00099 const uint16_t BUTTON_PIN[BUTTONn] = {KEY_BUTTON_PIN}; 00100 const uint8_t BUTTON_IRQn[BUTTONn] = {KEY_BUTTON_EXTI_IRQn}; 00101 00102 uint32_t I2cxTimeout = I2Cx_TIMEOUT_MAX; /*<! Value of Timeout when I2C communication fails */ 00103 uint32_t SpixTimeout = SPIx_TIMEOUT_MAX; /*<! Value of Timeout when SPI communication fails */ 00104 00105 I2C_HandleTypeDef I2cHandle; 00106 static SPI_HandleTypeDef SpiHandle; 00107 static uint8_t Is_LCD_IO_Initialized = 0; 00108 00109 /** 00110 * @} 00111 */ 00112 00113 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL_Private_FunctionPrototypes STM32F429I DISCOVERY LOW LEVEL Private FunctionPrototypes 00114 * @{ 00115 */ 00116 /* I2Cx bus function */ 00117 static void I2Cx_Init(void); 00118 static void I2Cx_ITConfig(void); 00119 static void I2Cx_WriteData(uint8_t Addr, uint8_t Reg, uint8_t Value); 00120 static void I2Cx_WriteBuffer(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length); 00121 static uint8_t I2Cx_ReadData(uint8_t Addr, uint8_t Reg); 00122 static uint8_t I2Cx_ReadBuffer(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length); 00123 static void I2Cx_Error(void); 00124 static void I2Cx_MspInit(I2C_HandleTypeDef *hi2c); 00125 #ifdef EE_M24LR64 00126 static HAL_StatusTypeDef I2Cx_WriteBufferDMA(uint8_t Addr, uint16_t Reg, uint8_t *pBuffer, uint16_t Length); 00127 static HAL_StatusTypeDef I2Cx_ReadBufferDMA(uint8_t Addr, uint16_t Reg, uint8_t *pBuffer, uint16_t Length); 00128 static HAL_StatusTypeDef I2Cx_IsDeviceReady(uint16_t DevAddress, uint32_t Trials); 00129 #endif /* EE_M24LR64 */ 00130 00131 /* SPIx bus function */ 00132 static void SPIx_Init(void); 00133 static void SPIx_Write(uint16_t Value); 00134 static uint32_t SPIx_Read(uint8_t ReadSize); 00135 static uint8_t SPIx_WriteRead(uint8_t Byte); 00136 static void SPIx_Error(void); 00137 static void SPIx_MspInit(SPI_HandleTypeDef *hspi); 00138 00139 /* Link function for LCD peripheral */ 00140 void LCD_IO_Init(void); 00141 void LCD_IO_WriteData(uint16_t RegValue); 00142 void LCD_IO_WriteReg(uint8_t Reg); 00143 uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize); 00144 void LCD_Delay(uint32_t delay); 00145 00146 /* IOExpander IO functions */ 00147 void IOE_Init(void); 00148 void IOE_ITConfig(void); 00149 void IOE_Delay(uint32_t Delay); 00150 void IOE_Write(uint8_t Addr, uint8_t Reg, uint8_t Value); 00151 uint8_t IOE_Read(uint8_t Addr, uint8_t Reg); 00152 uint16_t IOE_ReadMultiple(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length); 00153 void IOE_WriteMultiple(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length); 00154 00155 /* Link function for GYRO peripheral */ 00156 void GYRO_IO_Init(void); 00157 void GYRO_IO_Write(uint8_t* pBuffer, uint8_t WriteAddr, uint16_t NumByteToWrite); 00158 void GYRO_IO_Read(uint8_t* pBuffer, uint8_t ReadAddr, uint16_t NumByteToRead); 00159 00160 #ifdef EE_M24LR64 00161 /* Link function for I2C EEPROM peripheral */ 00162 void EEPROM_IO_Init(void); 00163 HAL_StatusTypeDef EEPROM_IO_WriteData(uint16_t DevAddress, uint16_t MemAddress, uint8_t* pBuffer, uint32_t BufferSize); 00164 HAL_StatusTypeDef EEPROM_IO_ReadData(uint16_t DevAddress, uint16_t MemAddress, uint8_t* pBuffer, uint32_t BufferSize); 00165 HAL_StatusTypeDef EEPROM_IO_IsDeviceReady(uint16_t DevAddress, uint32_t Trials); 00166 #endif /* EE_M24LR64 */ 00167 00168 /** 00169 * @} 00170 */ 00171 00172 /** @defgroup STM32F429I_DISCOVERY_LOW_LEVEL_Private_Functions STM32F429I DISCOVERY LOW LEVEL Private Functions 00173 * @{ 00174 */ 00175 00176 /** 00177 * @brief This method returns the STM32F429I DISCO BSP Driver revision 00178 * @retval version: 0xXYZR (8bits for each decimal, R for RC) 00179 */ 00180 uint32_t BSP_GetVersion(void) 00181 { 00182 return __STM32F429I_DISCO_BSP_VERSION; 00183 } 00184 00185 /** 00186 * @brief Configures LED GPIO. 00187 * @param Led: Specifies the Led to be configured. 00188 * This parameter can be one of following parameters: 00189 * @arg LED3 00190 * @arg LED4 00191 */ 00192 void BSP_LED_Init(Led_TypeDef Led) 00193 { 00194 GPIO_InitTypeDef GPIO_InitStruct; 00195 00196 /* Enable the GPIO_LED Clock */ 00197 LEDx_GPIO_CLK_ENABLE(Led); 00198 00199 /* Configure the GPIO_LED pin */ 00200 GPIO_InitStruct.Pin = GPIO_PIN[Led]; 00201 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 00202 GPIO_InitStruct.Pull = GPIO_PULLUP; 00203 GPIO_InitStruct.Speed = GPIO_SPEED_FAST; 00204 00205 HAL_GPIO_Init(GPIO_PORT[Led], &GPIO_InitStruct); 00206 00207 HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_RESET); 00208 } 00209 00210 /** 00211 * @brief Turns selected LED On. 00212 * @param Led: Specifies the Led to be set on. 00213 * This parameter can be one of following parameters: 00214 * @arg LED3 00215 * @arg LED4 00216 */ 00217 void BSP_LED_On(Led_TypeDef Led) 00218 { 00219 HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_SET); 00220 } 00221 00222 /** 00223 * @brief Turns selected LED Off. 00224 * @param Led: Specifies the Led to be set off. 00225 * This parameter can be one of following parameters: 00226 * @arg LED3 00227 * @arg LED4 00228 */ 00229 void BSP_LED_Off(Led_TypeDef Led) 00230 { 00231 HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_RESET); 00232 } 00233 00234 /** 00235 * @brief Toggles the selected LED. 00236 * @param Led: Specifies the Led to be toggled. 00237 * This parameter can be one of following parameters: 00238 * @arg LED3 00239 * @arg LED4 00240 */ 00241 void BSP_LED_Toggle(Led_TypeDef Led) 00242 { 00243 HAL_GPIO_TogglePin(GPIO_PORT[Led], GPIO_PIN[Led]); 00244 } 00245 00246 /** 00247 * @brief Configures Button GPIO and EXTI Line. 00248 * @param Button: Specifies the Button to be configured. 00249 * This parameter should be: BUTTON_KEY 00250 * @param ButtonMode: Specifies Button mode. 00251 * This parameter can be one of following parameters: 00252 * @arg BUTTON_MODE_GPIO: Button will be used as simple IO 00253 * @arg BUTTON_MODE_EXTI: Button will be connected to EXTI line with interrupt 00254 * generation capability 00255 */ 00256 void BSP_PB_Init(Button_TypeDef Button, ButtonMode_TypeDef ButtonMode) 00257 { 00258 GPIO_InitTypeDef GPIO_InitStruct; 00259 00260 /* Enable the BUTTON Clock */ 00261 BUTTONx_GPIO_CLK_ENABLE(Button); 00262 00263 if (ButtonMode == BUTTON_MODE_GPIO) 00264 { 00265 /* Configure Button pin as input */ 00266 GPIO_InitStruct.Pin = BUTTON_PIN[Button]; 00267 GPIO_InitStruct.Mode = GPIO_MODE_INPUT; 00268 GPIO_InitStruct.Pull = GPIO_PULLDOWN; 00269 GPIO_InitStruct.Speed = GPIO_SPEED_FAST; 00270 HAL_GPIO_Init(BUTTON_PORT[Button], &GPIO_InitStruct); 00271 } 00272 00273 if (ButtonMode == BUTTON_MODE_EXTI) 00274 { 00275 /* Configure Button pin as input with External interrupt */ 00276 GPIO_InitStruct.Pin = BUTTON_PIN[Button]; 00277 GPIO_InitStruct.Pull = GPIO_NOPULL; 00278 GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; 00279 HAL_GPIO_Init(BUTTON_PORT[Button], &GPIO_InitStruct); 00280 00281 /* Enable and set Button EXTI Interrupt to the lowest priority */ 00282 HAL_NVIC_SetPriority((IRQn_Type)(BUTTON_IRQn[Button]), 0x0F, 0x00); 00283 HAL_NVIC_EnableIRQ((IRQn_Type)(BUTTON_IRQn[Button])); 00284 } 00285 } 00286 00287 /** 00288 * @brief Returns the selected Button state. 00289 * @param Button: Specifies the Button to be checked. 00290 * This parameter should be: BUTTON_KEY 00291 * @retval The Button GPIO pin value. 00292 */ 00293 uint32_t BSP_PB_GetState(Button_TypeDef Button) 00294 { 00295 return HAL_GPIO_ReadPin(BUTTON_PORT[Button], BUTTON_PIN[Button]); 00296 } 00297 00298 /******************************************************************************* 00299 BUS OPERATIONS 00300 *******************************************************************************/ 00301 00302 /******************************* I2C Routines *********************************/ 00303 00304 /** 00305 * @brief I2Cx MSP Initialization 00306 * @param hi2c: I2C handle 00307 */ 00308 static void I2Cx_MspInit(I2C_HandleTypeDef *hi2c) 00309 { 00310 GPIO_InitTypeDef GPIO_InitStruct; 00311 #ifdef EE_M24LR64 00312 static DMA_HandleTypeDef hdma_tx; 00313 static DMA_HandleTypeDef hdma_rx; 00314 00315 I2C_HandleTypeDef* pI2cHandle; 00316 pI2cHandle = &I2cHandle; 00317 #endif /* EE_M24LR64 */ 00318 00319 if (hi2c->Instance == DISCOVERY_I2Cx) 00320 { 00321 /* Configure the GPIOs ---------------------------------------------------*/ 00322 /* Enable GPIO clock */ 00323 DISCOVERY_I2Cx_SDA_GPIO_CLK_ENABLE(); 00324 DISCOVERY_I2Cx_SCL_GPIO_CLK_ENABLE(); 00325 00326 /* Configure I2C Tx as alternate function */ 00327 GPIO_InitStruct.Pin = DISCOVERY_I2Cx_SCL_PIN; 00328 GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; 00329 GPIO_InitStruct.Pull = GPIO_NOPULL; 00330 GPIO_InitStruct.Speed = GPIO_SPEED_FAST; 00331 GPIO_InitStruct.Alternate = DISCOVERY_I2Cx_SCL_SDA_AF; 00332 HAL_GPIO_Init(DISCOVERY_I2Cx_SCL_GPIO_PORT, &GPIO_InitStruct); 00333 00334 /* Configure I2C Rx as alternate function */ 00335 GPIO_InitStruct.Pin = DISCOVERY_I2Cx_SDA_PIN; 00336 HAL_GPIO_Init(DISCOVERY_I2Cx_SDA_GPIO_PORT, &GPIO_InitStruct); 00337 00338 00339 /* Configure the Discovery I2Cx peripheral -------------------------------*/ 00340 /* Enable I2C3 clock */ 00341 DISCOVERY_I2Cx_CLOCK_ENABLE(); 00342 00343 /* Force the I2C Peripheral Clock Reset */ 00344 DISCOVERY_I2Cx_FORCE_RESET(); 00345 00346 /* Release the I2C Peripheral Clock Reset */ 00347 DISCOVERY_I2Cx_RELEASE_RESET(); 00348 00349 /* Enable and set Discovery I2Cx Interrupt to the lowest priority */ 00350 HAL_NVIC_SetPriority(DISCOVERY_I2Cx_EV_IRQn, 0x0F, 0); 00351 HAL_NVIC_EnableIRQ(DISCOVERY_I2Cx_EV_IRQn); 00352 00353 /* Enable and set Discovery I2Cx Interrupt to the lowest priority */ 00354 HAL_NVIC_SetPriority(DISCOVERY_I2Cx_ER_IRQn, 0x0F, 0); 00355 HAL_NVIC_EnableIRQ(DISCOVERY_I2Cx_ER_IRQn); 00356 00357 #ifdef EE_M24LR64 00358 /* I2C DMA TX and RX channels configuration */ 00359 /* Enable the DMA clock */ 00360 EEPROM_I2C_DMA_CLK_ENABLE(); 00361 00362 /* Configure the DMA stream for the EE I2C peripheral TX direction */ 00363 /* Configure the DMA Stream */ 00364 hdma_tx.Instance = EEPROM_I2C_DMA_STREAM_TX; 00365 /* Set the parameters to be configured */ 00366 hdma_tx.Init.Channel = EEPROM_I2C_DMA_CHANNEL; 00367 hdma_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; 00368 hdma_tx.Init.PeriphInc = DMA_PINC_DISABLE; 00369 hdma_tx.Init.MemInc = DMA_MINC_ENABLE; 00370 hdma_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; 00371 hdma_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; 00372 hdma_tx.Init.Mode = DMA_NORMAL; 00373 hdma_tx.Init.Priority = DMA_PRIORITY_VERY_HIGH; 00374 hdma_tx.Init.FIFOMode = DMA_FIFOMODE_ENABLE; 00375 hdma_tx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; 00376 hdma_tx.Init.MemBurst = DMA_MBURST_SINGLE; 00377 hdma_tx.Init.PeriphBurst = DMA_PBURST_SINGLE; 00378 00379 /* Associate the initilalized hdma_tx handle to the the pI2cHandle handle */ 00380 __HAL_LINKDMA(pI2cHandle, hdmatx, hdma_tx); 00381 00382 /* Configure the DMA Stream */ 00383 HAL_DMA_Init(&hdma_tx); 00384 00385 /* Configure and enable I2C DMA TX Channel interrupt */ 00386 HAL_NVIC_SetPriority((IRQn_Type)(EEPROM_I2C_DMA_TX_IRQn), EEPROM_I2C_DMA_PREPRIO, 0); 00387 HAL_NVIC_EnableIRQ((IRQn_Type)(EEPROM_I2C_DMA_TX_IRQn)); 00388 00389 /* Configure the DMA stream for the EE I2C peripheral TX direction */ 00390 /* Configure the DMA Stream */ 00391 hdma_rx.Instance = EEPROM_I2C_DMA_STREAM_RX; 00392 /* Set the parameters to be configured */ 00393 hdma_rx.Init.Channel = EEPROM_I2C_DMA_CHANNEL; 00394 hdma_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; 00395 hdma_rx.Init.PeriphInc = DMA_PINC_DISABLE; 00396 hdma_rx.Init.MemInc = DMA_MINC_ENABLE; 00397 hdma_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; 00398 hdma_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; 00399 hdma_rx.Init.Mode = DMA_NORMAL; 00400 hdma_rx.Init.Priority = DMA_PRIORITY_VERY_HIGH; 00401 hdma_rx.Init.FIFOMode = DMA_FIFOMODE_ENABLE; 00402 hdma_rx.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; 00403 hdma_rx.Init.MemBurst = DMA_MBURST_SINGLE; 00404 hdma_rx.Init.PeriphBurst = DMA_PBURST_SINGLE; 00405 00406 /* Associate the initilalized hdma_rx handle to the the pI2cHandle handle*/ 00407 __HAL_LINKDMA(pI2cHandle, hdmarx, hdma_rx); 00408 00409 /* Configure the DMA Stream */ 00410 HAL_DMA_Init(&hdma_rx); 00411 00412 /* Configure and enable I2C DMA RX Channel interrupt */ 00413 HAL_NVIC_SetPriority((IRQn_Type)(EEPROM_I2C_DMA_RX_IRQn), EEPROM_I2C_DMA_PREPRIO, 0); 00414 HAL_NVIC_EnableIRQ((IRQn_Type)(EEPROM_I2C_DMA_RX_IRQn)); 00415 #endif /* EE_M24LR64 */ 00416 } 00417 } 00418 00419 /** 00420 * @brief I2Cx Bus initialization. 00421 */ 00422 static void I2Cx_Init(void) 00423 { 00424 if(HAL_I2C_GetState(&I2cHandle) == HAL_I2C_STATE_RESET) 00425 { 00426 I2cHandle.Instance = DISCOVERY_I2Cx; 00427 I2cHandle.Init.ClockSpeed = BSP_I2C_SPEED; 00428 I2cHandle.Init.DutyCycle = I2C_DUTYCYCLE_2; 00429 I2cHandle.Init.OwnAddress1 = 0; 00430 I2cHandle.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; 00431 I2cHandle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLED; 00432 I2cHandle.Init.OwnAddress2 = 0; 00433 I2cHandle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLED; 00434 I2cHandle.Init.NoStretchMode = I2C_NOSTRETCH_DISABLED; 00435 00436 /* Init the I2C */ 00437 I2Cx_MspInit(&I2cHandle); 00438 HAL_I2C_Init(&I2cHandle); 00439 } 00440 } 00441 00442 /** 00443 * @brief Configures Interruption pin for I2C communication. 00444 */ 00445 static void I2Cx_ITConfig(void) 00446 { 00447 GPIO_InitTypeDef GPIO_InitStruct; 00448 00449 /* Enable the GPIO EXTI Clock */ 00450 STMPE811_INT_CLK_ENABLE(); 00451 00452 GPIO_InitStruct.Pin = STMPE811_INT_PIN; 00453 GPIO_InitStruct.Pull = GPIO_PULLUP; 00454 GPIO_InitStruct.Speed = GPIO_SPEED_LOW; 00455 GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING; 00456 HAL_GPIO_Init(STMPE811_INT_GPIO_PORT, &GPIO_InitStruct); 00457 00458 /* Enable and set GPIO EXTI Interrupt to the highest priority */ 00459 HAL_NVIC_SetPriority((IRQn_Type)(STMPE811_INT_EXTI), 0x0F, 0x00); 00460 HAL_NVIC_EnableIRQ((IRQn_Type)(STMPE811_INT_EXTI)); 00461 } 00462 00463 /** 00464 * @brief Writes a value in a register of the device through BUS. 00465 * @param Addr: Device address on BUS Bus. 00466 * @param Reg: The target register address to write 00467 * @param Value: The target register value to be written 00468 */ 00469 static void I2Cx_WriteData(uint8_t Addr, uint8_t Reg, uint8_t Value) 00470 { 00471 HAL_StatusTypeDef status = HAL_OK; 00472 00473 status = HAL_I2C_Mem_Write(&I2cHandle, Addr, (uint16_t)Reg, I2C_MEMADD_SIZE_8BIT, &Value, 1, I2cxTimeout); 00474 00475 /* Check the communication status */ 00476 if(status != HAL_OK) 00477 { 00478 /* Re-Initialize the BUS */ 00479 I2Cx_Error(); 00480 } 00481 } 00482 00483 /** 00484 * @brief Writes a value in a register of the device through BUS. 00485 * @param Addr: Device address on BUS Bus. 00486 * @param Reg: The target register address to write 00487 * @param pBuffer: The target register value to be written 00488 * @param Length: buffer size to be written 00489 */ 00490 static void I2Cx_WriteBuffer(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length) 00491 { 00492 HAL_StatusTypeDef status = HAL_OK; 00493 00494 status = HAL_I2C_Mem_Write(&I2cHandle, Addr, (uint16_t)Reg, I2C_MEMADD_SIZE_8BIT, pBuffer, Length, I2cxTimeout); 00495 00496 /* Check the communication status */ 00497 if(status != HAL_OK) 00498 { 00499 /* Re-Initialize the BUS */ 00500 I2Cx_Error(); 00501 } 00502 } 00503 00504 /** 00505 * @brief Reads a register of the device through BUS. 00506 * @param Addr: Device address on BUS Bus. 00507 * @param Reg: The target register address to write 00508 * @retval Data read at register address 00509 */ 00510 static uint8_t I2Cx_ReadData(uint8_t Addr, uint8_t Reg) 00511 { 00512 HAL_StatusTypeDef status = HAL_OK; 00513 uint8_t value = 0; 00514 00515 status = HAL_I2C_Mem_Read(&I2cHandle, Addr, Reg, I2C_MEMADD_SIZE_8BIT, &value, 1, I2cxTimeout); 00516 00517 /* Check the communication status */ 00518 if(status != HAL_OK) 00519 { 00520 /* Re-Initialize the BUS */ 00521 I2Cx_Error(); 00522 00523 } 00524 return value; 00525 } 00526 00527 /** 00528 * @brief Reads multiple data on the BUS. 00529 * @param Addr: I2C Address 00530 * @param Reg: Reg Address 00531 * @param pBuffer: pointer to read data buffer 00532 * @param Length: length of the data 00533 * @retval 0 if no problems to read multiple data 00534 */ 00535 static uint8_t I2Cx_ReadBuffer(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length) 00536 { 00537 HAL_StatusTypeDef status = HAL_OK; 00538 00539 status = HAL_I2C_Mem_Read(&I2cHandle, Addr, (uint16_t)Reg, I2C_MEMADD_SIZE_8BIT, pBuffer, Length, I2cxTimeout); 00540 00541 /* Check the communication status */ 00542 if(status == HAL_OK) 00543 { 00544 return 0; 00545 } 00546 else 00547 { 00548 /* Re-Initialize the BUS */ 00549 I2Cx_Error(); 00550 00551 return 1; 00552 } 00553 } 00554 00555 #ifdef EE_M24LR64 00556 /** 00557 * @brief Writes a value in a register of the device through BUS in using DMA mode. 00558 * @param Addr: Device address on BUS Bus. 00559 * @param Reg: The target register address to write 00560 * @param pBuffer: The target register value to be written 00561 * @param Length: buffer size to be written 00562 * @retval HAL status 00563 */ 00564 static HAL_StatusTypeDef I2Cx_WriteBufferDMA(uint8_t Addr, uint16_t Reg, uint8_t *pBuffer, uint16_t Length) 00565 { 00566 HAL_StatusTypeDef status = HAL_OK; 00567 00568 status = HAL_I2C_Mem_Write_DMA(&I2cHandle, Addr, Reg, I2C_MEMADD_SIZE_16BIT, pBuffer, Length); 00569 00570 /* Check the communication status */ 00571 if(status != HAL_OK) 00572 { 00573 /* Re-Initialize the BUS */ 00574 I2Cx_Error(); 00575 } 00576 00577 return status; 00578 } 00579 00580 /** 00581 * @brief Reads multiple data on the BUS in using DMA mode. 00582 * @param Addr: I2C Address 00583 * @param Reg: Reg Address 00584 * @param pBuffer: pointer to read data buffer 00585 * @param Length: length of the data 00586 * @retval HAL status 00587 */ 00588 static HAL_StatusTypeDef I2Cx_ReadBufferDMA(uint8_t Addr, uint16_t Reg, uint8_t *pBuffer, uint16_t Length) 00589 { 00590 HAL_StatusTypeDef status = HAL_OK; 00591 00592 status = HAL_I2C_Mem_Read_DMA(&I2cHandle, Addr, Reg, I2C_MEMADD_SIZE_16BIT, pBuffer, Length); 00593 00594 /* Check the communication status */ 00595 if(status != HAL_OK) 00596 { 00597 /* Re-Initialize the BUS */ 00598 I2Cx_Error(); 00599 } 00600 00601 return status; 00602 } 00603 00604 /** 00605 * @brief Checks if target device is ready for communication. 00606 * @note This function is used with Memory devices 00607 * @param DevAddress: Target device address 00608 * @param Trials: Number of trials 00609 * @retval HAL status 00610 */ 00611 static HAL_StatusTypeDef I2Cx_IsDeviceReady(uint16_t DevAddress, uint32_t Trials) 00612 { 00613 return (HAL_I2C_IsDeviceReady(&I2cHandle, DevAddress, Trials, I2cxTimeout)); 00614 } 00615 #endif /* EE_M24LR64 */ 00616 00617 /** 00618 * @brief I2Cx error treatment function 00619 */ 00620 static void I2Cx_Error(void) 00621 { 00622 /* De-initialize the SPI communication BUS */ 00623 HAL_I2C_DeInit(&I2cHandle); 00624 00625 /* Re-Initialize the SPI communication BUS */ 00626 I2Cx_Init(); 00627 } 00628 00629 /******************************* SPI Routines *********************************/ 00630 00631 /** 00632 * @brief SPIx Bus initialization 00633 */ 00634 static void SPIx_Init(void) 00635 { 00636 if(HAL_SPI_GetState(&SpiHandle) == HAL_SPI_STATE_RESET) 00637 { 00638 /* SPI configuration -----------------------------------------------------*/ 00639 SpiHandle.Instance = DISCOVERY_SPIx; 00640 /* SPI baudrate is set to 5.6 MHz (PCLK2/SPI_BaudRatePrescaler = 90/16 = 5.625 MHz) 00641 to verify these constraints: 00642 - ILI9341 LCD SPI interface max baudrate is 10MHz for write and 6.66MHz for read 00643 - l3gd20 SPI interface max baudrate is 10MHz for write/read 00644 - PCLK2 frequency is set to 90 MHz 00645 */ 00646 SpiHandle.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; 00647 00648 /* On STM32F429I-Discovery, LCD ID cannot be read then keep a common configuration */ 00649 /* for LCD and GYRO (SPI_DIRECTION_2LINES) */ 00650 /* Note: To read a register a LCD, SPI_DIRECTION_1LINE should be set */ 00651 SpiHandle.Init.Direction = SPI_DIRECTION_2LINES; 00652 SpiHandle.Init.CLKPhase = SPI_PHASE_1EDGE; 00653 SpiHandle.Init.CLKPolarity = SPI_POLARITY_LOW; 00654 SpiHandle.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLED; 00655 SpiHandle.Init.CRCPolynomial = 7; 00656 SpiHandle.Init.DataSize = SPI_DATASIZE_8BIT; 00657 SpiHandle.Init.FirstBit = SPI_FIRSTBIT_MSB; 00658 SpiHandle.Init.NSS = SPI_NSS_SOFT; 00659 SpiHandle.Init.TIMode = SPI_TIMODE_DISABLED; 00660 SpiHandle.Init.Mode = SPI_MODE_MASTER; 00661 00662 SPIx_MspInit(&SpiHandle); 00663 HAL_SPI_Init(&SpiHandle); 00664 } 00665 } 00666 00667 /** 00668 * @brief Reads 4 bytes from device. 00669 * @param ReadSize: Number of bytes to read (max 4 bytes) 00670 * @retval Value read on the SPI 00671 */ 00672 static uint32_t SPIx_Read(uint8_t ReadSize) 00673 { 00674 HAL_StatusTypeDef status = HAL_OK; 00675 uint32_t readvalue; 00676 00677 status = HAL_SPI_Receive(&SpiHandle, (uint8_t*) &readvalue, ReadSize, SpixTimeout); 00678 00679 /* Check the communication status */ 00680 if(status != HAL_OK) 00681 { 00682 /* Re-Initialize the BUS */ 00683 SPIx_Error(); 00684 } 00685 00686 return readvalue; 00687 } 00688 00689 /** 00690 * @brief Writes a byte to device. 00691 * @param Value: value to be written 00692 */ 00693 static void SPIx_Write(uint16_t Value) 00694 { 00695 HAL_StatusTypeDef status = HAL_OK; 00696 00697 status = HAL_SPI_Transmit(&SpiHandle, (uint8_t*) &Value, 1, SpixTimeout); 00698 00699 /* Check the communication status */ 00700 if(status != HAL_OK) 00701 { 00702 /* Re-Initialize the BUS */ 00703 SPIx_Error(); 00704 } 00705 } 00706 00707 /** 00708 * @brief Sends a Byte through the SPI interface and return the Byte received 00709 * from the SPI bus. 00710 * @param Byte: Byte send. 00711 * @retval The received byte value 00712 */ 00713 static uint8_t SPIx_WriteRead(uint8_t Byte) 00714 { 00715 uint8_t receivedbyte = 0; 00716 00717 /* Send a Byte through the SPI peripheral */ 00718 /* Read byte from the SPI bus */ 00719 if(HAL_SPI_TransmitReceive(&SpiHandle, (uint8_t*) &Byte, (uint8_t*) &receivedbyte, 1, SpixTimeout) != HAL_OK) 00720 { 00721 SPIx_Error(); 00722 } 00723 00724 return receivedbyte; 00725 } 00726 00727 /** 00728 * @brief SPIx error treatment function. 00729 */ 00730 static void SPIx_Error(void) 00731 { 00732 /* De-initialize the SPI communication BUS */ 00733 HAL_SPI_DeInit(&SpiHandle); 00734 00735 /* Re- Initialize the SPI communication BUS */ 00736 SPIx_Init(); 00737 } 00738 00739 /** 00740 * @brief SPI MSP Init. 00741 * @param hspi: SPI handle 00742 */ 00743 static void SPIx_MspInit(SPI_HandleTypeDef *hspi) 00744 { 00745 GPIO_InitTypeDef GPIO_InitStructure; 00746 00747 /* Enable SPIx clock */ 00748 DISCOVERY_SPIx_CLK_ENABLE(); 00749 00750 /* Enable DISCOVERY_SPI GPIO clock */ 00751 DISCOVERY_SPIx_GPIO_CLK_ENABLE(); 00752 00753 /* configure SPI SCK, MOSI and MISO */ 00754 GPIO_InitStructure.Pin = (DISCOVERY_SPIx_SCK_PIN | DISCOVERY_SPIx_MOSI_PIN | DISCOVERY_SPIx_MISO_PIN); 00755 GPIO_InitStructure.Mode = GPIO_MODE_AF_PP; 00756 GPIO_InitStructure.Pull = GPIO_PULLDOWN; 00757 GPIO_InitStructure.Speed = GPIO_SPEED_MEDIUM; 00758 GPIO_InitStructure.Alternate = DISCOVERY_SPIx_AF; 00759 HAL_GPIO_Init(DISCOVERY_SPIx_GPIO_PORT, &GPIO_InitStructure); 00760 } 00761 00762 /********************************* LINK LCD ***********************************/ 00763 00764 /** 00765 * @brief Configures the LCD_SPI interface. 00766 */ 00767 void LCD_IO_Init(void) 00768 { 00769 GPIO_InitTypeDef GPIO_InitStructure; 00770 00771 if(Is_LCD_IO_Initialized == 0) 00772 { 00773 Is_LCD_IO_Initialized = 1; 00774 00775 /* Configure NCS in Output Push-Pull mode */ 00776 LCD_WRX_GPIO_CLK_ENABLE(); 00777 GPIO_InitStructure.Pin = LCD_WRX_PIN; 00778 GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; 00779 GPIO_InitStructure.Pull = GPIO_NOPULL; 00780 GPIO_InitStructure.Speed = GPIO_SPEED_FAST; 00781 HAL_GPIO_Init(LCD_WRX_GPIO_PORT, &GPIO_InitStructure); 00782 00783 LCD_RDX_GPIO_CLK_ENABLE(); 00784 GPIO_InitStructure.Pin = LCD_RDX_PIN; 00785 GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; 00786 GPIO_InitStructure.Pull = GPIO_NOPULL; 00787 GPIO_InitStructure.Speed = GPIO_SPEED_FAST; 00788 HAL_GPIO_Init(LCD_RDX_GPIO_PORT, &GPIO_InitStructure); 00789 00790 /* Configure the LCD Control pins ----------------------------------------*/ 00791 LCD_NCS_GPIO_CLK_ENABLE(); 00792 00793 /* Configure NCS in Output Push-Pull mode */ 00794 GPIO_InitStructure.Pin = LCD_NCS_PIN; 00795 GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; 00796 GPIO_InitStructure.Pull = GPIO_NOPULL; 00797 GPIO_InitStructure.Speed = GPIO_SPEED_FAST; 00798 HAL_GPIO_Init(LCD_NCS_GPIO_PORT, &GPIO_InitStructure); 00799 00800 /* Set or Reset the control line */ 00801 LCD_CS_LOW(); 00802 LCD_CS_HIGH(); 00803 00804 SPIx_Init(); 00805 } 00806 } 00807 00808 /** 00809 * @brief Writes register value. 00810 */ 00811 void LCD_IO_WriteData(uint16_t RegValue) 00812 { 00813 /* Set WRX to send data */ 00814 LCD_WRX_HIGH(); 00815 00816 /* Reset LCD control line(/CS) and Send data */ 00817 LCD_CS_LOW(); 00818 SPIx_Write(RegValue); 00819 00820 /* Deselect: Chip Select high */ 00821 LCD_CS_HIGH(); 00822 } 00823 00824 /** 00825 * @brief Writes register address. 00826 */ 00827 void LCD_IO_WriteReg(uint8_t Reg) 00828 { 00829 /* Reset WRX to send command */ 00830 LCD_WRX_LOW(); 00831 00832 /* Reset LCD control line(/CS) and Send command */ 00833 LCD_CS_LOW(); 00834 SPIx_Write(Reg); 00835 00836 /* Deselect: Chip Select high */ 00837 LCD_CS_HIGH(); 00838 } 00839 00840 /** 00841 * @brief Reads register value. 00842 * @param RegValue Address of the register to read 00843 * @param ReadSize Number of bytes to read 00844 * @retval Content of the register value 00845 */ 00846 uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize) 00847 { 00848 uint32_t readvalue = 0; 00849 00850 /* Select: Chip Select low */ 00851 LCD_CS_LOW(); 00852 00853 /* Reset WRX to send command */ 00854 LCD_WRX_LOW(); 00855 00856 SPIx_Write(RegValue); 00857 00858 readvalue = SPIx_Read(ReadSize); 00859 00860 /* Set WRX to send data */ 00861 LCD_WRX_HIGH(); 00862 00863 /* Deselect: Chip Select high */ 00864 LCD_CS_HIGH(); 00865 00866 return readvalue; 00867 } 00868 00869 /** 00870 * @brief Wait for loop in ms. 00871 * @param Delay in ms. 00872 */ 00873 void LCD_Delay(uint32_t Delay) 00874 { 00875 HAL_Delay(Delay); 00876 } 00877 00878 /******************************************************************************* 00879 LINK OPERATIONS 00880 *******************************************************************************/ 00881 00882 /********************************* LINK IOE ***********************************/ 00883 00884 /** 00885 * @brief IOE Low Level Initialization. 00886 */ 00887 void IOE_Init(void) 00888 { 00889 I2Cx_Init(); 00890 } 00891 00892 /** 00893 * @brief IOE Low Level Interrupt configuration. 00894 */ 00895 void IOE_ITConfig(void) 00896 { 00897 I2Cx_ITConfig(); 00898 } 00899 00900 /** 00901 * @brief IOE Writes single data operation. 00902 * @param Addr: I2C Address 00903 * @param Reg: Reg Address 00904 * @param Value: Data to be written 00905 */ 00906 void IOE_Write(uint8_t Addr, uint8_t Reg, uint8_t Value) 00907 { 00908 I2Cx_WriteData(Addr, Reg, Value); 00909 } 00910 00911 /** 00912 * @brief IOE Reads single data. 00913 * @param Addr: I2C Address 00914 * @param Reg: Reg Address 00915 * @retval The read data 00916 */ 00917 uint8_t IOE_Read(uint8_t Addr, uint8_t Reg) 00918 { 00919 return I2Cx_ReadData(Addr, Reg); 00920 } 00921 00922 /** 00923 * @brief IOE Writes multiple data. 00924 * @param Addr: I2C Address 00925 * @param Reg: Reg Address 00926 * @param pBuffer: pointer to data buffer 00927 * @param Length: length of the data 00928 */ 00929 void IOE_WriteMultiple(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length) 00930 { 00931 I2Cx_WriteBuffer(Addr, Reg, pBuffer, Length); 00932 } 00933 00934 /** 00935 * @brief IOE Reads multiple data. 00936 * @param Addr: I2C Address 00937 * @param Reg: Reg Address 00938 * @param pBuffer: pointer to data buffer 00939 * @param Length: length of the data 00940 * @retval 0 if no problems to read multiple data 00941 */ 00942 uint16_t IOE_ReadMultiple(uint8_t Addr, uint8_t Reg, uint8_t *pBuffer, uint16_t Length) 00943 { 00944 return I2Cx_ReadBuffer(Addr, Reg, pBuffer, Length); 00945 } 00946 00947 /** 00948 * @brief IOE Delay. 00949 * @param Delay in ms 00950 */ 00951 void IOE_Delay(uint32_t Delay) 00952 { 00953 HAL_Delay(Delay); 00954 } 00955 00956 /********************************* LINK GYROSCOPE *****************************/ 00957 00958 /** 00959 * @brief Configures the Gyroscope SPI interface. 00960 */ 00961 void GYRO_IO_Init(void) 00962 { 00963 GPIO_InitTypeDef GPIO_InitStructure; 00964 00965 /* Configure the Gyroscope Control pins ------------------------------------*/ 00966 /* Enable CS GPIO clock and Configure GPIO PIN for Gyroscope Chip select */ 00967 GYRO_CS_GPIO_CLK_ENABLE(); 00968 GPIO_InitStructure.Pin = GYRO_CS_PIN; 00969 GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; 00970 GPIO_InitStructure.Pull = GPIO_NOPULL; 00971 GPIO_InitStructure.Speed = GPIO_SPEED_MEDIUM; 00972 HAL_GPIO_Init(GYRO_CS_GPIO_PORT, &GPIO_InitStructure); 00973 00974 /* Deselect: Chip Select high */ 00975 GYRO_CS_HIGH(); 00976 00977 /* Enable INT1, INT2 GPIO clock and Configure GPIO PINs to detect Interrupts */ 00978 GYRO_INT_GPIO_CLK_ENABLE(); 00979 GPIO_InitStructure.Pin = GYRO_INT1_PIN | GYRO_INT2_PIN; 00980 GPIO_InitStructure.Mode = GPIO_MODE_INPUT; 00981 GPIO_InitStructure.Speed = GPIO_SPEED_FAST; 00982 GPIO_InitStructure.Pull= GPIO_NOPULL; 00983 HAL_GPIO_Init(GYRO_INT_GPIO_PORT, &GPIO_InitStructure); 00984 00985 SPIx_Init(); 00986 } 00987 00988 /** 00989 * @brief Writes one byte to the Gyroscope. 00990 * @param pBuffer: Pointer to the buffer containing the data to be written to the Gyroscope. 00991 * @param WriteAddr: Gyroscope's internal address to write to. 00992 * @param NumByteToWrite: Number of bytes to write. 00993 */ 00994 void GYRO_IO_Write(uint8_t* pBuffer, uint8_t WriteAddr, uint16_t NumByteToWrite) 00995 { 00996 /* Configure the MS bit: 00997 - When 0, the address will remain unchanged in multiple read/write commands. 00998 - When 1, the address will be auto incremented in multiple read/write commands. 00999 */ 01000 if(NumByteToWrite > 0x01) 01001 { 01002 WriteAddr |= (uint8_t)MULTIPLEBYTE_CMD; 01003 } 01004 /* Set chip select Low at the start of the transmission */ 01005 GYRO_CS_LOW(); 01006 01007 /* Send the Address of the indexed register */ 01008 SPIx_WriteRead(WriteAddr); 01009 01010 /* Send the data that will be written into the device (MSB First) */ 01011 while(NumByteToWrite >= 0x01) 01012 { 01013 SPIx_WriteRead(*pBuffer); 01014 NumByteToWrite--; 01015 pBuffer++; 01016 } 01017 01018 /* Set chip select High at the end of the transmission */ 01019 GYRO_CS_HIGH(); 01020 } 01021 01022 /** 01023 * @brief Reads a block of data from the Gyroscope. 01024 * @param pBuffer: Pointer to the buffer that receives the data read from the Gyroscope. 01025 * @param ReadAddr: Gyroscope's internal address to read from. 01026 * @param NumByteToRead: Number of bytes to read from the Gyroscope. 01027 */ 01028 void GYRO_IO_Read(uint8_t* pBuffer, uint8_t ReadAddr, uint16_t NumByteToRead) 01029 { 01030 if(NumByteToRead > 0x01) 01031 { 01032 ReadAddr |= (uint8_t)(READWRITE_CMD | MULTIPLEBYTE_CMD); 01033 } 01034 else 01035 { 01036 ReadAddr |= (uint8_t)READWRITE_CMD; 01037 } 01038 /* Set chip select Low at the start of the transmission */ 01039 GYRO_CS_LOW(); 01040 01041 /* Send the Address of the indexed register */ 01042 SPIx_WriteRead(ReadAddr); 01043 01044 /* Receive the data that will be read from the device (MSB First) */ 01045 while(NumByteToRead > 0x00) 01046 { 01047 /* Send dummy byte (0x00) to generate the SPI clock to Gyroscope (Slave device) */ 01048 *pBuffer = SPIx_WriteRead(DUMMY_BYTE); 01049 NumByteToRead--; 01050 pBuffer++; 01051 } 01052 01053 /* Set chip select High at the end of the transmission */ 01054 GYRO_CS_HIGH(); 01055 } 01056 01057 01058 #ifdef EE_M24LR64 01059 01060 /******************************** LINK I2C EEPROM *****************************/ 01061 01062 /** 01063 * @brief Initializes peripherals used by the I2C EEPROM driver. 01064 */ 01065 void EEPROM_IO_Init(void) 01066 { 01067 I2Cx_Init(); 01068 } 01069 01070 /** 01071 * @brief Writes data to I2C EEPROM driver in using DMA channel. 01072 * @param DevAddress: Target device address 01073 * @param MemAddress: Internal memory address 01074 * @param pBuffer: Pointer to data buffer 01075 * @param BufferSize: Amount of data to be sent 01076 * @retval HAL status 01077 */ 01078 HAL_StatusTypeDef EEPROM_IO_WriteData(uint16_t DevAddress, uint16_t MemAddress, uint8_t* pBuffer, uint32_t BufferSize) 01079 { 01080 return (I2Cx_WriteBufferDMA(DevAddress, MemAddress, pBuffer, BufferSize)); 01081 } 01082 01083 /** 01084 * @brief Reads data from I2C EEPROM driver in using DMA channel. 01085 * @param DevAddress: Target device address 01086 * @param MemAddress: Internal memory address 01087 * @param pBuffer: Pointer to data buffer 01088 * @param BufferSize: Amount of data to be read 01089 * @retval HAL status 01090 */ 01091 HAL_StatusTypeDef EEPROM_IO_ReadData(uint16_t DevAddress, uint16_t MemAddress, uint8_t* pBuffer, uint32_t BufferSize) 01092 { 01093 return (I2Cx_ReadBufferDMA(DevAddress, MemAddress, pBuffer, BufferSize)); 01094 } 01095 01096 /** 01097 * @brief Checks if target device is ready for communication. 01098 * @note This function is used with Memory devices 01099 * @param DevAddress: Target device address 01100 * @param Trials: Number of trials 01101 * @retval HAL status 01102 */ 01103 HAL_StatusTypeDef EEPROM_IO_IsDeviceReady(uint16_t DevAddress, uint32_t Trials) 01104 { 01105 return (I2Cx_IsDeviceReady(DevAddress, Trials)); 01106 } 01107 #endif /* EE_M24LR64 */ 01108 01109 /** 01110 * @} 01111 */ 01112 01113 /** 01114 * @} 01115 */ 01116 01117 /** 01118 * @} 01119 */ 01120 01121 /** 01122 * @} 01123 */ 01124 01125 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
Generated on Fri Feb 17 2017 12:10:38 for STM32F429I-Discovery BSP User Manual by 1.7.6.1