diff --git a/stm32f0xx_hal_conf.h b/stm32f0xx_hal_conf.h
new file mode 100644
--- /dev/null
+++ b/stm32f0xx_hal_conf.h
@@ -0,0 +1,304 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_conf.h
+ * @brief HAL configuration template file.
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT(c) 2014 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F0xx_HAL_CONF_H
+#define __STM32F0xx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+ //#define HAL_ADC_MODULE_ENABLED
+//#define HAL_CAN_MODULE_ENABLED
+//#define HAL_CEC_MODULE_ENABLED
+//#define HAL_COMP_MODULE_ENABLED
+//#define HAL_CRC_MODULE_ENABLED
+//#define HAL_CRYP_MODULE_ENABLED
+//#define HAL_TSC_MODULE_ENABLED
+//#define HAL_DAC_MODULE_ENABLED
+//#define HAL_I2C_MODULE_ENABLED
+//#define HAL_I2S_MODULE_ENABLED
+//#define HAL_IWDG_MODULE_ENABLED
+//#define HAL_LCD_MODULE_ENABLED
+//#define HAL_LPTIM_MODULE_ENABLED
+//#define HAL_RNG_MODULE_ENABLED
+//#define HAL_RTC_MODULE_ENABLED
+#define HAL_SPI_MODULE_ENABLED
+//#define HAL_TIM_MODULE_ENABLED
+//#define HAL_UART_MODULE_ENABLED
+//#define HAL_USART_MODULE_ENABLED
+//#define HAL_IRDA_MODULE_ENABLED
+//#define HAL_SMARTCARD_MODULE_ENABLED
+//#define HAL_SMBUS_MODULE_ENABLED
+//#define HAL_WWDG_MODULE_ENABLED
+#define HAL_PCD_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+
+/* ########################## HSE/HSI Values adaptation ##################### */
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+/**
+ * @brief In the following line adjust the External High Speed oscillator (HSE) Startup
+ * Timeout value
+ */
+#if !defined (HSE_STARTUP_TIMEOUT)
+ #define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @brief In the following line adjust the Internal High Speed oscillator (HSI) Startup
+ * Timeout value
+ */
+#if !defined (HSI_STARTUP_TIMEOUT)
+ #define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
+#endif /* HSI_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator for ADC (HSI14) value.
+ */
+#if !defined (HSI14_VALUE)
+#define HSI14_VALUE ((uint32_t)14000000) /*!< Value of the Internal High Speed oscillator for ADC in Hz.
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+#endif /* HSI14_VALUE */
+
+/**
+ * @brief Internal High Speed oscillator for USB (HSI48) value.
+ */
+#if !defined (HSI48_VALUE)
+#define HSI48_VALUE ((uint32_t)48000000) /*!< Value of the Internal High Speed oscillator for USB in Hz.
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+#endif /* HSI48_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSI_VALUE)
+ #define LSI_VALUE ((uint32_t)40000)
+#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+/**
+ * @brief External Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSE_VALUE)
+ #define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
+#endif /* LSE_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY ((uint32_t)0) /*!< tick interrupt priority (lowest by default) */
+ /* Warning: Must be set to higher priority for HAL_Delay() */
+ /* and HAL_GetTick() usage under interrupt context */
+#define USE_RTOS 0
+#define PREFETCH_ENABLE 1
+#define INSTRUCTION_CACHE_ENABLE 0
+#define DATA_CACHE_ENABLE 0
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1 */
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+ #include "stm32f0xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+ #include "stm32f0xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+ #include "stm32f0xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+ #include "stm32f0xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+ #include "stm32f0xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_CAN_MODULE_ENABLED
+ #include "stm32f0xx_hal_can.h"
+#endif /* HAL_CAN_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+ #include "stm32f0xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+ #include "stm32f0xx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+ #include "stm32f0xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+ #include "stm32f0xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+ #include "stm32f0xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32f0xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32f0xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32f0xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32f0xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32f0xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32f0xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+ #include "stm32f0xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32f0xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32f0xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32f0xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32f0xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_TSC_MODULE_ENABLED
+ #include "stm32f0xx_hal_tsc.h"
+#endif /* HAL_TSC_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32f0xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32f0xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32f0xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr: If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(uint8_t* file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_CONF_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/stm32f0xx_hal_msp.c b/stm32f0xx_hal_msp.c
new file mode 100644
--- /dev/null
+++ b/stm32f0xx_hal_msp.c
@@ -0,0 +1,128 @@
+/**
+ ******************************************************************************
+ * File Name : stm32f0xx_hal_msp.c
+ * Date : 03/01/2015 14:04:02
+ * Description : This file provides code for the MSP Initialization
+ * and de-Initialization codes.
+ ******************************************************************************
+ *
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/**
+ * Initializes the Global MSP.
+ */
+void HAL_MspInit(void)
+{
+ /* USER CODE BEGIN MspInit 0 */
+
+ /* USER CODE END MspInit 0 */
+
+ /* System interrupt init*/
+/* SysTick_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+
+ /* USER CODE BEGIN MspInit 1 */
+
+ /* USER CODE END MspInit 1 */
+}
+
+void HAL_SPI_MspInit(SPI_HandleTypeDef* hspi)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct;
+ if(hspi->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspInit 0 */
+
+ /* USER CODE END SPI1_MspInit 0 */
+ /* Peripheral clock enable */
+ __SPI1_CLK_ENABLE();
+
+ /**SPI1 GPIO Configuration
+ PA5 ------> SPI1_SCK
+ PA6 ------> SPI1_MISO
+ PA7 ------> SPI1_MOSI
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF0_SPI1;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN SPI1_MspInit 1 */
+
+ /* USER CODE END SPI1_MspInit 1 */
+ }
+
+}
+
+void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi)
+{
+
+ if(hspi->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspDeInit 0 */
+
+ /* USER CODE END SPI1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __SPI1_CLK_DISABLE();
+
+ /**SPI1 GPIO Configuration
+ PA5 ------> SPI1_SCK
+ PA6 ------> SPI1_MISO
+ PA7 ------> SPI1_MOSI
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7);
+
+ /* USER CODE BEGIN SPI1_MspDeInit 1 */
+
+ /* USER CODE END SPI1_MspDeInit 1 */
+ }
+
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/stm32f0xx_it.c b/stm32f0xx_it.c
--- a/stm32f0xx_it.c
+++ b/stm32f0xx_it.c
@@ -1,198 +1,83 @@
/**
******************************************************************************
- * @file stm32f0xx_it.c
- * @author MCD Application Team
- * @version V1.0.0
- * @date 29-July-2013
- * @brief Main Interrupt Service Routines.
- * This file provides template for all exceptions handler and
- * peripherals interrupt service routine.
+ * @file stm32f0xx_it.c
+ * @date 03/01/2015 14:04:02
+ * @brief Interrupt Service Routines.
******************************************************************************
- * @attention
*
- * © COPYRIGHT 2013 STMicroelectronics
+ * COPYRIGHT(c) 2015 STMicroelectronics
*
- * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
- * You may not use this file except in compliance with the License.
- * You may obtain a copy of the License at:
- *
- * http://www.st.com/software_license_agreement_liberty_v2
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
*
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
-
/* Includes ------------------------------------------------------------------*/
-#include "hw_config.h"
+#include "stm32f0xx_hal.h"
+#include "stm32f0xx.h"
#include "stm32f0xx_it.h"
-#include "main.h"
-//#include "usb_lib.h"
-//#include "usb_istr.h"
+/* USER CODE BEGIN 0 */
-/* Private typedef -----------------------------------------------------------*/
-/* Private define ------------------------------------------------------------*/
-/* Private macro -------------------------------------------------------------*/
-/* Private variables ---------------------------------------------------------*/
-/* Private function prototypes -----------------------------------------------*/
-/* Private functions ---------------------------------------------------------*/
+/* USER CODE END 0 */
+/* External variables --------------------------------------------------------*/
+
+extern PCD_HandleTypeDef hpcd_USB_FS;
/******************************************************************************/
-/* Cortex-M3 Processor Exceptions Handlers */
+/* Cortex-M0 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
- * @brief This function handles NMI exception.
- * @param None
- * @retval None
- */
-void NMI_Handler(void)
+* @brief This function handles USB global Interrupt (combined with EXTI line 18).
+*/
+void USB_IRQHandler(void)
{
-}
-
-/**
- * @brief This function handles Hard Fault exception.
- * @param None
- * @retval None
- */
-void HardFault_Handler(void)
-{
- /* Go to infinite loop when Hard Fault exception occurs */
- while (1)
- {
- }
-}
+ /* USER CODE BEGIN USB_IRQn 0 */
-/**
- * @brief This function handles Memory Manage exception.
- * @param None
- * @retval None
- */
-void MemManage_Handler(void)
-{
- /* Go to infinite loop when Memory Manage exception occurs */
- while (1)
- {
- }
-}
+ /* USER CODE END USB_IRQn 0 */
+ HAL_PCD_IRQHandler(&hpcd_USB_FS);
+ /* USER CODE BEGIN USB_IRQn 1 */
-/**
- * @brief This function handles Bus Fault exception.
- * @param None
- * @retval None
- */
-void BusFault_Handler(void)
-{
- /* Go to infinite loop when Bus Fault exception occurs */
- while (1)
- {
- }
+ /* USER CODE END USB_IRQn 1 */
}
/**
- * @brief This function handles Usage Fault exception.
- * @param None
- * @retval None
- */
-void UsageFault_Handler(void)
-{
- /* Go to infinite loop when Usage Fault exception occurs */
- while (1)
- {
- }
-}
-
-/**
- * @brief This function handles SVCall exception.
- * @param None
- * @retval None
- */
-void SVC_Handler(void)
-{
-}
-
-/**
- * @brief This function handles Debug Monitor exception.
- * @param None
- * @retval None
- */
-void DebugMon_Handler(void)
-{
-}
-
-/**
- * @brief This function handles PendSVC exception.
- * @param None
- * @retval None
- */
-void PendSV_Handler(void)
-{
-}
-
-/**
- * @brief This function handles SysTick Handler.
- * @param None
- * @retval None
- */
+* @brief This function handles System tick timer.
+*/
void SysTick_Handler(void)
{
+ /* USER CODE BEGIN SysTick_IRQn 0 */
+
+ /* USER CODE END SysTick_IRQn 0 */
+ HAL_IncTick();
+ HAL_SYSTICK_IRQHandler();
+ /* USER CODE BEGIN SysTick_IRQn 1 */
+
TimingDelay_Decrement();
+
+ /* USER CODE END SysTick_IRQn 1 */
}
-
-
-
-
-
-/*******************************************************************************
-* Function Name : USB_IRQHandler
-* Description : This function handles USB Low Priority interrupts
-* requests.
-* Input : None
-* Output : None
-* Return : None
-*******************************************************************************/
-//void USB_LP_IRQHandler(void)
-//{
-// USB_Istr();
-//}
+/* USER CODE BEGIN 1 */
-/*******************************************************************************
-* Function Name : USB_FS_WKUP_IRQHandler
-* Description : This function handles USB WakeUp interrupt request.
-* Input : None
-* Output : None
-* Return : None
-*******************************************************************************/
-//void USB_FS_WKUP_IRQHandler(void)
-//{
-// EXTI_ClearITPendingBit(EXTI_Line18);
-//}
-
-
-
-
-
-
-/******************************************************************************/
-/* STM32L1xx Peripherals Interrupt Handlers */
-/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */
-/* available peripheral interrupt handler's name please refer to the startup */
-/* file (startup_stm32l1xx_xx.s). */
-/******************************************************************************/
-
-/**
- * @brief This function handles PPP interrupt request.
- * @param None
- * @retval None
- */
-/*void PPP_IRQHandler(void)
-{
-}*/
-
-
+/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_device.c b/usb_device.c
new file mode 100644
--- /dev/null
+++ b/usb_device.c
@@ -0,0 +1,68 @@
+/**
+ ******************************************************************************
+ * @file : USB_DEVICE
+ * @date : 03/01/2015 14:04:02
+ * @version : v1.0_Cube
+ * @brief : This file implements the USB Device
+ ******************************************************************************
+ *
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+
+/* Includes ------------------------------------------------------------------*/
+
+#include "usb_device.h"
+#include "usbd_core.h"
+#include "usbd_desc.h"
+#include "usbd_cdc.h"
+#include "usbd_cdc_if.h"
+
+/* USB Device Core handle declaration */
+USBD_HandleTypeDef hUsbDeviceFS;
+
+/* init function */
+void MX_USB_DEVICE_Init(void)
+{
+ /* Init Device Library,Add Supported Class and Start the library*/
+ USBD_Init(&hUsbDeviceFS, &FS_Desc, DEVICE_FS);
+
+ USBD_RegisterClass(&hUsbDeviceFS, &USBD_CDC);
+
+ USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS);
+
+ USBD_Start(&hUsbDeviceFS);
+
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usb_device.h b/usb_device.h
new file mode 100644
--- /dev/null
+++ b/usb_device.h
@@ -0,0 +1,64 @@
+/**
+ ******************************************************************************
+ * @file : USB_DEVICE
+ * @date : 03/01/2015 14:04:02
+ * @version : v1.0_Cube
+ * @brief : Header for usb_device file.
+ ******************************************************************************
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __usb_device_H
+#define __usb_device_H
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+#include "stm32f0xx_hal.h"
+#include "usbd_def.h"
+
+extern USBD_HandleTypeDef hUsbDeviceFS;
+
+/* USB_Device init function */
+void MX_USB_DEVICE_Init(void);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__usb_device_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usbd_cdc_if.c b/usbd_cdc_if.c
new file mode 100644
--- /dev/null
+++ b/usbd_cdc_if.c
@@ -0,0 +1,280 @@
+/**
+ ******************************************************************************
+ * @file : usbd_cdc_if.c
+ * @author : MCD Application Team
+ * @version : V1.1.0
+ * @date : 19-March-2012
+ * @brief :
+ ******************************************************************************
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_if.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_CDC
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_Private_TypesDefinitions
+ * @{
+ */
+ /* USER CODE BEGIN 0 */
+ /* USER CODE END 0 */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Defines
+ * @{
+ */
+ /* USER CODE BEGIN 1 */
+/* Define size for the receive and transmit buffer over CDC */
+/* It's up to user to redefine and/or remove those define */
+#define APP_RX_DATA_SIZE 512
+#define APP_TX_DATA_SIZE 512
+ /* USER CODE END 1 */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Macros
+ * @{
+ */
+ /* USER CODE BEGIN 2 */
+ /* USER CODE END 2 */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Variables
+ * @{
+ */
+ /* USER CODE BEGIN 3 */
+/* Create buffer for reception and transmission */
+/* It's up to user to redefine and/or remove those define */
+/* Received Data over USB are stored in this buffer */
+uint8_t UserRxBufferFS[APP_RX_DATA_SIZE];
+
+/* Send Data over USB CDC are stored in this buffer */
+uint8_t UserTxBufferFS[APP_TX_DATA_SIZE];
+
+ /* USER CODE END 3 */
+
+/* USB handler declaration */
+/* Handle for USB Full Speed IP */
+USBD_HandleTypeDef *hUsbDevice_0;
+
+extern USBD_HandleTypeDef hUsbDeviceFS;
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_FunctionPrototypes
+ * @{
+ */
+static int8_t CDC_Init_FS (void);
+static int8_t CDC_DeInit_FS (void);
+static int8_t CDC_Control_FS (uint8_t cmd, uint8_t* pbuf, uint16_t length);
+static int8_t CDC_Receive_FS (uint8_t* pbuf, uint32_t *Len);
+
+USBD_CDC_ItfTypeDef USBD_Interface_fops_FS =
+{
+ CDC_Init_FS,
+ CDC_DeInit_FS,
+ CDC_Control_FS,
+ CDC_Receive_FS
+};
+
+/* Private functions ---------------------------------------------------------*/
+/**
+ * @brief CDC_Init_FS
+ * Initializes the CDC media low layer over the FS USB IP
+ * @param None
+ * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Init_FS(void)
+{
+ hUsbDevice_0 = &hUsbDeviceFS;
+ /* USER CODE BEGIN 4 */
+ /* Set Application Buffers */
+ USBD_CDC_SetTxBuffer(hUsbDevice_0, UserTxBufferFS, 0);
+ USBD_CDC_SetRxBuffer(hUsbDevice_0, UserRxBufferFS);
+ return (USBD_OK);
+ /* USER CODE END 4 */
+}
+
+/**
+ * @brief CDC_DeInit_FS
+ * DeInitializes the CDC media low layer
+ * @param None
+ * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_DeInit_FS(void)
+{
+ /* USER CODE BEGIN 5 */
+ return (USBD_OK);
+ /* USER CODE END 5 */
+}
+
+/**
+ * @brief CDC_Control_FS
+ * Manage the CDC class requests
+ * @param Cmd: Command code
+ * @param Buf: Buffer containing command data (request parameters)
+ * @param Len: Number of data to be sent (in bytes)
+ * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Control_FS (uint8_t cmd, uint8_t* pbuf, uint16_t length)
+{
+ /* USER CODE BEGIN 6 */
+ switch (cmd)
+ {
+ case CDC_SEND_ENCAPSULATED_COMMAND:
+
+ break;
+
+ case CDC_GET_ENCAPSULATED_RESPONSE:
+
+ break;
+
+ case CDC_SET_COMM_FEATURE:
+
+ break;
+
+ case CDC_GET_COMM_FEATURE:
+
+ break;
+
+ case CDC_CLEAR_COMM_FEATURE:
+
+ break;
+
+ /*******************************************************************************/
+ /* Line Coding Structure */
+ /*-----------------------------------------------------------------------------*/
+ /* Offset | Field | Size | Value | Description */
+ /* 0 | dwDTERate | 4 | Number |Data terminal rate, in bits per second*/
+ /* 4 | bCharFormat | 1 | Number | Stop bits */
+ /* 0 - 1 Stop bit */
+ /* 1 - 1.5 Stop bits */
+ /* 2 - 2 Stop bits */
+ /* 5 | bParityType | 1 | Number | Parity */
+ /* 0 - None */
+ /* 1 - Odd */
+ /* 2 - Even */
+ /* 3 - Mark */
+ /* 4 - Space */
+ /* 6 | bDataBits | 1 | Number Data bits (5, 6, 7, 8 or 16). */
+ /*******************************************************************************/
+ case CDC_SET_LINE_CODING:
+
+ break;
+
+ case CDC_GET_LINE_CODING:
+
+ break;
+
+ case CDC_SET_CONTROL_LINE_STATE:
+
+ break;
+
+ case CDC_SEND_BREAK:
+
+ break;
+
+ default:
+ break;
+ }
+
+ return (USBD_OK);
+ /* USER CODE END 6 */
+}
+
+/**
+ * @brief CDC_Receive_FS
+ * Data received over USB OUT endpoint are sent over CDC interface
+ * through this function.
+ *
+ * @note
+ * This function will block any OUT packet reception on USB endpoint
+ * untill exiting this function. If you exit this function before transfer
+ * is complete on CDC interface (ie. using DMA controller) it will result
+ * in receiving more data while previous ones are still not sent.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Receive_FS (uint8_t* Buf, uint32_t *Len)
+{
+ /* USER CODE BEGIN 7 */
+ return (USBD_OK);
+ /* USER CODE END 7 */
+}
+
+/**
+ * @brief CDC_Transmit_FS
+ * Data send over USB IN endpoint are sent over CDC interface
+ * through this function.
+ * @note
+ *
+ *
+ * @param Buf: Buffer of data to be send
+ * @param Len: Number of data to be send (in bytes)
+ * @retval Result of the opeartion: USBD_OK if all operations are OK else USBD_FAIL or USBD_BUSY
+ */
+uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len)
+{
+ uint8_t result = USBD_OK;
+ /* USER CODE BEGIN 8 */
+ USBD_CDC_SetTxBuffer(hUsbDevice_0, UserTxBufferFS, Len);
+ result = USBD_CDC_TransmitPacket(hUsbDevice_0);
+ /* USER CODE END 8 */
+ return result;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/usbd_cdc_if.h b/usbd_cdc_if.h
new file mode 100644
--- /dev/null
+++ b/usbd_cdc_if.h
@@ -0,0 +1,60 @@
+/**
+ ******************************************************************************
+ * @file : usbd_cdc_if.h
+ * @author : MCD Application Team
+ * @version : V1.1.0
+ * @date : 19-March-2012
+ * @brief : Header for usbd_cdc_if file.
+ ******************************************************************************
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CDC_IF_H
+#define __USBD_CDC_IF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported cariables --------------------------------------------------------*/
+extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS;
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+/** @defgroup USBD_CDC_IF_Exported_FunctionsPrototype
+ * @{
+ */
+uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len);
+
+/**
+ * @}
+ */
+#endif /* __USBD_CDC_IF_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usbd_conf.c b/usbd_conf.c
new file mode 100644
--- /dev/null
+++ b/usbd_conf.c
@@ -0,0 +1,529 @@
+/**
+ ******************************************************************************
+ * @file : usbd_conf.c
+ * @date : 03/01/2015 14:04:02
+ * @version : v1.0_Cube
+ * @brief : This file implements the board support package for the USB device library
+ ******************************************************************************
+ *
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+#include "stm32f0xx_hal.h"
+#include "usbd_def.h"
+#include "usbd_core.h"
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+PCD_HandleTypeDef hpcd_USB_FS;
+
+/* USER CODE BEGIN 0 */
+__IO uint32_t remotewakeupon=0;
+/* USER CODE END 0 */
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/* USER CODE BEGIN 1 */
+static void SystemClockConfig_Resume(void);
+/* USER CODE END 1 */
+void HAL_PCDEx_SetConnectionState(PCD_HandleTypeDef *hpcd, uint8_t state);
+extern void SystemClock_Config(void);
+
+/*******************************************************************************
+ LL Driver Callbacks (PCD -> USB Device Library)
+*******************************************************************************/
+/* MSP Init */
+
+void HAL_PCD_MspInit(PCD_HandleTypeDef* hpcd)
+{
+ if(hpcd->Instance==USB)
+ {
+ /* USER CODE BEGIN USB_MspInit 0 */
+
+ /* USER CODE END USB_MspInit 0 */
+ /* Peripheral clock enable */
+ __USB_CLK_ENABLE();
+ HAL_NVIC_SetPriority(USB_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(USB_IRQn);
+ /* USER CODE BEGIN USB_MspInit 1 */
+
+ /* USER CODE END USB_MspInit 1 */
+ }
+}
+
+void HAL_PCD_MspDeInit(PCD_HandleTypeDef* hpcd)
+{
+ if(hpcd->Instance==USB)
+ {
+ /* USER CODE BEGIN USB_MspDeInit 0 */
+
+ /* USER CODE END USB_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __USB_CLK_DISABLE();
+
+ /* Peripheral interrupt Deinit*/
+ HAL_NVIC_DisableIRQ(USB_IRQn);
+
+ /* USER CODE BEGIN USB_MspDeInit 1 */
+
+ /* USER CODE END USB_MspDeInit 1 */
+ }
+}
+
+/**
+ * @brief Setup stage callback
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_SetupStage(hpcd->pData, (uint8_t *)hpcd->Setup);
+}
+
+/**
+ * @brief Data Out stage callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint Number
+ * @retval None
+ */
+void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+{
+ USBD_LL_DataOutStage(hpcd->pData, epnum, hpcd->OUT_ep[epnum].xfer_buff);
+}
+
+/**
+ * @brief Data In stage callback..
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint Number
+ * @retval None
+ */
+void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+{
+ USBD_LL_DataInStage(hpcd->pData, epnum, hpcd->IN_ep[epnum].xfer_buff);
+}
+
+/**
+ * @brief SOF callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_SOF(hpcd->pData);
+}
+
+/**
+ * @brief Reset callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_SpeedTypeDef speed = USBD_SPEED_FULL;
+
+ /*Set USB Current Speed*/
+ switch (hpcd->Init.speed)
+ {
+ case PCD_SPEED_FULL:
+ speed = USBD_SPEED_FULL;
+ break;
+
+ default:
+ speed = USBD_SPEED_FULL;
+ break;
+ }
+ USBD_LL_SetSpeed(hpcd->pData, speed);
+
+ /*Reset Device*/
+ USBD_LL_Reset(hpcd->pData);
+}
+
+/**
+ * @brief Suspend callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_Suspend(hpcd->pData);
+ /*Enter in STOP mode */
+ /* USER CODE BEGIN 2 */
+ if (hpcd->Init.low_power_enable)
+ {
+ /* Set SLEEPDEEP bit and SleepOnExit of Cortex System Control Register */
+ SCB->SCR |= (uint32_t)((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
+ }
+ /* USER CODE END 2 */
+}
+
+/**
+ * @brief Resume callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
+{
+ /* USER CODE BEGIN 3 */
+ if ((hpcd->Init.low_power_enable)&&(remotewakeupon == 0))
+ {
+ SystemClockConfig_Resume();
+ /* Reset SLEEPDEEP bit of Cortex System Control Register */
+ SCB->SCR &= (uint32_t)~((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
+ }
+ remotewakeupon=0;
+ /* USER CODE END 3 */
+ USBD_LL_Resume(hpcd->pData);
+
+}
+
+/**
+ * @brief ISOC Out Incomplete callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint Number
+ * @retval None
+ */
+void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+{
+ USBD_LL_IsoOUTIncomplete(hpcd->pData, epnum);
+}
+
+/**
+ * @brief ISOC In Incomplete callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint Number
+ * @retval None
+ */
+void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+{
+ USBD_LL_IsoINIncomplete(hpcd->pData, epnum);
+}
+
+/**
+ * @brief Connect callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_DevConnected(hpcd->pData);
+}
+
+/**
+ * @brief Disconnect callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_DevDisconnected(hpcd->pData);
+}
+
+/*******************************************************************************
+ LL Driver Interface (USB Device Library --> PCD)
+*******************************************************************************/
+/**
+ * @brief Initializes the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Init (USBD_HandleTypeDef *pdev)
+{
+ /* Init USB_IP */
+ /* Link The driver to the stack */
+ hpcd_USB_FS.pData = pdev;
+ pdev->pData = &hpcd_USB_FS;
+
+ hpcd_USB_FS.Instance = USB;
+ hpcd_USB_FS.Init.dev_endpoints = 8;
+ hpcd_USB_FS.Init.speed = PCD_SPEED_FULL;
+ hpcd_USB_FS.Init.ep0_mps = DEP0CTL_MPS_8;
+ hpcd_USB_FS.Init.phy_itface = PCD_PHY_EMBEDDED;
+ hpcd_USB_FS.Init.Sof_enable = DISABLE;
+ hpcd_USB_FS.Init.low_power_enable = DISABLE;
+ hpcd_USB_FS.Init.battery_charging_enable = DISABLE;
+ HAL_PCD_Init(&hpcd_USB_FS);
+
+ HAL_PCDEx_PMAConfig(pdev->pData , 0x00 , PCD_SNG_BUF, 0x18);
+ HAL_PCDEx_PMAConfig(pdev->pData , 0x80 , PCD_SNG_BUF, 0x58);
+ return USBD_OK;
+}
+
+/**
+ * @brief De-Initializes the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_DeInit (USBD_HandleTypeDef *pdev)
+{
+ HAL_PCD_DeInit(pdev->pData);
+ return USBD_OK;
+}
+
+/**
+ * @brief Starts the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Start(USBD_HandleTypeDef *pdev)
+{
+ HAL_PCD_Start(pdev->pData);
+ return USBD_OK;
+}
+
+/**
+ * @brief Stops the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Stop (USBD_HandleTypeDef *pdev)
+{
+ HAL_PCD_Stop(pdev->pData);
+ return USBD_OK;
+}
+
+/**
+ * @brief Opens an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @param ep_type: Endpoint Type
+ * @param ep_mps: Endpoint Max Packet Size
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_OpenEP (USBD_HandleTypeDef *pdev,
+ uint8_t ep_addr,
+ uint8_t ep_type,
+ uint16_t ep_mps)
+{
+
+ HAL_PCD_EP_Open(pdev->pData,
+ ep_addr,
+ ep_mps,
+ ep_type);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Closes an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_CloseEP (USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+
+ HAL_PCD_EP_Close(pdev->pData, ep_addr);
+ return USBD_OK;
+}
+
+/**
+ * @brief Flushes an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_FlushEP (USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+
+ HAL_PCD_EP_Flush(pdev->pData, ep_addr);
+ return USBD_OK;
+}
+
+/**
+ * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_StallEP (USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+
+ HAL_PCD_EP_SetStall(pdev->pData, ep_addr);
+ return USBD_OK;
+}
+
+/**
+ * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_ClearStallEP (USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+
+ HAL_PCD_EP_ClrStall(pdev->pData, ep_addr);
+ return USBD_OK;
+}
+
+/**
+ * @brief Returns Stall condition.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval Stall (1: Yes, 0: No)
+ */
+uint8_t USBD_LL_IsStallEP (USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ PCD_HandleTypeDef *hpcd = pdev->pData;
+
+ if((ep_addr & 0x80) == 0x80)
+ {
+ return hpcd->IN_ep[ep_addr & 0x7F].is_stall;
+ }
+ else
+ {
+ return hpcd->OUT_ep[ep_addr & 0x7F].is_stall;
+ }
+}
+/**
+ * @brief Assigns a USB address to the device.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_SetUSBAddress (USBD_HandleTypeDef *pdev, uint8_t dev_addr)
+{
+
+ HAL_PCD_SetAddress(pdev->pData, dev_addr);
+ return USBD_OK;
+}
+
+/**
+ * @brief Transmits data over an endpoint.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @param pbuf: Pointer to data to be sent
+ * @param size: Data size
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Transmit (USBD_HandleTypeDef *pdev,
+ uint8_t ep_addr,
+ uint8_t *pbuf,
+ uint16_t size)
+{
+
+ HAL_PCD_EP_Transmit(pdev->pData, ep_addr, pbuf, size);
+ return USBD_OK;
+}
+
+/**
+ * @brief Prepares an endpoint for reception.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @param pbuf: Pointer to data to be received
+ * @param size: Data size
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev,
+ uint8_t ep_addr,
+ uint8_t *pbuf,
+ uint16_t size)
+{
+
+ HAL_PCD_EP_Receive(pdev->pData, ep_addr, pbuf, size);
+ return USBD_OK;
+}
+
+/**
+ * @brief Returns the last transfered packet size.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval Recived Data Size
+ */
+uint32_t USBD_LL_GetRxDataSize (USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ return HAL_PCD_EP_GetRxCount(pdev->pData, ep_addr);
+}
+
+/**
+ * @brief Delays routine for the USB Device Library.
+ * @param Delay: Delay in ms
+ * @retval None
+ */
+void USBD_LL_Delay (uint32_t Delay)
+{
+ HAL_Delay(Delay);
+}
+
+/**
+ * @brief static single allocation.
+ * @param size: size of allocated memory
+ * @retval None
+ */
+void *USBD_static_malloc(uint32_t size)
+{
+ static uint32_t mem[MAX_STATIC_ALLOC_SIZE];
+ return mem;
+}
+
+/**
+ * @brief Dummy memory free
+ * @param *p pointer to allocated memory address
+ * @retval None
+ */
+void USBD_static_free(void *p)
+{
+
+}
+
+/* USER CODE BEGIN 4 */
+/**
+ * @brief Configures system clock after wake-up from USB Resume CallBack:
+ * enable HSI, PLL and select PLL as system clock source.
+ * @param None
+ * @retval None
+ */
+static void SystemClockConfig_Resume(void)
+{
+ SystemClock_Config();
+}
+/* USER CODE END 4 */
+
+/**
+* @brief Software Device Connection
+* @param hpcd: PCD handle
+* @param state: connection state (0 : disconnected / 1: connected)
+* @retval None
+*/
+void HAL_PCDEx_SetConnectionState(PCD_HandleTypeDef *hpcd, uint8_t state)
+{
+/* USER CODE BEGIN 5 */
+ if (state == 1)
+ {
+ /* Configure Low Connection State */
+
+ }
+ else
+ {
+ /* Configure High Connection State */
+
+ }
+/* USER CODE END 5 */
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usbd_conf.h b/usbd_conf.h
new file mode 100644
--- /dev/null
+++ b/usbd_conf.h
@@ -0,0 +1,169 @@
+/**
+ ******************************************************************************
+ * @file : usbd_conf.h
+ * @date : 03/01/2015 14:04:02
+ * @version : v1.0_Cube
+ * @brief : Header for usbd_conf file.
+ ******************************************************************************
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CONF__H__
+#define __USBD_CONF__H__
+/* Includes ------------------------------------------------------------------*/
+#include
+#include
+#include
+#include "stm32f0xx.h"
+#include "stm32f0xx_hal.h"
+#include "usbd_def.h"
+
+/** @addtogroup USBD_OTG_DRIVER
+ * @{
+ */
+
+/** @defgroup USBD_CONF
+ * @brief usb otg low level driver configuration file
+ * @{
+ */
+
+/** @defgroup USBD_CONF_Exported_Defines
+ * @{
+ */
+
+/*---------- -----------*/
+#define USBD_MAX_NUM_INTERFACES 1
+/*---------- -----------*/
+#define USBD_MAX_NUM_CONFIGURATION 1
+/*---------- -----------*/
+#define USBD_MAX_STR_DESC_SIZ 512
+/*---------- -----------*/
+#define USBD_SUPPORT_USER_STRING 0
+/*---------- -----------*/
+#define USBD_DEBUG_LEVEL 0
+/*---------- -----------*/
+#define USBD_SELF_POWERED 1
+/*---------- -----------*/
+#define USBD_CDC_INTERVAL 1000
+/*---------- -----------*/
+#define MAX_STATIC_ALLOC_SIZE 1000
+/****************************************/
+/* #define for FS and HS identification */
+#define DEVICE_FS 0
+
+/** @defgroup USBD_Exported_Macros
+ * @{
+ */
+
+/* Memory management macros */
+#define USBD_malloc (uint32_t *)USBD_static_malloc
+#define USBD_free USBD_static_free
+#define USBD_memset /* Not used */
+#define USBD_memcpy /* Not used */
+
+#define USBD_Delay HAL_Delay
+
+ /* DEBUG macros */
+
+#if (USBD_DEBUG_LEVEL > 0)
+#define USBD_UsrLog(...) printf(__VA_ARGS__);\
+ printf("\n");
+#else
+#define USBD_UsrLog(...)
+#endif
+
+
+#if (USBD_DEBUG_LEVEL > 1)
+
+#define USBD_ErrLog(...) printf("ERROR: ") ;\
+ printf(__VA_ARGS__);\
+ printf("\n");
+#else
+#define USBD_ErrLog(...)
+#endif
+
+
+#if (USBD_DEBUG_LEVEL > 2)
+#define USBD_DbgLog(...) printf("DEBUG : ") ;\
+ printf(__VA_ARGS__);\
+ printf("\n");
+#else
+#define USBD_DbgLog(...)
+#endif
+
+/**
+ * @}
+ */
+
+
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Types
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Variables
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_FunctionsPrototype
+ * @{
+ */
+/**
+ * @}
+ */
+/* Exported functions ------------------------------------------------------- */
+void *USBD_static_malloc(uint32_t size);
+void USBD_static_free(void *p);
+
+#endif //__USBD_CONF__H__
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/usbd_desc.c b/usbd_desc.c
new file mode 100644
--- /dev/null
+++ b/usbd_desc.c
@@ -0,0 +1,293 @@
+/**
+ ******************************************************************************
+ * @file : usbd_desc.c
+ * @date : 03/01/2015 14:04:02
+ * @version : v1.0_Cube
+ * @brief : This file implements the USB Device descriptors
+ ******************************************************************************
+ *
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+#include "usbd_desc.h"
+#include "usbd_conf.h"
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_DESC
+ * @brief USBD descriptors module
+ * @{
+ */
+
+/** @defgroup USBD_DESC_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Defines
+ * @{
+ */
+#define USBD_VID 1155
+#define USBD_LANGID_STRING 1033
+#define USBD_MANUFACTURER_STRING "STMicroelectronics"
+#define USBD_PID_FS 22336
+#define USBD_PRODUCT_STRING_FS "STM32 Virtual ComPort"
+#define USBD_SERIALNUMBER_STRING_FS "00000000001A"
+#define USBD_CONFIGURATION_STRING_FS "CDC Config"
+#define USBD_INTERFACE_STRING_FS "CDC Interface"
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Variables
+ * @{
+ */
+uint8_t * USBD_FS_DeviceDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
+uint8_t * USBD_FS_LangIDStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
+uint8_t * USBD_FS_ManufacturerStrDescriptor ( USBD_SpeedTypeDef speed , uint16_t *length);
+uint8_t * USBD_FS_ProductStrDescriptor ( USBD_SpeedTypeDef speed , uint16_t *length);
+uint8_t * USBD_FS_SerialStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
+uint8_t * USBD_FS_ConfigStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
+uint8_t * USBD_FS_InterfaceStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length);
+
+#ifdef USB_SUPPORT_USER_STRING_DESC
+uint8_t * USBD_FS_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx , uint16_t *length);
+#endif /* USB_SUPPORT_USER_STRING_DESC */
+
+USBD_DescriptorsTypeDef FS_Desc =
+{
+ USBD_FS_DeviceDescriptor,
+ USBD_FS_LangIDStrDescriptor,
+ USBD_FS_ManufacturerStrDescriptor,
+ USBD_FS_ProductStrDescriptor,
+ USBD_FS_SerialStrDescriptor,
+ USBD_FS_ConfigStrDescriptor,
+ USBD_FS_InterfaceStrDescriptor,
+};
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN uint8_t USBD_FS_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
+ {
+ 0x12, /*bLength */
+ USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
+ 0x00, /*bcdUSB */
+ 0x02,
+ 0x00, /*bDeviceClass*/
+ 0x00, /*bDeviceSubClass*/
+ 0x00, /*bDeviceProtocol*/
+ USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
+ LOBYTE(USBD_VID), /*idVendor*/
+ HIBYTE(USBD_VID), /*idVendor*/
+ LOBYTE(USBD_PID_FS), /*idVendor*/
+ HIBYTE(USBD_PID_FS), /*idVendor*/
+ 0x00, /*bcdDevice rel. 2.00*/
+ 0x02,
+ USBD_IDX_MFC_STR, /*Index of manufacturer string*/
+ USBD_IDX_PRODUCT_STR, /*Index of product string*/
+ USBD_IDX_SERIAL_STR, /*Index of serial number string*/
+ USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
+ } ; /* USB_DeviceDescriptor */
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END =
+{
+ USB_LEN_LANGID_STR_DESC,
+ USB_DESC_TYPE_STRING,
+ LOBYTE(USBD_LANGID_STRING),
+ HIBYTE(USBD_LANGID_STRING),
+};
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_FunctionPrototypes
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Private_Functions
+ * @{
+ */
+
+/**
+* @brief USBD_FS_DeviceDescriptor
+* return the device descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_DeviceDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ *length = sizeof(USBD_FS_DeviceDesc);
+ return USBD_FS_DeviceDesc;
+}
+
+/**
+* @brief USBD_FS_LangIDStrDescriptor
+* return the LangID string descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_LangIDStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ *length = sizeof(USBD_LangIDDesc);
+ return USBD_LangIDDesc;
+}
+
+/**
+* @brief USBD_FS_ProductStrDescriptor
+* return the product string descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_ProductStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ if(speed == 0)
+ {
+ USBD_GetString (USBD_PRODUCT_STRING_FS, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString (USBD_PRODUCT_STRING_FS, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+
+/**
+* @brief USBD_FS_ManufacturerStrDescriptor
+* return the manufacturer string descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_ManufacturerStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ USBD_GetString (USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
+ return USBD_StrDesc;
+}
+
+/**
+* @brief USBD_FS_SerialStrDescriptor
+* return the serial number string descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_SerialStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ if(speed == USBD_SPEED_HIGH)
+ {
+ USBD_GetString (USBD_SERIALNUMBER_STRING_FS, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString (USBD_SERIALNUMBER_STRING_FS, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+
+/**
+* @brief USBD_FS_ConfigStrDescriptor
+* return the configuration string descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_ConfigStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ if(speed == USBD_SPEED_HIGH)
+ {
+ USBD_GetString (USBD_CONFIGURATION_STRING_FS, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString (USBD_CONFIGURATION_STRING_FS, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+
+/**
+* @brief USBD_HS_InterfaceStrDescriptor
+* return the interface string descriptor
+* @param speed : current device speed
+* @param length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t * USBD_FS_InterfaceStrDescriptor( USBD_SpeedTypeDef speed , uint16_t *length)
+{
+ if(speed == 0)
+ {
+ USBD_GetString (USBD_INTERFACE_STRING_FS, USBD_StrDesc, length);
+ }
+ else
+ {
+ USBD_GetString (USBD_INTERFACE_STRING_FS, USBD_StrDesc, length);
+ }
+ return USBD_StrDesc;
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/usbd_desc.h b/usbd_desc.h
new file mode 100644
--- /dev/null
+++ b/usbd_desc.h
@@ -0,0 +1,98 @@
+/**
+ ******************************************************************************
+ * @file : usbd_desc.h
+ * @date : 03/01/2015 14:04:02
+ * @version : v1.0_Cube
+ * @brief : Header for usbd_desc file.
+ ******************************************************************************
+ * COPYRIGHT(c) 2015 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+*/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_DESC__H__
+#define __USBD_DESC__H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USB_DESC
+ * @brief general defines for the usb device library file
+ * @{
+ */
+
+/** @defgroup USB_DESC_Exported_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_Variables
+ * @{
+ */
+extern USBD_DescriptorsTypeDef FS_Desc;
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DESC_Exported_FunctionsPrototype
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+#endif /* __USBD_DESC_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/