STM32F4: VCP support

This commit is contained in:
blckmn 2016-06-08 05:32:58 +10:00
parent d4e96ba8e7
commit 1df7846977
10 changed files with 1663 additions and 0 deletions

View File

@ -0,0 +1,124 @@
#include "stm32f4xx_it.h"
#include "stm32f4xx_conf.h"
#include "usb_core.h"
#include "usbd_core.h"
#include "usbd_cdc_core.h"
extern uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
extern USB_OTG_CORE_HANDLE USB_OTG_dev;
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
extern uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
extern uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
#endif
/**
* @brief This function handles NMI exception.
* @param None
* @retval None
*/
void NMI_Handler(void)
{
}
/**
* @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)
{
}
/******************************************************************************/
/* STM32F4xx 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_stm32f4xx.s). */
/******************************************************************************/
#ifdef USE_USB_OTG_FS
void OTG_FS_WKUP_IRQHandler(void)
{
if(USB_OTG_dev.cfg.low_power)
{
*(uint32_t *)(0xE000ED10) &= 0xFFFFFFF9 ;
SystemInit();
USB_OTG_UngateClock(&USB_OTG_dev);
}
EXTI_ClearITPendingBit(EXTI_Line18);
}
#endif
/**
* @brief This function handles EXTI15_10_IRQ Handler.
* @param None
* @retval None
*/
#ifdef USE_USB_OTG_HS
void OTG_HS_WKUP_IRQHandler(void)
{
if(USB_OTG_dev.cfg.low_power)
{
*(uint32_t *)(0xE000ED10) &= 0xFFFFFFF9 ;
SystemInit();
USB_OTG_UngateClock(&USB_OTG_dev);
}
EXTI_ClearITPendingBit(EXTI_Line20);
}
#endif
/**
* @brief This function handles OTG_HS Handler.
* @param None
* @retval None
*/
#ifdef USE_USB_OTG_HS
void OTG_HS_IRQHandler(void)
#else
void OTG_FS_IRQHandler(void)
#endif
{
USBD_OTG_ISR_Handler (&USB_OTG_dev);
}
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
/**
* @brief This function handles EP1_IN Handler.
* @param None
* @retval None
*/
void OTG_HS_EP1_IN_IRQHandler(void)
{
USBD_OTG_EP1IN_ISR_Handler (&USB_OTG_dev);
}
/**
* @brief This function handles EP1_OUT Handler.
* @param None
* @retval None
*/
void OTG_HS_EP1_OUT_IRQHandler(void)
{
USBD_OTG_EP1OUT_ISR_Handler (&USB_OTG_dev);
}
#endif

View File

@ -0,0 +1,54 @@
/**
******************************************************************************
* @file GPIO/IOToggle/stm32f4xx_it.h
* @author MCD Application Team
* @version V1.0.0
* @date 19-September-2011
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_IT_H
#define __STM32F4xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void NMI_Handler(void);
void HardFault_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F4xx_IT_H */
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

177
src/main/vcpf4/usb_bsp.c Normal file
View File

@ -0,0 +1,177 @@
/**
******************************************************************************
* @file usb_bsp.c
* @author MCD Application Team
* @version V1.0.0
* @date 19-September-2011
* @brief This file is responsible to offer board support package and is
* configurable by user.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_bsp.h"
#include "usbd_conf.h"
#include "stm32f4xx_conf.h"
#include "../drivers/nvic.h"
#include "../drivers/io.h"
void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) {
(void)pdev;
}
void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) {
(void)pdev;
(void)state;
}
/**
* @brief USB_OTG_BSP_Init
* Initilizes BSP configurations
* @param None
* @retval None
*/
void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev)
{
(void)pdev;
GPIO_InitTypeDef GPIO_InitStructure;
#ifndef USE_ULPI_PHY
#ifdef USB_OTG_FS_LOW_PWR_MGMT_SUPPORT
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
#endif
#endif
NVIC_InitTypeDef NVIC_InitStructure;
#ifdef USE_USB_OTG_HS
NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_IRQn;
#else
NVIC_InitStructure.NVIC_IRQChannel = OTG_FS_IRQn;
#endif
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_USB);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_USB);
NVIC_InitStructure.NVIC_IRQChannelCmd = DISABLE;
NVIC_Init(&NVIC_InitStructure);
RCC_AHB1PeriphClockCmd( RCC_AHB1Periph_GPIOA , ENABLE);
/* Configure SOF VBUS ID DM DP Pins */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOA,GPIO_PinSource11,GPIO_AF_OTG1_FS) ;
GPIO_PinAFConfig(GPIOA,GPIO_PinSource12,GPIO_AF_OTG1_FS) ;
#ifdef VBUS_SENSING_ENABLED
IOConfigGPIO(IOGetByTag(IO_TAG(VBUS_SENSING_PIN)), IOCFG_IN_FLOATING);
#endif
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE) ;
/* enable the PWR clock */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
EXTI_ClearITPendingBit(EXTI_Line0);
}
/**
* @brief USB_OTG_BSP_EnableInterrupt
* Enabele USB Global interrupt
* @param None
* @retval None
*/
void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev)
{
(void)pdev;
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
#ifdef USE_USB_OTG_HS
NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_IRQn;
#else
NVIC_InitStructure.NVIC_IRQChannel = OTG_FS_IRQn;
#endif
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_USB);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_USB);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_EP1_OUT_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_EP1_IN_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif
}
/**
* @brief USB_OTG_BSP_uDelay
* This function provides delay time in micro sec
* @param usec : Value of delay required in micro sec
* @retval None
*/
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunsafe-loop-optimizations"
void USB_OTG_BSP_uDelay (const uint32_t usec)
{
uint32_t count = 0;
const uint32_t utime = (120 * usec / 7);
do
{
if ( ++count > utime )
{
return ;
}
}
while (1);
}
#pragma GCC diagnostic pop
/**
* @brief USB_OTG_BSP_mDelay
* This function provides delay time in milli sec
* @param msec : Value of delay required in milli sec
* @retval None
*/
void USB_OTG_BSP_mDelay (const uint32_t msec)
{
USB_OTG_BSP_uDelay(msec * 1000);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

289
src/main/vcpf4/usb_conf.h Normal file
View File

@ -0,0 +1,289 @@
/**
******************************************************************************
* @file usb_conf.h
* @author MCD Application Team
* @version V2.0.0
* @date 22-July-2011
* @brief general low level driver configuration
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CONF__H__
#define __USB_CONF__H__
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_CONF
* @brief USB low level driver configuration file
* @{
*/
/** @defgroup USB_CONF_Exported_Defines
* @{
*/
/* USB Core and PHY interface configuration.
Tip: To avoid modifying these defines each time you need to change the USB
configuration, you can declare the needed define in your toolchain
compiler preprocessor.
*/
#ifndef USE_USB_OTG_FS
#define USE_USB_OTG_FS
#endif /* USE_USB_OTG_FS */
#ifndef USE_USB_OTG_HS
//#define USE_USB_OTG_HS
#endif /* USE_USB_OTG_HS */
#ifndef USE_ULPI_PHY
#define USE_ULPI_PHY
#endif /* USE_ULPI_PHY */
#ifndef USE_EMBEDDED_PHY
//#define USE_EMBEDDED_PHY
#endif /* USE_EMBEDDED_PHY */
#ifndef USE_I2C_PHY
//#define USE_I2C_PHY
#endif /* USE_I2C_PHY */
#ifdef USE_USB_OTG_FS
#define USB_OTG_FS_CORE
#endif
#ifdef USE_USB_OTG_HS
#define USB_OTG_HS_CORE
#endif
/*******************************************************************************
* FIFO Size Configuration in Device mode
*
* (i) Receive data FIFO size = RAM for setup packets +
* OUT endpoint control information +
* data OUT packets + miscellaneous
* Space = ONE 32-bits words
* --> RAM for setup packets = 10 spaces
* (n is the nbr of CTRL EPs the device core supports)
* --> OUT EP CTRL info = 1 space
* (one space for status information written to the FIFO along with each
* received packet)
* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces
* (MINIMUM to receive packets)
* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces
* (if high-bandwidth EP is enabled or multiple isochronous EPs)
* --> miscellaneous = 1 space per OUT EP
* (one space for transfer complete status information also pushed to the
* FIFO with each endpoint's last packet)
*
* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for
* that particular IN EP. More space allocated in the IN EP Tx FIFO results
* in a better performance on the USB and can hide latencies on the AHB.
*
* (iii) TXn min size = 16 words. (n : Transmit FIFO index)
* (iv) When a TxFIFO is not used, the Configuration should be as follows:
* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txm can use the space allocated for Txn.
* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes)
* --> Txn should be configured with the minimum space of 16 words
* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top
* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
*******************************************************************************/
/*******************************************************************************
* FIFO Size Configuration in Host mode
*
* (i) Receive data FIFO size = (Largest Packet Size / 4) + 1 or
* 2x (Largest Packet Size / 4) + 1, If a
* high-bandwidth channel or multiple isochronous
* channels are enabled
*
* (ii) For the host nonperiodic Transmit FIFO is the largest maximum packet size
* for all supported nonperiodic OUT channels. Typically, a space
* corresponding to two Largest Packet Size is recommended.
*
* (iii) The minimum amount of RAM required for Host periodic Transmit FIFO is
* the largest maximum packet size for all supported periodic OUT channels.
* If there is at least one High Bandwidth Isochronous OUT endpoint,
* then the space must be at least two times the maximum packet size for
* that channel.
*******************************************************************************/
/****************** USB OTG HS CONFIGURATION **********************************/
#ifdef USB_OTG_HS_CORE
#define RX_FIFO_HS_SIZE 512
#define TX0_FIFO_HS_SIZE 512
#define TX1_FIFO_HS_SIZE 512
#define TX2_FIFO_HS_SIZE 0
#define TX3_FIFO_HS_SIZE 0
#define TX4_FIFO_HS_SIZE 0
#define TX5_FIFO_HS_SIZE 0
#define TXH_NP_HS_FIFOSIZ 96
#define TXH_P_HS_FIFOSIZ 96
//#define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT
//#define USB_OTG_HS_SOF_OUTPUT_ENABLED
//#define USB_OTG_INTERNAL_VBUS_ENABLED
#define USB_OTG_EXTERNAL_VBUS_ENABLED
#ifdef USE_ULPI_PHY
#define USB_OTG_ULPI_PHY_ENABLED
#endif
#ifdef USE_EMBEDDED_PHY
#define USB_OTG_EMBEDDED_PHY_ENABLED
#endif
#ifdef USE_I2C_PHY
#define USB_OTG_I2C_PHY_ENABLED
#endif
#define USB_OTG_HS_INTERNAL_DMA_ENABLED
#define USB_OTG_HS_DEDICATED_EP1_ENABLED
#endif
/****************** USB OTG FS CONFIGURATION **********************************/
#ifdef USB_OTG_FS_CORE
#define RX_FIFO_FS_SIZE 128
#define TX0_FIFO_FS_SIZE 64
#define TX1_FIFO_FS_SIZE 128
#define TX2_FIFO_FS_SIZE 0
#define TX3_FIFO_FS_SIZE 0
#define TXH_NP_FS_FIFOSIZ 96
#define TXH_P_FS_FIFOSIZ 96
//#define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT
//#define USB_OTG_FS_SOF_OUTPUT_ENABLED
#endif
/****************** USB OTG MODE CONFIGURATION ********************************/
//#define USE_HOST_MODE
#define USE_DEVICE_MODE
//#define USE_OTG_MODE
#ifndef USB_OTG_FS_CORE
#ifndef USB_OTG_HS_CORE
#error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined"
#endif
#endif
#ifndef USE_DEVICE_MODE
#ifndef USE_HOST_MODE
#error "USE_DEVICE_MODE or USE_HOST_MODE should be defined"
#endif
#endif
#ifndef USE_USB_OTG_HS
#ifndef USE_USB_OTG_FS
#error "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined"
#endif
#else //USE_USB_OTG_HS
#ifndef USE_ULPI_PHY
#ifndef USE_EMBEDDED_PHY
#ifndef USE_I2C_PHY
#error "USE_ULPI_PHY or USE_EMBEDDED_PHY or USE_I2C_PHY should be defined"
#endif
#endif
#endif
#endif
/****************** C Compilers dependant keywords ****************************/
/* In HS mode and when the DMA is used, all variables and data structures dealing
with the DMA during the transaction process should be 4-bytes aligned */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined (__GNUC__) /* GNU Compiler */
#define __ALIGN_END __attribute__ ((aligned (4)))
#define __ALIGN_BEGIN
#else
#define __ALIGN_END
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#elif defined (__TASKING__) /* TASKING Compiler */
#define __ALIGN_BEGIN __align(4)
#endif /* __CC_ARM */
#endif /* __GNUC__ */
#else
#define __ALIGN_BEGIN
#define __ALIGN_END
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* __packed keyword used to decrease the data type alignment to 1-byte */
#if defined (__CC_ARM) /* ARM Compiler */
#define __packed __packed
#elif defined (__ICCARM__) /* IAR Compiler */
#define __packed __packed
#elif defined ( __GNUC__ ) /* GNU Compiler */
#ifndef __packed
#define __packed __attribute__ ((__packed__))
#endif
#elif defined (__TASKING__) /* TASKING Compiler */
#define __packed __unaligned
#endif /* __CC_ARM */
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif //__USB_CONF__H__
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,280 @@
/**
******************************************************************************
* @file usbd_cdc_vcp.c
* @author MCD Application Team
* @version V1.0.0
* @date 22-July-2011
* @brief Generic media access Layer.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#pragma data_alignment = 4
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* Includes ------------------------------------------------------------------*/
#include "usbd_cdc_vcp.h"
#include "stm32f4xx_conf.h"
#include "stdbool.h"
#include "drivers/system.h"
LINE_CODING g_lc;
extern __IO uint8_t USB_Tx_State;
__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
/* These are external variables imported from CDC core to be used for IN
transfer management. */
extern uint8_t APP_Rx_Buffer[]; /* Write CDC received data in this buffer.
These data will be sent over USB IN endpoint
in the CDC core functions. */
extern uint32_t APP_Rx_ptr_out;
extern uint32_t APP_Rx_ptr_in; /* Increment this pointer or roll it back to
start address when writing received data
in the buffer APP_Rx_Buffer. */
__IO uint32_t receiveLength=0;
usbStruct_t usbData;
/* Private function prototypes -----------------------------------------------*/
static uint16_t VCP_Init(void);
static uint16_t VCP_DeInit(void);
static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len);
static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len);
static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len);
CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_DataRx };
/* Private functions ---------------------------------------------------------*/
/**
* @brief VCP_Init
* Initializes the Media on the STM32
* @param None
* @retval Result of the opeartion (USBD_OK in all cases)
*/
static uint16_t VCP_Init(void)
{
bDeviceState = CONFIGURED;
return USBD_OK;
}
/**
* @brief VCP_DeInit
* DeInitializes the Media on the STM32
* @param None
* @retval Result of the opeartion (USBD_OK in all cases)
*/
static uint16_t VCP_DeInit(void)
{
bDeviceState = UNCONNECTED;
return USBD_OK;
}
void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1)
{
plc2->bitrate = plc1->bitrate;
plc2->format = plc1->format;
plc2->paritytype = plc1->paritytype;
plc2->datatype = plc1->datatype;
}
/**
* @brief VCP_Ctrl
* 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 in all cases)
*/
static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
{
(void)Len;
LINE_CODING* plc = (LINE_CODING*)Buf;
assert_param(Len>=sizeof(LINE_CODING));
switch (Cmd) {
/* Not needed for this driver, AT modem commands */
case SEND_ENCAPSULATED_COMMAND:
case GET_ENCAPSULATED_RESPONSE:
break;
// Not needed for this driver
case SET_COMM_FEATURE:
case GET_COMM_FEATURE:
case CLEAR_COMM_FEATURE:
break;
//Note - hw flow control on UART 1-3 and 6 only
case SET_LINE_CODING:
ust_cpy(&g_lc, plc); //Copy into structure to save for later
break;
case GET_LINE_CODING:
ust_cpy(plc, &g_lc);
break;
case SET_CONTROL_LINE_STATE:
/* Not needed for this driver */
//RSW - This tells how to set RTS and DTR
break;
case SEND_BREAK:
/* Not needed for this driver */
break;
default:
break;
}
return USBD_OK;
}
/*******************************************************************************
* Function Name : Send DATA .
* Description : send the data received from the STM32 to the PC through USB
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
{
if(USB_Tx_State!=1)
{
VCP_DataTx(ptrBuffer,sendLength);
return sendLength;
}
return 0;
}
/**
* @brief VCP_DataTx
* CDC received data to be send over USB IN endpoint are managed in
* this function.
* @param Buf: Buffer of data to be sent
* @param Len: Number of data to be sent (in bytes)
* @retval Result of the opeartion: USBD_OK if all operations are OK else VCP_FAIL
*/
static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len)
{
uint16_t ptr = APP_Rx_ptr_in;
uint32_t i;
for (i = 0; i < Len; i++)
APP_Rx_Buffer[ptr++ & (APP_RX_DATA_SIZE-1)] = Buf[i];
APP_Rx_ptr_in = ptr % APP_RX_DATA_SIZE;
return USBD_OK;
}
uint8_t usbAvailable(void) {
return (usbData.rxBufHead != usbData.rxBufTail);
}
/*******************************************************************************
* Function Name : Receive DATA .
* Description : receive the data from the PC to STM32 and send it through USB
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
{
(void)len;
uint8_t ch = 0;
if (usbAvailable()) {
recvBuf[0] = usbData.rxBuf[usbData.rxBufTail];
usbData.rxBufTail = (usbData.rxBufTail + 1) % USB_RX_BUFSIZE;
ch=1;
receiveLength--;
}
return ch;
}
/**
* @brief VCP_DataRx
* 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
* until 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 VCP_FAIL
*/
static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len)
{
uint16_t ptr = usbData.rxBufHead;
uint32_t i;
for (i = 0; i < Len; i++)
usbData.rxBuf[ptr++ & (USB_RX_BUFSIZE-1)] = Buf[i];
usbData.rxBufHead = ptr % USB_RX_BUFSIZE;
receiveLength = ((usbData.rxBufHead - usbData.rxBufTail)>0?(usbData.rxBufHead - usbData.rxBufTail):(usbData.rxBufHead + USB_RX_BUFSIZE - usbData.rxBufTail)) % USB_RX_BUFSIZE;
if((receiveLength) > (USB_RX_BUFSIZE-1))
return USBD_FAIL;
return USBD_OK;
}
/*******************************************************************************
* Function Name : usbIsConfigured.
* Description : Determines if USB VCP is configured or not
* Input : None.
* Output : None.
* Return : True if configured.
*******************************************************************************/
uint8_t usbIsConfigured(void)
{
return (bDeviceState == CONFIGURED);
}
/*******************************************************************************
* Function Name : usbIsConnected.
* Description : Determines if USB VCP is connected ot not
* Input : None.
* Output : None.
* Return : True if connected.
*******************************************************************************/
uint8_t usbIsConnected(void)
{
return (bDeviceState != UNCONNECTED);
}
/*******************************************************************************
* Function Name : CDC_BaudRate.
* Description : Get the current baud rate
* Input : None.
* Output : None.
* Return : Baud rate in bps
*******************************************************************************/
uint32_t CDC_BaudRate(void)
{
return g_lc.bitrate;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,81 @@
/**
******************************************************************************
* @file usbd_cdc_vcp.h
* @author MCD Application Team
* @version V1.0.0
* @date 22-July-2011
* @brief Header for usbd_cdc_vcp.c file.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_CDC_VCP_H
#define __USBD_CDC_VCP_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx_conf.h"
#include "usbd_cdc_core.h"
#include "usbd_conf.h"
#include <stdint.h>
#include "usbd_core.h"
#include "usbd_usr.h"
#include "usbd_desc.h"
#define USB_RX_BUFSIZE 1024
__ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END;
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
uint32_t CDC_BaudRate(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t receiveLength; // HJI
extern __IO uint32_t bDeviceState; /* USB device status */
typedef enum _DEVICE_STATE {
UNCONNECTED,
ATTACHED,
POWERED,
SUSPENDED,
ADDRESSED,
CONFIGURED
} DEVICE_STATE;
/* Exported typef ------------------------------------------------------------*/
/* The following structures groups all needed parameters to be configured for the
ComPort. These parameters can modified on the fly by the host through CDC class
command class requests. */
typedef struct
{
uint32_t bitrate;
uint8_t format;
uint8_t paritytype;
uint8_t datatype;
} LINE_CODING;
typedef struct {
uint8_t rxBuf[USB_RX_BUFSIZE];
uint16_t rxBufHead;
uint16_t rxBufTail;
} usbStruct_t;
#endif /* __USBD_CDC_VCP_H */

View File

@ -0,0 +1,98 @@
/**
******************************************************************************
* @file usbd_conf.h
* @author MCD Application Team
* @version V1.0.0
* @date 22-July-2011
* @brief USB Device configuration file
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_CONF__H__
#define __USBD_CONF__H__
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
/** @defgroup USB_CONF_Exported_Defines
* @{
*/
#define USBD_CFG_MAX_NUM 1
#define USBD_ITF_MAX_NUM 1
#define USB_MAX_STR_DESC_SIZ 50
/** @defgroup USB_VCP_Class_Layer_Parameter
* @{
*/
#define CDC_IN_EP 0x81 /* EP1 for data IN */
#define CDC_OUT_EP 0x01 /* EP1 for data OUT */
#define CDC_CMD_EP 0x82 /* EP2 for CDC commands */
/* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */
#ifdef USE_USB_OTG_HS
#define CDC_DATA_MAX_PACKET_SIZE 512 /* Endpoint IN & OUT Packet size */
#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */
#define CDC_IN_FRAME_INTERVAL 40 /* Number of micro-frames between IN transfers */
#define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer:
APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL*8 */
#else
#define CDC_DATA_MAX_PACKET_SIZE 64 /* Endpoint IN & OUT Packet size */
#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */
#define CDC_IN_FRAME_INTERVAL 15 /* Number of frames between IN transfers */
#define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer:
APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL */
#endif /* USE_USB_OTG_HS */
#define APP_FOPS VCP_fops
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif //__USBD_CONF__H__
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

320
src/main/vcpf4/usbd_desc.c Normal file
View File

@ -0,0 +1,320 @@
/**
******************************************************************************
* @file usbd_desc.c
* @author MCD Application Team
* @version V1.0.0
* @date 19-September-2011
* @brief This file provides the USBD descriptors and string formating method.
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_core.h"
#include "usbd_desc.h"
#include "usbd_req.h"
#include "usbd_conf.h"
#include "usb_regs.h"
#include "platform.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 0x0483
#define USBD_PID 0x5740
/** @defgroup USB_String_Descriptors
* @{
*/
#define USBD_LANGID_STRING 0x409
#define USBD_MANUFACTURER_STRING "RaceFlight"
#ifdef USBD_PRODUCT_STRING
#define USBD_PRODUCT_HS_STRING USBD_PRODUCT_STRING
#define USBD_PRODUCT_FS_STRING USBD_PRODUCT_STRING
#else
#define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS mode"
#define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode"
#endif /* USBD_PRODUCT_STRING */
#ifdef USBD_SERIALNUMBER_STRING
#define USBD_SERIALNUMBER_HS_STRING USBD_SERIALNUMBER_STRING
#define USBD_SERIALNUMBER_FS_STRING USBD_SERIALNUMBER_STRING
#else
// start of STM32 flash
#define USBD_SERIALNUMBER_HS_STRING "0x8000000"
#define USBD_SERIALNUMBER_FS_STRING "0x8000000"
#endif /* USBD_SERIALNUMBER_STRING */
#define USBD_CONFIGURATION_HS_STRING "VCP Config"
#define USBD_INTERFACE_HS_STRING "VCP Interface"
#define USBD_CONFIGURATION_FS_STRING "VCP Config"
#define USBD_INTERFACE_FS_STRING "VCP Interface"
/**
* @}
*/
/** @defgroup USBD_DESC_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Private_Variables
* @{
*/
USBD_DEVICE USR_desc =
{
USBD_USR_DeviceDescriptor,
USBD_USR_LangIDStrDescriptor,
USBD_USR_ManufacturerStrDescriptor,
USBD_USR_ProductStrDescriptor,
USBD_USR_SerialStrDescriptor,
USBD_USR_ConfigStrDescriptor,
USBD_USR_InterfaceStrDescriptor,
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END =
{
0x12, /*bLength */
USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType*/
0x00, /*bcdUSB */
0x02,
0xef, /*bDeviceClass*/
0x02, /*bDeviceSubClass*/
0x01, /*bDeviceProtocol*/
USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/
LOBYTE(USBD_VID), /*idVendor*/
HIBYTE(USBD_VID), /*idVendor*/
LOBYTE(USBD_PID), /*idVendor*/
HIBYTE(USBD_PID), /*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_CFG_MAX_NUM /*bNumConfigurations*/
} ; /* USB_DeviceDescriptor */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
{
USB_LEN_DEV_QUALIFIER_DESC,
USB_DESC_TYPE_DEVICE_QUALIFIER,
0x00,
0x02,
0x00,
0x00,
0x00,
0x40,
0x01,
0x00,
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END =
{
USB_SIZ_STRING_LANGID,
USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
};
/**
* @}
*/
/** @defgroup USBD_DESC_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Private_Functions
* @{
*/
/**
* @brief USBD_USR_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_USR_DeviceDescriptor( uint8_t speed , uint16_t *length)
{
(void)speed;
*length = sizeof(USBD_DeviceDesc);
return USBD_DeviceDesc;
}
/**
* @brief USBD_USR_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_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
{
(void)speed;
*length = sizeof(USBD_LangIDDesc);
return USBD_LangIDDesc;
}
/**
* @brief USBD_USR_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_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == 0)
USBD_GetString ((uint8_t*)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
else
USBD_GetString ((uint8_t*)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
/**
* @brief USBD_USR_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_USR_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length)
{
(void)speed;
USBD_GetString ((uint8_t*)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
/**
* @brief USBD_USR_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_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == USB_OTG_SPEED_HIGH)
USBD_GetString ((uint8_t*)USBD_SERIALNUMBER_HS_STRING, USBD_StrDesc, length);
else
USBD_GetString ((uint8_t*)USBD_SERIALNUMBER_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
/**
* @brief USBD_USR_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_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == USB_OTG_SPEED_HIGH)
USBD_GetString ((uint8_t*)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
else
USBD_GetString ((uint8_t*)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
/**
* @brief USBD_USR_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_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == 0)
USBD_GetString ((uint8_t*)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length);
else
USBD_GetString ((uint8_t*)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

114
src/main/vcpf4/usbd_desc.h Normal file
View File

@ -0,0 +1,114 @@
/**
******************************************************************************
* @file usbd_desc.h
* @author MCD Application Team
* @version V1.0.0
* @date 19-September-2011
* @brief header file for the usbd_desc.c file
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DESC_H
#define __USB_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
* @{
*/
#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
#define USB_STRING_DESCRIPTOR_TYPE 0x03
#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
#define USB_SIZ_DEVICE_DESC 18
#define USB_SIZ_STRING_LANGID 4
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_Variables
* @{
*/
extern uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC];
extern uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ];
extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC];
extern uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC];
extern uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID];
extern USBD_DEVICE USR_desc;
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_FunctionsPrototype
* @{
*/
uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_ProductStrDescriptor ( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
/**
* @}
*/
#endif /* __USBD_DESC_H */
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

126
src/main/vcpf4/usbd_usr.c Normal file
View File

@ -0,0 +1,126 @@
/**
******************************************************************************
* @file usbd_usr.c
* @author MCD Application Team
* @version V1.0.0
* @date 19-September-2011
* @brief This file includes the user application layer
******************************************************************************
* @attention
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
#include "usbd_usr.h"
#include "usbd_ioreq.h"
USBD_Usr_cb_TypeDef USR_cb =
{
USBD_USR_Init,
USBD_USR_DeviceReset,
USBD_USR_DeviceConfigured,
USBD_USR_DeviceSuspended,
USBD_USR_DeviceResumed,
USBD_USR_DeviceConnected,
USBD_USR_DeviceDisconnected,
};
/**
* @brief USBD_USR_Init
* Displays the message on LCD for host lib initialization
* @param None
* @retval None
*/
void USBD_USR_Init(void)
{
}
/**
* @brief USBD_USR_DeviceReset
* Displays the message on LCD on device Reset Event
* @param speed : device speed
* @retval None
*/
void USBD_USR_DeviceReset(uint8_t speed )
{
switch (speed)
{
case USB_OTG_SPEED_HIGH:
break;
case USB_OTG_SPEED_FULL:
break;
default:
break;
}
}
/**
* @brief USBD_USR_DeviceConfigured
* Displays the message on LCD on device configuration Event
* @param None
* @retval Staus
*/
void USBD_USR_DeviceConfigured (void)
{
}
/**
* @brief USBD_USR_DeviceConnected
* Displays the message on LCD on device connection Event
* @param None
* @retval Staus
*/
void USBD_USR_DeviceConnected (void)
{
}
/**
* @brief USBD_USR_DeviceDisonnected
* Displays the message on LCD on device disconnection Event
* @param None
* @retval Staus
*/
void USBD_USR_DeviceDisconnected (void)
{
}
/**
* @brief USBD_USR_DeviceSuspended
* Displays the message on LCD on device suspend Event
* @param None
* @retval None
*/
void USBD_USR_DeviceSuspended(void)
{
/* Users can do their application actions here for the USB-Reset */
}
/**
* @brief USBD_USR_DeviceResumed
* Displays the message on LCD on device resume Event
* @param None
* @retval None
*/
void USBD_USR_DeviceResumed(void)
{
/* Users can do their application actions here for the USB-Reset */
}