_BSP_User_Manual: stm32f1xx_nucleo.c Source File

STM32F1xx Nucleo BSP Driver

stm32f1xx_nucleo.c
Go to the documentation of this file.
00001 /**
00002   ******************************************************************************
00003   * @file    stm32f1xx_nucleo.c
00004   * @author  MCD Application Team
00005   * @version $VERSION$
00006   * @date    $DATE$
00007   * @brief   This file provides set of firmware functions to manage:
00008   *          - LEDs and push-button available on STM32F1XX-Nucleo Kit 
00009   *            from STMicroelectronics
00010   *          - LCD, joystick and microSD available on Adafruit 1.8" TFT LCD 
00011   *            shield (reference ID 802)
00012   ******************************************************************************
00013   * @attention
00014   *
00015   * <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
00016   *
00017   * Redistribution and use in source and binary forms, with or without modification,
00018   * are permitted provided that the following conditions are met:
00019   *   1. Redistributions of source code must retain the above copyright notice,
00020   *      this list of conditions and the following disclaimer.
00021   *   2. Redistributions in binary form must reproduce the above copyright notice,
00022   *      this list of conditions and the following disclaimer in the documentation
00023   *      and/or other materials provided with the distribution.
00024   *   3. Neither the name of STMicroelectronics nor the names of its contributors
00025   *      may be used to endorse or promote products derived from this software
00026   *      without specific prior written permission.
00027   *
00028   * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00029   * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00030   * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00031   * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00032   * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00033   * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00034   * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00035   * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00036   * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00037   * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00038   *
00039   ******************************************************************************
00040   */
00041 
00042 /* Includes ------------------------------------------------------------------*/
00043 #include "stm32f1xx_nucleo.h"
00044 
00045 /** @addtogroup BSP
00046   * @{
00047   */ 
00048 
00049 /** @defgroup STM32F1XX_NUCLEO STM32F103RB-Nucleo
00050   * @brief This file provides set of firmware functions to manage Leds and push-button
00051   *        available on STM32F1XX-Nucleo Kit from STMicroelectronics.
00052   *        It provides also LCD, joystick and uSD functions to communicate with 
00053   *        Adafruit 1.8" TFT LCD shield (reference ID 802)
00054   * @{
00055   */ 
00056 
00057 
00058 /** @defgroup STM32F1XX_NUCLEO_Private_Defines Private Defines
00059   * @{
00060   */ 
00061   
00062 /**
00063 * @brief STM32F103RB NUCLEO BSP Driver version
00064 */
00065 #define __STM32F1XX_NUCLEO_BSP_VERSION_MAIN   (0x01) /*!< [31:24] main version */
00066 #define __STM32F1XX_NUCLEO_BSP_VERSION_SUB1   (0x00) /*!< [23:16] sub1 version */
00067 #define __STM32F1XX_NUCLEO_BSP_VERSION_SUB2   (0x00) /*!< [15:8]  sub2 version */
00068 #define __STM32F1XX_NUCLEO_BSP_VERSION_RC     (0x00) /*!< [7:0]  release candidate */ 
00069 #define __STM32F1XX_NUCLEO_BSP_VERSION       ((__STM32F1XX_NUCLEO_BSP_VERSION_MAIN << 24)\
00070                                              |(__STM32F1XX_NUCLEO_BSP_VERSION_SUB1 << 16)\
00071                                              |(__STM32F1XX_NUCLEO_BSP_VERSION_SUB2 << 8 )\
00072                                              |(__STM32F1XX_NUCLEO_BSP_VERSION_RC))
00073 
00074 /**
00075   * @brief LINK SD Card
00076   */
00077 #define SD_DUMMY_BYTE            0xFF    
00078 #define SD_NO_RESPONSE_EXPECTED  0x80
00079    
00080 /**
00081   * @}
00082   */ 
00083 
00084 
00085 /** @defgroup STM32F1XX_NUCLEO_Private_Variables Private Variables
00086   * @{
00087   */ 
00088 GPIO_TypeDef* GPIO_PORT[LEDn] = {LED2_GPIO_PORT};
00089 
00090 const uint16_t GPIO_PIN[LEDn] = {LED2_PIN};
00091 
00092 GPIO_TypeDef* BUTTON_PORT[BUTTONn]  = {USER_BUTTON_GPIO_PORT}; 
00093 const uint16_t BUTTON_PIN[BUTTONn]  = {USER_BUTTON_PIN}; 
00094 const uint16_t BUTTON_IRQn[BUTTONn] = {USER_BUTTON_EXTI_IRQn};
00095 
00096 /**
00097  * @brief BUS variables
00098  */
00099 
00100 #ifdef HAL_SPI_MODULE_ENABLED
00101 uint32_t SpixTimeout = NUCLEO_SPIx_TIMEOUT_MAX;        /*<! Value of Timeout when SPI communication fails */
00102 static SPI_HandleTypeDef hnucleo_Spi;
00103 #endif /* HAL_SPI_MODULE_ENABLED */
00104 
00105 #ifdef HAL_ADC_MODULE_ENABLED
00106 static ADC_HandleTypeDef hnucleo_Adc;
00107 /* ADC channel configuration structure declaration */
00108 static ADC_ChannelConfTypeDef sConfig;
00109 #endif /* HAL_ADC_MODULE_ENABLED */
00110 
00111 /**
00112   * @}
00113   */ 
00114 
00115 /** @defgroup STM32F1XX_NUCLEO_Private_Functions Private Functions
00116   * @{
00117   */ 
00118 #ifdef HAL_SPI_MODULE_ENABLED
00119 static void               SPIx_Init(void);
00120 static void               SPIx_Write(uint8_t Value);
00121 static uint32_t           SPIx_Read(void);
00122 static void               SPIx_Error (void);
00123 static void               SPIx_MspInit(void);
00124 #endif /* HAL_SPI_MODULE_ENABLED */
00125 
00126 #ifdef HAL_ADC_MODULE_ENABLED
00127 static void               ADCx_Init(void);
00128 static void               ADCx_MspInit(ADC_HandleTypeDef *hadc);
00129 #endif /* HAL_ADC_MODULE_ENABLED */
00130 
00131 #ifdef HAL_SPI_MODULE_ENABLED
00132 /* SD IO functions */
00133 void                      SD_IO_Init(void);
00134 HAL_StatusTypeDef         SD_IO_WriteCmd(uint8_t Cmd, uint32_t Arg, uint8_t Crc, uint8_t Response);
00135 HAL_StatusTypeDef         SD_IO_WaitResponse(uint8_t Response);
00136 void                      SD_IO_WriteDummy(void);
00137 void                      SD_IO_WriteByte(uint8_t Data);
00138 uint8_t                   SD_IO_ReadByte(void);
00139 
00140 /* LCD IO functions */
00141 void                      LCD_IO_Init(void);
00142 void                      LCD_IO_WriteMultipleData(uint8_t *pData, uint32_t Size);
00143 void                      LCD_IO_WriteReg(uint8_t LCDReg);
00144 void                      LCD_Delay(uint32_t delay);
00145 #endif /* HAL_SPI_MODULE_ENABLED */
00146 /**
00147   * @}
00148   */ 
00149 
00150 /** @defgroup STM32F1XX_NUCLEO_Exported_Functions Exported Functions
00151   * @{
00152   */ 
00153 
00154 /**
00155   * @brief  This method returns the STM32F1XX NUCLEO BSP Driver revision
00156   * @retval version : 0xXYZR (8bits for each decimal, R for RC)
00157   */
00158 uint32_t BSP_GetVersion(void)
00159 {
00160   return __STM32F1XX_NUCLEO_BSP_VERSION;
00161 }
00162 
00163 /** @defgroup STM32F1XX_NUCLEO_LED_Functions LED Functions
00164   * @{
00165   */ 
00166 
00167 /**
00168   * @brief  Configures LED GPIO.
00169   * @param  Led: LED to be configured. 
00170   *          This parameter can be one of the following values:
00171   *     @arg LED2
00172   * @retval None
00173   */
00174 void BSP_LED_Init(Led_TypeDef Led)
00175 {
00176   GPIO_InitTypeDef  gpioinitstruct = {0};
00177   
00178   /* Enable the GPIO_LED Clock */
00179   LEDx_GPIO_CLK_ENABLE(Led);
00180 
00181   /* Configure the GPIO_LED pin */
00182   gpioinitstruct.Pin    = GPIO_PIN[Led];
00183   gpioinitstruct.Mode   = GPIO_MODE_OUTPUT_PP;
00184   gpioinitstruct.Pull   = GPIO_PULLUP;
00185   gpioinitstruct.Speed  = GPIO_SPEED_HIGH;
00186   HAL_GPIO_Init(GPIO_PORT[Led], &gpioinitstruct);
00187 
00188   /* Reset PIN to switch off the LED */
00189   HAL_GPIO_WritePin(GPIO_PORT[Led],GPIO_PIN[Led], GPIO_PIN_RESET);
00190 }
00191 
00192 /**
00193   * @brief  Turns selected LED On.
00194   * @param  Led: Specifies the Led to be set on. 
00195   *   This parameter can be one of following parameters:
00196   *     @arg LED2
00197   * @retval None
00198   */
00199 void BSP_LED_On(Led_TypeDef Led)
00200 {
00201   HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_SET); 
00202 }
00203 
00204 /**
00205   * @brief  Turns selected LED Off.
00206   * @param  Led: Specifies the Led to be set off. 
00207   *   This parameter can be one of following parameters:
00208   *     @arg LED2
00209   * @retval None
00210   */
00211 void BSP_LED_Off(Led_TypeDef Led)
00212 {
00213   HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_RESET); 
00214 }
00215 
00216 /**
00217   * @brief  Toggles the selected LED.
00218   * @param  Led: Specifies the Led to be toggled. 
00219   *   This parameter can be one of following parameters:
00220   *            @arg  LED2
00221   * @retval None
00222   */
00223 void BSP_LED_Toggle(Led_TypeDef Led)
00224 {
00225   HAL_GPIO_TogglePin(GPIO_PORT[Led], GPIO_PIN[Led]);
00226 }
00227 
00228 /**
00229   * @}
00230   */ 
00231 
00232 /** @defgroup STM32F1XX_NUCLEO_BUTTON_Functions BUTTON Functions
00233   * @{
00234   */ 
00235 
00236 /**
00237   * @brief  Configures Button GPIO and EXTI Line.
00238   * @param  Button: Specifies the Button to be configured.
00239   *   This parameter should be: BUTTON_USER
00240   * @param  ButtonMode: Specifies Button mode.
00241   *   This parameter can be one of following parameters:   
00242   *     @arg BUTTON_MODE_GPIO: Button will be used as simple IO 
00243   *     @arg BUTTON_MODE_EXTI: Button will be connected to EXTI line with interrupt
00244   *                     generation capability  
00245   * @retval None
00246   */
00247 void BSP_PB_Init(Button_TypeDef Button, ButtonMode_TypeDef ButtonMode)
00248 {
00249   GPIO_InitTypeDef gpioinitstruct = {0};
00250 
00251   /* Enable the BUTTON Clock */
00252   BUTTONx_GPIO_CLK_ENABLE(Button);
00253 
00254   if (ButtonMode == BUTTON_MODE_GPIO)
00255   {
00256     /* Configure Button pin as input */
00257     gpioinitstruct.Pin    = BUTTON_PIN[Button];
00258     gpioinitstruct.Mode   = GPIO_MODE_INPUT;
00259     gpioinitstruct.Pull   = GPIO_NOPULL;
00260     gpioinitstruct.Speed  = GPIO_SPEED_MEDIUM;
00261   
00262     HAL_GPIO_Init(BUTTON_PORT[Button], &gpioinitstruct);
00263   }
00264  
00265   if (ButtonMode == BUTTON_MODE_EXTI)
00266   {
00267     /* Configure Button pin as input with External interrupt */
00268     gpioinitstruct.Pin    = BUTTON_PIN[Button];
00269     gpioinitstruct.Pull   = GPIO_NOPULL;
00270     gpioinitstruct.Speed  = GPIO_SPEED_MEDIUM;
00271     gpioinitstruct.Mode   = GPIO_MODE_IT_FALLING; 
00272     HAL_GPIO_Init(BUTTON_PORT[Button], &gpioinitstruct);
00273 
00274     /* Enable and set Button EXTI Interrupt to the lowest priority */
00275     HAL_NVIC_SetPriority((IRQn_Type)(BUTTON_IRQn[Button]), 0x0F, 0);
00276     HAL_NVIC_EnableIRQ((IRQn_Type)(BUTTON_IRQn[Button]));
00277   }
00278 }
00279 
00280 /**
00281   * @brief  Returns the selected Button state.
00282   * @param  Button: Specifies the Button to be checked.
00283   *   This parameter should be: BUTTON_USER  
00284   * @retval Button state.
00285   */
00286 uint32_t BSP_PB_GetState(Button_TypeDef Button)
00287 {
00288   return HAL_GPIO_ReadPin(BUTTON_PORT[Button], BUTTON_PIN[Button]);
00289 }
00290 
00291 #ifdef HAL_ADC_MODULE_ENABLED
00292 /**
00293   * @brief  Configures joystick available on adafruit 1.8" TFT shield 
00294   *         managed through ADC to detect motion.
00295   * @retval Joystickstatus (0=> success, 1=> fail) 
00296   */
00297 uint8_t BSP_JOY_Init(void)
00298 {
00299    ADCx_Init();
00300    
00301   /* Select Channel 8 to be converted */
00302   sConfig.Channel       = ADC_CHANNEL_8;    
00303   sConfig.SamplingTime  = ADC_SAMPLETIME_71CYCLES_5;
00304   sConfig.Rank          = 1;
00305   
00306   /* Return Joystick initialization status */
00307   return HAL_ADC_ConfigChannel(&hnucleo_Adc, &sConfig);
00308 }
00309 
00310 /**
00311   * @brief  Returns the Joystick key pressed.
00312   * @note   To know which Joystick key is pressed we need to detect the voltage
00313   *         level on each key output
00314   *           - None  : 3.3 V / 4095
00315   *           - SEL   : 1.055 V / 1308
00316   *           - DOWN  : 0.71 V / 88
00317   *           - LEFT  : 3.0 V / 3720 
00318   *           - RIGHT : 0.595 V / 737
00319   *           - UP    : 1.65 V / 2046
00320   * @retval JOYState_TypeDef: Code of the Joystick key pressed.
00321   */
00322 JOYState_TypeDef BSP_JOY_GetState(void)
00323 {
00324   JOYState_TypeDef state = JOY_NONE;
00325   uint16_t  keyconvertedvalue = 0; 
00326 
00327  /* Start the conversion process */
00328   HAL_ADC_Start(&hnucleo_Adc);
00329   
00330   /* Wait for the end of conversion */
00331   HAL_ADC_PollForConversion(&hnucleo_Adc, 10);
00332   
00333   /* Check if the continous conversion of regular channel is finished */
00334   if(HAL_ADC_GetState(&hnucleo_Adc) == HAL_ADC_STATE_EOC_REG)
00335   {
00336     /* Get the converted value of regular channel */
00337     keyconvertedvalue = HAL_ADC_GetValue(&hnucleo_Adc);
00338   }
00339   
00340   if((keyconvertedvalue > 1800) && (keyconvertedvalue < 2090))
00341   {
00342     state = JOY_UP;
00343   }
00344   else if((keyconvertedvalue > 500) && (keyconvertedvalue < 780))
00345   {
00346     state = JOY_RIGHT;
00347   }
00348   else if((keyconvertedvalue > 1200) && (keyconvertedvalue < 1350))
00349   {
00350     state = JOY_SEL;
00351   }
00352   else if((keyconvertedvalue > 10) && (keyconvertedvalue < 130))
00353   {
00354     state = JOY_DOWN;
00355   }
00356   else if((keyconvertedvalue > 3500) && (keyconvertedvalue < 3760))
00357   {
00358     state = JOY_LEFT;
00359   }
00360   else
00361   {
00362     state = JOY_NONE;
00363   }
00364   
00365   /* Return the code of the Joystick key pressed*/
00366   return state;
00367 }
00368 
00369 #endif /* HAL_ADC_MODULE_ENABLED */
00370 
00371 /**
00372   * @}
00373   */ 
00374 
00375 /**
00376   * @}
00377   */
00378 
00379 /** @addtogroup STM32F1XX_NUCLEO_Private_Functions
00380   * @{
00381   */ 
00382   
00383 #ifdef HAL_SPI_MODULE_ENABLED
00384 /******************************************************************************
00385                             BUS OPERATIONS
00386 *******************************************************************************/
00387 /**
00388   * @brief  Initializes SPI MSP.
00389   * @retval None
00390   */
00391 static void SPIx_MspInit(void)
00392 {
00393   GPIO_InitTypeDef  gpioinitstruct = {0};
00394   
00395   /*** Configure the GPIOs ***/  
00396   /* Enable GPIO clock */
00397   NUCLEO_SPIx_SCK_GPIO_CLK_ENABLE();
00398   NUCLEO_SPIx_MISO_MOSI_GPIO_CLK_ENABLE();
00399 
00400   /* Configure SPI SCK */
00401   gpioinitstruct.Pin        = NUCLEO_SPIx_SCK_PIN;
00402   gpioinitstruct.Mode       = GPIO_MODE_AF_PP;
00403   gpioinitstruct.Speed      = GPIO_SPEED_HIGH;
00404   HAL_GPIO_Init(NUCLEO_SPIx_SCK_GPIO_PORT, &gpioinitstruct);
00405 
00406   /* Configure SPI MISO and MOSI */ 
00407   gpioinitstruct.Pin        = NUCLEO_SPIx_MOSI_PIN;
00408   HAL_GPIO_Init(NUCLEO_SPIx_MISO_MOSI_GPIO_PORT, &gpioinitstruct);
00409   
00410   gpioinitstruct.Pin        = NUCLEO_SPIx_MISO_PIN;
00411   gpioinitstruct.Mode       = GPIO_MODE_INPUT;
00412   HAL_GPIO_Init(NUCLEO_SPIx_MISO_MOSI_GPIO_PORT, &gpioinitstruct);
00413 
00414   /*** Configure the SPI peripheral ***/ 
00415   /* Enable SPI clock */
00416   NUCLEO_SPIx_CLK_ENABLE();
00417 }
00418 
00419 /**
00420   * @brief  Initializes SPI HAL.
00421   * @retval None
00422   */
00423 static void SPIx_Init(void)
00424 {
00425   if(HAL_SPI_GetState(&hnucleo_Spi) == HAL_SPI_STATE_RESET)
00426   {
00427     /* SPI Config */
00428     hnucleo_Spi.Instance = NUCLEO_SPIx;
00429       /* SPI baudrate is set to 8 MHz maximum (PCLK2/SPI_BaudRatePrescaler = 64/8 = 8 MHz) 
00430        to verify these constraints:
00431           - ST7735 LCD SPI interface max baudrate is 15MHz for write and 6.66MHz for read
00432             Since the provided driver doesn't use read capability from LCD, only constraint 
00433             on write baudrate is considered.
00434           - SD card SPI interface max baudrate is 25MHz for write/read
00435           - PCLK2 max frequency is 32 MHz 
00436        */
00437     hnucleo_Spi.Init.BaudRatePrescaler  = SPI_BAUDRATEPRESCALER_8;
00438     hnucleo_Spi.Init.Direction          = SPI_DIRECTION_2LINES;
00439     hnucleo_Spi.Init.CLKPhase           = SPI_PHASE_1EDGE;
00440     hnucleo_Spi.Init.CLKPolarity        = SPI_POLARITY_LOW;
00441     hnucleo_Spi.Init.CRCCalculation     = SPI_CRCCALCULATION_DISABLE;
00442     hnucleo_Spi.Init.CRCPolynomial      = 7;
00443     hnucleo_Spi.Init.DataSize           = SPI_DATASIZE_8BIT;
00444     hnucleo_Spi.Init.FirstBit           = SPI_FIRSTBIT_MSB;
00445     hnucleo_Spi.Init.NSS                = SPI_NSS_SOFT;
00446     hnucleo_Spi.Init.TIMode             = SPI_TIMODE_DISABLE;
00447     hnucleo_Spi.Init.Mode               = SPI_MODE_MASTER;
00448     
00449     SPIx_MspInit();
00450     HAL_SPI_Init(&hnucleo_Spi);
00451   }
00452 }
00453 
00454 /**
00455   * @brief  SPI Read 4 bytes from device
00456   * @retval Read data
00457 */
00458 static uint32_t SPIx_Read(void)
00459 {
00460   HAL_StatusTypeDef status = HAL_OK;
00461   uint32_t readvalue = 0;
00462   uint32_t writevalue = 0xFFFFFFFF;
00463   
00464   status = HAL_SPI_TransmitReceive(&hnucleo_Spi, (uint8_t*) &writevalue, (uint8_t*) &readvalue, 1, SpixTimeout);
00465   
00466   /* Check the communication status */
00467   if(status != HAL_OK)
00468   {
00469     /* Execute user timeout callback */
00470     SPIx_Error();
00471   }
00472 
00473   return readvalue;
00474 }
00475 
00476 /**
00477   * @brief  SPI Write a byte to device
00478   * @param  Value: value to be written
00479   * @retval None
00480   */
00481 static void SPIx_Write(uint8_t Value)
00482 {
00483   HAL_StatusTypeDef status = HAL_OK;
00484 
00485   status = HAL_SPI_Transmit(&hnucleo_Spi, (uint8_t*) &Value, 1, SpixTimeout);
00486 
00487   /* Check the communication status */
00488   if(status != HAL_OK)
00489   {
00490     /* Execute user timeout callback */
00491     SPIx_Error();
00492   }
00493 }
00494 
00495 /**
00496   * @brief  SPI error treatment function
00497   * @retval None
00498   */
00499 static void SPIx_Error (void)
00500 {
00501   /* De-initialize the SPI communication BUS */
00502   HAL_SPI_DeInit(&hnucleo_Spi);
00503 
00504   /* Re-Initiaize the SPI communication BUS */
00505   SPIx_Init();
00506 }
00507 
00508 /******************************************************************************
00509                             LINK OPERATIONS
00510 *******************************************************************************/
00511 
00512 /********************************* LINK SD ************************************/
00513 /**
00514   * @brief  Initializes the SD Card and put it into StandBy State (Ready for 
00515   *         data transfer).
00516   * @retval None
00517   */
00518 void SD_IO_Init(void)
00519 {
00520   GPIO_InitTypeDef  gpioinitstruct = {0};
00521   uint8_t counter = 0;
00522 
00523   /* SD_CS_GPIO Periph clock enable */
00524   SD_CS_GPIO_CLK_ENABLE();
00525 
00526   /* Configure SD_CS_PIN pin: SD Card CS pin */
00527   gpioinitstruct.Pin    = SD_CS_PIN;
00528   gpioinitstruct.Mode   = GPIO_MODE_OUTPUT_PP;
00529   gpioinitstruct.Pull   = GPIO_PULLUP;
00530   gpioinitstruct.Speed  = GPIO_SPEED_HIGH;
00531   HAL_GPIO_Init(SD_CS_GPIO_PORT, &gpioinitstruct);
00532 
00533   /*------------Put SD in SPI mode--------------*/
00534   /* SD SPI Config */
00535   SPIx_Init();
00536 
00537   /* SD chip select high */
00538   SD_CS_HIGH();
00539   
00540   /* Send dummy byte 0xFF, 10 times with CS high */
00541   /* Rise CS and MOSI for 80 clocks cycles */
00542   for (counter = 0; counter <= 9; counter++)
00543   {
00544     /* Send dummy byte 0xFF */
00545     SD_IO_WriteByte(SD_DUMMY_BYTE);
00546   }
00547 }
00548 
00549 /**
00550   * @brief  Writes a byte on the SD.
00551   * @param  Data: byte to send.
00552   * @retval None
00553   */
00554 void SD_IO_WriteByte(uint8_t Data)
00555 {
00556   /* Send the byte */
00557   SPIx_Write(Data);
00558 }
00559  
00560 /**
00561   * @brief  Reads a byte from the SD.
00562   * @retval The received byte.
00563   */
00564 uint8_t SD_IO_ReadByte(void)
00565   {
00566   uint8_t data = 0;
00567   
00568   /* Get the received data */
00569   data = SPIx_Read();
00570 
00571   /* Return the shifted data */
00572   return data;
00573 }
00574 
00575 /**
00576   * @brief  Sends 5 bytes command to the SD card and get response
00577   * @param  Cmd: The user expected command to send to SD card.
00578   * @param  Arg: The command argument.
00579   * @param  Crc: The CRC.
00580   * @param  Response: Expected response from the SD card
00581   * @retval HAL_StatusTypeDef HAL Status
00582   */
00583 HAL_StatusTypeDef SD_IO_WriteCmd(uint8_t Cmd, uint32_t Arg, uint8_t Crc, uint8_t Response)
00584 {
00585   uint32_t counter = 0x00;
00586   uint8_t frame[6] = {0};
00587 
00588   /* Prepare Frame to send */
00589   frame[0] = (Cmd | 0x40);         /* Construct byte 1 */
00590   frame[1] = (uint8_t)(Arg >> 24); /* Construct byte 2 */
00591   frame[2] = (uint8_t)(Arg >> 16); /* Construct byte 3 */
00592   frame[3] = (uint8_t)(Arg >> 8);  /* Construct byte 4 */
00593   frame[4] = (uint8_t)(Arg);       /* Construct byte 5 */
00594   frame[5] = (Crc);                /* Construct byte 6 */
00595   
00596   /* SD chip select low */
00597   SD_CS_LOW();
00598     
00599   /* Send Frame */
00600   for (counter = 0; counter < 6; counter++)
00601   {
00602     SD_IO_WriteByte(frame[counter]); /* Send the Cmd bytes */
00603   }
00604 
00605   if(Response != SD_NO_RESPONSE_EXPECTED)
00606   {
00607     return SD_IO_WaitResponse(Response);
00608   }  
00609   
00610   return HAL_OK;
00611 }
00612 
00613 /**
00614   * @brief  Waits response from the SD card
00615   * @param  Response: Expected response from the SD card
00616   * @retval HAL_StatusTypeDef HAL Status
00617   */
00618 HAL_StatusTypeDef SD_IO_WaitResponse(uint8_t Response)
00619 {
00620   uint32_t timeout = 0xFFFF;
00621 
00622   /* Check if response is got or a timeout is happen */
00623   while ((SD_IO_ReadByte() != Response) && timeout)
00624   {
00625     timeout--;
00626   }
00627 
00628   if (timeout == 0)
00629   {
00630     /* After time out */
00631     return HAL_TIMEOUT;
00632   }   
00633   else
00634   {
00635     /* Right response got */
00636     return HAL_OK;
00637   }
00638   }  
00639  
00640 /**
00641   * @brief  Sends dummy byte with CS High
00642   * @retval None
00643   */
00644 void SD_IO_WriteDummy(void)
00645 {
00646   /* SD chip select high */
00647   SD_CS_HIGH();
00648   
00649   /* Send Dummy byte 0xFF */
00650   SD_IO_WriteByte(SD_DUMMY_BYTE);
00651 }
00652 
00653 /********************************* LINK LCD ***********************************/
00654 /**
00655   * @brief  Initializes the LCD
00656   * @retval None
00657   */
00658 void LCD_IO_Init(void)
00659 {
00660   GPIO_InitTypeDef  gpioinitstruct = {0};
00661 
00662   /* LCD_CS_GPIO and LCD_DC_GPIO Periph clock enable */
00663   LCD_CS_GPIO_CLK_ENABLE();
00664   LCD_DC_GPIO_CLK_ENABLE();
00665   
00666   /* Configure LCD_CS_PIN pin: LCD Card CS pin */
00667   gpioinitstruct.Pin    = LCD_CS_PIN;
00668   gpioinitstruct.Mode   = GPIO_MODE_OUTPUT_PP;
00669   gpioinitstruct.Speed  = GPIO_SPEED_HIGH;
00670   HAL_GPIO_Init(SD_CS_GPIO_PORT, &gpioinitstruct);
00671       
00672   /* Configure LCD_DC_PIN pin: LCD Card DC pin */
00673   gpioinitstruct.Pin    = LCD_DC_PIN;
00674   HAL_GPIO_Init(LCD_DC_GPIO_PORT, &gpioinitstruct);
00675 
00676   /* LCD chip select high */
00677   LCD_CS_HIGH();
00678   
00679   /* LCD SPI Config */
00680   SPIx_Init();
00681 }
00682 
00683 /**
00684   * @brief  Writes command to select the LCD register.
00685   * @param  LCDReg: Address of the selected register.
00686   * @retval None
00687   */
00688 void LCD_IO_WriteReg(uint8_t LCDReg)
00689 {
00690   /* Reset LCD control line CS */
00691   LCD_CS_LOW();
00692   
00693   /* Set LCD data/command line DC to Low */
00694   LCD_DC_LOW();
00695     
00696   /* Send Command */
00697   SPIx_Write(LCDReg);
00698   
00699   /* Deselect : Chip Select high */
00700   LCD_CS_HIGH();
00701 }
00702 
00703 /**
00704 * @brief  Write register value.
00705 * @param  pData Pointer on the register value
00706 * @param  Size Size of byte to transmit to the register
00707 * @retval None
00708 */
00709 void LCD_IO_WriteMultipleData(uint8_t *pData, uint32_t Size)
00710 {
00711   uint32_t counter = 0;
00712   
00713   /* Reset LCD control line CS */
00714   LCD_CS_LOW();
00715   
00716   /* Set LCD data/command line DC to High */
00717   LCD_DC_HIGH();
00718 
00719   if (Size == 1)
00720   {
00721     /* Only 1 byte to be sent to LCD - general interface can be used */
00722     /* Send Data */
00723     SPIx_Write(*pData);
00724   }
00725   else
00726 {
00727     /* Several data should be sent in a raw */
00728     /* Direct SPI accesses for optimization */
00729     for (counter = Size; counter != 0; counter--)
00730   {
00731       while(((hnucleo_Spi.Instance->SR) & SPI_FLAG_TXE) != SPI_FLAG_TXE)
00732   {
00733 }
00734       /* Need to invert bytes for LCD*/
00735       *((__IO uint8_t*)&hnucleo_Spi.Instance->DR) = *(pData+1);
00736 
00737       while(((hnucleo_Spi.Instance->SR) & SPI_FLAG_TXE) != SPI_FLAG_TXE)
00738 {
00739 }
00740       *((__IO uint8_t*)&hnucleo_Spi.Instance->DR) = *pData;
00741       counter--;
00742       pData += 2;
00743   }  
00744   
00745     /* Wait until the bus is ready before releasing Chip select */ 
00746     while(((hnucleo_Spi.Instance->SR) & SPI_FLAG_BSY) != RESET)
00747   {
00748   } 
00749   } 
00750   /* Deselect : Chip Select high */
00751   LCD_CS_HIGH();
00752 }
00753 
00754 /**
00755   * @brief  Wait for loop in ms.
00756   * @param  Delay in ms.
00757   * @retval None
00758   */
00759 void LCD_Delay(uint32_t Delay)
00760 {
00761   HAL_Delay(Delay);
00762 }
00763 
00764 #endif /* HAL_SPI_MODULE_ENABLED */
00765 
00766 #ifdef HAL_ADC_MODULE_ENABLED
00767 /******************************* LINK JOYSTICK ********************************/
00768 /**
00769   * @brief  Initializes ADC MSP.
00770   * @retval None
00771   */
00772 static void ADCx_MspInit(ADC_HandleTypeDef *hadc)
00773 {
00774   GPIO_InitTypeDef  gpioinitstruct = {0};
00775   
00776   /*** Configure the GPIOs ***/  
00777   /* Enable GPIO clock */
00778   NUCLEO_ADCx_GPIO_CLK_ENABLE();
00779   
00780   /* Configure ADC1 Channel8 as analog input */
00781   gpioinitstruct.Pin    = NUCLEO_ADCx_GPIO_PIN ;
00782   gpioinitstruct.Mode   = GPIO_MODE_ANALOG;
00783   gpioinitstruct.Pull   = GPIO_NOPULL;
00784   gpioinitstruct.Speed  = GPIO_SPEED_MEDIUM;
00785   HAL_GPIO_Init(NUCLEO_ADCx_GPIO_PORT, &gpioinitstruct);
00786 
00787   /*** Configure the ADC peripheral ***/ 
00788   /* Enable ADC clock */
00789   NUCLEO_ADCx_CLK_ENABLE(); 
00790 }
00791 
00792 /**
00793   * @brief  Initializes ADC HAL.
00794   * @retval None
00795   */
00796 static void ADCx_Init(void)
00797 {
00798   if(HAL_ADC_GetState(&hnucleo_Adc) == HAL_ADC_STATE_RESET)
00799   {
00800     /* ADC Config */
00801     hnucleo_Adc.Instance                    = NUCLEO_ADCx;
00802 
00803     hnucleo_Adc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
00804     hnucleo_Adc.Init.ScanConvMode = ADC_SCAN_DISABLE;
00805     hnucleo_Adc.Init.ContinuousConvMode = DISABLE;
00806     hnucleo_Adc.Init.NbrOfConversion = 1;
00807     hnucleo_Adc.Init.DiscontinuousConvMode = DISABLE;
00808     hnucleo_Adc.Init.NbrOfDiscConversion = 1;
00809     hnucleo_Adc.Init.ExternalTrigConv = ADC_SOFTWARE_START;
00810     
00811     ADCx_MspInit(&hnucleo_Adc);
00812     HAL_ADC_Init(&hnucleo_Adc);
00813   }
00814 }  
00815 
00816 #endif /* HAL_ADC_MODULE_ENABLED */
00817 
00818 /**
00819   * @}
00820   */
00821   
00822 /**
00823   * @}
00824   */    
00825 
00826 /**
00827   * @}
00828   */ 
00829     
00830 /**
00831   * @}
00832   */ 
00833     
00834 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
Generated on Thu Dec 11 2014 16:58:14 for _BSP_User_Manual by   doxygen 1.7.5.1