summaryrefslogtreecommitdiff
path: root/bsp/radio-controller-1/Src
diff options
context:
space:
mode:
authorTrygve Laugstøl <trygvis@inamo.no>2017-05-27 10:55:23 +0200
committerTrygve Laugstøl <trygvis@inamo.no>2017-05-27 11:01:19 +0200
commita819d3cbddbb5294b98b2fd6590f9fff13491d85 (patch)
treea529b8260f7f8a8d589de3f4dcdb278fea08ab25 /bsp/radio-controller-1/Src
parent46b7f97720293e098fa26eb5269b481c45819deb (diff)
downloadradio-controller-a819d3cbddbb5294b98b2fd6590f9fff13491d85.tar.gz
radio-controller-a819d3cbddbb5294b98b2fd6590f9fff13491d85.tar.bz2
radio-controller-a819d3cbddbb5294b98b2fd6590f9fff13491d85.tar.xz
radio-controller-a819d3cbddbb5294b98b2fd6590f9fff13491d85.zip
o Moving generated code to under bsp/. Renaming to match PCB.
Diffstat (limited to 'bsp/radio-controller-1/Src')
-rw-r--r--bsp/radio-controller-1/Src/main.c309
-rw-r--r--bsp/radio-controller-1/Src/stm32f1xx_hal_msp.c240
-rw-r--r--bsp/radio-controller-1/Src/stm32f1xx_it.c262
-rw-r--r--bsp/radio-controller-1/Src/system_stm32f1xx.c448
-rw-r--r--bsp/radio-controller-1/Src/usb_device.c77
-rw-r--r--bsp/radio-controller-1/Src/usbd_cdc_if.c322
-rw-r--r--bsp/radio-controller-1/Src/usbd_conf.c754
-rw-r--r--bsp/radio-controller-1/Src/usbd_desc.c307
8 files changed, 2719 insertions, 0 deletions
diff --git a/bsp/radio-controller-1/Src/main.c b/bsp/radio-controller-1/Src/main.c
new file mode 100644
index 0000000..f57b555
--- /dev/null
+++ b/bsp/radio-controller-1/Src/main.c
@@ -0,0 +1,309 @@
+/**
+ ******************************************************************************
+ * File Name : main.c
+ * Description : Main program body
+ ******************************************************************************
+ *
+ * Copyright (c) 2017 STMicroelectronics International N.V.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted, provided that the following conditions are met:
+ *
+ * 1. Redistribution 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 other
+ * contributors to this software may be used to endorse or promote products
+ * derived from this software without specific written permission.
+ * 4. This software, including modifications and/or derivative works of this
+ * software, must execute solely and exclusively on microcontroller or
+ * microprocessor devices manufactured by or for STMicroelectronics.
+ * 5. Redistribution and use of this software other than as permitted under
+ * this license is void and will automatically terminate your rights under
+ * this license.
+ *
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
+ * SHALL STMICROELECTRONICS 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 "main.h"
+#include "stm32f1xx_hal.h"
+#include "usb_device.h"
+
+/* USER CODE BEGIN Includes */
+#include "radio-controller.h"
+/* USER CODE END Includes */
+
+/* Private variables ---------------------------------------------------------*/
+TIM_HandleTypeDef htim1;
+DMA_HandleTypeDef hdma_tim1_ch1;
+
+UART_HandleTypeDef huart2;
+
+/* USER CODE BEGIN PV */
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+void SystemClock_Config(void);
+void Error_Handler(void);
+static void MX_GPIO_Init(void);
+static void MX_DMA_Init(void);
+static void MX_TIM1_Init(void);
+static void MX_USART2_UART_Init(void);
+
+/* USER CODE BEGIN PFP */
+/* Private function prototypes -----------------------------------------------*/
+
+/* USER CODE END PFP */
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+int main(void)
+{
+
+ /* USER CODE BEGIN 1 */
+ main_pre_init();
+ /* USER CODE END 1 */
+
+ /* MCU Configuration----------------------------------------------------------*/
+
+ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
+ HAL_Init();
+
+ /* Configure the system clock */
+ SystemClock_Config();
+
+ /* Initialize all configured peripherals */
+ MX_GPIO_Init();
+ MX_DMA_Init();
+ MX_TIM1_Init();
+ MX_USB_DEVICE_Init();
+ MX_USART2_UART_Init();
+
+ /* USER CODE BEGIN 2 */
+ main_post_init();
+ /* USER CODE END 2 */
+
+ /* Infinite loop */
+ /* USER CODE BEGIN WHILE */
+ while (1)
+ {
+ /* USER CODE END WHILE */
+
+ /* USER CODE BEGIN 3 */
+ main_loop();
+ }
+ /* USER CODE END 3 */
+
+}
+
+/** System Clock Configuration
+*/
+void SystemClock_Config(void)
+{
+
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+ RCC_PeriphCLKInitTypeDef PeriphClkInit;
+
+ /**Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /**Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
+ PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /**Configure the Systick interrupt time
+ */
+ HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
+
+ /**Configure the Systick
+ */
+ HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
+
+ /* SysTick_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+}
+
+/* TIM1 init function */
+static void MX_TIM1_Init(void)
+{
+
+ TIM_MasterConfigTypeDef sMasterConfig;
+ TIM_IC_InitTypeDef sConfigIC;
+
+ htim1.Instance = TIM1;
+ htim1.Init.Prescaler = RX_TIMER_PRESCALER;
+ htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim1.Init.Period = 65535;
+ htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim1.Init.RepetitionCounter = 0;
+ if (HAL_TIM_IC_Init(&htim1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
+ sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
+ if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
+ sConfigIC.ICSelection = TIM_ICSELECTION_DIRECTTI;
+ sConfigIC.ICPrescaler = TIM_ICPSC_DIV1;
+ sConfigIC.ICFilter = 0;
+ if (HAL_TIM_IC_ConfigChannel(&htim1, &sConfigIC, TIM_CHANNEL_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+/* USART2 init function */
+static void MX_USART2_UART_Init(void)
+{
+
+ huart2.Instance = USART2;
+ huart2.Init.BaudRate = 115200;
+ huart2.Init.WordLength = UART_WORDLENGTH_8B;
+ huart2.Init.StopBits = UART_STOPBITS_1;
+ huart2.Init.Parity = UART_PARITY_NONE;
+ huart2.Init.Mode = UART_MODE_TX_RX;
+ huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart2.Init.OverSampling = UART_OVERSAMPLING_16;
+ if (HAL_UART_Init(&huart2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+/**
+ * Enable DMA controller clock
+ */
+static void MX_DMA_Init(void)
+{
+ /* DMA controller clock enable */
+ __HAL_RCC_DMA1_CLK_ENABLE();
+
+ /* DMA interrupt init */
+ /* DMA1_Channel2_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn);
+
+}
+
+/** Configure pins as
+ * Analog
+ * Input
+ * Output
+ * EVENT_OUT
+ * EXTI
+*/
+static void MX_GPIO_Init(void)
+{
+
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOD_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+
+}
+
+/* USER CODE BEGIN 4 */
+
+/* USER CODE END 4 */
+
+/**
+ * @brief This function is executed in case of error occurrence.
+ * @param None
+ * @retval None
+ */
+void Error_Handler(void)
+{
+ /* USER CODE BEGIN Error_Handler */
+ /* User can add his own implementation to report the HAL error return state */
+ while(1)
+ {
+ }
+ /* USER CODE END Error_Handler */
+}
+
+#ifdef USE_FULL_ASSERT
+
+/**
+ * @brief Reports the name of the source file and the source line number
+ * where the assert_param error has occurred.
+ * @param file: pointer to the source file name
+ * @param line: assert_param error line source number
+ * @retval None
+ */
+void assert_failed(uint8_t* file, uint32_t line)
+{
+ /* USER CODE BEGIN 6 */
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+ /* USER CODE END 6 */
+
+}
+
+#endif
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/bsp/radio-controller-1/Src/stm32f1xx_hal_msp.c b/bsp/radio-controller-1/Src/stm32f1xx_hal_msp.c
new file mode 100644
index 0000000..b90d153
--- /dev/null
+++ b/bsp/radio-controller-1/Src/stm32f1xx_hal_msp.c
@@ -0,0 +1,240 @@
+/**
+ ******************************************************************************
+ * File Name : stm32f1xx_hal_msp.c
+ * Description : This file provides code for the MSP Initialization
+ * and de-Initialization codes.
+ ******************************************************************************
+ *
+ * Copyright (c) 2017 STMicroelectronics International N.V.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted, provided that the following conditions are met:
+ *
+ * 1. Redistribution 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 other
+ * contributors to this software may be used to endorse or promote products
+ * derived from this software without specific written permission.
+ * 4. This software, including modifications and/or derivative works of this
+ * software, must execute solely and exclusively on microcontroller or
+ * microprocessor devices manufactured by or for STMicroelectronics.
+ * 5. Redistribution and use of this software other than as permitted under
+ * this license is void and will automatically terminate your rights under
+ * this license.
+ *
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
+ * SHALL STMICROELECTRONICS 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 "stm32f1xx_hal.h"
+
+extern DMA_HandleTypeDef hdma_tim1_ch1;
+
+extern void Error_Handler(void);
+/* 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 */
+
+ __HAL_RCC_AFIO_CLK_ENABLE();
+
+ HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
+
+ /* System interrupt init*/
+ /* MemoryManagement_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
+ /* BusFault_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0);
+ /* UsageFault_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
+ /* SVCall_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0);
+ /* DebugMonitor_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
+ /* PendSV_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0);
+ /* SysTick_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+
+ /**NOJTAG: JTAG-DP Disabled and SW-DP Enabled
+ */
+ __HAL_AFIO_REMAP_SWJ_NOJTAG();
+
+ /* USER CODE BEGIN MspInit 1 */
+
+ /* USER CODE END MspInit 1 */
+}
+
+void HAL_TIM_IC_MspInit(TIM_HandleTypeDef* htim_ic)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct;
+ if(htim_ic->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspInit 0 */
+
+ /* USER CODE END TIM1_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_TIM1_CLK_ENABLE();
+
+ /**TIM1 GPIO Configuration
+ PA8 ------> TIM1_CH1
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_8;
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* Peripheral DMA init*/
+
+ hdma_tim1_ch1.Instance = DMA1_Channel2;
+ hdma_tim1_ch1.Init.Direction = DMA_PERIPH_TO_MEMORY;
+ hdma_tim1_ch1.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_tim1_ch1.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_tim1_ch1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ hdma_tim1_ch1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ hdma_tim1_ch1.Init.Mode = DMA_NORMAL;
+ hdma_tim1_ch1.Init.Priority = DMA_PRIORITY_LOW;
+ if (HAL_DMA_Init(&hdma_tim1_ch1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ __HAL_LINKDMA(htim_ic,hdma[TIM_DMA_ID_CC1],hdma_tim1_ch1);
+
+ /* Peripheral interrupt init */
+ HAL_NVIC_SetPriority(TIM1_TRG_COM_IRQn, 1, 0);
+ HAL_NVIC_EnableIRQ(TIM1_TRG_COM_IRQn);
+ HAL_NVIC_SetPriority(TIM1_CC_IRQn, 1, 0);
+ HAL_NVIC_EnableIRQ(TIM1_CC_IRQn);
+ /* USER CODE BEGIN TIM1_MspInit 1 */
+
+ /* USER CODE END TIM1_MspInit 1 */
+ }
+
+}
+
+void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef* htim_ic)
+{
+
+ if(htim_ic->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspDeInit 0 */
+
+ /* USER CODE END TIM1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM1_CLK_DISABLE();
+
+ /**TIM1 GPIO Configuration
+ PA8 ------> TIM1_CH1
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_8);
+
+ /* Peripheral DMA DeInit*/
+ HAL_DMA_DeInit(htim_ic->hdma[TIM_DMA_ID_CC1]);
+
+ /* Peripheral interrupt DeInit*/
+ HAL_NVIC_DisableIRQ(TIM1_TRG_COM_IRQn);
+
+ HAL_NVIC_DisableIRQ(TIM1_CC_IRQn);
+
+ }
+ /* USER CODE BEGIN TIM1_MspDeInit 1 */
+
+ /* USER CODE END TIM1_MspDeInit 1 */
+
+}
+
+void HAL_UART_MspInit(UART_HandleTypeDef* huart)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct;
+ if(huart->Instance==USART2)
+ {
+ /* USER CODE BEGIN USART2_MspInit 0 */
+
+ /* USER CODE END USART2_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_USART2_CLK_ENABLE();
+
+ /**USART2 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = GPIO_PIN_3;
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN USART2_MspInit 1 */
+
+ /* USER CODE END USART2_MspInit 1 */
+ }
+
+}
+
+void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
+{
+
+ if(huart->Instance==USART2)
+ {
+ /* USER CODE BEGIN USART2_MspDeInit 0 */
+
+ /* USER CODE END USART2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USART2_CLK_DISABLE();
+
+ /**USART2 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_2|GPIO_PIN_3);
+
+ }
+ /* USER CODE BEGIN USART2_MspDeInit 1 */
+
+ /* USER CODE END USART2_MspDeInit 1 */
+
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/bsp/radio-controller-1/Src/stm32f1xx_it.c b/bsp/radio-controller-1/Src/stm32f1xx_it.c
new file mode 100644
index 0000000..ac5d604
--- /dev/null
+++ b/bsp/radio-controller-1/Src/stm32f1xx_it.c
@@ -0,0 +1,262 @@
+/**
+ ******************************************************************************
+ * @file stm32f1xx_it.c
+ * @brief Interrupt Service Routines.
+ ******************************************************************************
+ *
+ * COPYRIGHT(c) 2017 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 "stm32f1xx_hal.h"
+#include "stm32f1xx.h"
+#include "stm32f1xx_it.h"
+
+/* USER CODE BEGIN 0 */
+#include <radio-controller.h>
+/* USER CODE END 0 */
+
+/* External variables --------------------------------------------------------*/
+extern PCD_HandleTypeDef hpcd_USB_FS;
+extern DMA_HandleTypeDef hdma_tim1_ch1;
+extern TIM_HandleTypeDef htim1;
+
+/******************************************************************************/
+/* Cortex-M3 Processor Interruption and Exception Handlers */
+/******************************************************************************/
+
+/**
+* @brief This function handles Non maskable interrupt.
+*/
+void NMI_Handler(void)
+{
+ /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
+
+ /* USER CODE END NonMaskableInt_IRQn 0 */
+ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
+
+ /* USER CODE END NonMaskableInt_IRQn 1 */
+}
+
+/**
+* @brief This function handles Hard fault interrupt.
+*/
+void HardFault_Handler(void)
+{
+ /* USER CODE BEGIN HardFault_IRQn 0 */
+
+ /* USER CODE END HardFault_IRQn 0 */
+ while (1)
+ {
+ }
+ /* USER CODE BEGIN HardFault_IRQn 1 */
+
+ /* USER CODE END HardFault_IRQn 1 */
+}
+
+/**
+* @brief This function handles Memory management fault.
+*/
+void MemManage_Handler(void)
+{
+ /* USER CODE BEGIN MemoryManagement_IRQn 0 */
+
+ /* USER CODE END MemoryManagement_IRQn 0 */
+ while (1)
+ {
+ }
+ /* USER CODE BEGIN MemoryManagement_IRQn 1 */
+
+ /* USER CODE END MemoryManagement_IRQn 1 */
+}
+
+/**
+* @brief This function handles Prefetch fault, memory access fault.
+*/
+void BusFault_Handler(void)
+{
+ /* USER CODE BEGIN BusFault_IRQn 0 */
+
+ /* USER CODE END BusFault_IRQn 0 */
+ while (1)
+ {
+ }
+ /* USER CODE BEGIN BusFault_IRQn 1 */
+
+ /* USER CODE END BusFault_IRQn 1 */
+}
+
+/**
+* @brief This function handles Undefined instruction or illegal state.
+*/
+void UsageFault_Handler(void)
+{
+ /* USER CODE BEGIN UsageFault_IRQn 0 */
+
+ /* USER CODE END UsageFault_IRQn 0 */
+ while (1)
+ {
+ }
+ /* USER CODE BEGIN UsageFault_IRQn 1 */
+
+ /* USER CODE END UsageFault_IRQn 1 */
+}
+
+/**
+* @brief This function handles System service call via SWI instruction.
+*/
+void SVC_Handler(void)
+{
+ /* USER CODE BEGIN SVCall_IRQn 0 */
+
+ /* USER CODE END SVCall_IRQn 0 */
+ /* USER CODE BEGIN SVCall_IRQn 1 */
+
+ /* USER CODE END SVCall_IRQn 1 */
+}
+
+/**
+* @brief This function handles Debug monitor.
+*/
+void DebugMon_Handler(void)
+{
+ /* USER CODE BEGIN DebugMonitor_IRQn 0 */
+
+ /* USER CODE END DebugMonitor_IRQn 0 */
+ /* USER CODE BEGIN DebugMonitor_IRQn 1 */
+
+ /* USER CODE END DebugMonitor_IRQn 1 */
+}
+
+/**
+* @brief This function handles Pendable request for system service.
+*/
+void PendSV_Handler(void)
+{
+ /* USER CODE BEGIN PendSV_IRQn 0 */
+
+ /* USER CODE END PendSV_IRQn 0 */
+ /* USER CODE BEGIN PendSV_IRQn 1 */
+
+ /* USER CODE END PendSV_IRQn 1 */
+}
+
+/**
+* @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 */
+
+ /* USER CODE END SysTick_IRQn 1 */
+}
+
+/******************************************************************************/
+/* STM32F1xx Peripheral Interrupt Handlers */
+/* Add here the Interrupt Handlers for the used peripherals. */
+/* For the available peripheral interrupt handler names, */
+/* please refer to the startup file (startup_stm32f1xx.s). */
+/******************************************************************************/
+
+/**
+* @brief This function handles DMA1 channel2 global interrupt.
+*/
+void DMA1_Channel2_IRQHandler(void)
+{
+ /* USER CODE BEGIN DMA1_Channel2_IRQn 0 */
+
+ /* USER CODE END DMA1_Channel2_IRQn 0 */
+ HAL_DMA_IRQHandler(&hdma_tim1_ch1);
+ /* USER CODE BEGIN DMA1_Channel2_IRQn 1 */
+
+ /* USER CODE END DMA1_Channel2_IRQn 1 */
+}
+
+/**
+* @brief This function handles USB high priority or CAN TX interrupts.
+*/
+void USB_HP_CAN1_TX_IRQHandler(void)
+{
+ /* USER CODE BEGIN USB_HP_CAN1_TX_IRQn 0 */
+
+ /* USER CODE END USB_HP_CAN1_TX_IRQn 0 */
+ HAL_PCD_IRQHandler(&hpcd_USB_FS);
+ /* USER CODE BEGIN USB_HP_CAN1_TX_IRQn 1 */
+
+ /* USER CODE END USB_HP_CAN1_TX_IRQn 1 */
+}
+
+/**
+* @brief This function handles USB low priority or CAN RX0 interrupts.
+*/
+void USB_LP_CAN1_RX0_IRQHandler(void)
+{
+ /* USER CODE BEGIN USB_LP_CAN1_RX0_IRQn 0 */
+
+ /* USER CODE END USB_LP_CAN1_RX0_IRQn 0 */
+ HAL_PCD_IRQHandler(&hpcd_USB_FS);
+ /* USER CODE BEGIN USB_LP_CAN1_RX0_IRQn 1 */
+
+ /* USER CODE END USB_LP_CAN1_RX0_IRQn 1 */
+}
+
+/**
+* @brief This function handles TIM1 trigger and commutation interrupts.
+*/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM1_TRG_COM_IRQn 0 */
+ it_tim1();
+ /* USER CODE END TIM1_TRG_COM_IRQn 0 */
+ HAL_TIM_IRQHandler(&htim1);
+ /* USER CODE BEGIN TIM1_TRG_COM_IRQn 1 */
+
+ /* USER CODE END TIM1_TRG_COM_IRQn 1 */
+}
+
+/**
+* @brief This function handles TIM1 capture compare interrupt.
+*/
+void TIM1_CC_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM1_CC_IRQn 0 */
+ it_tim1();
+ /* USER CODE END TIM1_CC_IRQn 0 */
+ HAL_TIM_IRQHandler(&htim1);
+ /* USER CODE BEGIN TIM1_CC_IRQn 1 */
+
+ /* USER CODE END TIM1_CC_IRQn 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/bsp/radio-controller-1/Src/system_stm32f1xx.c b/bsp/radio-controller-1/Src/system_stm32f1xx.c
new file mode 100644
index 0000000..9d07f89
--- /dev/null
+++ b/bsp/radio-controller-1/Src/system_stm32f1xx.c
@@ -0,0 +1,448 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f1xx.c
+ * @author MCD Application Team
+ * @version V4.1.0
+ * @date 29-April-2016
+ * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * factors, AHB/APBx prescalers and Flash settings).
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f1xx_xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (8 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f1xx_xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 4. The default value of HSE crystal is set to 8 MHz (or 25 MHz, depending on
+ * the product used), refer to "HSE_VALUE".
+ * When HSE is used as system clock source, directly or through PLL, and you
+ * are using different crystal you have to adapt the HSE value to your own
+ * configuration.
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f1xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F1xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f1xx.h"
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F1xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F1xx_System_Private_Defines
+ * @{
+ */
+
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSI_VALUE */
+
+/*!< Uncomment the following line if you need to use external SRAM */
+#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F1xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F1xx_System_Private_Variables
+ * @{
+ */
+
+/*******************************************************************************
+* Clock Definitions
+*******************************************************************************/
+#if defined(STM32F100xB) ||defined(STM32F100xE)
+ uint32_t SystemCoreClock = 24000000; /*!< System Clock Frequency (Core Clock) */
+#else /*!< HSI Selected as System Clock source */
+ uint32_t SystemCoreClock = 72000000; /*!< System Clock Frequency (Core Clock) */
+#endif
+
+const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F1xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
+#ifdef DATA_IN_ExtSRAM
+ static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM */
+#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F1xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemCoreClock variable.
+ * @note This function should be used only after reset.
+ * @param None
+ * @retval None
+ */
+void SystemInit (void)
+{
+ /* Reset the RCC clock configuration to the default reset state(for debug purpose) */
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
+#if !defined(STM32F105xC) && !defined(STM32F107xC)
+ RCC->CFGR &= (uint32_t)0xF8FF0000;
+#else
+ RCC->CFGR &= (uint32_t)0xF0FF0000;
+#endif /* STM32F105xC */
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
+ RCC->CFGR &= (uint32_t)0xFF80FFFF;
+
+#if defined(STM32F105xC) || defined(STM32F107xC)
+ /* Reset PLL2ON and PLL3ON bits */
+ RCC->CR &= (uint32_t)0xEBFFFFFF;
+
+ /* Disable all interrupts and clear pending bits */
+ RCC->CIR = 0x00FF0000;
+
+ /* Reset CFGR2 register */
+ RCC->CFGR2 = 0x00000000;
+#elif defined(STM32F100xB) || defined(STM32F100xE)
+ /* Disable all interrupts and clear pending bits */
+ RCC->CIR = 0x009F0000;
+
+ /* Reset CFGR2 register */
+ RCC->CFGR2 = 0x00000000;
+#else
+ /* Disable all interrupts and clear pending bits */
+ RCC->CIR = 0x009F0000;
+#endif /* STM32F105xC */
+
+#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
+ #ifdef DATA_IN_ExtSRAM
+ SystemInit_ExtMemCtl();
+ #endif /* DATA_IN_ExtSRAM */
+#endif
+
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f1xx.h file (default value
+ * 8 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f1xx.h file (default value
+ * 8 MHz or 25 MHz, depending on the product used), user has to ensure
+ * that HSE_VALUE is same as the real frequency of the crystal used.
+ * Otherwise, this function may have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate (void)
+{
+ uint32_t tmp = 0, pllmull = 0, pllsource = 0;
+
+#if defined(STM32F105xC) || defined(STM32F107xC)
+ uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0;
+#endif /* STM32F105xC */
+
+#if defined(STM32F100xB) || defined(STM32F100xE)
+ uint32_t prediv1factor = 0;
+#endif /* STM32F100xB or STM32F100xE */
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL used as system clock */
+
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
+ pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+
+#if !defined(STM32F105xC) && !defined(STM32F107xC)
+ pllmull = ( pllmull >> 18) + 2;
+
+ if (pllsource == 0x00)
+ {
+ /* HSI oscillator clock divided by 2 selected as PLL clock entry */
+ SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
+ }
+ else
+ {
+ #if defined(STM32F100xB) || defined(STM32F100xE)
+ prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
+ /* HSE oscillator clock selected as PREDIV1 clock entry */
+ SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
+ #else
+ /* HSE selected as PLL clock entry */
+ if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t)RESET)
+ {/* HSE oscillator clock divided by 2 */
+ SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
+ }
+ else
+ {
+ SystemCoreClock = HSE_VALUE * pllmull;
+ }
+ #endif
+ }
+#else
+ pllmull = pllmull >> 18;
+
+ if (pllmull != 0x0D)
+ {
+ pllmull += 2;
+ }
+ else
+ { /* PLL multiplication factor = PLL input clock * 6.5 */
+ pllmull = 13 / 2;
+ }
+
+ if (pllsource == 0x00)
+ {
+ /* HSI oscillator clock divided by 2 selected as PLL clock entry */
+ SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
+ }
+ else
+ {/* PREDIV1 selected as PLL clock entry */
+
+ /* Get PREDIV1 clock source and division factor */
+ prediv1source = RCC->CFGR2 & RCC_CFGR2_PREDIV1SRC;
+ prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
+
+ if (prediv1source == 0)
+ {
+ /* HSE oscillator clock selected as PREDIV1 clock entry */
+ SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
+ }
+ else
+ {/* PLL2 clock selected as PREDIV1 clock entry */
+
+ /* Get PREDIV2 division factor and PLL2 multiplication factor */
+ prediv2factor = ((RCC->CFGR2 & RCC_CFGR2_PREDIV2) >> 4) + 1;
+ pll2mull = ((RCC->CFGR2 & RCC_CFGR2_PLL2MUL) >> 8 ) + 2;
+ SystemCoreClock = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull;
+ }
+ }
+#endif /* STM32F105xC */
+ break;
+
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+
+ /* Compute HCLK clock frequency ----------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG)
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f1xx.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f1xx_xx.s/.c before jump to main.
+ * This function configures the external SRAM mounted on STM3210E-EVAL
+ * board (STM32 High density devices). This SRAM will be used as program
+ * data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ __IO uint32_t tmpreg;
+ /*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is
+ required, then adjust the Register Addresses */
+
+ /* Enable FSMC clock */
+ RCC->AHBENR = 0x00000114;
+
+ /* Delay after an RCC peripheral clock enabling */
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_FSMCEN);
+
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */
+ RCC->APB2ENR = 0x000001E0;
+
+ /* Delay after an RCC peripheral clock enabling */
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_IOPDEN);
+
+ (void)(tmpreg);
+
+/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/
+/*---------------- SRAM Address lines configuration -------------------------*/
+/*---------------- NOE and NWE configuration --------------------------------*/
+/*---------------- NE3 configuration ----------------------------------------*/
+/*---------------- NBL0, NBL1 configuration ---------------------------------*/
+
+ GPIOD->CRL = 0x44BB44BB;
+ GPIOD->CRH = 0xBBBBBBBB;
+
+ GPIOE->CRL = 0xB44444BB;
+ GPIOE->CRH = 0xBBBBBBBB;
+
+ GPIOF->CRL = 0x44BBBBBB;
+ GPIOF->CRH = 0xBBBB4444;
+
+ GPIOG->CRL = 0x44BBBBBB;
+ GPIOG->CRH = 0x444B4B44;
+
+/*---------------- FSMC Configuration ---------------------------------------*/
+/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/
+
+ FSMC_Bank1->BTCR[4] = 0x00001091;
+ FSMC_Bank1->BTCR[5] = 0x00110212;
+}
+#endif /* DATA_IN_ExtSRAM */
+#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/bsp/radio-controller-1/Src/usb_device.c b/bsp/radio-controller-1/Src/usb_device.c
new file mode 100644
index 0000000..0e0ed5b
--- /dev/null
+++ b/bsp/radio-controller-1/Src/usb_device.c
@@ -0,0 +1,77 @@
+/**
+ ******************************************************************************
+ * @file : USB_DEVICE
+ * @version : v2.0_Cube
+ * @brief : This file implements the USB Device
+ ******************************************************************************
+ *
+ * Copyright (c) 2017 STMicroelectronics International N.V.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted, provided that the following conditions are met:
+ *
+ * 1. Redistribution 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 other
+ * contributors to this software may be used to endorse or promote products
+ * derived from this software without specific written permission.
+ * 4. This software, including modifications and/or derivative works of this
+ * software, must execute solely and exclusively on microcontroller or
+ * microprocessor devices manufactured by or for STMicroelectronics.
+ * 5. Redistribution and use of this software other than as permitted under
+ * this license is void and will automatically terminate your rights under
+ * this license.
+ *
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
+ * SHALL STMICROELECTRONICS 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/bsp/radio-controller-1/Src/usbd_cdc_if.c b/bsp/radio-controller-1/Src/usbd_cdc_if.c
new file mode 100644
index 0000000..6e6d192
--- /dev/null
+++ b/bsp/radio-controller-1/Src/usbd_cdc_if.c
@@ -0,0 +1,322 @@
+/**
+ ******************************************************************************
+ * @file : usbd_cdc_if.c
+ * @brief :
+ ******************************************************************************
+ *
+ * Copyright (c) 2017 STMicroelectronics International N.V.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted, provided that the following conditions are met:
+ *
+ * 1. Redistribution 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 other
+ * contributors to this software may be used to endorse or promote products
+ * derived from this software without specific written permission.
+ * 4. This software, including modifications and/or derivative works of this
+ * software, must execute solely and exclusively on microcontroller or
+ * microprocessor devices manufactured by or for STMicroelectronics.
+ * 5. Redistribution and use of this software other than as permitted under
+ * this license is void and will automatically terminate your rights under
+ * this license.
+ *
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
+ * SHALL STMICROELECTRONICS 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"
+/* USER CODE BEGIN INCLUDE */
+/* USER CODE END INCLUDE */
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_CDC
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_Private_TypesDefinitions
+ * @{
+ */
+/* USER CODE BEGIN PRIVATE_TYPES */
+/* USER CODE END PRIVATE_TYPES */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Defines
+ * @{
+ */
+/* USER CODE BEGIN PRIVATE_DEFINES */
+/* 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 4
+#define APP_TX_DATA_SIZE 4
+/* USER CODE END PRIVATE_DEFINES */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Macros
+ * @{
+ */
+/* USER CODE BEGIN PRIVATE_MACRO */
+/* USER CODE END PRIVATE_MACRO */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Variables
+ * @{
+ */
+/* 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 BEGIN PRIVATE_VARIABLES */
+/* USER CODE END PRIVATE_VARIABLES */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_IF_Exported_Variables
+ * @{
+ */
+ extern USBD_HandleTypeDef hUsbDeviceFS;
+/* USER CODE BEGIN EXPORTED_VARIABLES */
+/* USER CODE END EXPORTED_VARIABLES */
+
+/**
+ * @}
+ */
+
+/** @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);
+
+/* USER CODE BEGIN PRIVATE_FUNCTIONS_DECLARATION */
+/* USER CODE END PRIVATE_FUNCTIONS_DECLARATION */
+
+/**
+ * @}
+ */
+
+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 operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_Init_FS(void)
+{
+ /* USER CODE BEGIN 3 */
+ /* Set Application Buffers */
+ USBD_CDC_SetTxBuffer(&hUsbDeviceFS, UserTxBufferFS, 0);
+ USBD_CDC_SetRxBuffer(&hUsbDeviceFS, UserRxBufferFS);
+ printf("%s: \n", __FUNCTION__);
+ return (USBD_OK);
+ /* USER CODE END 3 */
+}
+
+/**
+ * @brief CDC_DeInit_FS
+ * DeInitializes the CDC media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_DeInit_FS(void)
+{
+ /* USER CODE BEGIN 4 */
+ printf("%s: \n", __FUNCTION__);
+ return (USBD_OK);
+ /* USER CODE END 4 */
+}
+
+/**
+ * @brief CDC_Control_FS
+ * Manage the CDC class requests
+ * @param cmd: Command code
+ * @param pbuf: Buffer containing command data (request parameters)
+ * @param length: Number of data to be sent (in bytes)
+ * @retval Result of the operation: 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 5 */
+ 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: {
+ uint32_t bps = pbuf[0] << 24 | pbuf[1] << 16 | pbuf[2] << 8 | pbuf[3];
+ const char *stop_bits = pbuf[4] == 0 ? "1" : pbuf[4] == 1 ? "1.5" : "2";
+ const char *parities[5] = {"none", "odd", "even", "mark", "space"};
+ const char *parity = parities[pbuf[5]];
+ int bits = pbuf[6];
+ printf("Line coding, bps=%lu, bits=%s, parity=%s, bits=%d\n", bps, stop_bits, parity, bits);
+ }
+ 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 5 */
+}
+
+/**
+ * @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 operation: 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 6 */
+ USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
+ USBD_CDC_ReceivePacket(&hUsbDeviceFS);
+
+ printf("USB OUT: len=%lu, data=", *Len);
+ for(uint32_t i = 0; i < *Len; i++) {
+ printf("%02x", Buf[i]);
+ }
+ printf("\n");
+
+ return (USBD_OK);
+ /* USER CODE END 6 */
+}
+
+/**
+ * @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 operation: 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 7 */
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)hUsbDeviceFS.pClassData;
+ if (hcdc->TxState != 0){
+ return USBD_BUSY;
+ }
+ USBD_CDC_SetTxBuffer(&hUsbDeviceFS, Buf, Len);
+ result = USBD_CDC_TransmitPacket(&hUsbDeviceFS);
+ /* USER CODE END 7 */
+ return result;
+}
+
+/* USER CODE BEGIN PRIVATE_FUNCTIONS_IMPLEMENTATION */
+/* USER CODE END PRIVATE_FUNCTIONS_IMPLEMENTATION */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/bsp/radio-controller-1/Src/usbd_conf.c b/bsp/radio-controller-1/Src/usbd_conf.c
new file mode 100644
index 0000000..858fb0c
--- /dev/null
+++ b/bsp/radio-controller-1/Src/usbd_conf.c
@@ -0,0 +1,754 @@
+/**
+ ******************************************************************************
+ * @file : usbd_conf.c
+ * @version : v2.0_Cube
+ * @brief : This file implements the board support package for the USB device library
+ ******************************************************************************
+ *
+ * Copyright (c) 2017 STMicroelectronics International N.V.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted, provided that the following conditions are met:
+ *
+ * 1. Redistribution 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 other
+ * contributors to this software may be used to endorse or promote products
+ * derived from this software without specific written permission.
+ * 4. This software, including modifications and/or derivative works of this
+ * software, must execute solely and exclusively on microcontroller or
+ * microprocessor devices manufactured by or for STMicroelectronics.
+ * 5. Redistribution and use of this software other than as permitted under
+ * this license is void and will automatically terminate your rights under
+ * this license.
+ *
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
+ * SHALL STMICROELECTRONICS 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 "stm32f1xx.h"
+#include "stm32f1xx_hal.h"
+#include "usbd_def.h"
+#include "usbd_core.h"
+#include "usbd_cdc.h"
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+PCD_HandleTypeDef hpcd_USB_FS;
+void Error_Handler(void);
+
+/* USER CODE BEGIN 0 */
+/* USER CODE END 0 */
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/* USER CODE BEGIN 1 */
+/* USER CODE END 1 */
+void HAL_PCDEx_SetConnectionState(PCD_HandleTypeDef *hpcd, uint8_t state);
+
+/*******************************************************************************
+ LL Driver Callbacks (PCD -> USB Device Library)
+*******************************************************************************/
+/* MSP Init */
+
+void HAL_PCD_MspInit(PCD_HandleTypeDef* pcdHandle)
+{
+ if(pcdHandle->Instance==USB)
+ {
+ /* USER CODE BEGIN USB_MspInit 0 */
+
+ /* USER CODE END USB_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_USB_CLK_ENABLE();
+
+ /* Peripheral interrupt init */
+ HAL_NVIC_SetPriority(USB_HP_CAN1_TX_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(USB_HP_CAN1_TX_IRQn);
+ HAL_NVIC_SetPriority(USB_LP_CAN1_RX0_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(USB_LP_CAN1_RX0_IRQn);
+ /* USER CODE BEGIN USB_MspInit 1 */
+
+ /* USER CODE END USB_MspInit 1 */
+ }
+}
+
+void HAL_PCD_MspDeInit(PCD_HandleTypeDef* pcdHandle)
+{
+ if(pcdHandle->Instance==USB)
+ {
+ /* USER CODE BEGIN USB_MspDeInit 0 */
+
+ /* USER CODE END USB_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USB_CLK_DISABLE();
+
+ /* Peripheral interrupt Deinit*/
+ HAL_NVIC_DisableIRQ(USB_HP_CAN1_TX_IRQn);
+
+ HAL_NVIC_DisableIRQ(USB_LP_CAN1_RX0_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((USBD_HandleTypeDef*)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((USBD_HandleTypeDef*)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((USBD_HandleTypeDef*)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((USBD_HandleTypeDef*)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((USBD_HandleTypeDef*)hpcd->pData, speed);
+
+ /*Reset Device*/
+ USBD_LL_Reset((USBD_HandleTypeDef*)hpcd->pData);
+}
+
+/**
+ * @brief Suspend callback.
+ * When Low power mode is enabled the debug cannot be used (IAR, Keil doesn't support it)
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd)
+{
+ /* Inform USB library that core enters in suspend Mode */
+ USBD_LL_Suspend((USBD_HandleTypeDef*)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.
+ * When Low power mode is enabled the debug cannot be used (IAR, Keil doesn't support it)
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
+{
+ /* USER CODE BEGIN 3 */
+ /* USER CODE END 3 */
+ USBD_LL_Resume((USBD_HandleTypeDef*)hpcd->pData);
+
+}
+
+/**
+ * @brief ISOOUTIncomplete callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint Number
+ * @retval None
+ */
+void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+{
+ USBD_LL_IsoOUTIncomplete((USBD_HandleTypeDef*)hpcd->pData, epnum);
+}
+
+/**
+ * @brief ISOINIncomplete callback.
+ * @param hpcd: PCD handle
+ * @param epnum: Endpoint Number
+ * @retval None
+ */
+void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
+{
+ USBD_LL_IsoINIncomplete((USBD_HandleTypeDef*)hpcd->pData, epnum);
+}
+
+/**
+ * @brief ConnectCallback callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_DevConnected((USBD_HandleTypeDef*)hpcd->pData);
+}
+
+/**
+ * @brief Disconnect callback.
+ * @param hpcd: PCD handle
+ * @retval None
+ */
+void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd)
+{
+ USBD_LL_DevDisconnected((USBD_HandleTypeDef*)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.low_power_enable = DISABLE;
+ hpcd_USB_FS.Init.lpm_enable = DISABLE;
+ hpcd_USB_FS.Init.battery_charging_enable = DISABLE;
+ if (HAL_PCD_Init(&hpcd_USB_FS) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x00 , PCD_SNG_BUF, 0x18);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x80 , PCD_SNG_BUF, 0x58);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x81 , PCD_SNG_BUF, 0xC0);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x01 , PCD_SNG_BUF, 0x110);
+ HAL_PCDEx_PMAConfig((PCD_HandleTypeDef*)pdev->pData , 0x82 , PCD_SNG_BUF, 0x100);
+ 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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_DeInit(pdev->pData);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_Start(pdev->pData);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_Stop(pdev->pData);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Open(pdev->pData,
+ ep_addr,
+ ep_mps,
+ ep_type);
+
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Close(pdev->pData, ep_addr);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Flush(pdev->pData, ep_addr);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_SetStall(pdev->pData, ep_addr);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_ClrStall(pdev->pData, ep_addr);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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 = (PCD_HandleTypeDef*) 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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_SetAddress(pdev->pData, dev_addr);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Transmit(pdev->pData, ep_addr, pbuf, size);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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_StatusTypeDef hal_status = HAL_OK;
+ USBD_StatusTypeDef usb_status = USBD_OK;
+
+ hal_status = HAL_PCD_EP_Receive(pdev->pData, ep_addr, pbuf, size);
+
+ switch (hal_status) {
+ case HAL_OK :
+ usb_status = USBD_OK;
+ break;
+ case HAL_ERROR :
+ usb_status = USBD_FAIL;
+ break;
+ case HAL_BUSY :
+ usb_status = USBD_BUSY;
+ break;
+ case HAL_TIMEOUT :
+ usb_status = USBD_FAIL;
+ break;
+ default :
+ usb_status = USBD_FAIL;
+ break;
+ }
+ return usb_status;
+}
+
+/**
+ * @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((PCD_HandleTypeDef*) 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[(sizeof(USBD_CDC_HandleTypeDef)/4)+1];/* On 32-bit boundary */
+ return mem;
+}
+
+/**
+ * @brief Dummy memory free
+ * @param *p pointer to allocated memory address
+ * @retval None
+ */
+void USBD_static_free(void *p)
+{
+
+}
+
+/**
+* @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/bsp/radio-controller-1/Src/usbd_desc.c b/bsp/radio-controller-1/Src/usbd_desc.c
new file mode 100644
index 0000000..432c1d4
--- /dev/null
+++ b/bsp/radio-controller-1/Src/usbd_desc.c
@@ -0,0 +1,307 @@
+/**
+ ******************************************************************************
+ * @file : usbd_desc.c
+ * @version : v2.0_Cube
+ * @brief : This file implements the USB Device descriptors
+ ******************************************************************************
+ *
+ * Copyright (c) 2017 STMicroelectronics International N.V.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted, provided that the following conditions are met:
+ *
+ * 1. Redistribution 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 other
+ * contributors to this software may be used to endorse or promote products
+ * derived from this software without specific written permission.
+ * 4. This software, including modifications and/or derivative works of this
+ * software, must execute solely and exclusively on microcontroller or
+ * microprocessor devices manufactured by or for STMicroelectronics.
+ * 5. Redistribution and use of this software other than as permitted under
+ * this license is void and will automatically terminate your rights under
+ * this license.
+ *
+ * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+ * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
+ * SHALL STMICROELECTRONICS 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"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0*/
+/**
+ * @}
+ */
+
+/** @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,
+ 0x02, /*bDeviceClass*/
+ 0x02, /*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****/