mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
[USBVCP] Enable USB+VCP
This commit is contained in:
parent
de1c1d5377
commit
20161f00f6
8 changed files with 1730 additions and 2 deletions
|
@ -40,8 +40,12 @@
|
|||
#include "usbd_hid_cdc_wrapper.h"
|
||||
#endif
|
||||
#include "usb_io.h"
|
||||
#elif defined(STM32F7)
|
||||
#elif defined(STM32F7) || defined(STM32H7)
|
||||
#ifdef STM32F7
|
||||
#include "vcp_hal/usbd_cdc_interface.h"
|
||||
#else
|
||||
#include "vcph7/usbd_cdc_interface.h"
|
||||
#endif
|
||||
#include "usb_io.h"
|
||||
#ifdef USE_USB_CDC_HID
|
||||
#include "usbd_cdc_hid.h"
|
||||
|
@ -234,7 +238,8 @@ serialPort_t *usbVcpOpen(void)
|
|||
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
|
||||
break;
|
||||
}
|
||||
#elif defined(STM32F7)
|
||||
#elif defined(STM32F7) || defined(STM32H7)
|
||||
|
||||
usbGenerateDisconnectPulse();
|
||||
|
||||
/* Init Device Library */
|
||||
|
@ -258,6 +263,9 @@ serialPort_t *usbVcpOpen(void)
|
|||
|
||||
/* Start Device Process */
|
||||
USBD_Start(&USBD_Device);
|
||||
#ifdef STM32H7
|
||||
HAL_PWREx_EnableUSBVoltageDetector();
|
||||
#endif
|
||||
#else
|
||||
Set_System();
|
||||
Set_USBClock();
|
||||
|
|
|
@ -27,6 +27,11 @@
|
|||
|
||||
#include "usbd_cdc.h"
|
||||
|
||||
extern USBD_HandleTypeDef USBD_Device;
|
||||
|
||||
#elif defined(STM32H7)
|
||||
#include "usbd_cdc.h"
|
||||
|
||||
extern USBD_HandleTypeDef USBD_Device;
|
||||
#endif
|
||||
|
||||
|
|
462
src/main/vcph7/usbd_cdc_interface.c
Normal file
462
src/main/vcph7/usbd_cdc_interface.c
Normal file
|
@ -0,0 +1,462 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file USB_Device/CDC_Standalone/Src/usbd_cdc_interface.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-April-2016
|
||||
* @brief Source file for USBD CDC interface
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* 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 "platform.h"
|
||||
|
||||
#include "drivers/serial_usb_vcp.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "stm32h7xx_hal.h"
|
||||
#include "usbd_core.h"
|
||||
#include "usbd_desc.h"
|
||||
#include "usbd_cdc.h"
|
||||
#include "usbd_cdc_interface.h"
|
||||
#include "stdbool.h"
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define APP_RX_DATA_SIZE 2048
|
||||
#define APP_TX_DATA_SIZE 2048
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
USBD_CDC_LineCodingTypeDef LineCoding =
|
||||
{
|
||||
115200, /* baud rate*/
|
||||
0x00, /* stop bits-1*/
|
||||
0x00, /* parity - none*/
|
||||
0x08 /* nb. of bits 8*/
|
||||
};
|
||||
|
||||
uint8_t UserRxBuffer[APP_RX_DATA_SIZE];/* Received Data over USB are stored in this buffer */
|
||||
uint8_t UserTxBuffer[APP_TX_DATA_SIZE];/* Received Data over UART (CDC interface) are stored in this buffer */
|
||||
uint32_t BuffLength;
|
||||
uint32_t UserTxBufPtrIn = 0;/* Increment this pointer or roll it back to
|
||||
start address when data are received over USART */
|
||||
uint32_t UserTxBufPtrOut = 0; /* Increment this pointer or roll it back to
|
||||
start address when data are sent over USB */
|
||||
|
||||
uint32_t rxAvailable = 0;
|
||||
uint8_t* rxBuffPtr = NULL;
|
||||
|
||||
/* TIM handler declaration */
|
||||
TIM_HandleTypeDef TimHandle;
|
||||
|
||||
static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
|
||||
static void *ctrlLineStateCbContext;
|
||||
static void (*baudRateCb)(void *context, uint32_t baud);
|
||||
static void *baudRateCbContext;
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
static int8_t CDC_Itf_Init(void);
|
||||
static int8_t CDC_Itf_DeInit(void);
|
||||
static int8_t CDC_Itf_Control(uint8_t cmd, uint8_t* pbuf, uint16_t length);
|
||||
static int8_t CDC_Itf_Receive(uint8_t* pbuf, uint32_t *Len);
|
||||
|
||||
static void TIM_Config(void);
|
||||
static void Error_Handler(void);
|
||||
|
||||
USBD_CDC_ItfTypeDef USBD_CDC_fops =
|
||||
{
|
||||
CDC_Itf_Init,
|
||||
CDC_Itf_DeInit,
|
||||
CDC_Itf_Control,
|
||||
CDC_Itf_Receive
|
||||
};
|
||||
|
||||
|
||||
void TIMx_IRQHandler(void)
|
||||
{
|
||||
HAL_TIM_IRQHandler(&TimHandle);
|
||||
}
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief CDC_Itf_Init
|
||||
* Initializes 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_Itf_Init(void)
|
||||
{
|
||||
/*##-3- Configure the TIM Base generation #################################*/
|
||||
TIM_Config();
|
||||
|
||||
/*##-4- Start the TIM Base generation in interrupt mode ####################*/
|
||||
/* Start Channel1 */
|
||||
if (HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
|
||||
{
|
||||
/* Starting Error */
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/*##-5- Set Application Buffers ############################################*/
|
||||
USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0);
|
||||
USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer);
|
||||
|
||||
ctrlLineStateCb = NULL;
|
||||
baudRateCb = NULL;
|
||||
|
||||
return (USBD_OK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief CDC_Itf_DeInit
|
||||
* 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_Itf_DeInit(void)
|
||||
{
|
||||
|
||||
return (USBD_OK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief CDC_Itf_Control
|
||||
* 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 operation: USBD_OK if all operations are OK else USBD_FAIL
|
||||
*/
|
||||
static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
|
||||
{
|
||||
LINE_CODING* plc = (LINE_CODING*)pbuf;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case CDC_SEND_ENCAPSULATED_COMMAND:
|
||||
/* Add your code here */
|
||||
break;
|
||||
|
||||
case CDC_GET_ENCAPSULATED_RESPONSE:
|
||||
/* Add your code here */
|
||||
break;
|
||||
|
||||
case CDC_SET_COMM_FEATURE:
|
||||
/* Add your code here */
|
||||
break;
|
||||
|
||||
case CDC_GET_COMM_FEATURE:
|
||||
/* Add your code here */
|
||||
break;
|
||||
|
||||
case CDC_CLEAR_COMM_FEATURE:
|
||||
/* Add your code here */
|
||||
break;
|
||||
|
||||
case CDC_SET_LINE_CODING:
|
||||
if (pbuf && (length == sizeof (*plc))) {
|
||||
LineCoding.bitrate = plc->bitrate;
|
||||
LineCoding.format = plc->format;
|
||||
LineCoding.paritytype = plc->paritytype;
|
||||
LineCoding.datatype = plc->datatype;
|
||||
|
||||
// If a callback is provided, tell the upper driver of changes in baud rate
|
||||
if (baudRateCb) {
|
||||
baudRateCb(baudRateCbContext, LineCoding.bitrate);
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case CDC_GET_LINE_CODING:
|
||||
if (pbuf && (length == sizeof (*plc))) {
|
||||
plc->bitrate = LineCoding.bitrate;
|
||||
plc->format = LineCoding.format;
|
||||
plc->paritytype = LineCoding.paritytype;
|
||||
plc->datatype = LineCoding.datatype;
|
||||
}
|
||||
break;
|
||||
|
||||
case CDC_SET_CONTROL_LINE_STATE:
|
||||
// If a callback is provided, tell the upper driver of changes in DTR/RTS state
|
||||
if (pbuf && (length == sizeof (uint16_t))) {
|
||||
if (ctrlLineStateCb) {
|
||||
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case CDC_SEND_BREAK:
|
||||
/* Add your code here */
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return (USBD_OK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM period elapsed callback
|
||||
* @param htim: TIM handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
|
||||
{
|
||||
if (htim->Instance != TIMusb) return;
|
||||
|
||||
uint32_t buffptr;
|
||||
uint32_t buffsize;
|
||||
|
||||
if (UserTxBufPtrOut != UserTxBufPtrIn)
|
||||
{
|
||||
if (UserTxBufPtrOut > UserTxBufPtrIn) /* Roll-back */
|
||||
{
|
||||
buffsize = APP_RX_DATA_SIZE - UserTxBufPtrOut;
|
||||
}
|
||||
else
|
||||
{
|
||||
buffsize = UserTxBufPtrIn - UserTxBufPtrOut;
|
||||
}
|
||||
|
||||
buffptr = UserTxBufPtrOut;
|
||||
|
||||
USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[buffptr], buffsize);
|
||||
|
||||
if (USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK)
|
||||
{
|
||||
UserTxBufPtrOut += buffsize;
|
||||
if (UserTxBufPtrOut == APP_TX_DATA_SIZE)
|
||||
{
|
||||
UserTxBufPtrOut = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief CDC_Itf_DataRx
|
||||
* Data received over USB OUT endpoint are sent over CDC interface
|
||||
* through this function.
|
||||
* @param Buf: Buffer of data to be transmitted
|
||||
* @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_Itf_Receive(uint8_t* Buf, uint32_t *Len)
|
||||
{
|
||||
rxAvailable = *Len;
|
||||
rxBuffPtr = Buf;
|
||||
return (USBD_OK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief TIM_Config: Configure TIMusb timer
|
||||
* @param None.
|
||||
* @retval None
|
||||
*/
|
||||
static void TIM_Config(void)
|
||||
{
|
||||
/* Set TIMusb instance */
|
||||
TimHandle.Instance = TIMusb;
|
||||
|
||||
/* Initialize TIMx peripheral as follow:
|
||||
+ Period = 10000 - 1
|
||||
+ Prescaler = ((SystemCoreClock/2)/10000) - 1
|
||||
+ ClockDivision = 0
|
||||
+ Counter direction = Up
|
||||
*/
|
||||
TimHandle.Init.Period = (CDC_POLLING_INTERVAL*1000) - 1;
|
||||
TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1;
|
||||
TimHandle.Init.ClockDivision = 0;
|
||||
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
if (HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
|
||||
{
|
||||
/* Initialization Error */
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/*##-6- Enable TIM peripherals Clock #######################################*/
|
||||
TIMx_CLK_ENABLE();
|
||||
|
||||
/*##-7- Configure the NVIC for TIMx ########################################*/
|
||||
/* Set Interrupt Group Priority */
|
||||
HAL_NVIC_SetPriority(TIMx_IRQn, 6, 0);
|
||||
|
||||
/* Enable the TIMx global Interrupt */
|
||||
HAL_NVIC_EnableIRQ(TIMx_IRQn);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function is executed in case of error occurrence.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void Error_Handler(void)
|
||||
{
|
||||
/* Add your own code here */
|
||||
}
|
||||
|
||||
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
|
||||
{
|
||||
uint32_t count = 0;
|
||||
if ( (rxBuffPtr != NULL))
|
||||
{
|
||||
while ((rxAvailable > 0) && count < len)
|
||||
{
|
||||
recvBuf[count] = rxBuffPtr[0];
|
||||
rxBuffPtr++;
|
||||
rxAvailable--;
|
||||
count++;
|
||||
if (rxAvailable < 1)
|
||||
USBD_CDC_ReceivePacket(&USBD_Device);
|
||||
}
|
||||
}
|
||||
return count;
|
||||
}
|
||||
|
||||
uint32_t CDC_Receive_BytesAvailable(void)
|
||||
{
|
||||
return rxAvailable;
|
||||
}
|
||||
|
||||
uint32_t CDC_Send_FreeBytes(void)
|
||||
{
|
||||
/*
|
||||
return the bytes free in the circular buffer
|
||||
|
||||
functionally equivalent to:
|
||||
(APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in)
|
||||
but without the impact of the condition check.
|
||||
*/
|
||||
return ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief CDC_Send_DATA
|
||||
* CDC received data to be send over USB IN endpoint are managed in
|
||||
* this function.
|
||||
* @param ptrBuffer: Buffer of data to be sent
|
||||
* @param sendLength: Number of data to be sent (in bytes)
|
||||
* @retval Bytes sent
|
||||
*/
|
||||
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
|
||||
{
|
||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pClassData;
|
||||
while (hcdc->TxState != 0);
|
||||
|
||||
for (uint32_t i = 0; i < sendLength; i++)
|
||||
{
|
||||
UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i];
|
||||
UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
|
||||
while (CDC_Send_FreeBytes() == 0) {
|
||||
delay(1);
|
||||
}
|
||||
}
|
||||
return sendLength;
|
||||
}
|
||||
|
||||
|
||||
/*******************************************************************************
|
||||
* 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 (USBD_Device.dev_state == USBD_STATE_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 (USBD_Device.dev_state != USBD_STATE_DEFAULT);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* 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 LineCoding.bitrate;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : CDC_SetBaudRateCb
|
||||
* Description : Set a callback to call when baud rate changes
|
||||
* Input : callback function and context.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
|
||||
{
|
||||
baudRateCbContext = context;
|
||||
baudRateCb = cb;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : CDC_SetCtrlLineStateCb
|
||||
* Description : Set a callback to call when control line state changes
|
||||
* Input : callback function and context.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
|
||||
{
|
||||
ctrlLineStateCbContext = context;
|
||||
ctrlLineStateCb = cb;
|
||||
}
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
98
src/main/vcph7/usbd_cdc_interface.h
Normal file
98
src/main/vcph7/usbd_cdc_interface.h
Normal file
|
@ -0,0 +1,98 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file USB_Device/CDC_Standalone/Inc/usbd_cdc_interface.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-April-2016
|
||||
* @brief Header for usbd_cdc_interface.c file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __USBD_CDC_IF_H
|
||||
#define __USBD_CDC_IF_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
//#include "common/maths.h"
|
||||
|
||||
#include "usbd_cdc.h"
|
||||
#include "stm32h7xx_hal.h"
|
||||
#include "usbd_core.h"
|
||||
#include "usbd_desc.h"
|
||||
|
||||
/* Definition for TIMx clock resources */
|
||||
#define TIMusb TIM7
|
||||
#define TIMx_IRQn TIM7_IRQn
|
||||
#define TIMx_IRQHandler TIM7_IRQHandler
|
||||
#define TIMx_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE
|
||||
|
||||
/* Periodically, the state of the buffer "UserTxBuffer" is checked.
|
||||
The period depends on CDC_POLLING_INTERVAL */
|
||||
#define CDC_POLLING_INTERVAL 10 /* in ms. The max is 65 and the min is 1 */
|
||||
|
||||
/* 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 __attribute__ ((packed))
|
||||
{
|
||||
uint32_t bitrate;
|
||||
uint8_t format;
|
||||
uint8_t paritytype;
|
||||
uint8_t datatype;
|
||||
} LINE_CODING;
|
||||
|
||||
extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
|
||||
|
||||
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength);
|
||||
uint32_t CDC_Send_FreeBytes(void);
|
||||
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len);
|
||||
uint32_t CDC_Receive_BytesAvailable(void);
|
||||
uint8_t usbIsConfigured(void);
|
||||
uint8_t usbIsConnected(void);
|
||||
uint32_t CDC_BaudRate(void);
|
||||
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context);
|
||||
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
#endif /* __USBD_CDC_IF_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
623
src/main/vcph7/usbd_conf.c
Executable file
623
src/main/vcph7/usbd_conf.c
Executable file
|
@ -0,0 +1,623 @@
|
|||
#warning Support for USE_USB_CDC_HID and USE_USB_MSC is not yet merged.
|
||||
|
||||
/**
|
||||
* usbd_conf.c adopted from
|
||||
* STM32Cube_FW_H7_V1.3.0/Projects/STM32H743I_EVAL/Applications/USB_Device/CDC_Standalone
|
||||
**/
|
||||
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file USB_Device/CDC_Standalone/Src/usbd_conf.c
|
||||
* @author MCD Application Team
|
||||
* @brief This file implements the USB Device library callbacks and MSP
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2017 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* 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 "stm32h7xx_hal.h"
|
||||
#include "usbd_conf.h"
|
||||
#include "usbd_core.h"
|
||||
#include "usbd_desc.h"
|
||||
#include "usbd_cdc.h"
|
||||
#include "usbd_cdc_interface.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
/* Private typedef ----------------------------------------------------------- */
|
||||
/* Private define ------------------------------------------------------------ */
|
||||
/* Private macro ------------------------------------------------------------- */
|
||||
/* Private variables --------------------------------------------------------- */
|
||||
PCD_HandleTypeDef hpcd;
|
||||
/* Private function prototypes ----------------------------------------------- */
|
||||
/* Private functions --------------------------------------------------------- */
|
||||
|
||||
/*******************************************************************************
|
||||
PCD BSP Routines
|
||||
*******************************************************************************/
|
||||
|
||||
#ifdef USE_USB_FS
|
||||
void OTG_FS_IRQHandler(void)
|
||||
#else
|
||||
void OTG_HS_IRQHandler(void)
|
||||
#endif
|
||||
{
|
||||
HAL_PCD_IRQHandler(&hpcd);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the PCD MSP.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_MspInit(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct;
|
||||
|
||||
if (hpcd->Instance == USB_OTG_FS)
|
||||
{
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
|
||||
/* Configure DM DP Pins */
|
||||
GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12);
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
if (hpcd->Init.vbus_sensing_enable == 1) {
|
||||
/* Configure VBUS Pin */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_9;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
}
|
||||
#ifdef USE_USB_ID
|
||||
|
||||
/* Configure ID pin */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_10;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
#endif
|
||||
|
||||
/* Enable USB FS Clocks */
|
||||
__HAL_RCC_USB2_OTG_FS_CLK_ENABLE();
|
||||
|
||||
/* XXX Todo: Configure and enable CRS for HSI48 */
|
||||
|
||||
/* Set USBFS Interrupt to the lowest priority */
|
||||
HAL_NVIC_SetPriority(OTG_FS_IRQn, 6, 0);
|
||||
|
||||
/* Enable USBFS Interrupt */
|
||||
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
|
||||
|
||||
}
|
||||
else if (hpcd->Instance == USB1_OTG_HS)
|
||||
{
|
||||
/* Configure USB FS GPIOs */
|
||||
__GPIOA_CLK_ENABLE();
|
||||
__GPIOB_CLK_ENABLE();
|
||||
__GPIOC_CLK_ENABLE();
|
||||
__GPIOH_CLK_ENABLE();
|
||||
__GPIOI_CLK_ENABLE();
|
||||
|
||||
/* CLK */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_5;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/* D0 */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_3;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/* D1 D2 D3 D4 D5 D6 D7 */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_5 |
|
||||
GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS;
|
||||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||
|
||||
/* STP */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_0;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
|
||||
/* NXT */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_4;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS;
|
||||
HAL_GPIO_Init(GPIOH, &GPIO_InitStruct);
|
||||
|
||||
/* DIR */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_11;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS;
|
||||
HAL_GPIO_Init(GPIOI, &GPIO_InitStruct);
|
||||
__HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE();
|
||||
|
||||
/* Enable USB HS Clocks */
|
||||
__HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
|
||||
|
||||
/* Set USBHS Interrupt to the lowest priority */
|
||||
HAL_NVIC_SetPriority(OTG_HS_IRQn, 1, 0);
|
||||
|
||||
/* Enable USBHS Interrupt */
|
||||
HAL_NVIC_EnableIRQ(OTG_HS_IRQn);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief De-Initializes the PCD MSP.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_MspDeInit(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
if (hpcd->Instance == USB2_OTG_FS)
|
||||
{
|
||||
/* Disable USB FS Clocks */
|
||||
__HAL_RCC_USB2_OTG_FS_CLK_DISABLE();
|
||||
}
|
||||
else if (hpcd->Instance == USB1_OTG_HS)
|
||||
{
|
||||
/* Disable USB HS Clocks */
|
||||
__HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
|
||||
__HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE();
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
LL Driver Callbacks (PCD -> USB Device Library)
|
||||
*******************************************************************************/
|
||||
|
||||
/**
|
||||
* @brief SetupStage callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_LL_SetupStage(hpcd->pData, (uint8_t *) hpcd->Setup);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DataOut Stage callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @param epnum: Endpoint Number
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef * hpcd, uint8_t epnum)
|
||||
{
|
||||
USBD_LL_DataOutStage(hpcd->pData, epnum, hpcd->OUT_ep[epnum].xfer_buff);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief DataIn Stage callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @param epnum: Endpoint Number
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef * hpcd, uint8_t epnum)
|
||||
{
|
||||
USBD_LL_DataInStage(hpcd->pData, epnum, hpcd->IN_ep[epnum].xfer_buff);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief SOF callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_SOFCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_LL_SOF(hpcd->pData);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Reset callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_ResetCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_SpeedTypeDef speed = USBD_SPEED_FULL;
|
||||
|
||||
/* Set USB Current Speed */
|
||||
switch (hpcd->Init.speed)
|
||||
{
|
||||
case PCD_SPEED_HIGH:
|
||||
speed = USBD_SPEED_HIGH;
|
||||
break;
|
||||
|
||||
case PCD_SPEED_FULL:
|
||||
speed = USBD_SPEED_FULL;
|
||||
break;
|
||||
|
||||
default:
|
||||
speed = USBD_SPEED_FULL;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Reset Device */
|
||||
USBD_LL_Reset(hpcd->pData);
|
||||
|
||||
USBD_LL_SetSpeed(hpcd->pData, speed);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Suspend callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_SuspendCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_LL_Suspend(hpcd->pData);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Resume callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_ResumeCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_LL_Resume(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(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(hpcd->pData, epnum);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief ConnectCallback callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_ConnectCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_LL_DevConnected(hpcd->pData);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Disconnect callback.
|
||||
* @param hpcd: PCD handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef * hpcd)
|
||||
{
|
||||
USBD_LL_DevDisconnected(hpcd->pData);
|
||||
}
|
||||
|
||||
|
||||
/*******************************************************************************
|
||||
LL Driver Interface (USB Device Library --> PCD)
|
||||
*******************************************************************************/
|
||||
|
||||
/**
|
||||
* @brief Initializes the Low Level portion of the Device driver.
|
||||
* @param pdev: Device handle
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef * pdev)
|
||||
{
|
||||
#ifdef USE_USB_FS
|
||||
/* Set LL Driver parameters */
|
||||
hpcd.Instance = USB2_OTG_FS;
|
||||
hpcd.Init.dev_endpoints = 9;
|
||||
hpcd.Init.use_dedicated_ep1 = DISABLE;
|
||||
hpcd.Init.ep0_mps = DEP0CTL_MPS_64;
|
||||
hpcd.Init.low_power_enable = DISABLE;
|
||||
hpcd.Init.phy_itface = PCD_PHY_EMBEDDED;
|
||||
hpcd.Init.Sof_enable = DISABLE;
|
||||
hpcd.Init.battery_charging_enable = DISABLE;
|
||||
hpcd.Init.speed = PCD_SPEED_FULL;
|
||||
hpcd.Init.vbus_sensing_enable = DISABLE;
|
||||
hpcd.Init.dma_enable = DISABLE;
|
||||
hpcd.Init.lpm_enable = DISABLE;
|
||||
|
||||
/* Link The driver to the stack */
|
||||
hpcd.pData = pdev;
|
||||
pdev->pData = &hpcd;
|
||||
|
||||
hpcd.Init.vbus_sensing_enable = 0;
|
||||
|
||||
/* Initialize LL Driver */
|
||||
HAL_PCD_Init(&hpcd);
|
||||
|
||||
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
|
||||
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x40);
|
||||
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x80);
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_USB_HS
|
||||
/* Set LL Driver parameters */
|
||||
hpcd.Instance = USB1_OTG_HS;
|
||||
hpcd.Init.dev_endpoints = 8;
|
||||
hpcd.Init.use_dedicated_ep1 = 0;
|
||||
hpcd.Init.ep0_mps = 0x40;
|
||||
|
||||
/* Be aware that enabling DMA mode will result in data being sent only by
|
||||
* multiple of 4 packet sizes. This is due to the fact that USB DMA does not
|
||||
* allow sending data from non word-aligned addresses. For this specific
|
||||
* application, it is advised to not enable this option unless required. */
|
||||
hpcd.Init.dma_enable = 0;
|
||||
hpcd.Init.low_power_enable = 0;
|
||||
hpcd.Init.lpm_enable = 0;
|
||||
hpcd.Init.phy_itface = PCD_PHY_ULPI;
|
||||
hpcd.Init.Sof_enable = 0;
|
||||
hpcd.Init.speed = PCD_SPEED_HIGH;
|
||||
hpcd.Init.vbus_sensing_enable = 0;
|
||||
|
||||
/* Link The driver to the stack */
|
||||
hpcd.pData = pdev;
|
||||
pdev->pData = &hpcd;
|
||||
|
||||
/* Initialize LL Driver */
|
||||
HAL_PCD_Init(&hpcd);
|
||||
|
||||
HAL_PCDEx_SetRxFiFo(&hpcd, 0x200);
|
||||
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x80);
|
||||
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x174);
|
||||
#endif
|
||||
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief De-Initializes the Low Level portion of the Device driver.
|
||||
* @param pdev: Device handle
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_DeInit(USBD_HandleTypeDef * pdev)
|
||||
{
|
||||
HAL_PCD_DeInit(pdev->pData);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Starts the Low Level portion of the Device driver.
|
||||
* @param pdev: Device handle
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_Start(USBD_HandleTypeDef * pdev)
|
||||
{
|
||||
HAL_PCD_Start(pdev->pData);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Stops the Low Level portion of the Device driver.
|
||||
* @param pdev: Device handle
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_Stop(USBD_HandleTypeDef * pdev)
|
||||
{
|
||||
HAL_PCD_Stop(pdev->pData);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Opens an endpoint of the Low Level Driver.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @param ep_type: Endpoint Type
|
||||
* @param ep_mps: Endpoint Max Packet Size
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_OpenEP(USBD_HandleTypeDef * pdev,
|
||||
uint8_t ep_addr,
|
||||
uint8_t ep_type, uint16_t ep_mps)
|
||||
{
|
||||
HAL_PCD_EP_Open(pdev->pData, ep_addr, ep_mps, ep_type);
|
||||
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Closes an endpoint of the Low Level Driver.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_CloseEP(USBD_HandleTypeDef * pdev, uint8_t ep_addr)
|
||||
{
|
||||
HAL_PCD_EP_Close(pdev->pData, ep_addr);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Flushes an endpoint of the Low Level Driver.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_FlushEP(USBD_HandleTypeDef * pdev, uint8_t ep_addr)
|
||||
{
|
||||
HAL_PCD_EP_Flush(pdev->pData, ep_addr);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets a Stall condition on an endpoint of the Low Level Driver.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_StallEP(USBD_HandleTypeDef * pdev, uint8_t ep_addr)
|
||||
{
|
||||
HAL_PCD_EP_SetStall(pdev->pData, ep_addr);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears a Stall condition on an endpoint of the Low Level Driver.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef * pdev,
|
||||
uint8_t ep_addr)
|
||||
{
|
||||
HAL_PCD_EP_ClrStall(pdev->pData, ep_addr);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns Stall condition.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval Stall (1: Yes, 0: No)
|
||||
*/
|
||||
uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef * pdev, uint8_t ep_addr)
|
||||
{
|
||||
PCD_HandleTypeDef *hpcd = pdev->pData;
|
||||
|
||||
if ((ep_addr & 0x80) == 0x80)
|
||||
{
|
||||
return hpcd->IN_ep[ep_addr & 0x7F].is_stall;
|
||||
}
|
||||
else
|
||||
{
|
||||
return hpcd->OUT_ep[ep_addr & 0x7F].is_stall;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Assigns a USB address to the device.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef * pdev,
|
||||
uint8_t dev_addr)
|
||||
{
|
||||
HAL_PCD_SetAddress(pdev->pData, dev_addr);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Transmits data over an endpoint.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @param pbuf: Pointer to data to be sent
|
||||
* @param size: Data size
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef * pdev,
|
||||
uint8_t ep_addr,
|
||||
uint8_t * pbuf, uint16_t size)
|
||||
{
|
||||
/* Get the packet total length */
|
||||
pdev->ep_in[ep_addr & 0x7F].total_length = size;
|
||||
|
||||
HAL_PCD_EP_Transmit(pdev->pData, ep_addr, pbuf, size);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Prepares an endpoint for reception.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @param pbuf: Pointer to data to be received
|
||||
* @param size: Data size
|
||||
* @retval USBD Status
|
||||
*/
|
||||
USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef * pdev,
|
||||
uint8_t ep_addr,
|
||||
uint8_t * pbuf, uint16_t size)
|
||||
{
|
||||
HAL_PCD_EP_Receive(pdev->pData, ep_addr, pbuf, size);
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the last transferred packet size.
|
||||
* @param pdev: Device handle
|
||||
* @param ep_addr: Endpoint Number
|
||||
* @retval Received Data Size
|
||||
*/
|
||||
uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef * pdev, uint8_t ep_addr)
|
||||
{
|
||||
return HAL_PCD_EP_GetRxCount(pdev->pData, ep_addr);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Delays routine for the USB Device Library.
|
||||
* @param Delay: Delay in ms
|
||||
* @retval None
|
||||
*/
|
||||
void USBD_LL_Delay(uint32_t Delay)
|
||||
{
|
||||
HAL_Delay(Delay);
|
||||
}
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
113
src/main/vcph7/usbd_conf.h
Normal file
113
src/main/vcph7/usbd_conf.h
Normal file
|
@ -0,0 +1,113 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file USB_Device/CDC_Standalone/Inc/usbd_conf.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-April-2016
|
||||
* @brief General low level driver configuration
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __USBD_CONF_H
|
||||
#define __USBD_CONF_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "common/maths.h" // For MIN and MAX
|
||||
#include "stm32h7xx_hal.h"
|
||||
|
||||
#if (USBD_DEBUG_LEVEL > 0)
|
||||
#include <stdio.h>
|
||||
#endif
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
#define USE_USB_FS
|
||||
|
||||
/* Common Config */
|
||||
#define USBD_MAX_NUM_INTERFACES 3
|
||||
#define USBD_MAX_NUM_CONFIGURATION 1
|
||||
#define USBD_MAX_STR_DESC_SIZ 0x100
|
||||
#define USBD_SUPPORT_USER_STRING 0
|
||||
#define USBD_SELF_POWERED 1
|
||||
#define USBD_DEBUG_LEVEL 0
|
||||
#define MSC_MEDIA_PACKET 512
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Memory management macros */
|
||||
#define USBD_malloc malloc
|
||||
#define USBD_free free
|
||||
#define USBD_memset memset
|
||||
#define USBD_memcpy memcpy
|
||||
|
||||
/* DEBUG macros */
|
||||
#if (USBD_DEBUG_LEVEL > 0)
|
||||
#define USBD_UsrLog(...) printf(__VA_ARGS__);\
|
||||
printf("\n");
|
||||
#else
|
||||
#define USBD_UsrLog(...)
|
||||
#endif
|
||||
|
||||
#if (USBD_DEBUG_LEVEL > 1)
|
||||
|
||||
#define USBD_ErrLog(...) printf("ERROR: ") ;\
|
||||
printf(__VA_ARGS__);\
|
||||
printf("\n");
|
||||
#else
|
||||
#define USBD_ErrLog(...)
|
||||
#endif
|
||||
|
||||
#if (USBD_DEBUG_LEVEL > 2)
|
||||
#define USBD_DbgLog(...) printf("DEBUG : ") ;\
|
||||
printf(__VA_ARGS__);\
|
||||
printf("\n");
|
||||
#else
|
||||
#define USBD_DbgLog(...)
|
||||
#endif
|
||||
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
#endif /* __USBD_CONF_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
354
src/main/vcph7/usbd_desc.c
Normal file
354
src/main/vcph7/usbd_desc.c
Normal file
|
@ -0,0 +1,354 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file USB_Device/CDC_Standalone/Src/usbd_desc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-April-2016
|
||||
* @brief This file provides the USBD descriptors and string formating method.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* 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"
|
||||
#include "platform.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/usb.h"
|
||||
#ifdef USE_USB_MSC
|
||||
#include "drivers/usb_msc.h"
|
||||
#endif
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define USBD_VID 0x0483
|
||||
#define USBD_PID 0x5740
|
||||
#define USBD_LANGID_STRING 0x409
|
||||
#define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME
|
||||
#define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode"
|
||||
#define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode"
|
||||
#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"
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
|
||||
#ifdef USB_SUPPORT_USER_STRING_DESC
|
||||
uint8_t *USBD_VCP_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
|
||||
#endif /* USB_SUPPORT_USER_STRING_DESC */
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
USBD_DescriptorsTypeDef VCP_Desc = {
|
||||
USBD_VCP_DeviceDescriptor,
|
||||
USBD_VCP_LangIDStrDescriptor,
|
||||
USBD_VCP_ManufacturerStrDescriptor,
|
||||
USBD_VCP_ProductStrDescriptor,
|
||||
USBD_VCP_SerialStrDescriptor,
|
||||
USBD_VCP_ConfigStrDescriptor,
|
||||
USBD_VCP_InterfaceStrDescriptor,
|
||||
};
|
||||
|
||||
/* USB Standard Device Descriptor */
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma data_alignment=4
|
||||
#endif
|
||||
__ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
|
||||
0x12, /* bLength */
|
||||
USB_DESC_TYPE_DEVICE, /* bDescriptorType */
|
||||
0x00, /* bcdUSB */
|
||||
0x02,
|
||||
0x02, /* bDeviceClass */
|
||||
0x00, /* bDeviceSubClass */
|
||||
0x00, /* bDeviceProtocol */
|
||||
USB_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_MAX_NUM_CONFIGURATION /* bNumConfigurations */
|
||||
}; /* USB_DeviceDescriptor */
|
||||
|
||||
#ifdef USE_USB_CDC_HID
|
||||
extern uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC];
|
||||
#endif
|
||||
|
||||
#ifdef USE_USB_MSC
|
||||
|
||||
#define USBD_PID_MSC 22314
|
||||
|
||||
__ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
|
||||
{
|
||||
0x12, /*bLength */
|
||||
USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
|
||||
0x00, /*bcdUSB */
|
||||
0x02,
|
||||
0x00, /*bDeviceClass*/
|
||||
0x00, /*bDeviceSubClass*/
|
||||
0x00, /*bDeviceProtocol*/
|
||||
USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
|
||||
LOBYTE(USBD_VID), /*idVendor*/
|
||||
HIBYTE(USBD_VID), /*idVendor*/
|
||||
LOBYTE(USBD_PID_MSC), /*idProduct*/
|
||||
HIBYTE(USBD_PID_MSC), /*idProduct*/
|
||||
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*/
|
||||
};
|
||||
#endif
|
||||
|
||||
/* USB Standard Device Descriptor */
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma data_alignment=4
|
||||
#endif
|
||||
__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),
|
||||
};
|
||||
|
||||
uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] =
|
||||
{
|
||||
USB_SIZ_STRING_SERIAL,
|
||||
USB_DESC_TYPE_STRING,
|
||||
};
|
||||
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma data_alignment=4
|
||||
#endif
|
||||
__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len);
|
||||
static void Get_SerialNum(void);
|
||||
|
||||
/**
|
||||
* @brief Returns the device descriptor.
|
||||
* @param speed: Current device speed
|
||||
* @param length: Pointer to data length variable
|
||||
* @retval Pointer to descriptor buffer
|
||||
*/
|
||||
uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
(void)speed;
|
||||
#ifdef USE_USB_MSC
|
||||
if (mscCheckBoot()) {
|
||||
*length = sizeof(USBD_MSC_DeviceDesc);
|
||||
return USBD_MSC_DeviceDesc;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_USB_CDC_HID
|
||||
if (usbDevConfig()->type == COMPOSITE) {
|
||||
*length = sizeof(USBD_HID_CDC_DeviceDescriptor);
|
||||
return USBD_HID_CDC_DeviceDescriptor;
|
||||
}
|
||||
#endif
|
||||
*length = sizeof(USBD_DeviceDesc);
|
||||
return (uint8_t*)USBD_DeviceDesc;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the LangID string descriptor.
|
||||
* @param speed: Current device speed
|
||||
* @param length: Pointer to data length variable
|
||||
* @retval Pointer to descriptor buffer
|
||||
*/
|
||||
uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
(void)speed;
|
||||
*length = sizeof(USBD_LangIDDesc);
|
||||
return (uint8_t*)USBD_LangIDDesc;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the product string descriptor.
|
||||
* @param speed: Current device speed
|
||||
* @param length: Pointer to data length variable
|
||||
* @retval Pointer to descriptor buffer
|
||||
*/
|
||||
uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
if (speed == USBD_SPEED_HIGH)
|
||||
{
|
||||
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 Returns the manufacturer string descriptor.
|
||||
* @param speed: Current device speed
|
||||
* @param length: Pointer to data length variable
|
||||
* @retval Pointer to descriptor buffer
|
||||
*/
|
||||
uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
(void)speed;
|
||||
USBD_GetString((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
|
||||
return USBD_StrDesc;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns 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_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
(void)speed;
|
||||
*length = USB_SIZ_STRING_SERIAL;
|
||||
|
||||
/* Update the serial number string descriptor with the data from the unique ID*/
|
||||
Get_SerialNum();
|
||||
|
||||
return (uint8_t*)USBD_StringSerial;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the configuration string descriptor.
|
||||
* @param speed: Current device speed
|
||||
* @param length: Pointer to data length variable
|
||||
* @retval Pointer to descriptor buffer
|
||||
*/
|
||||
uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
if (speed == USBD_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 Returns the interface string descriptor.
|
||||
* @param speed: Current device speed
|
||||
* @param length: Pointer to data length variable
|
||||
* @retval Pointer to descriptor buffer
|
||||
*/
|
||||
uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
if (speed == USBD_SPEED_HIGH)
|
||||
{
|
||||
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;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Create the serial number string descriptor
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void Get_SerialNum(void)
|
||||
{
|
||||
uint32_t deviceserial0, deviceserial1, deviceserial2;
|
||||
|
||||
deviceserial0 = U_ID_0;
|
||||
deviceserial1 = U_ID_1;
|
||||
deviceserial2 = U_ID_2;
|
||||
|
||||
deviceserial0 += deviceserial2;
|
||||
|
||||
if (deviceserial0 != 0)
|
||||
{
|
||||
IntToUnicode (deviceserial0, &USBD_StringSerial[2] ,8);
|
||||
IntToUnicode (deviceserial1, &USBD_StringSerial[18] ,4);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Convert Hex 32Bits value into char
|
||||
* @param value: value to convert
|
||||
* @param pbuf: pointer to the buffer
|
||||
* @param len: buffer length
|
||||
* @retval None
|
||||
*/
|
||||
static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
|
||||
{
|
||||
uint8_t idx = 0;
|
||||
|
||||
for ( idx = 0; idx < len; idx ++)
|
||||
{
|
||||
if ( ((value >> 28)) < 0xA )
|
||||
{
|
||||
pbuf[ 2* idx] = (value >> 28) + '0';
|
||||
}
|
||||
else
|
||||
{
|
||||
pbuf[2* idx] = (value >> 28) + 'A' - 10;
|
||||
}
|
||||
|
||||
value = value << 4;
|
||||
|
||||
pbuf[ 2* idx + 1] = 0;
|
||||
}
|
||||
}
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
65
src/main/vcph7/usbd_desc.h
Normal file
65
src/main/vcph7/usbd_desc.h
Normal file
|
@ -0,0 +1,65 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file USB_Device/CDC_Standalone/Inc/usbd_desc.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-April-2016
|
||||
* @brief Header for usbd_desc.c module
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2016 STMicroelectronics International N.V.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __USBD_DESC_H
|
||||
#define __USBD_DESC_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_def.h"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
#define USB_SIZ_STRING_SERIAL 0x1A
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
extern USBD_DescriptorsTypeDef VCP_Desc;
|
||||
|
||||
#endif /* __USBD_DESC_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
Loading…
Add table
Add a link
Reference in a new issue