Add CDC+HID on F7 (#5596)
This commit is contained in:
parent
c091fa8e48
commit
a9136e2ba0
|
@ -516,18 +516,18 @@ static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
|
||||||
CDC_CMD_PACKET_SIZE);
|
CDC_CMD_PACKET_SIZE);
|
||||||
|
|
||||||
|
|
||||||
pdev->pClassData = USBD_malloc(sizeof (USBD_CDC_HandleTypeDef));
|
pdev->pCDC_ClassData = USBD_malloc(sizeof (USBD_CDC_HandleTypeDef));
|
||||||
|
|
||||||
if(pdev->pClassData == NULL)
|
if(pdev->pCDC_ClassData == NULL)
|
||||||
{
|
{
|
||||||
ret = 1;
|
ret = 1;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
/* Init physical Interface components */
|
/* Init physical Interface components */
|
||||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Init();
|
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Init();
|
||||||
|
|
||||||
/* Init Xfer states */
|
/* Init Xfer states */
|
||||||
hcdc->TxState =0;
|
hcdc->TxState =0;
|
||||||
|
@ -582,11 +582,11 @@ static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
|
|
||||||
|
|
||||||
/* DeInit physical Interface components */
|
/* DeInit physical Interface components */
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pCDC_ClassData != NULL)
|
||||||
{
|
{
|
||||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->DeInit();
|
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->DeInit();
|
||||||
USBD_free(pdev->pClassData);
|
USBD_free(pdev->pCDC_ClassData);
|
||||||
pdev->pClassData = NULL;
|
pdev->pCDC_ClassData = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
|
@ -602,7 +602,7 @@ static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
||||||
USBD_SetupReqTypedef *req)
|
USBD_SetupReqTypedef *req)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
static uint8_t ifalt = 0;
|
static uint8_t ifalt = 0;
|
||||||
|
|
||||||
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
||||||
|
@ -612,7 +612,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
||||||
{
|
{
|
||||||
if (req->bmRequest & 0x80)
|
if (req->bmRequest & 0x80)
|
||||||
{
|
{
|
||||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
|
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(req->bRequest,
|
||||||
(uint8_t *)hcdc->data,
|
(uint8_t *)hcdc->data,
|
||||||
req->wLength);
|
req->wLength);
|
||||||
USBD_CtlSendData (pdev,
|
USBD_CtlSendData (pdev,
|
||||||
|
@ -632,7 +632,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
|
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(req->bRequest,
|
||||||
(uint8_t*)req,
|
(uint8_t*)req,
|
||||||
0);
|
0);
|
||||||
}
|
}
|
||||||
|
@ -667,9 +667,9 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
||||||
static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
{
|
{
|
||||||
(void)epnum;
|
(void)epnum;
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pCDC_ClassData != NULL)
|
||||||
{
|
{
|
||||||
|
|
||||||
hcdc->TxState = 0;
|
hcdc->TxState = 0;
|
||||||
|
@ -691,16 +691,16 @@ static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
static uint8_t USBD_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
/* Get the received data length */
|
/* Get the received data length */
|
||||||
hcdc->RxLength = USBD_LL_GetRxDataSize (pdev, epnum);
|
hcdc->RxLength = USBD_LL_GetRxDataSize (pdev, epnum);
|
||||||
|
|
||||||
/* USB data will be immediately processed, this allow next USB traffic being
|
/* USB data will be immediately processed, this allow next USB traffic being
|
||||||
NAKed till the end of the application Xfer */
|
NAKed till the end of the application Xfer */
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pCDC_ClassData != NULL)
|
||||||
{
|
{
|
||||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength);
|
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength);
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
@ -721,11 +721,11 @@ static uint8_t USBD_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev)
|
static uint8_t USBD_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
if((pdev->pUserData != NULL) && (hcdc->CmdOpCode != 0xFF))
|
if((pdev->pCDC_UserData != NULL) && (hcdc->CmdOpCode != 0xFF))
|
||||||
{
|
{
|
||||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(hcdc->CmdOpCode,
|
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(hcdc->CmdOpCode,
|
||||||
(uint8_t *)hcdc->data,
|
(uint8_t *)hcdc->data,
|
||||||
hcdc->CmdLength);
|
hcdc->CmdLength);
|
||||||
hcdc->CmdOpCode = 0xFF;
|
hcdc->CmdOpCode = 0xFF;
|
||||||
|
@ -798,7 +798,7 @@ uint8_t USBD_CDC_RegisterInterface (USBD_HandleTypeDef *pdev,
|
||||||
|
|
||||||
if(fops != NULL)
|
if(fops != NULL)
|
||||||
{
|
{
|
||||||
pdev->pUserData= fops;
|
pdev->pCDC_UserData= fops;
|
||||||
ret = USBD_OK;
|
ret = USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -815,7 +815,7 @@ uint8_t USBD_CDC_SetTxBuffer (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t *pbuff,
|
uint8_t *pbuff,
|
||||||
uint16_t length)
|
uint16_t length)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
hcdc->TxBuffer = pbuff;
|
hcdc->TxBuffer = pbuff;
|
||||||
hcdc->TxLength = length;
|
hcdc->TxLength = length;
|
||||||
|
@ -833,7 +833,7 @@ uint8_t USBD_CDC_SetTxBuffer (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t *pbuff)
|
uint8_t *pbuff)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
hcdc->RxBuffer = pbuff;
|
hcdc->RxBuffer = pbuff;
|
||||||
|
|
||||||
|
@ -849,9 +849,9 @@ uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev,
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev)
|
uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pCDC_ClassData != NULL)
|
||||||
{
|
{
|
||||||
if(hcdc->TxState == 0)
|
if(hcdc->TxState == 0)
|
||||||
{
|
{
|
||||||
|
@ -886,10 +886,10 @@ uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev)
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev)
|
uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||||
|
|
||||||
/* Suspend or Resume USB Out process */
|
/* Suspend or Resume USB Out process */
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pCDC_ClassData != NULL)
|
||||||
{
|
{
|
||||||
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
||||||
{
|
{
|
||||||
|
|
|
@ -0,0 +1,26 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
* Author: Chris Hockuba (https://github.com/conkerkh)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "usbd_ioreq.h"
|
||||||
|
|
||||||
|
extern USBD_ClassTypeDef USBD_HID_CDC;
|
||||||
|
#define USBD_HID_CDC_CLASS &USBD_HID_CDC
|
|
@ -0,0 +1,332 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
* Author: Chris Hockuba (https://github.com/conkerkh)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "usbd_cdc_hid.h"
|
||||||
|
#include "usbd_desc.h"
|
||||||
|
#include "usbd_ctlreq.h"
|
||||||
|
#include "usbd_def.h"
|
||||||
|
#include "usbd_conf.h"
|
||||||
|
|
||||||
|
#include "usbd_cdc.h"
|
||||||
|
#include "usbd_hid.h"
|
||||||
|
|
||||||
|
#define USB_HID_CDC_CONFIG_DESC_SIZ (USB_HID_CONFIG_DESC_SIZ - 9 + USB_CDC_CONFIG_DESC_SIZ + 8)
|
||||||
|
|
||||||
|
#define HID_INTERFACE 0x0
|
||||||
|
#define HID_POOLING_INTERVAL 0x0A // 10ms - 100Hz update rate
|
||||||
|
|
||||||
|
#define CDC_COM_INTERFACE 0x1
|
||||||
|
|
||||||
|
#define USBD_VID 0x0483
|
||||||
|
#define USBD_PID 0x3256
|
||||||
|
|
||||||
|
__ALIGN_BEGIN uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC] __ALIGN_END =
|
||||||
|
{
|
||||||
|
0x12, /*bLength */
|
||||||
|
USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
|
||||||
|
0x00, 0x02, /*bcdUSB */
|
||||||
|
0xEF, /*bDeviceClass*/
|
||||||
|
0x02, /*bDeviceSubClass*/
|
||||||
|
0x01, /*bDeviceProtocol*/
|
||||||
|
USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/
|
||||||
|
LOBYTE(USBD_VID), HIBYTE(USBD_VID), /*idVendor*/
|
||||||
|
LOBYTE(USBD_PID),
|
||||||
|
HIBYTE(USBD_PID), /*idProduct*/
|
||||||
|
0x00, 0x02, /*bcdDevice rel. 2.00*/
|
||||||
|
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*/
|
||||||
|
};
|
||||||
|
|
||||||
|
__ALIGN_BEGIN static uint8_t USBD_HID_CDC_CfgDesc[USB_HID_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
|
{
|
||||||
|
0x09, /* bLength: Configuration Descriptor size */
|
||||||
|
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
|
||||||
|
USB_HID_CDC_CONFIG_DESC_SIZ,
|
||||||
|
/* wTotalLength: Bytes returned */
|
||||||
|
0x00,
|
||||||
|
0x03, /*bNumInterfaces: 2 interfaces (1 for CDC, 1 for HID)*/
|
||||||
|
0x01, /*bConfigurationValue: Configuration value*/
|
||||||
|
0x00, /*iConfiguration: Index of string descriptor describing
|
||||||
|
the configuration*/
|
||||||
|
0xC0, /*bmAttributes: bus powered and Support Remote Wake-up */
|
||||||
|
0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/
|
||||||
|
|
||||||
|
/************** Descriptor of Joystick Mouse interface ****************/
|
||||||
|
/* 09 */
|
||||||
|
0x09, /*bLength: Interface Descriptor size*/
|
||||||
|
USB_DESC_TYPE_INTERFACE, /*bDescriptorType: Interface descriptor type*/
|
||||||
|
HID_INTERFACE, /*bInterfaceNumber: Number of Interface*/
|
||||||
|
0x00, /*bAlternateSetting: Alternate setting*/
|
||||||
|
0x01, /*bNumEndpoints*/
|
||||||
|
0x03, /*bInterfaceClass: HID*/
|
||||||
|
0x00, /*bInterfaceSubClass : 1=BOOT, 0=no boot*/
|
||||||
|
0x00, /*nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse*/
|
||||||
|
0, /*iInterface: Index of string descriptor*/
|
||||||
|
/******************** Descriptor of Joystick Mouse HID ********************/
|
||||||
|
/* 18 */
|
||||||
|
0x09, /*bLength: HID Descriptor size*/
|
||||||
|
HID_DESCRIPTOR_TYPE, /*bDescriptorType: HID*/
|
||||||
|
0x11, /*bcdHID: HID Class Spec release number*/
|
||||||
|
0x01,
|
||||||
|
0x00, /*bCountryCode: Hardware target country*/
|
||||||
|
0x01, /*bNumDescriptors: Number of HID class descriptors to follow*/
|
||||||
|
0x22, /*bDescriptorType*/
|
||||||
|
HID_MOUSE_REPORT_DESC_SIZE, /*wItemLength: Total length of Report descriptor*/
|
||||||
|
0x00,
|
||||||
|
/******************** Descriptor of Mouse endpoint ********************/
|
||||||
|
/* 27 */
|
||||||
|
0x07, /*bLength: Endpoint Descriptor size*/
|
||||||
|
USB_DESC_TYPE_ENDPOINT, /*bDescriptorType:*/
|
||||||
|
|
||||||
|
HID_EPIN_ADDR, /*bEndpointAddress: Endpoint Address (IN)*/
|
||||||
|
0x03, /*bmAttributes: Interrupt endpoint*/
|
||||||
|
HID_EPIN_SIZE, /*wMaxPacketSize: 8 Byte max */
|
||||||
|
0x00,
|
||||||
|
HID_POOLING_INTERVAL, /*bInterval: Polling Interval (10 ms)*/
|
||||||
|
/* 34 */
|
||||||
|
|
||||||
|
/******** /IAD should be positioned just before the CDC interfaces ******
|
||||||
|
IAD to associate the two CDC interfaces */
|
||||||
|
|
||||||
|
0x08, /* bLength */
|
||||||
|
0x0B, /* bDescriptorType */
|
||||||
|
0x01, /* bFirstInterface */
|
||||||
|
0x02, /* bInterfaceCount */
|
||||||
|
0x02, /* bFunctionClass */
|
||||||
|
0x02, /* bFunctionSubClass */
|
||||||
|
0x01, /* bFunctionProtocol */
|
||||||
|
0x00, /* iFunction (Index of string descriptor describing this function) */
|
||||||
|
|
||||||
|
/*Interface Descriptor */
|
||||||
|
0x09, /* bLength: Interface Descriptor size */
|
||||||
|
USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface */
|
||||||
|
/* Interface descriptor type */
|
||||||
|
CDC_COM_INTERFACE, /* bInterfaceNumber: Number of Interface */
|
||||||
|
0x00, /* bAlternateSetting: Alternate setting */
|
||||||
|
0x01, /* bNumEndpoints: One endpoints used */
|
||||||
|
0x02, /* bInterfaceClass: Communication Interface Class */
|
||||||
|
0x02, /* bInterfaceSubClass: Abstract Control Model */
|
||||||
|
0x01, /* bInterfaceProtocol: Common AT commands */
|
||||||
|
0x00, /* iInterface: */
|
||||||
|
|
||||||
|
/*Header Functional Descriptor*/
|
||||||
|
0x05, /* bLength: Endpoint Descriptor size */
|
||||||
|
0x24, /* bDescriptorType: CS_INTERFACE */
|
||||||
|
0x00, /* bDescriptorSubtype: Header Func Desc */
|
||||||
|
0x10, /* bcdCDC: spec release number */
|
||||||
|
0x01,
|
||||||
|
|
||||||
|
/*Call Management Functional Descriptor*/
|
||||||
|
0x05, /* bFunctionLength */
|
||||||
|
0x24, /* bDescriptorType: CS_INTERFACE */
|
||||||
|
0x01, /* bDescriptorSubtype: Call Management Func Desc */
|
||||||
|
0x00, /* bmCapabilities: D0+D1 */
|
||||||
|
0x02, /* bDataInterface: 2 */
|
||||||
|
|
||||||
|
/*ACM Functional Descriptor*/
|
||||||
|
0x04, /* bFunctionLength */
|
||||||
|
0x24, /* bDescriptorType: CS_INTERFACE */
|
||||||
|
0x02, /* bDescriptorSubtype: Abstract Control Management desc */
|
||||||
|
0x02, /* bmCapabilities */
|
||||||
|
|
||||||
|
/*Union Functional Descriptor*/
|
||||||
|
0x05, /* bFunctionLength */
|
||||||
|
0x24, /* bDescriptorType: CS_INTERFACE */
|
||||||
|
0x06, /* bDescriptorSubtype: Union func desc */
|
||||||
|
0x01, /* bMasterInterface: Communication class interface */
|
||||||
|
0x02, /* bSlaveInterface0: Data Class Interface */
|
||||||
|
|
||||||
|
/*Endpoint 2 Descriptor*/
|
||||||
|
0x07, /* bLength: Endpoint Descriptor size */
|
||||||
|
USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
|
||||||
|
CDC_CMD_EP, /* bEndpointAddress */
|
||||||
|
0x03, /* bmAttributes: Interrupt */
|
||||||
|
LOBYTE(CDC_CMD_PACKET_SIZE), /* wMaxPacketSize: */
|
||||||
|
HIBYTE(CDC_CMD_PACKET_SIZE),
|
||||||
|
0xFF, /* bInterval: */
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/*Data class interface descriptor*/
|
||||||
|
0x09, /* bLength: Endpoint Descriptor size */
|
||||||
|
USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
|
||||||
|
0x02, /* bInterfaceNumber: Number of Interface */
|
||||||
|
0x00, /* bAlternateSetting: Alternate setting */
|
||||||
|
0x02, /* bNumEndpoints: Two endpoints used */
|
||||||
|
0x0A, /* bInterfaceClass: CDC */
|
||||||
|
0x00, /* bInterfaceSubClass: */
|
||||||
|
0x00, /* bInterfaceProtocol: */
|
||||||
|
0x00, /* iInterface: */
|
||||||
|
|
||||||
|
/*Endpoint OUT Descriptor*/
|
||||||
|
0x07, /* bLength: Endpoint Descriptor size */
|
||||||
|
USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
|
||||||
|
CDC_OUT_EP, /* bEndpointAddress */
|
||||||
|
0x02, /* bmAttributes: Bulk */
|
||||||
|
LOBYTE(CDC_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
|
||||||
|
HIBYTE(CDC_DATA_FS_MAX_PACKET_SIZE),
|
||||||
|
0x00, /* bInterval: ignore for Bulk transfer */
|
||||||
|
|
||||||
|
/*Endpoint IN Descriptor*/
|
||||||
|
0x07, /* bLength: Endpoint Descriptor size */
|
||||||
|
USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
|
||||||
|
CDC_IN_EP, /* bEndpointAddress */
|
||||||
|
0x02, /* bmAttributes: Bulk */
|
||||||
|
LOBYTE(CDC_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
|
||||||
|
HIBYTE(CDC_DATA_FS_MAX_PACKET_SIZE),
|
||||||
|
0x00, /* bInterval */
|
||||||
|
};
|
||||||
|
|
||||||
|
/* USB Standard Device Descriptor */
|
||||||
|
__ALIGN_BEGIN static uint8_t USBD_HID_CDC_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,
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Wrapper related callbacks */
|
||||||
|
static uint8_t USBD_HID_CDC_Init (USBD_HandleTypeDef *pdev, uint8_t cfgidx);
|
||||||
|
static uint8_t USBD_HID_CDC_DeInit (USBD_HandleTypeDef *pdev, uint8_t cfgidx);
|
||||||
|
|
||||||
|
/* Control Endpoints*/
|
||||||
|
static uint8_t USBD_HID_CDC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
|
||||||
|
static uint8_t USBD_HID_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev);
|
||||||
|
|
||||||
|
/* Class Specific Endpoints*/
|
||||||
|
static uint8_t USBD_HID_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum);
|
||||||
|
static uint8_t USBD_HID_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum);
|
||||||
|
|
||||||
|
static uint8_t *USBD_HID_CDC_GetFSCfgDesc (uint16_t *length);
|
||||||
|
uint8_t *USBD_HID_CDC_GetDeviceQualifierDescriptor (uint16_t *length); //Will be NULL Callback because it's unused
|
||||||
|
|
||||||
|
/* CDC interface class callbacks structure */
|
||||||
|
USBD_ClassTypeDef USBD_HID_CDC =
|
||||||
|
{
|
||||||
|
USBD_HID_CDC_Init,
|
||||||
|
USBD_HID_CDC_DeInit,
|
||||||
|
USBD_HID_CDC_Setup,
|
||||||
|
NULL, /* EP0_TxSent, */
|
||||||
|
USBD_HID_CDC_EP0_RxReady,
|
||||||
|
USBD_HID_CDC_DataIn,
|
||||||
|
USBD_HID_CDC_DataOut,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
USBD_HID_CDC_GetFSCfgDesc,
|
||||||
|
NULL,
|
||||||
|
USBD_HID_CDC_GetDeviceQualifierDescriptor,
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint8_t USBD_HID_CDC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
|
||||||
|
{
|
||||||
|
//Init CDC
|
||||||
|
USBD_CDC.Init(pdev, cfgidx);
|
||||||
|
|
||||||
|
//Init HID
|
||||||
|
USBD_HID.Init(pdev, cfgidx);
|
||||||
|
|
||||||
|
return USBD_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t USBD_HID_CDC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
|
||||||
|
{
|
||||||
|
//DeInit CDC
|
||||||
|
USBD_CDC.DeInit(pdev, cfgidx);
|
||||||
|
|
||||||
|
//DeInit HID
|
||||||
|
USBD_HID.DeInit(pdev, cfgidx);
|
||||||
|
|
||||||
|
return USBD_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t USBD_HID_CDC_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
||||||
|
{
|
||||||
|
switch(req->bmRequest & USB_REQ_RECIPIENT_MASK) {
|
||||||
|
case USB_REQ_RECIPIENT_INTERFACE:
|
||||||
|
if (req->wIndex == HID_INTERFACE) {
|
||||||
|
return USBD_HID.Setup(pdev, req);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
return USBD_CDC.Setup(pdev, req);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case USB_REQ_RECIPIENT_ENDPOINT:
|
||||||
|
if (req->wIndex == HID_EPIN_ADDR) {
|
||||||
|
return USBD_HID.Setup(pdev, req);
|
||||||
|
} else {
|
||||||
|
return USBD_CDC.Setup(pdev, req);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return USBD_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t USBD_HID_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev)
|
||||||
|
{
|
||||||
|
return (USBD_CDC.EP0_RxReady(pdev));
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t USBD_HID_CDC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
|
{
|
||||||
|
if (epnum == (CDC_IN_EP &~ 0x80)) {
|
||||||
|
return USBD_CDC.DataIn(pdev, epnum);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
return USBD_HID.DataIn(pdev, epnum);
|
||||||
|
}
|
||||||
|
|
||||||
|
return USBD_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t USBD_HID_CDC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
|
{
|
||||||
|
if (epnum == (CDC_OUT_EP &~ 0x80)) {
|
||||||
|
return (USBD_CDC.DataOut(pdev, epnum));
|
||||||
|
}
|
||||||
|
|
||||||
|
return USBD_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t *USBD_HID_CDC_GetFSCfgDesc (uint16_t *length)
|
||||||
|
{
|
||||||
|
*length = sizeof(USBD_HID_CDC_CfgDesc);
|
||||||
|
return USBD_HID_CDC_CfgDesc;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t *USBD_HID_CDC_GetDeviceQualifierDescriptor (uint16_t *length)
|
||||||
|
{
|
||||||
|
*length = sizeof(USBD_HID_CDC_DeviceQualifierDesc);
|
||||||
|
return USBD_HID_CDC_DeviceQualifierDesc;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -16,8 +16,8 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
|
@ -39,22 +39,22 @@
|
||||||
/** @addtogroup STM32_USB_DEVICE_LIBRARY
|
/** @addtogroup STM32_USB_DEVICE_LIBRARY
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_HID
|
/** @defgroup USBD_HID
|
||||||
* @brief This file is the Header file for usbd_hid.c
|
* @brief This file is the Header file for usbd_hid.c
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_HID_Exported_Defines
|
/** @defgroup USBD_HID_Exported_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
#define HID_EPIN_ADDR 0x81
|
#define HID_EPIN_ADDR 0x83
|
||||||
#define HID_EPIN_SIZE 0x04
|
#define HID_EPIN_SIZE 0x08
|
||||||
|
|
||||||
#define USB_HID_CONFIG_DESC_SIZ 34
|
#define USB_HID_CONFIG_DESC_SIZ 34
|
||||||
#define USB_HID_DESC_SIZ 9
|
#define USB_HID_DESC_SIZ 9
|
||||||
#define HID_MOUSE_REPORT_DESC_SIZE 74
|
#define HID_MOUSE_REPORT_DESC_SIZE 38
|
||||||
|
|
||||||
#define HID_DESCRIPTOR_TYPE 0x21
|
#define HID_DESCRIPTOR_TYPE 0x21
|
||||||
#define HID_REPORT_DESC 0x22
|
#define HID_REPORT_DESC 0x22
|
||||||
|
@ -73,7 +73,7 @@
|
||||||
#define HID_REQ_GET_REPORT 0x01
|
#define HID_REQ_GET_REPORT 0x01
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Exported_TypesDefinitions
|
/** @defgroup USBD_CORE_Exported_TypesDefinitions
|
||||||
|
@ -84,45 +84,45 @@ typedef enum
|
||||||
HID_IDLE = 0,
|
HID_IDLE = 0,
|
||||||
HID_BUSY,
|
HID_BUSY,
|
||||||
}
|
}
|
||||||
HID_StateTypeDef;
|
HID_StateTypeDef;
|
||||||
|
|
||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
uint32_t Protocol;
|
uint32_t Protocol;
|
||||||
uint32_t IdleState;
|
uint32_t IdleState;
|
||||||
uint32_t AltSetting;
|
uint32_t AltSetting;
|
||||||
HID_StateTypeDef state;
|
HID_StateTypeDef state;
|
||||||
}
|
}
|
||||||
USBD_HID_HandleTypeDef;
|
USBD_HID_HandleTypeDef;
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Exported_Macros
|
/** @defgroup USBD_CORE_Exported_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Exported_Variables
|
/** @defgroup USBD_CORE_Exported_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
extern USBD_ClassTypeDef USBD_HID;
|
extern USBD_ClassTypeDef USBD_HID;
|
||||||
#define USBD_HID_CLASS &USBD_HID
|
#define USBD_HID_CLASS &USBD_HID
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USB_CORE_Exported_Functions
|
/** @defgroup USB_CORE_Exported_Functions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t *report,
|
uint8_t *report,
|
||||||
uint16_t len);
|
uint16_t len);
|
||||||
|
|
||||||
|
@ -130,7 +130,7 @@ uint32_t USBD_HID_GetPollingInterval (USBD_HandleTypeDef *pdev);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
@ -139,10 +139,10 @@ uint32_t USBD_HID_GetPollingInterval (USBD_HandleTypeDef *pdev);
|
||||||
#endif /* __USB_HID_H */
|
#endif /* __USB_HID_H */
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -7,10 +7,10 @@
|
||||||
* @brief This file provides the HID core functions.
|
* @brief This file provides the HID core functions.
|
||||||
*
|
*
|
||||||
* @verbatim
|
* @verbatim
|
||||||
*
|
*
|
||||||
* ===================================================================
|
* ===================================================================
|
||||||
* HID Class Description
|
* HID Class Description
|
||||||
* ===================================================================
|
* ===================================================================
|
||||||
* This module manages the HID class V1.11 following the "Device Class Definition
|
* This module manages the HID class V1.11 following the "Device Class Definition
|
||||||
* for Human Interface Devices (HID) Version 1.11 Jun 27, 2001".
|
* for Human Interface Devices (HID) Version 1.11 Jun 27, 2001".
|
||||||
* This driver implements the following aspects of the specification:
|
* This driver implements the following aspects of the specification:
|
||||||
|
@ -18,12 +18,12 @@
|
||||||
* - The Mouse protocol
|
* - The Mouse protocol
|
||||||
* - Usage Page : Generic Desktop
|
* - Usage Page : Generic Desktop
|
||||||
* - Usage : Joystick
|
* - Usage : Joystick
|
||||||
* - Collection : Application
|
* - Collection : Application
|
||||||
*
|
*
|
||||||
* @note In HS mode and when the DMA is used, all variables and data structures
|
* @note In HS mode and when the DMA is used, all variables and data structures
|
||||||
* dealing with the DMA during the transaction process should be 32-bit aligned.
|
* dealing with the DMA during the transaction process should be 32-bit aligned.
|
||||||
*
|
*
|
||||||
*
|
*
|
||||||
* @endverbatim
|
* @endverbatim
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
|
@ -37,14 +37,14 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
#include "usbd_hid.h"
|
#include "usbd_hid.h"
|
||||||
|
@ -57,34 +57,34 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_HID
|
/** @defgroup USBD_HID
|
||||||
* @brief usbd core module
|
* @brief usbd core module
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_HID_Private_TypesDefinitions
|
/** @defgroup USBD_HID_Private_TypesDefinitions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_HID_Private_Defines
|
/** @defgroup USBD_HID_Private_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_HID_Private_Macros
|
/** @defgroup USBD_HID_Private_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -94,13 +94,13 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx);
|
uint8_t cfgidx);
|
||||||
|
|
||||||
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx);
|
uint8_t cfgidx);
|
||||||
|
|
||||||
static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
||||||
USBD_SetupReqTypedef *req);
|
USBD_SetupReqTypedef *req);
|
||||||
|
|
||||||
static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length);
|
static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length);
|
||||||
|
@ -110,26 +110,26 @@ static uint8_t *USBD_HID_GetDeviceQualifierDesc (uint16_t *length);
|
||||||
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum);
|
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum);
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_HID_Private_Variables
|
/** @defgroup USBD_HID_Private_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
USBD_ClassTypeDef USBD_HID =
|
USBD_ClassTypeDef USBD_HID =
|
||||||
{
|
{
|
||||||
USBD_HID_Init,
|
USBD_HID_Init,
|
||||||
USBD_HID_DeInit,
|
USBD_HID_DeInit,
|
||||||
USBD_HID_Setup,
|
USBD_HID_Setup,
|
||||||
NULL, /*EP0_TxSent*/
|
NULL, /*EP0_TxSent*/
|
||||||
NULL, /*EP0_RxReady*/
|
NULL, /*EP0_RxReady*/
|
||||||
USBD_HID_DataIn, /*DataIn*/
|
USBD_HID_DataIn, /*DataIn*/
|
||||||
NULL, /*DataOut*/
|
NULL, /*DataOut*/
|
||||||
NULL, /*SOF */
|
NULL, /*SOF */
|
||||||
NULL,
|
NULL,
|
||||||
NULL,
|
NULL,
|
||||||
|
USBD_HID_GetCfgDesc,
|
||||||
USBD_HID_GetCfgDesc,
|
USBD_HID_GetCfgDesc,
|
||||||
USBD_HID_GetCfgDesc,
|
|
||||||
USBD_HID_GetCfgDesc,
|
USBD_HID_GetCfgDesc,
|
||||||
USBD_HID_GetDeviceQualifierDesc,
|
USBD_HID_GetDeviceQualifierDesc,
|
||||||
};
|
};
|
||||||
|
@ -148,7 +148,7 @@ __ALIGN_BEGIN static uint8_t USBD_HID_CfgDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_
|
||||||
the configuration*/
|
the configuration*/
|
||||||
0xE0, /*bmAttributes: bus powered and Support Remote Wake-up */
|
0xE0, /*bmAttributes: bus powered and Support Remote Wake-up */
|
||||||
0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/
|
0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/
|
||||||
|
|
||||||
/************** Descriptor of Joystick Mouse interface ****************/
|
/************** Descriptor of Joystick Mouse interface ****************/
|
||||||
/* 09 */
|
/* 09 */
|
||||||
0x09, /*bLength: Interface Descriptor size*/
|
0x09, /*bLength: Interface Descriptor size*/
|
||||||
|
@ -175,7 +175,7 @@ __ALIGN_BEGIN static uint8_t USBD_HID_CfgDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_
|
||||||
/* 27 */
|
/* 27 */
|
||||||
0x07, /*bLength: Endpoint Descriptor size*/
|
0x07, /*bLength: Endpoint Descriptor size*/
|
||||||
USB_DESC_TYPE_ENDPOINT, /*bDescriptorType:*/
|
USB_DESC_TYPE_ENDPOINT, /*bDescriptorType:*/
|
||||||
|
|
||||||
HID_EPIN_ADDR, /*bEndpointAddress: Endpoint Address (IN)*/
|
HID_EPIN_ADDR, /*bEndpointAddress: Endpoint Address (IN)*/
|
||||||
0x03, /*bmAttributes: Interrupt endpoint*/
|
0x03, /*bmAttributes: Interrupt endpoint*/
|
||||||
HID_EPIN_SIZE, /*wMaxPacketSize: 4 Byte max */
|
HID_EPIN_SIZE, /*wMaxPacketSize: 4 Byte max */
|
||||||
|
@ -216,61 +216,35 @@ __ALIGN_BEGIN static uint8_t USBD_HID_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_
|
||||||
|
|
||||||
__ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] __ALIGN_END =
|
__ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] __ALIGN_END =
|
||||||
{
|
{
|
||||||
0x05, 0x01,
|
0x05, 0x01, // USAGE_PAGE (Generic Desktop)
|
||||||
0x09, 0x02,
|
0x09, 0x05, // USAGE (Game Pad)
|
||||||
0xA1, 0x01,
|
0xa1, 0x01, // COLLECTION (Application)
|
||||||
0x09, 0x01,
|
0xa1, 0x00, // COLLECTION (Physical)
|
||||||
|
0x05, 0x01, // USAGE_PAGE (Generic Desktop)
|
||||||
0xA1, 0x00,
|
0x09, 0x30, // USAGE (X)
|
||||||
0x05, 0x09,
|
0x09, 0x31, // USAGE (Y)
|
||||||
0x19, 0x01,
|
0x09, 0x32, // USAGE (Z)
|
||||||
0x29, 0x03,
|
0x09, 0x33, // USAGE (Rx)
|
||||||
|
0x09, 0x35, // USAGE (Rz)
|
||||||
0x15, 0x00,
|
0x09, 0x34, // USAGE (Ry)
|
||||||
0x25, 0x01,
|
0x09, 0x40, // USAGE (Vx)
|
||||||
0x95, 0x03,
|
0x09, 0x38, // USAGE (Wheel)
|
||||||
0x75, 0x01,
|
0x15, 0x81, // LOGICAL_MINIMUM (-127)
|
||||||
|
0x25, 0x7f, // LOGICAL_MAXIMUM (127)
|
||||||
0x81, 0x02,
|
0x75, 0x08, // REPORT_SIZE (8)
|
||||||
0x95, 0x01,
|
0x95, 0x08, // REPORT_COUNT (8)
|
||||||
0x75, 0x05,
|
0x81, 0x02, // INPUT (Data,Var,Abs)
|
||||||
0x81, 0x01,
|
0xc0, // END_COLLECTION
|
||||||
|
0xc0 /* END_COLLECTION */
|
||||||
0x05, 0x01,
|
};
|
||||||
0x09, 0x30,
|
|
||||||
0x09, 0x31,
|
|
||||||
0x09, 0x38,
|
|
||||||
|
|
||||||
0x15, 0x81,
|
|
||||||
0x25, 0x7F,
|
|
||||||
0x75, 0x08,
|
|
||||||
0x95, 0x03,
|
|
||||||
|
|
||||||
0x81, 0x06,
|
|
||||||
0xC0, 0x09,
|
|
||||||
0x3c, 0x05,
|
|
||||||
0xff, 0x09,
|
|
||||||
|
|
||||||
0x01, 0x15,
|
|
||||||
0x00, 0x25,
|
|
||||||
0x01, 0x75,
|
|
||||||
0x01, 0x95,
|
|
||||||
|
|
||||||
0x02, 0xb1,
|
|
||||||
0x22, 0x75,
|
|
||||||
0x06, 0x95,
|
|
||||||
0x01, 0xb1,
|
|
||||||
|
|
||||||
0x01, 0xc0
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_HID_Private_Functions
|
/** @defgroup USBD_HID_Private_Functions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_HID_Init
|
* @brief USBD_HID_Init
|
||||||
|
@ -279,26 +253,27 @@ __ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] _
|
||||||
* @param cfgidx: Configuration index
|
* @param cfgidx: Configuration index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx)
|
uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
|
(void) cfgidx;
|
||||||
|
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
HID_EPIN_ADDR,
|
HID_EPIN_ADDR,
|
||||||
USBD_EP_TYPE_INTR,
|
USBD_EP_TYPE_INTR,
|
||||||
HID_EPIN_SIZE);
|
HID_EPIN_SIZE);
|
||||||
|
|
||||||
pdev->pClassData = USBD_malloc(sizeof (USBD_HID_HandleTypeDef));
|
pdev->pHID_ClassData = USBD_malloc(sizeof (USBD_HID_HandleTypeDef));
|
||||||
|
|
||||||
if(pdev->pClassData == NULL)
|
if(pdev->pHID_ClassData == NULL)
|
||||||
{
|
{
|
||||||
ret = 1;
|
ret = 1;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE;
|
((USBD_HID_HandleTypeDef *)pdev->pHID_ClassData)->state = HID_IDLE;
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
@ -310,20 +285,21 @@ static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
||||||
* @param cfgidx: Configuration index
|
* @param cfgidx: Configuration index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx)
|
uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
|
(void) cfgidx;
|
||||||
/* Close HID EPs */
|
/* Close HID EPs */
|
||||||
USBD_LL_CloseEP(pdev,
|
USBD_LL_CloseEP(pdev,
|
||||||
HID_EPIN_ADDR);
|
HID_EPIN_ADDR);
|
||||||
|
|
||||||
/* FRee allocated memory */
|
/* FRee allocated memory */
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pHID_ClassData != NULL)
|
||||||
{
|
{
|
||||||
USBD_free(pdev->pClassData);
|
USBD_free(pdev->pHID_ClassData);
|
||||||
pdev->pClassData = NULL;
|
pdev->pHID_ClassData = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -334,50 +310,50 @@ static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
* @param req: usb requests
|
* @param req: usb requests
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
||||||
USBD_SetupReqTypedef *req)
|
USBD_SetupReqTypedef *req)
|
||||||
{
|
{
|
||||||
uint16_t len = 0;
|
uint16_t len = 0;
|
||||||
uint8_t *pbuf = NULL;
|
uint8_t *pbuf = NULL;
|
||||||
USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*) pdev->pClassData;
|
USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*) pdev->pHID_ClassData;
|
||||||
|
|
||||||
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
||||||
{
|
{
|
||||||
case USB_REQ_TYPE_CLASS :
|
case USB_REQ_TYPE_CLASS :
|
||||||
switch (req->bRequest)
|
switch (req->bRequest)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
case HID_REQ_SET_PROTOCOL:
|
case HID_REQ_SET_PROTOCOL:
|
||||||
hhid->Protocol = (uint8_t)(req->wValue);
|
hhid->Protocol = (uint8_t)(req->wValue);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case HID_REQ_GET_PROTOCOL:
|
case HID_REQ_GET_PROTOCOL:
|
||||||
USBD_CtlSendData (pdev,
|
USBD_CtlSendData (pdev,
|
||||||
(uint8_t *)&hhid->Protocol,
|
(uint8_t *)&hhid->Protocol,
|
||||||
1);
|
1);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case HID_REQ_SET_IDLE:
|
case HID_REQ_SET_IDLE:
|
||||||
hhid->IdleState = (uint8_t)(req->wValue >> 8);
|
hhid->IdleState = (uint8_t)(req->wValue >> 8);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case HID_REQ_GET_IDLE:
|
case HID_REQ_GET_IDLE:
|
||||||
USBD_CtlSendData (pdev,
|
USBD_CtlSendData (pdev,
|
||||||
(uint8_t *)&hhid->IdleState,
|
(uint8_t *)&hhid->IdleState,
|
||||||
1);
|
1);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
USBD_CtlError (pdev, req);
|
USBD_CtlError (pdev, req);
|
||||||
return USBD_FAIL;
|
return USBD_FAIL;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_TYPE_STANDARD:
|
case USB_REQ_TYPE_STANDARD:
|
||||||
switch (req->bRequest)
|
switch (req->bRequest)
|
||||||
{
|
{
|
||||||
case USB_REQ_GET_DESCRIPTOR:
|
case USB_REQ_GET_DESCRIPTOR:
|
||||||
if( req->wValue >> 8 == HID_REPORT_DESC)
|
if( req->wValue >> 8 == HID_REPORT_DESC)
|
||||||
{
|
{
|
||||||
len = MIN(HID_MOUSE_REPORT_DESC_SIZE , req->wLength);
|
len = MIN(HID_MOUSE_REPORT_DESC_SIZE , req->wLength);
|
||||||
|
@ -385,22 +361,22 @@ static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
||||||
}
|
}
|
||||||
else if( req->wValue >> 8 == HID_DESCRIPTOR_TYPE)
|
else if( req->wValue >> 8 == HID_DESCRIPTOR_TYPE)
|
||||||
{
|
{
|
||||||
pbuf = USBD_HID_Desc;
|
pbuf = USBD_HID_Desc;
|
||||||
len = MIN(USB_HID_DESC_SIZ , req->wLength);
|
len = MIN(USB_HID_DESC_SIZ , req->wLength);
|
||||||
}
|
}
|
||||||
|
|
||||||
USBD_CtlSendData (pdev,
|
USBD_CtlSendData (pdev,
|
||||||
pbuf,
|
pbuf,
|
||||||
len);
|
len);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_GET_INTERFACE :
|
case USB_REQ_GET_INTERFACE :
|
||||||
USBD_CtlSendData (pdev,
|
USBD_CtlSendData (pdev,
|
||||||
(uint8_t *)&hhid->AltSetting,
|
(uint8_t *)&hhid->AltSetting,
|
||||||
1);
|
1);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_SET_INTERFACE :
|
case USB_REQ_SET_INTERFACE :
|
||||||
hhid->AltSetting = (uint8_t)(req->wValue);
|
hhid->AltSetting = (uint8_t)(req->wValue);
|
||||||
break;
|
break;
|
||||||
|
@ -410,25 +386,25 @@ static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_HID_SendReport
|
* @brief USBD_HID_SendReport
|
||||||
* Send HID Report
|
* Send HID Report
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @param buff: pointer to report
|
* @param buff: pointer to report
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t *report,
|
uint8_t *report,
|
||||||
uint16_t len)
|
uint16_t len)
|
||||||
{
|
{
|
||||||
USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*)pdev->pClassData;
|
USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*)pdev->pHID_ClassData;
|
||||||
|
|
||||||
if (pdev->dev_state == USBD_STATE_CONFIGURED )
|
if (pdev->dev_state == USBD_STATE_CONFIGURED )
|
||||||
{
|
{
|
||||||
if(hhid->state == HID_IDLE)
|
if(hhid->state == HID_IDLE)
|
||||||
{
|
{
|
||||||
hhid->state = HID_BUSY;
|
hhid->state = HID_BUSY;
|
||||||
USBD_LL_Transmit (pdev,
|
USBD_LL_Transmit (pdev,
|
||||||
HID_EPIN_ADDR,
|
HID_EPIN_ADDR,
|
||||||
report,
|
report,
|
||||||
len);
|
len);
|
||||||
}
|
}
|
||||||
|
@ -437,7 +413,7 @@ uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_HID_GetPollingInterval
|
* @brief USBD_HID_GetPollingInterval
|
||||||
* return polling interval from endpoint descriptor
|
* return polling interval from endpoint descriptor
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval polling interval
|
* @retval polling interval
|
||||||
|
@ -449,23 +425,23 @@ uint32_t USBD_HID_GetPollingInterval (USBD_HandleTypeDef *pdev)
|
||||||
/* HIGH-speed endpoints */
|
/* HIGH-speed endpoints */
|
||||||
if(pdev->dev_speed == USBD_SPEED_HIGH)
|
if(pdev->dev_speed == USBD_SPEED_HIGH)
|
||||||
{
|
{
|
||||||
/* Sets the data transfer polling interval for high speed transfers.
|
/* Sets the data transfer polling interval for high speed transfers.
|
||||||
Values between 1..16 are allowed. Values correspond to interval
|
Values between 1..16 are allowed. Values correspond to interval
|
||||||
of 2 ^ (bInterval-1). This option (8 ms, corresponds to HID_HS_BINTERVAL */
|
of 2 ^ (bInterval-1). This option (8 ms, corresponds to HID_HS_BINTERVAL */
|
||||||
polling_interval = (((1 <<(HID_HS_BINTERVAL - 1)))/8);
|
polling_interval = (((1 <<(HID_HS_BINTERVAL - 1)))/8);
|
||||||
}
|
}
|
||||||
else /* LOW and FULL-speed endpoints */
|
else /* LOW and FULL-speed endpoints */
|
||||||
{
|
{
|
||||||
/* Sets the data transfer polling interval for low and full
|
/* Sets the data transfer polling interval for low and full
|
||||||
speed transfers */
|
speed transfers */
|
||||||
polling_interval = HID_FS_BINTERVAL;
|
polling_interval = HID_FS_BINTERVAL;
|
||||||
}
|
}
|
||||||
|
|
||||||
return ((uint32_t)(polling_interval));
|
return ((uint32_t)(polling_interval));
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_HID_GetCfgDesc
|
* @brief USBD_HID_GetCfgDesc
|
||||||
* return configuration descriptor
|
* return configuration descriptor
|
||||||
* @param speed : current device speed
|
* @param speed : current device speed
|
||||||
* @param length : pointer data length
|
* @param length : pointer data length
|
||||||
|
@ -485,19 +461,19 @@ static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length)
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum)
|
uint8_t epnum)
|
||||||
{
|
{
|
||||||
|
(void) epnum;
|
||||||
/* Ensure that the FIFO is empty before a new transfer, this condition could
|
/* Ensure that the FIFO is empty before a new transfer, this condition could
|
||||||
be caused by a new transfer before the end of the previous transfer */
|
be caused by a new transfer before the end of the previous transfer */
|
||||||
((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE;
|
((USBD_HID_HandleTypeDef *)pdev->pHID_ClassData)->state = HID_IDLE;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief DeviceQualifierDescriptor
|
* @brief DeviceQualifierDescriptor
|
||||||
* return Device Qualifier descriptor
|
* return Device Qualifier descriptor
|
||||||
* @param length : pointer data length
|
* @param length : pointer data length
|
||||||
* @retval pointer to descriptor buffer
|
* @retval pointer to descriptor buffer
|
||||||
|
@ -510,16 +486,16 @@ static uint8_t *USBD_HID_GetDeviceQualifierDesc (uint16_t *length)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -7,17 +7,17 @@
|
||||||
* @brief This file provides all the MSC core functions.
|
* @brief This file provides all the MSC core functions.
|
||||||
*
|
*
|
||||||
* @verbatim
|
* @verbatim
|
||||||
*
|
*
|
||||||
* ===================================================================
|
* ===================================================================
|
||||||
* MSC Class Description
|
* MSC Class Description
|
||||||
* ===================================================================
|
* ===================================================================
|
||||||
* This module manages the MSC class V1.0 following the "Universal
|
* This module manages the MSC class V1.0 following the "Universal
|
||||||
* Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0
|
* Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0
|
||||||
* Sep. 31, 1999".
|
* Sep. 31, 1999".
|
||||||
* This driver implements the following aspects of the specification:
|
* This driver implements the following aspects of the specification:
|
||||||
* - Bulk-Only Transport protocol
|
* - Bulk-Only Transport protocol
|
||||||
* - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3))
|
* - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3))
|
||||||
*
|
*
|
||||||
* @endverbatim
|
* @endverbatim
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
|
@ -31,14 +31,14 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
#include "usbd_msc.h"
|
#include "usbd_msc.h"
|
||||||
|
@ -49,53 +49,53 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_CORE
|
/** @defgroup MSC_CORE
|
||||||
* @brief Mass storage core module
|
* @brief Mass storage core module
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup MSC_CORE_Private_TypesDefinitions
|
/** @defgroup MSC_CORE_Private_TypesDefinitions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_CORE_Private_Defines
|
/** @defgroup MSC_CORE_Private_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_CORE_Private_Macros
|
/** @defgroup MSC_CORE_Private_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_CORE_Private_FunctionPrototypes
|
/** @defgroup MSC_CORE_Private_FunctionPrototypes
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx);
|
uint8_t cfgidx);
|
||||||
|
|
||||||
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx);
|
uint8_t cfgidx);
|
||||||
|
|
||||||
uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev,
|
||||||
USBD_SetupReqTypedef *req);
|
USBD_SetupReqTypedef *req);
|
||||||
|
|
||||||
uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum);
|
uint8_t epnum);
|
||||||
|
|
||||||
|
|
||||||
uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum);
|
uint8_t epnum);
|
||||||
|
|
||||||
uint8_t *USBD_MSC_GetHSCfgDesc (uint16_t *length);
|
uint8_t *USBD_MSC_GetHSCfgDesc (uint16_t *length);
|
||||||
|
@ -109,28 +109,28 @@ uint8_t *USBD_MSC_GetDeviceQualifierDescriptor (uint16_t *length);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_CORE_Private_Variables
|
/** @defgroup MSC_CORE_Private_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
USBD_ClassTypeDef USBD_MSC =
|
USBD_ClassTypeDef USBD_MSC =
|
||||||
{
|
{
|
||||||
USBD_MSC_Init,
|
USBD_MSC_Init,
|
||||||
USBD_MSC_DeInit,
|
USBD_MSC_DeInit,
|
||||||
USBD_MSC_Setup,
|
USBD_MSC_Setup,
|
||||||
NULL, /*EP0_TxSent*/
|
NULL, /*EP0_TxSent*/
|
||||||
NULL, /*EP0_RxReady*/
|
NULL, /*EP0_RxReady*/
|
||||||
USBD_MSC_DataIn,
|
USBD_MSC_DataIn,
|
||||||
USBD_MSC_DataOut,
|
USBD_MSC_DataOut,
|
||||||
NULL, /*SOF */
|
NULL, /*SOF */
|
||||||
NULL,
|
NULL,
|
||||||
NULL,
|
NULL,
|
||||||
USBD_MSC_GetHSCfgDesc,
|
USBD_MSC_GetHSCfgDesc,
|
||||||
USBD_MSC_GetFSCfgDesc,
|
USBD_MSC_GetFSCfgDesc,
|
||||||
USBD_MSC_GetOtherSpeedCfgDesc,
|
USBD_MSC_GetOtherSpeedCfgDesc,
|
||||||
USBD_MSC_GetDeviceQualifierDescriptor,
|
USBD_MSC_GetDeviceQualifierDescriptor,
|
||||||
};
|
};
|
||||||
|
@ -139,18 +139,18 @@ USBD_ClassTypeDef USBD_MSC =
|
||||||
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
|
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
|
||||||
__ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
__ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
{
|
{
|
||||||
|
|
||||||
0x09, /* bLength: Configuation Descriptor size */
|
0x09, /* bLength: Configuation Descriptor size */
|
||||||
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
|
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
|
||||||
USB_MSC_CONFIG_DESC_SIZ,
|
USB_MSC_CONFIG_DESC_SIZ,
|
||||||
|
|
||||||
0x00,
|
0x00,
|
||||||
0x01, /* bNumInterfaces: 1 interface */
|
0x01, /* bNumInterfaces: 1 interface */
|
||||||
0x01, /* bConfigurationValue: */
|
0x01, /* bConfigurationValue: */
|
||||||
0x04, /* iConfiguration: */
|
0x04, /* iConfiguration: */
|
||||||
0xC0, /* bmAttributes: */
|
0xC0, /* bmAttributes: */
|
||||||
0x32, /* MaxPower 100 mA */
|
0x32, /* MaxPower 100 mA */
|
||||||
|
|
||||||
/******************** Mass Storage interface ********************/
|
/******************** Mass Storage interface ********************/
|
||||||
0x09, /* bLength: Interface Descriptor size */
|
0x09, /* bLength: Interface Descriptor size */
|
||||||
0x04, /* bDescriptorType: */
|
0x04, /* bDescriptorType: */
|
||||||
|
@ -169,7 +169,7 @@ __ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
LOBYTE(MSC_MAX_HS_PACKET),
|
LOBYTE(MSC_MAX_HS_PACKET),
|
||||||
HIBYTE(MSC_MAX_HS_PACKET),
|
HIBYTE(MSC_MAX_HS_PACKET),
|
||||||
0x00, /*Polling interval in milliseconds */
|
0x00, /*Polling interval in milliseconds */
|
||||||
|
|
||||||
0x07, /*Endpoint descriptor length = 7 */
|
0x07, /*Endpoint descriptor length = 7 */
|
||||||
0x05, /*Endpoint descriptor type */
|
0x05, /*Endpoint descriptor type */
|
||||||
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
|
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
|
||||||
|
@ -183,18 +183,18 @@ __ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
|
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
|
||||||
uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
{
|
{
|
||||||
|
|
||||||
0x09, /* bLength: Configuation Descriptor size */
|
0x09, /* bLength: Configuation Descriptor size */
|
||||||
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
|
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
|
||||||
USB_MSC_CONFIG_DESC_SIZ,
|
USB_MSC_CONFIG_DESC_SIZ,
|
||||||
|
|
||||||
0x00,
|
0x00,
|
||||||
0x01, /* bNumInterfaces: 1 interface */
|
0x01, /* bNumInterfaces: 1 interface */
|
||||||
0x01, /* bConfigurationValue: */
|
0x01, /* bConfigurationValue: */
|
||||||
0x04, /* iConfiguration: */
|
0x04, /* iConfiguration: */
|
||||||
0xC0, /* bmAttributes: */
|
0xC0, /* bmAttributes: */
|
||||||
0x32, /* MaxPower 100 mA */
|
0x32, /* MaxPower 100 mA */
|
||||||
|
|
||||||
/******************** Mass Storage interface ********************/
|
/******************** Mass Storage interface ********************/
|
||||||
0x09, /* bLength: Interface Descriptor size */
|
0x09, /* bLength: Interface Descriptor size */
|
||||||
0x04, /* bDescriptorType: */
|
0x04, /* bDescriptorType: */
|
||||||
|
@ -213,7 +213,7 @@ uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
LOBYTE(MSC_MAX_FS_PACKET),
|
LOBYTE(MSC_MAX_FS_PACKET),
|
||||||
HIBYTE(MSC_MAX_FS_PACKET),
|
HIBYTE(MSC_MAX_FS_PACKET),
|
||||||
0x00, /*Polling interval in milliseconds */
|
0x00, /*Polling interval in milliseconds */
|
||||||
|
|
||||||
0x07, /*Endpoint descriptor length = 7 */
|
0x07, /*Endpoint descriptor length = 7 */
|
||||||
0x05, /*Endpoint descriptor type */
|
0x05, /*Endpoint descriptor type */
|
||||||
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
|
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
|
||||||
|
@ -225,18 +225,18 @@ uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
|
|
||||||
__ALIGN_BEGIN uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
__ALIGN_BEGIN uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
|
||||||
{
|
{
|
||||||
|
|
||||||
0x09, /* bLength: Configuation Descriptor size */
|
0x09, /* bLength: Configuation Descriptor size */
|
||||||
USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
|
USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
|
||||||
USB_MSC_CONFIG_DESC_SIZ,
|
USB_MSC_CONFIG_DESC_SIZ,
|
||||||
|
|
||||||
0x00,
|
0x00,
|
||||||
0x01, /* bNumInterfaces: 1 interface */
|
0x01, /* bNumInterfaces: 1 interface */
|
||||||
0x01, /* bConfigurationValue: */
|
0x01, /* bConfigurationValue: */
|
||||||
0x04, /* iConfiguration: */
|
0x04, /* iConfiguration: */
|
||||||
0xC0, /* bmAttributes: */
|
0xC0, /* bmAttributes: */
|
||||||
0x32, /* MaxPower 100 mA */
|
0x32, /* MaxPower 100 mA */
|
||||||
|
|
||||||
/******************** Mass Storage interface ********************/
|
/******************** Mass Storage interface ********************/
|
||||||
0x09, /* bLength: Interface Descriptor size */
|
0x09, /* bLength: Interface Descriptor size */
|
||||||
0x04, /* bDescriptorType: */
|
0x04, /* bDescriptorType: */
|
||||||
|
@ -255,7 +255,7 @@ __ALIGN_BEGIN uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __AL
|
||||||
0x40,
|
0x40,
|
||||||
0x00,
|
0x00,
|
||||||
0x00, /*Polling interval in milliseconds */
|
0x00, /*Polling interval in milliseconds */
|
||||||
|
|
||||||
0x07, /*Endpoint descriptor length = 7 */
|
0x07, /*Endpoint descriptor length = 7 */
|
||||||
0x05, /*Endpoint descriptor type */
|
0x05, /*Endpoint descriptor type */
|
||||||
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
|
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
|
||||||
|
@ -281,12 +281,12 @@ __ALIGN_BEGIN uint8_t USBD_MSC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]
|
||||||
};
|
};
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_CORE_Private_Functions
|
/** @defgroup MSC_CORE_Private_Functions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_MSC_Init
|
* @brief USBD_MSC_Init
|
||||||
|
@ -295,24 +295,25 @@ __ALIGN_BEGIN uint8_t USBD_MSC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]
|
||||||
* @param cfgidx: configuration index
|
* @param cfgidx: configuration index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx)
|
uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
int16_t ret = 0;
|
int16_t ret = 0;
|
||||||
|
(void)cfgidx;
|
||||||
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
|
||||||
|
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
||||||
{
|
{
|
||||||
/* Open EP OUT */
|
/* Open EP OUT */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_HS_PACKET);
|
MSC_MAX_HS_PACKET);
|
||||||
|
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPIN_ADDR,
|
MSC_EPIN_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_HS_PACKET);
|
MSC_MAX_HS_PACKET);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -321,26 +322,26 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_FS_PACKET);
|
MSC_MAX_FS_PACKET);
|
||||||
|
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPIN_ADDR,
|
MSC_EPIN_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_FS_PACKET);
|
MSC_MAX_FS_PACKET);
|
||||||
}
|
}
|
||||||
pdev->pClassData = USBD_malloc(sizeof (USBD_MSC_BOT_HandleTypeDef));
|
pdev->pMSC_ClassData = USBD_malloc(sizeof (USBD_MSC_BOT_HandleTypeDef));
|
||||||
|
|
||||||
if(pdev->pClassData == NULL)
|
if(pdev->pMSC_ClassData == NULL)
|
||||||
{
|
{
|
||||||
ret = 1;
|
ret = 1;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
/* Init the BOT layer */
|
/* Init the BOT layer */
|
||||||
MSC_BOT_Init(pdev);
|
MSC_BOT_Init(pdev);
|
||||||
ret = 0;
|
ret = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -351,26 +352,28 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
||||||
* @param cfgidx: configuration index
|
* @param cfgidx: configuration index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx)
|
uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
|
(void) cfgidx;
|
||||||
|
|
||||||
/* Close MSC EPs */
|
/* Close MSC EPs */
|
||||||
USBD_LL_CloseEP(pdev,
|
USBD_LL_CloseEP(pdev,
|
||||||
MSC_EPOUT_ADDR);
|
MSC_EPOUT_ADDR);
|
||||||
|
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_CloseEP(pdev,
|
USBD_LL_CloseEP(pdev,
|
||||||
MSC_EPIN_ADDR);
|
MSC_EPIN_ADDR);
|
||||||
|
|
||||||
|
|
||||||
/* De-Init the BOT layer */
|
/* De-Init the BOT layer */
|
||||||
MSC_BOT_DeInit(pdev);
|
MSC_BOT_DeInit(pdev);
|
||||||
|
|
||||||
/* Free MSC Class Resources */
|
/* Free MSC Class Resources */
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pMSC_ClassData != NULL)
|
||||||
{
|
{
|
||||||
USBD_free(pdev->pClassData);
|
USBD_free(pdev->pMSC_ClassData);
|
||||||
pdev->pClassData = NULL;
|
pdev->pMSC_ClassData = NULL;
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -383,8 +386,8 @@ uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
|
||||||
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
@ -394,11 +397,11 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
||||||
{
|
{
|
||||||
case BOT_GET_MAX_LUN :
|
case BOT_GET_MAX_LUN :
|
||||||
|
|
||||||
if((req->wValue == 0) &&
|
if((req->wValue == 0) &&
|
||||||
(req->wLength == 1) &&
|
(req->wLength == 1) &&
|
||||||
((req->bmRequest & 0x80) == 0x80))
|
((req->bmRequest & 0x80) == 0x80))
|
||||||
{
|
{
|
||||||
hmsc->max_lun = ((USBD_StorageTypeDef *)pdev->pUserData)->GetMaxLun();
|
hmsc->max_lun = ((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetMaxLun();
|
||||||
USBD_CtlSendData (pdev,
|
USBD_CtlSendData (pdev,
|
||||||
(uint8_t *)&hmsc->max_lun,
|
(uint8_t *)&hmsc->max_lun,
|
||||||
1);
|
1);
|
||||||
|
@ -406,27 +409,27 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
USBD_CtlError(pdev , req);
|
USBD_CtlError(pdev , req);
|
||||||
return USBD_FAIL;
|
return USBD_FAIL;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BOT_RESET :
|
case BOT_RESET :
|
||||||
if((req->wValue == 0) &&
|
if((req->wValue == 0) &&
|
||||||
(req->wLength == 0) &&
|
(req->wLength == 0) &&
|
||||||
((req->bmRequest & 0x80) != 0x80))
|
((req->bmRequest & 0x80) != 0x80))
|
||||||
{
|
{
|
||||||
MSC_BOT_Reset(pdev);
|
MSC_BOT_Reset(pdev);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
USBD_CtlError(pdev , req);
|
USBD_CtlError(pdev , req);
|
||||||
return USBD_FAIL;
|
return USBD_FAIL;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
USBD_CtlError(pdev , req);
|
USBD_CtlError(pdev , req);
|
||||||
return USBD_FAIL;
|
return USBD_FAIL;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
/* Interface & Endpoint request */
|
/* Interface & Endpoint request */
|
||||||
|
@ -438,64 +441,64 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
||||||
(uint8_t *)&hmsc->interface,
|
(uint8_t *)&hmsc->interface,
|
||||||
1);
|
1);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_SET_INTERFACE :
|
case USB_REQ_SET_INTERFACE :
|
||||||
hmsc->interface = (uint8_t)(req->wValue);
|
hmsc->interface = (uint8_t)(req->wValue);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_CLEAR_FEATURE:
|
case USB_REQ_CLEAR_FEATURE:
|
||||||
|
|
||||||
/* Flush the FIFO and Clear the stall status */
|
/* Flush the FIFO and Clear the stall status */
|
||||||
USBD_LL_FlushEP(pdev, (uint8_t)req->wIndex);
|
USBD_LL_FlushEP(pdev, (uint8_t)req->wIndex);
|
||||||
|
|
||||||
/* Reactivate the EP */
|
/* Reactivate the EP */
|
||||||
USBD_LL_CloseEP (pdev , (uint8_t)req->wIndex);
|
USBD_LL_CloseEP (pdev , (uint8_t)req->wIndex);
|
||||||
if((((uint8_t)req->wIndex) & 0x80) == 0x80)
|
if((((uint8_t)req->wIndex) & 0x80) == 0x80)
|
||||||
{
|
{
|
||||||
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
||||||
{
|
{
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPIN_ADDR,
|
MSC_EPIN_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_HS_PACKET);
|
MSC_MAX_HS_PACKET);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPIN_ADDR,
|
MSC_EPIN_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_FS_PACKET);
|
MSC_MAX_FS_PACKET);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
||||||
{
|
{
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_HS_PACKET);
|
MSC_MAX_HS_PACKET);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
USBD_EP_TYPE_BULK,
|
USBD_EP_TYPE_BULK,
|
||||||
MSC_MAX_FS_PACKET);
|
MSC_MAX_FS_PACKET);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Handle BOT error */
|
/* Handle BOT error */
|
||||||
MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex);
|
MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -509,7 +512,7 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum)
|
uint8_t epnum)
|
||||||
{
|
{
|
||||||
MSC_BOT_DataIn(pdev , epnum);
|
MSC_BOT_DataIn(pdev , epnum);
|
||||||
|
@ -523,7 +526,7 @@ uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum)
|
uint8_t epnum)
|
||||||
{
|
{
|
||||||
MSC_BOT_DataOut(pdev , epnum);
|
MSC_BOT_DataOut(pdev , epnum);
|
||||||
|
@ -531,7 +534,7 @@ uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_MSC_GetHSCfgDesc
|
* @brief USBD_MSC_GetHSCfgDesc
|
||||||
* return configuration descriptor
|
* return configuration descriptor
|
||||||
* @param length : pointer data length
|
* @param length : pointer data length
|
||||||
* @retval pointer to descriptor buffer
|
* @retval pointer to descriptor buffer
|
||||||
|
@ -543,7 +546,7 @@ uint8_t *USBD_MSC_GetHSCfgDesc (uint16_t *length)
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_MSC_GetFSCfgDesc
|
* @brief USBD_MSC_GetFSCfgDesc
|
||||||
* return configuration descriptor
|
* return configuration descriptor
|
||||||
* @param length : pointer data length
|
* @param length : pointer data length
|
||||||
* @retval pointer to descriptor buffer
|
* @retval pointer to descriptor buffer
|
||||||
|
@ -555,7 +558,7 @@ uint8_t *USBD_MSC_GetFSCfgDesc (uint16_t *length)
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_MSC_GetOtherSpeedCfgDesc
|
* @brief USBD_MSC_GetOtherSpeedCfgDesc
|
||||||
* return other speed configuration descriptor
|
* return other speed configuration descriptor
|
||||||
* @param length : pointer data length
|
* @param length : pointer data length
|
||||||
* @retval pointer to descriptor buffer
|
* @retval pointer to descriptor buffer
|
||||||
|
@ -566,7 +569,7 @@ uint8_t *USBD_MSC_GetOtherSpeedCfgDesc (uint16_t *length)
|
||||||
return USBD_MSC_OtherSpeedCfgDesc;
|
return USBD_MSC_OtherSpeedCfgDesc;
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
* @brief DeviceQualifierDescriptor
|
* @brief DeviceQualifierDescriptor
|
||||||
* return Device Qualifier descriptor
|
* return Device Qualifier descriptor
|
||||||
* @param length : pointer data length
|
* @param length : pointer data length
|
||||||
* @retval pointer to descriptor buffer
|
* @retval pointer to descriptor buffer
|
||||||
|
@ -582,28 +585,28 @@ uint8_t *USBD_MSC_GetDeviceQualifierDescriptor (uint16_t *length)
|
||||||
* @param fops: storage callback
|
* @param fops: storage callback
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
uint8_t USBD_MSC_RegisterStorage (USBD_HandleTypeDef *pdev,
|
uint8_t USBD_MSC_RegisterStorage (USBD_HandleTypeDef *pdev,
|
||||||
USBD_StorageTypeDef *fops)
|
USBD_StorageTypeDef *fops)
|
||||||
{
|
{
|
||||||
if(fops != NULL)
|
if(fops != NULL)
|
||||||
{
|
{
|
||||||
pdev->pUserData= fops;
|
pdev->pMSC_UserData= fops;
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -16,14 +16,14 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
#include "usbd_msc_bot.h"
|
#include "usbd_msc_bot.h"
|
||||||
|
@ -36,63 +36,63 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_BOT
|
/** @defgroup MSC_BOT
|
||||||
* @brief BOT protocol module
|
* @brief BOT protocol module
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup MSC_BOT_Private_TypesDefinitions
|
/** @defgroup MSC_BOT_Private_TypesDefinitions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_BOT_Private_Defines
|
/** @defgroup MSC_BOT_Private_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_BOT_Private_Macros
|
/** @defgroup MSC_BOT_Private_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_BOT_Private_Variables
|
/** @defgroup MSC_BOT_Private_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_BOT_Private_FunctionPrototypes
|
/** @defgroup MSC_BOT_Private_FunctionPrototypes
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev);
|
static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev);
|
||||||
|
|
||||||
static void MSC_BOT_SendData (USBD_HandleTypeDef *pdev,
|
static void MSC_BOT_SendData (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t* pbuf,
|
uint8_t* pbuf,
|
||||||
uint16_t len);
|
uint16_t len);
|
||||||
|
|
||||||
static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev);
|
static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev);
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_BOT_Private_Functions
|
/** @defgroup MSC_BOT_Private_Functions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -104,24 +104,24 @@ static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev);
|
||||||
*/
|
*/
|
||||||
void MSC_BOT_Init (USBD_HandleTypeDef *pdev)
|
void MSC_BOT_Init (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
hmsc->bot_state = USBD_BOT_IDLE;
|
hmsc->bot_state = USBD_BOT_IDLE;
|
||||||
hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
|
hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
|
||||||
|
|
||||||
hmsc->scsi_sense_tail = 0;
|
hmsc->scsi_sense_tail = 0;
|
||||||
hmsc->scsi_sense_head = 0;
|
hmsc->scsi_sense_head = 0;
|
||||||
|
|
||||||
((USBD_StorageTypeDef *)pdev->pUserData)->Init(0);
|
((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Init(0);
|
||||||
|
|
||||||
USBD_LL_FlushEP(pdev, MSC_EPOUT_ADDR);
|
USBD_LL_FlushEP(pdev, MSC_EPOUT_ADDR);
|
||||||
USBD_LL_FlushEP(pdev, MSC_EPIN_ADDR);
|
USBD_LL_FlushEP(pdev, MSC_EPIN_ADDR);
|
||||||
|
|
||||||
/* Prapare EP to Receive First BOT Cmd */
|
/* Prapare EP to Receive First BOT Cmd */
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
(uint8_t *)&hmsc->cbw,
|
(uint8_t *)&hmsc->cbw,
|
||||||
USBD_BOT_CBW_LENGTH);
|
USBD_BOT_CBW_LENGTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -132,16 +132,16 @@ void MSC_BOT_Init (USBD_HandleTypeDef *pdev)
|
||||||
*/
|
*/
|
||||||
void MSC_BOT_Reset (USBD_HandleTypeDef *pdev)
|
void MSC_BOT_Reset (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
hmsc->bot_state = USBD_BOT_IDLE;
|
hmsc->bot_state = USBD_BOT_IDLE;
|
||||||
hmsc->bot_status = USBD_BOT_STATUS_RECOVERY;
|
hmsc->bot_status = USBD_BOT_STATUS_RECOVERY;
|
||||||
|
|
||||||
/* Prapare EP to Receive First BOT Cmd */
|
/* Prapare EP to Receive First BOT Cmd */
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
(uint8_t *)&hmsc->cbw,
|
(uint8_t *)&hmsc->cbw,
|
||||||
USBD_BOT_CBW_LENGTH);
|
USBD_BOT_CBW_LENGTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -152,7 +152,7 @@ void MSC_BOT_Reset (USBD_HandleTypeDef *pdev)
|
||||||
*/
|
*/
|
||||||
void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev)
|
void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
hmsc->bot_state = USBD_BOT_IDLE;
|
hmsc->bot_state = USBD_BOT_IDLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -163,11 +163,12 @@ void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev)
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
|
void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum)
|
uint8_t epnum)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) epnum;
|
||||||
|
|
||||||
switch (hmsc->bot_state)
|
switch (hmsc->bot_state)
|
||||||
{
|
{
|
||||||
case USBD_BOT_DATA_IN:
|
case USBD_BOT_DATA_IN:
|
||||||
|
@ -178,13 +179,13 @@ void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED);
|
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USBD_BOT_SEND_DATA:
|
case USBD_BOT_SEND_DATA:
|
||||||
case USBD_BOT_LAST_DATA_IN:
|
case USBD_BOT_LAST_DATA_IN:
|
||||||
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED);
|
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -196,19 +197,20 @@ void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
|
void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t epnum)
|
uint8_t epnum)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) epnum;
|
||||||
|
|
||||||
switch (hmsc->bot_state)
|
switch (hmsc->bot_state)
|
||||||
{
|
{
|
||||||
case USBD_BOT_IDLE:
|
case USBD_BOT_IDLE:
|
||||||
MSC_BOT_CBW_Decode(pdev);
|
MSC_BOT_CBW_Decode(pdev);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USBD_BOT_DATA_OUT:
|
case USBD_BOT_DATA_OUT:
|
||||||
|
|
||||||
if(SCSI_ProcessCmd(pdev,
|
if(SCSI_ProcessCmd(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
&hmsc->cbw.CB[0]) < 0)
|
&hmsc->cbw.CB[0]) < 0)
|
||||||
|
@ -217,7 +219,7 @@ void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -225,32 +227,32 @@ void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief MSC_BOT_CBW_Decode
|
* @brief MSC_BOT_CBW_Decode
|
||||||
* Decode the CBW command and set the BOT state machine accordingly
|
* Decode the CBW command and set the BOT state machine accordingly
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
|
static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
hmsc->csw.dTag = hmsc->cbw.dTag;
|
hmsc->csw.dTag = hmsc->cbw.dTag;
|
||||||
hmsc->csw.dDataResidue = hmsc->cbw.dDataLength;
|
hmsc->csw.dDataResidue = hmsc->cbw.dDataLength;
|
||||||
|
|
||||||
if ((USBD_LL_GetRxDataSize (pdev ,MSC_EPOUT_ADDR) != USBD_BOT_CBW_LENGTH) ||
|
if ((USBD_LL_GetRxDataSize (pdev ,MSC_EPOUT_ADDR) != USBD_BOT_CBW_LENGTH) ||
|
||||||
(hmsc->cbw.dSignature != USBD_BOT_CBW_SIGNATURE)||
|
(hmsc->cbw.dSignature != USBD_BOT_CBW_SIGNATURE)||
|
||||||
(hmsc->cbw.bLUN > 1) ||
|
(hmsc->cbw.bLUN > 1) ||
|
||||||
(hmsc->cbw.bCBLength < 1) ||
|
(hmsc->cbw.bCBLength < 1) ||
|
||||||
(hmsc->cbw.bCBLength > 16))
|
(hmsc->cbw.bCBLength > 16))
|
||||||
{
|
{
|
||||||
|
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
|
|
||||||
hmsc->bot_status = USBD_BOT_STATUS_ERROR;
|
hmsc->bot_status = USBD_BOT_STATUS_ERROR;
|
||||||
MSC_BOT_Abort(pdev);
|
MSC_BOT_Abort(pdev);
|
||||||
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -261,7 +263,7 @@ static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
|
||||||
if(hmsc->bot_state == USBD_BOT_NO_DATA)
|
if(hmsc->bot_state == USBD_BOT_NO_DATA)
|
||||||
{
|
{
|
||||||
MSC_BOT_SendCSW (pdev,
|
MSC_BOT_SendCSW (pdev,
|
||||||
USBD_CSW_CMD_FAILED);
|
USBD_CSW_CMD_FAILED);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -269,17 +271,17 @@ static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/*Burst xfer handled internally*/
|
/*Burst xfer handled internally*/
|
||||||
else if ((hmsc->bot_state != USBD_BOT_DATA_IN) &&
|
else if ((hmsc->bot_state != USBD_BOT_DATA_IN) &&
|
||||||
(hmsc->bot_state != USBD_BOT_DATA_OUT) &&
|
(hmsc->bot_state != USBD_BOT_DATA_OUT) &&
|
||||||
(hmsc->bot_state != USBD_BOT_LAST_DATA_IN))
|
(hmsc->bot_state != USBD_BOT_LAST_DATA_IN))
|
||||||
{
|
{
|
||||||
if (hmsc->bot_data_length > 0)
|
if (hmsc->bot_data_length > 0)
|
||||||
{
|
{
|
||||||
MSC_BOT_SendData(pdev,
|
MSC_BOT_SendData(pdev,
|
||||||
hmsc->bot_data,
|
hmsc->bot_data,
|
||||||
hmsc->bot_data_length);
|
hmsc->bot_data_length);
|
||||||
}
|
}
|
||||||
else if (hmsc->bot_data_length == 0)
|
else if (hmsc->bot_data_length == 0)
|
||||||
{
|
{
|
||||||
MSC_BOT_SendCSW (pdev,
|
MSC_BOT_SendCSW (pdev,
|
||||||
USBD_CSW_CMD_PASSED);
|
USBD_CSW_CMD_PASSED);
|
||||||
|
@ -297,17 +299,17 @@ static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
|
static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
|
||||||
uint8_t* buf,
|
uint8_t* buf,
|
||||||
uint16_t len)
|
uint16_t len)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
len = MIN (hmsc->cbw.dDataLength, len);
|
len = MIN (hmsc->cbw.dDataLength, len);
|
||||||
hmsc->csw.dDataResidue -= len;
|
hmsc->csw.dDataResidue -= len;
|
||||||
hmsc->csw.bStatus = USBD_CSW_CMD_PASSED;
|
hmsc->csw.bStatus = USBD_CSW_CMD_PASSED;
|
||||||
hmsc->bot_state = USBD_BOT_SEND_DATA;
|
hmsc->bot_state = USBD_BOT_SEND_DATA;
|
||||||
|
|
||||||
USBD_LL_Transmit (pdev, MSC_EPIN_ADDR, buf, len);
|
USBD_LL_Transmit (pdev, MSC_EPIN_ADDR, buf, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -320,23 +322,23 @@ static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
|
||||||
void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev,
|
void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t CSW_Status)
|
uint8_t CSW_Status)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
hmsc->csw.dSignature = USBD_BOT_CSW_SIGNATURE;
|
hmsc->csw.dSignature = USBD_BOT_CSW_SIGNATURE;
|
||||||
hmsc->csw.bStatus = CSW_Status;
|
hmsc->csw.bStatus = CSW_Status;
|
||||||
hmsc->bot_state = USBD_BOT_IDLE;
|
hmsc->bot_state = USBD_BOT_IDLE;
|
||||||
|
|
||||||
USBD_LL_Transmit (pdev,
|
USBD_LL_Transmit (pdev,
|
||||||
MSC_EPIN_ADDR,
|
MSC_EPIN_ADDR,
|
||||||
(uint8_t *)&hmsc->csw,
|
(uint8_t *)&hmsc->csw,
|
||||||
USBD_BOT_CSW_LENGTH);
|
USBD_BOT_CSW_LENGTH);
|
||||||
|
|
||||||
/* Prepare EP to Receive next Cmd */
|
/* Prepare EP to Receive next Cmd */
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
(uint8_t *)&hmsc->cbw,
|
(uint8_t *)&hmsc->cbw,
|
||||||
USBD_BOT_CBW_LENGTH);
|
USBD_BOT_CBW_LENGTH);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -348,22 +350,22 @@ void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev,
|
||||||
|
|
||||||
static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev)
|
static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if ((hmsc->cbw.bmFlags == 0) &&
|
if ((hmsc->cbw.bmFlags == 0) &&
|
||||||
(hmsc->cbw.dDataLength != 0) &&
|
(hmsc->cbw.dDataLength != 0) &&
|
||||||
(hmsc->bot_status == USBD_BOT_STATUS_NORMAL) )
|
(hmsc->bot_status == USBD_BOT_STATUS_NORMAL) )
|
||||||
{
|
{
|
||||||
USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR );
|
USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR );
|
||||||
}
|
}
|
||||||
USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
|
USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
|
||||||
|
|
||||||
if(hmsc->bot_status == USBD_BOT_STATUS_ERROR)
|
if(hmsc->bot_status == USBD_BOT_STATUS_ERROR)
|
||||||
{
|
{
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
(uint8_t *)&hmsc->cbw,
|
(uint8_t *)&hmsc->cbw,
|
||||||
USBD_BOT_CBW_LENGTH);
|
USBD_BOT_CBW_LENGTH);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -377,31 +379,31 @@ static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev)
|
||||||
|
|
||||||
void MSC_BOT_CplClrFeature (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
void MSC_BOT_CplClrFeature (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if(hmsc->bot_status == USBD_BOT_STATUS_ERROR )/* Bad CBW Signature */
|
if(hmsc->bot_status == USBD_BOT_STATUS_ERROR )/* Bad CBW Signature */
|
||||||
{
|
{
|
||||||
USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
|
USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
|
||||||
hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
|
hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
|
||||||
}
|
}
|
||||||
else if(((epnum & 0x80) == 0x80) && ( hmsc->bot_status != USBD_BOT_STATUS_RECOVERY))
|
else if(((epnum & 0x80) == 0x80) && ( hmsc->bot_status != USBD_BOT_STATUS_RECOVERY))
|
||||||
{
|
{
|
||||||
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED);
|
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -16,14 +16,14 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
#include "usbd_msc_bot.h"
|
#include "usbd_msc_bot.h"
|
||||||
|
@ -38,48 +38,48 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI
|
/** @defgroup MSC_SCSI
|
||||||
* @brief Mass storage SCSI layer module
|
* @brief Mass storage SCSI layer module
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI_Private_TypesDefinitions
|
/** @defgroup MSC_SCSI_Private_TypesDefinitions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI_Private_Defines
|
/** @defgroup MSC_SCSI_Private_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI_Private_Macros
|
/** @defgroup MSC_SCSI_Private_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI_Private_Variables
|
/** @defgroup MSC_SCSI_Private_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI_Private_FunctionPrototypes
|
/** @defgroup MSC_SCSI_Private_FunctionPrototypes
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
||||||
static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
||||||
static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
||||||
|
@ -91,9 +91,9 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
|
||||||
static int8_t SCSI_Write10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params);
|
static int8_t SCSI_Write10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params);
|
||||||
static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params);
|
static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params);
|
||||||
static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
|
||||||
static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev,
|
static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t lun ,
|
uint8_t lun ,
|
||||||
uint32_t blk_offset ,
|
uint32_t blk_offset ,
|
||||||
uint16_t blk_nbr);
|
uint16_t blk_nbr);
|
||||||
static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev,
|
static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t lun);
|
uint8_t lun);
|
||||||
|
@ -102,12 +102,12 @@ static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t lun);
|
uint8_t lun);
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup MSC_SCSI_Private_Functions
|
/** @defgroup MSC_SCSI_Private_Functions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -119,52 +119,52 @@ static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev,
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev,
|
int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev,
|
||||||
uint8_t lun,
|
uint8_t lun,
|
||||||
uint8_t *params)
|
uint8_t *params)
|
||||||
{
|
{
|
||||||
|
|
||||||
switch (params[0])
|
switch (params[0])
|
||||||
{
|
{
|
||||||
case SCSI_TEST_UNIT_READY:
|
case SCSI_TEST_UNIT_READY:
|
||||||
return SCSI_TestUnitReady(pdev, lun, params);
|
return SCSI_TestUnitReady(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_REQUEST_SENSE:
|
case SCSI_REQUEST_SENSE:
|
||||||
return SCSI_RequestSense (pdev, lun, params);
|
return SCSI_RequestSense (pdev, lun, params);
|
||||||
case SCSI_INQUIRY:
|
case SCSI_INQUIRY:
|
||||||
return SCSI_Inquiry(pdev, lun, params);
|
return SCSI_Inquiry(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_START_STOP_UNIT:
|
case SCSI_START_STOP_UNIT:
|
||||||
return SCSI_StartStopUnit(pdev, lun, params);
|
return SCSI_StartStopUnit(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_ALLOW_MEDIUM_REMOVAL:
|
case SCSI_ALLOW_MEDIUM_REMOVAL:
|
||||||
return SCSI_StartStopUnit(pdev, lun, params);
|
return SCSI_StartStopUnit(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_MODE_SENSE6:
|
case SCSI_MODE_SENSE6:
|
||||||
return SCSI_ModeSense6 (pdev, lun, params);
|
return SCSI_ModeSense6 (pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_MODE_SENSE10:
|
case SCSI_MODE_SENSE10:
|
||||||
return SCSI_ModeSense10 (pdev, lun, params);
|
return SCSI_ModeSense10 (pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_READ_FORMAT_CAPACITIES:
|
case SCSI_READ_FORMAT_CAPACITIES:
|
||||||
return SCSI_ReadFormatCapacity(pdev, lun, params);
|
return SCSI_ReadFormatCapacity(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_READ_CAPACITY10:
|
case SCSI_READ_CAPACITY10:
|
||||||
return SCSI_ReadCapacity10(pdev, lun, params);
|
return SCSI_ReadCapacity10(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_READ10:
|
case SCSI_READ10:
|
||||||
return SCSI_Read10(pdev, lun, params);
|
return SCSI_Read10(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_WRITE10:
|
case SCSI_WRITE10:
|
||||||
return SCSI_Write10(pdev, lun, params);
|
return SCSI_Write10(pdev, lun, params);
|
||||||
|
|
||||||
case SCSI_VERIFY10:
|
case SCSI_VERIFY10:
|
||||||
return SCSI_Verify10(pdev, lun, params);
|
return SCSI_Verify10(pdev, lun, params);
|
||||||
|
|
||||||
default:
|
default:
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -179,28 +179,29 @@ int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev,
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) params;
|
||||||
|
|
||||||
/* case 9 : Hi > D0 */
|
/* case 9 : Hi > D0 */
|
||||||
if (hmsc->cbw.dDataLength != 0)
|
if (hmsc->cbw.dDataLength != 0)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 )
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
NOT_READY,
|
NOT_READY,
|
||||||
MEDIUM_NOT_PRESENT);
|
MEDIUM_NOT_PRESENT);
|
||||||
|
|
||||||
hmsc->bot_state = USBD_BOT_NO_DATA;
|
hmsc->bot_state = USBD_BOT_NO_DATA;
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
hmsc->bot_data_length = 0;
|
hmsc->bot_data_length = 0;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -216,8 +217,8 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
|
||||||
{
|
{
|
||||||
uint8_t* pPage;
|
uint8_t* pPage;
|
||||||
uint16_t len;
|
uint16_t len;
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if (params[1] & 0x01)/*Evpd is set*/
|
if (params[1] & 0x01)/*Evpd is set*/
|
||||||
{
|
{
|
||||||
pPage = (uint8_t *)MSC_Page00_Inquiry_Data;
|
pPage = (uint8_t *)MSC_Page00_Inquiry_Data;
|
||||||
|
@ -225,18 +226,18 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
|
||||||
pPage = (uint8_t *)&((USBD_StorageTypeDef *)pdev->pUserData)->pInquiry[lun * STANDARD_INQUIRY_DATA_LEN];
|
pPage = (uint8_t *)&((USBD_StorageTypeDef *)pdev->pMSC_UserData)->pInquiry[lun * STANDARD_INQUIRY_DATA_LEN];
|
||||||
len = pPage[4] + 5;
|
len = pPage[4] + 5;
|
||||||
|
|
||||||
if (params[4] <= len)
|
if (params[4] <= len)
|
||||||
{
|
{
|
||||||
len = params[4];
|
len = params[4];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hmsc->bot_data_length = len;
|
hmsc->bot_data_length = len;
|
||||||
|
|
||||||
while (len)
|
while (len)
|
||||||
{
|
{
|
||||||
len--;
|
len--;
|
||||||
hmsc->bot_data[len] = pPage[len];
|
hmsc->bot_data[len] = pPage[len];
|
||||||
|
@ -253,29 +254,30 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) params;
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &hmsc->scsi_blk_nbr, &hmsc->scsi_blk_size) != 0)
|
|
||||||
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetCapacity(lun, &hmsc->scsi_blk_nbr, &hmsc->scsi_blk_size) != 0)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
NOT_READY,
|
NOT_READY,
|
||||||
MEDIUM_NOT_PRESENT);
|
MEDIUM_NOT_PRESENT);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
|
||||||
hmsc->bot_data[0] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 24);
|
hmsc->bot_data[0] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 24);
|
||||||
hmsc->bot_data[1] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 16);
|
hmsc->bot_data[1] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 16);
|
||||||
hmsc->bot_data[2] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 8);
|
hmsc->bot_data[2] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 8);
|
||||||
hmsc->bot_data[3] = (uint8_t)(hmsc->scsi_blk_nbr - 1);
|
hmsc->bot_data[3] = (uint8_t)(hmsc->scsi_blk_nbr - 1);
|
||||||
|
|
||||||
hmsc->bot_data[4] = (uint8_t)(hmsc->scsi_blk_size >> 24);
|
hmsc->bot_data[4] = (uint8_t)(hmsc->scsi_blk_size >> 24);
|
||||||
hmsc->bot_data[5] = (uint8_t)(hmsc->scsi_blk_size >> 16);
|
hmsc->bot_data[5] = (uint8_t)(hmsc->scsi_blk_size >> 16);
|
||||||
hmsc->bot_data[6] = (uint8_t)(hmsc->scsi_blk_size >> 8);
|
hmsc->bot_data[6] = (uint8_t)(hmsc->scsi_blk_size >> 8);
|
||||||
hmsc->bot_data[7] = (uint8_t)(hmsc->scsi_blk_size);
|
hmsc->bot_data[7] = (uint8_t)(hmsc->scsi_blk_size);
|
||||||
|
|
||||||
hmsc->bot_data_length = 8;
|
hmsc->bot_data_length = 8;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -289,25 +291,26 @@ static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) params;
|
||||||
|
|
||||||
uint16_t blk_size;
|
uint16_t blk_size;
|
||||||
uint32_t blk_nbr;
|
uint32_t blk_nbr;
|
||||||
uint16_t i;
|
uint16_t i;
|
||||||
|
|
||||||
for(i=0 ; i < 12 ; i++)
|
for(i=0 ; i < 12 ; i++)
|
||||||
{
|
{
|
||||||
hmsc->bot_data[i] = 0;
|
hmsc->bot_data[i] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &blk_nbr, &blk_size) != 0)
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetCapacity(lun, &blk_nbr, &blk_size) != 0)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
NOT_READY,
|
NOT_READY,
|
||||||
MEDIUM_NOT_PRESENT);
|
MEDIUM_NOT_PRESENT);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
hmsc->bot_data[3] = 0x08;
|
hmsc->bot_data[3] = 0x08;
|
||||||
|
@ -315,12 +318,12 @@ static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, ui
|
||||||
hmsc->bot_data[5] = (uint8_t)((blk_nbr - 1) >> 16);
|
hmsc->bot_data[5] = (uint8_t)((blk_nbr - 1) >> 16);
|
||||||
hmsc->bot_data[6] = (uint8_t)((blk_nbr - 1) >> 8);
|
hmsc->bot_data[6] = (uint8_t)((blk_nbr - 1) >> 8);
|
||||||
hmsc->bot_data[7] = (uint8_t)(blk_nbr - 1);
|
hmsc->bot_data[7] = (uint8_t)(blk_nbr - 1);
|
||||||
|
|
||||||
hmsc->bot_data[8] = 0x02;
|
hmsc->bot_data[8] = 0x02;
|
||||||
hmsc->bot_data[9] = (uint8_t)(blk_size >> 16);
|
hmsc->bot_data[9] = (uint8_t)(blk_size >> 16);
|
||||||
hmsc->bot_data[10] = (uint8_t)(blk_size >> 8);
|
hmsc->bot_data[10] = (uint8_t)(blk_size >> 8);
|
||||||
hmsc->bot_data[11] = (uint8_t)(blk_size);
|
hmsc->bot_data[11] = (uint8_t)(blk_size);
|
||||||
|
|
||||||
hmsc->bot_data_length = 12;
|
hmsc->bot_data_length = 12;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -334,11 +337,12 @@ static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, ui
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) lun; (void) params;
|
||||||
uint16_t len = 8 ;
|
uint16_t len = 8 ;
|
||||||
hmsc->bot_data_length = len;
|
hmsc->bot_data_length = len;
|
||||||
|
|
||||||
while (len)
|
while (len)
|
||||||
{
|
{
|
||||||
len--;
|
len--;
|
||||||
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
|
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
|
||||||
|
@ -356,11 +360,12 @@ static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
|
||||||
static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
uint16_t len = 8;
|
uint16_t len = 8;
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) lun; (void) params;
|
||||||
|
|
||||||
hmsc->bot_data_length = len;
|
hmsc->bot_data_length = len;
|
||||||
|
|
||||||
while (len)
|
while (len)
|
||||||
{
|
{
|
||||||
len--;
|
len--;
|
||||||
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
|
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
|
||||||
|
@ -379,30 +384,31 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
|
||||||
static int8_t SCSI_RequestSense (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_RequestSense (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) lun;
|
||||||
for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++)
|
|
||||||
|
for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++)
|
||||||
{
|
{
|
||||||
hmsc->bot_data[i] = 0;
|
hmsc->bot_data[i] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
hmsc->bot_data[0] = 0x70;
|
hmsc->bot_data[0] = 0x70;
|
||||||
hmsc->bot_data[7] = REQUEST_SENSE_DATA_LEN - 6;
|
hmsc->bot_data[7] = REQUEST_SENSE_DATA_LEN - 6;
|
||||||
|
|
||||||
if((hmsc->scsi_sense_head != hmsc->scsi_sense_tail)) {
|
if((hmsc->scsi_sense_head != hmsc->scsi_sense_tail)) {
|
||||||
|
|
||||||
hmsc->bot_data[2] = hmsc->scsi_sense[hmsc->scsi_sense_head].Skey;
|
hmsc->bot_data[2] = hmsc->scsi_sense[hmsc->scsi_sense_head].Skey;
|
||||||
hmsc->bot_data[12] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASCQ;
|
hmsc->bot_data[12] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASCQ;
|
||||||
hmsc->bot_data[13] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASC;
|
hmsc->bot_data[13] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASC;
|
||||||
hmsc->scsi_sense_head++;
|
hmsc->scsi_sense_head++;
|
||||||
|
|
||||||
if (hmsc->scsi_sense_head == SENSE_LIST_DEEPTH)
|
if (hmsc->scsi_sense_head == SENSE_LIST_DEEPTH)
|
||||||
{
|
{
|
||||||
hmsc->scsi_sense_head = 0;
|
hmsc->scsi_sense_head = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hmsc->bot_data_length = REQUEST_SENSE_DATA_LEN;
|
hmsc->bot_data_length = REQUEST_SENSE_DATA_LEN;
|
||||||
|
|
||||||
if (params[4] <= REQUEST_SENSE_DATA_LEN)
|
if (params[4] <= REQUEST_SENSE_DATA_LEN)
|
||||||
{
|
{
|
||||||
hmsc->bot_data_length = params[4];
|
hmsc->bot_data_length = params[4];
|
||||||
|
@ -421,8 +427,9 @@ static int8_t SCSI_RequestSense (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
|
||||||
*/
|
*/
|
||||||
void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_t ASC)
|
void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_t ASC)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
|
(void) lun;
|
||||||
|
|
||||||
hmsc->scsi_sense[hmsc->scsi_sense_tail].Skey = sKey;
|
hmsc->scsi_sense[hmsc->scsi_sense_tail].Skey = sKey;
|
||||||
hmsc->scsi_sense[hmsc->scsi_sense_tail].w.ASC = ASC << 8;
|
hmsc->scsi_sense[hmsc->scsi_sense_tail].w.ASC = ASC << 8;
|
||||||
hmsc->scsi_sense_tail++;
|
hmsc->scsi_sense_tail++;
|
||||||
|
@ -440,7 +447,8 @@ void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
(void) lun; (void) params;
|
||||||
hmsc->bot_data_length = 0;
|
hmsc->bot_data_length = 0;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -454,62 +462,62 @@ static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
|
static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if(hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
|
if(hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
|
||||||
{
|
{
|
||||||
|
|
||||||
/* case 10 : Ho <> Di */
|
/* case 10 : Ho <> Di */
|
||||||
|
|
||||||
if ((hmsc->cbw.bmFlags & 0x80) != 0x80)
|
if ((hmsc->cbw.bmFlags & 0x80) != 0x80)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 )
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
NOT_READY,
|
NOT_READY,
|
||||||
MEDIUM_NOT_PRESENT);
|
MEDIUM_NOT_PRESENT);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
hmsc->scsi_blk_addr = (params[2] << 24) | \
|
hmsc->scsi_blk_addr = (params[2] << 24) | \
|
||||||
(params[3] << 16) | \
|
(params[3] << 16) | \
|
||||||
(params[4] << 8) | \
|
(params[4] << 8) | \
|
||||||
params[5];
|
params[5];
|
||||||
|
|
||||||
hmsc->scsi_blk_len = (params[7] << 8) | \
|
hmsc->scsi_blk_len = (params[7] << 8) | \
|
||||||
params[8];
|
params[8];
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if( SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr, hmsc->scsi_blk_len) < 0)
|
if( SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr, hmsc->scsi_blk_len) < 0)
|
||||||
{
|
{
|
||||||
return -1; /* error */
|
return -1; /* error */
|
||||||
}
|
}
|
||||||
|
|
||||||
hmsc->bot_state = USBD_BOT_DATA_IN;
|
hmsc->bot_state = USBD_BOT_DATA_IN;
|
||||||
hmsc->scsi_blk_addr *= hmsc->scsi_blk_size;
|
hmsc->scsi_blk_addr *= hmsc->scsi_blk_size;
|
||||||
hmsc->scsi_blk_len *= hmsc->scsi_blk_size;
|
hmsc->scsi_blk_len *= hmsc->scsi_blk_size;
|
||||||
|
|
||||||
/* cases 4,5 : Hi <> Dn */
|
/* cases 4,5 : Hi <> Dn */
|
||||||
if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len)
|
if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hmsc->bot_data_length = MSC_MEDIA_PACKET;
|
hmsc->bot_data_length = MSC_MEDIA_PACKET;
|
||||||
|
|
||||||
return SCSI_ProcessRead(pdev, lun);
|
return SCSI_ProcessRead(pdev, lun);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -523,78 +531,78 @@ static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *para
|
||||||
|
|
||||||
static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
|
static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
|
if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
|
||||||
{
|
{
|
||||||
|
|
||||||
/* case 8 : Hi <> Do */
|
/* case 8 : Hi <> Do */
|
||||||
|
|
||||||
if ((hmsc->cbw.bmFlags & 0x80) == 0x80)
|
if ((hmsc->cbw.bmFlags & 0x80) == 0x80)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Check whether Media is ready */
|
/* Check whether Media is ready */
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 )
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
NOT_READY,
|
NOT_READY,
|
||||||
MEDIUM_NOT_PRESENT);
|
MEDIUM_NOT_PRESENT);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Check If media is write-protected */
|
/* Check If media is write-protected */
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsWriteProtected(lun) !=0 )
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) !=0 )
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
NOT_READY,
|
NOT_READY,
|
||||||
WRITE_PROTECTED);
|
WRITE_PROTECTED);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
hmsc->scsi_blk_addr = (params[2] << 24) | \
|
hmsc->scsi_blk_addr = (params[2] << 24) | \
|
||||||
(params[3] << 16) | \
|
(params[3] << 16) | \
|
||||||
(params[4] << 8) | \
|
(params[4] << 8) | \
|
||||||
params[5];
|
params[5];
|
||||||
hmsc->scsi_blk_len = (params[7] << 8) | \
|
hmsc->scsi_blk_len = (params[7] << 8) | \
|
||||||
params[8];
|
params[8];
|
||||||
|
|
||||||
/* check if LBA address is in the right range */
|
/* check if LBA address is in the right range */
|
||||||
if(SCSI_CheckAddressRange(pdev,
|
if(SCSI_CheckAddressRange(pdev,
|
||||||
lun,
|
lun,
|
||||||
hmsc->scsi_blk_addr,
|
hmsc->scsi_blk_addr,
|
||||||
hmsc->scsi_blk_len) < 0)
|
hmsc->scsi_blk_len) < 0)
|
||||||
{
|
{
|
||||||
return -1; /* error */
|
return -1; /* error */
|
||||||
}
|
}
|
||||||
|
|
||||||
hmsc->scsi_blk_addr *= hmsc->scsi_blk_size;
|
hmsc->scsi_blk_addr *= hmsc->scsi_blk_size;
|
||||||
hmsc->scsi_blk_len *= hmsc->scsi_blk_size;
|
hmsc->scsi_blk_len *= hmsc->scsi_blk_size;
|
||||||
|
|
||||||
/* cases 3,11,13 : Hn,Ho <> D0 */
|
/* cases 3,11,13 : Hn,Ho <> D0 */
|
||||||
if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len)
|
if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
hmsc->cbw.bLUN,
|
hmsc->cbw.bLUN,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_CDB);
|
INVALID_CDB);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Prepare EP to receive first data packet */
|
/* Prepare EP to receive first data packet */
|
||||||
hmsc->bot_state = USBD_BOT_DATA_OUT;
|
hmsc->bot_state = USBD_BOT_DATA_OUT;
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
hmsc->bot_data,
|
hmsc->bot_data,
|
||||||
MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET));
|
MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET));
|
||||||
}
|
}
|
||||||
else /* Write Process ongoing */
|
else /* Write Process ongoing */
|
||||||
{
|
{
|
||||||
|
@ -614,23 +622,23 @@ static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *pa
|
||||||
|
|
||||||
static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
|
static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if ((params[1]& 0x02) == 0x02)
|
if ((params[1]& 0x02) == 0x02)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode (pdev,
|
SCSI_SenseCode (pdev,
|
||||||
lun,
|
lun,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
INVALID_FIELED_IN_COMMAND);
|
INVALID_FIELED_IN_COMMAND);
|
||||||
return -1; /* Error, Verify Mode Not supported*/
|
return -1; /* Error, Verify Mode Not supported*/
|
||||||
}
|
}
|
||||||
|
|
||||||
if(SCSI_CheckAddressRange(pdev,
|
if(SCSI_CheckAddressRange(pdev,
|
||||||
lun,
|
lun,
|
||||||
hmsc->scsi_blk_addr,
|
hmsc->scsi_blk_addr,
|
||||||
hmsc->scsi_blk_len) < 0)
|
hmsc->scsi_blk_len) < 0)
|
||||||
{
|
{
|
||||||
return -1; /* error */
|
return -1; /* error */
|
||||||
}
|
}
|
||||||
hmsc->bot_data_length = 0;
|
hmsc->bot_data_length = 0;
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -646,13 +654,13 @@ static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *pa
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr)
|
static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
|
||||||
if ((blk_offset + blk_nbr) > hmsc->scsi_blk_nbr )
|
if ((blk_offset + blk_nbr) > hmsc->scsi_blk_nbr )
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
ILLEGAL_REQUEST,
|
ILLEGAL_REQUEST,
|
||||||
ADDRESS_OUT_OF_RANGE);
|
ADDRESS_OUT_OF_RANGE);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
@ -667,37 +675,37 @@ static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , u
|
||||||
*/
|
*/
|
||||||
static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun)
|
static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun)
|
||||||
{
|
{
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
|
||||||
uint32_t len;
|
uint32_t len;
|
||||||
|
|
||||||
len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET);
|
len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET);
|
||||||
|
|
||||||
if( ((USBD_StorageTypeDef *)pdev->pUserData)->Read(lun ,
|
if( ((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Read(lun ,
|
||||||
hmsc->bot_data,
|
hmsc->bot_data,
|
||||||
hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
|
hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
|
||||||
len / hmsc->scsi_blk_size) < 0)
|
len / hmsc->scsi_blk_size) < 0)
|
||||||
{
|
{
|
||||||
|
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
HARDWARE_ERROR,
|
HARDWARE_ERROR,
|
||||||
UNRECOVERED_READ_ERROR);
|
UNRECOVERED_READ_ERROR);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
USBD_LL_Transmit (pdev,
|
USBD_LL_Transmit (pdev,
|
||||||
MSC_EPIN_ADDR,
|
MSC_EPIN_ADDR,
|
||||||
hmsc->bot_data,
|
hmsc->bot_data,
|
||||||
len);
|
len);
|
||||||
|
|
||||||
|
|
||||||
hmsc->scsi_blk_addr += len;
|
hmsc->scsi_blk_addr += len;
|
||||||
hmsc->scsi_blk_len -= len;
|
hmsc->scsi_blk_len -= len;
|
||||||
|
|
||||||
/* case 6 : Hi = Di */
|
/* case 6 : Hi = Di */
|
||||||
hmsc->csw.dDataResidue -= len;
|
hmsc->csw.dDataResidue -= len;
|
||||||
|
|
||||||
if (hmsc->scsi_blk_len == 0)
|
if (hmsc->scsi_blk_len == 0)
|
||||||
{
|
{
|
||||||
hmsc->bot_state = USBD_BOT_LAST_DATA_IN;
|
hmsc->bot_state = USBD_BOT_LAST_DATA_IN;
|
||||||
|
@ -715,29 +723,29 @@ static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun)
|
||||||
static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun)
|
static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun)
|
||||||
{
|
{
|
||||||
uint32_t len;
|
uint32_t len;
|
||||||
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData;
|
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
|
||||||
|
|
||||||
len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET);
|
len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET);
|
||||||
|
|
||||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->Write(lun ,
|
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Write(lun ,
|
||||||
hmsc->bot_data,
|
hmsc->bot_data,
|
||||||
hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
|
hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
|
||||||
len / hmsc->scsi_blk_size) < 0)
|
len / hmsc->scsi_blk_size) < 0)
|
||||||
{
|
{
|
||||||
SCSI_SenseCode(pdev,
|
SCSI_SenseCode(pdev,
|
||||||
lun,
|
lun,
|
||||||
HARDWARE_ERROR,
|
HARDWARE_ERROR,
|
||||||
WRITE_FAULT);
|
WRITE_FAULT);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
hmsc->scsi_blk_addr += len;
|
hmsc->scsi_blk_addr += len;
|
||||||
hmsc->scsi_blk_len -= len;
|
hmsc->scsi_blk_len -= len;
|
||||||
|
|
||||||
/* case 12 : Ho = Do */
|
/* case 12 : Ho = Do */
|
||||||
hmsc->csw.dDataResidue -= len;
|
hmsc->csw.dDataResidue -= len;
|
||||||
|
|
||||||
if (hmsc->scsi_blk_len == 0)
|
if (hmsc->scsi_blk_len == 0)
|
||||||
{
|
{
|
||||||
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED);
|
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED);
|
||||||
|
@ -747,24 +755,24 @@ static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun)
|
||||||
/* Prepare EP to Receive next packet */
|
/* Prepare EP to Receive next packet */
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
MSC_EPOUT_ADDR,
|
MSC_EPOUT_ADDR,
|
||||||
hmsc->bot_data,
|
hmsc->bot_data,
|
||||||
MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET));
|
MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET));
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -4,7 +4,7 @@
|
||||||
* @author MCD Application Team
|
* @author MCD Application Team
|
||||||
* @version V2.4.2
|
* @version V2.4.2
|
||||||
* @date 11-December-2015
|
* @date 11-December-2015
|
||||||
* @brief General defines for the usb device library
|
* @brief General defines for the usb device library
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
* @attention
|
* @attention
|
||||||
*
|
*
|
||||||
|
@ -16,14 +16,14 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
#ifndef __USBD_DEF_H
|
#ifndef __USBD_DEF_H
|
||||||
|
@ -39,15 +39,15 @@
|
||||||
/** @addtogroup STM32_USBD_DEVICE_LIBRARY
|
/** @addtogroup STM32_USBD_DEVICE_LIBRARY
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USB_DEF
|
/** @defgroup USB_DEF
|
||||||
* @brief general defines for the usb device library file
|
* @brief general defines for the usb device library file
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USB_DEF_Exported_Defines
|
/** @defgroup USB_DEF_Exported_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef NULL
|
#ifndef NULL
|
||||||
#define NULL 0
|
#define NULL 0
|
||||||
|
@ -63,12 +63,12 @@
|
||||||
#define USB_LEN_LANGID_STR_DESC 0x04
|
#define USB_LEN_LANGID_STR_DESC 0x04
|
||||||
#define USB_LEN_OTHER_SPEED_DESC_SIZ 0x09
|
#define USB_LEN_OTHER_SPEED_DESC_SIZ 0x09
|
||||||
|
|
||||||
#define USBD_IDX_LANGID_STR 0x00
|
#define USBD_IDX_LANGID_STR 0x00
|
||||||
#define USBD_IDX_MFC_STR 0x01
|
#define USBD_IDX_MFC_STR 0x01
|
||||||
#define USBD_IDX_PRODUCT_STR 0x02
|
#define USBD_IDX_PRODUCT_STR 0x02
|
||||||
#define USBD_IDX_SERIAL_STR 0x03
|
#define USBD_IDX_SERIAL_STR 0x03
|
||||||
#define USBD_IDX_CONFIG_STR 0x04
|
#define USBD_IDX_CONFIG_STR 0x04
|
||||||
#define USBD_IDX_INTERFACE_STR 0x05
|
#define USBD_IDX_INTERFACE_STR 0x05
|
||||||
|
|
||||||
#define USB_REQ_TYPE_STANDARD 0x00
|
#define USB_REQ_TYPE_STANDARD 0x00
|
||||||
#define USB_REQ_TYPE_CLASS 0x20
|
#define USB_REQ_TYPE_CLASS 0x20
|
||||||
|
@ -121,14 +121,14 @@
|
||||||
#define USBD_STATE_SUSPENDED 4
|
#define USBD_STATE_SUSPENDED 4
|
||||||
|
|
||||||
|
|
||||||
/* EP0 State */
|
/* EP0 State */
|
||||||
#define USBD_EP0_IDLE 0
|
#define USBD_EP0_IDLE 0
|
||||||
#define USBD_EP0_SETUP 1
|
#define USBD_EP0_SETUP 1
|
||||||
#define USBD_EP0_DATA_IN 2
|
#define USBD_EP0_DATA_IN 2
|
||||||
#define USBD_EP0_DATA_OUT 3
|
#define USBD_EP0_DATA_OUT 3
|
||||||
#define USBD_EP0_STATUS_IN 4
|
#define USBD_EP0_STATUS_IN 4
|
||||||
#define USBD_EP0_STATUS_OUT 5
|
#define USBD_EP0_STATUS_OUT 5
|
||||||
#define USBD_EP0_STALL 6
|
#define USBD_EP0_STALL 6
|
||||||
|
|
||||||
#define USBD_EP_TYPE_CTRL 0
|
#define USBD_EP_TYPE_CTRL 0
|
||||||
#define USBD_EP_TYPE_ISOC 1
|
#define USBD_EP_TYPE_ISOC 1
|
||||||
|
@ -138,56 +138,56 @@
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_DEF_Exported_TypesDefinitions
|
/** @defgroup USBD_DEF_Exported_TypesDefinitions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
typedef struct usb_setup_req
|
typedef struct usb_setup_req
|
||||||
{
|
{
|
||||||
|
|
||||||
uint8_t bmRequest;
|
uint8_t bmRequest;
|
||||||
uint8_t bRequest;
|
uint8_t bRequest;
|
||||||
uint16_t wValue;
|
uint16_t wValue;
|
||||||
uint16_t wIndex;
|
uint16_t wIndex;
|
||||||
uint16_t wLength;
|
uint16_t wLength;
|
||||||
}USBD_SetupReqTypedef;
|
}USBD_SetupReqTypedef;
|
||||||
|
|
||||||
struct _USBD_HandleTypeDef;
|
struct _USBD_HandleTypeDef;
|
||||||
|
|
||||||
typedef struct _Device_cb
|
typedef struct _Device_cb
|
||||||
{
|
{
|
||||||
uint8_t (*Init) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx);
|
uint8_t (*Init) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx);
|
||||||
uint8_t (*DeInit) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx);
|
uint8_t (*DeInit) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx);
|
||||||
/* Control Endpoints*/
|
/* Control Endpoints*/
|
||||||
uint8_t (*Setup) (struct _USBD_HandleTypeDef *pdev , USBD_SetupReqTypedef *req);
|
uint8_t (*Setup) (struct _USBD_HandleTypeDef *pdev , USBD_SetupReqTypedef *req);
|
||||||
uint8_t (*EP0_TxSent) (struct _USBD_HandleTypeDef *pdev );
|
uint8_t (*EP0_TxSent) (struct _USBD_HandleTypeDef *pdev );
|
||||||
uint8_t (*EP0_RxReady) (struct _USBD_HandleTypeDef *pdev );
|
uint8_t (*EP0_RxReady) (struct _USBD_HandleTypeDef *pdev );
|
||||||
/* Class Specific Endpoints*/
|
/* Class Specific Endpoints*/
|
||||||
uint8_t (*DataIn) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
uint8_t (*DataIn) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
||||||
uint8_t (*DataOut) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
uint8_t (*DataOut) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
||||||
uint8_t (*SOF) (struct _USBD_HandleTypeDef *pdev);
|
uint8_t (*SOF) (struct _USBD_HandleTypeDef *pdev);
|
||||||
uint8_t (*IsoINIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
uint8_t (*IsoINIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
||||||
uint8_t (*IsoOUTIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
uint8_t (*IsoOUTIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
|
||||||
|
|
||||||
uint8_t *(*GetHSConfigDescriptor)(uint16_t *length);
|
uint8_t *(*GetHSConfigDescriptor)(uint16_t *length);
|
||||||
uint8_t *(*GetFSConfigDescriptor)(uint16_t *length);
|
uint8_t *(*GetFSConfigDescriptor)(uint16_t *length);
|
||||||
uint8_t *(*GetOtherSpeedConfigDescriptor)(uint16_t *length);
|
uint8_t *(*GetOtherSpeedConfigDescriptor)(uint16_t *length);
|
||||||
uint8_t *(*GetDeviceQualifierDescriptor)(uint16_t *length);
|
uint8_t *(*GetDeviceQualifierDescriptor)(uint16_t *length);
|
||||||
#if (USBD_SUPPORT_USER_STRING == 1)
|
#if (USBD_SUPPORT_USER_STRING == 1)
|
||||||
uint8_t *(*GetUsrStrDescriptor)(struct _USBD_HandleTypeDef *pdev ,uint8_t index, uint16_t *length);
|
uint8_t *(*GetUsrStrDescriptor)(struct _USBD_HandleTypeDef *pdev ,uint8_t index, uint16_t *length);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
} USBD_ClassTypeDef;
|
} USBD_ClassTypeDef;
|
||||||
|
|
||||||
/* Following USB Device Speed */
|
/* Following USB Device Speed */
|
||||||
typedef enum
|
typedef enum
|
||||||
{
|
{
|
||||||
USBD_SPEED_HIGH = 0,
|
USBD_SPEED_HIGH = 0,
|
||||||
USBD_SPEED_FULL = 1,
|
USBD_SPEED_FULL = 1,
|
||||||
USBD_SPEED_LOW = 2,
|
USBD_SPEED_LOW = 2,
|
||||||
}USBD_SpeedTypeDef;
|
}USBD_SpeedTypeDef;
|
||||||
|
|
||||||
/* Following USB Device status */
|
/* Following USB Device status */
|
||||||
|
@ -200,25 +200,25 @@ typedef enum {
|
||||||
/* USB Device descriptors structure */
|
/* USB Device descriptors structure */
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
uint8_t *(*GetDeviceDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetDeviceDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
uint8_t *(*GetLangIDStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetLangIDStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
uint8_t *(*GetManufacturerStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetManufacturerStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
uint8_t *(*GetProductStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetProductStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
uint8_t *(*GetSerialStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetSerialStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
uint8_t *(*GetConfigurationStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetConfigurationStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
uint8_t *(*GetInterfaceStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetInterfaceStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
#if (USBD_LPM_ENABLED == 1)
|
#if (USBD_LPM_ENABLED == 1)
|
||||||
uint8_t *(*GetBOSDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
uint8_t *(*GetBOSDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
|
||||||
#endif
|
#endif
|
||||||
} USBD_DescriptorsTypeDef;
|
} USBD_DescriptorsTypeDef;
|
||||||
|
|
||||||
/* USB Device handle structure */
|
/* USB Device handle structure */
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
uint32_t status;
|
uint32_t status;
|
||||||
uint32_t total_length;
|
uint32_t total_length;
|
||||||
uint32_t rem_length;
|
uint32_t rem_length;
|
||||||
uint32_t maxpacket;
|
uint32_t maxpacket;
|
||||||
} USBD_EndpointTypeDef;
|
} USBD_EndpointTypeDef;
|
||||||
|
|
||||||
/* USB Device handle structure */
|
/* USB Device handle structure */
|
||||||
|
@ -227,43 +227,54 @@ typedef struct _USBD_HandleTypeDef
|
||||||
uint8_t id;
|
uint8_t id;
|
||||||
uint32_t dev_config;
|
uint32_t dev_config;
|
||||||
uint32_t dev_default_config;
|
uint32_t dev_default_config;
|
||||||
uint32_t dev_config_status;
|
uint32_t dev_config_status;
|
||||||
USBD_SpeedTypeDef dev_speed;
|
USBD_SpeedTypeDef dev_speed;
|
||||||
USBD_EndpointTypeDef ep_in[15];
|
USBD_EndpointTypeDef ep_in[15];
|
||||||
USBD_EndpointTypeDef ep_out[15];
|
USBD_EndpointTypeDef ep_out[15];
|
||||||
uint32_t ep0_state;
|
uint32_t ep0_state;
|
||||||
uint32_t ep0_data_len;
|
uint32_t ep0_data_len;
|
||||||
uint8_t dev_state;
|
uint8_t dev_state;
|
||||||
uint8_t dev_old_state;
|
uint8_t dev_old_state;
|
||||||
uint8_t dev_address;
|
uint8_t dev_address;
|
||||||
uint8_t dev_connection_status;
|
uint8_t dev_connection_status;
|
||||||
uint8_t dev_test_mode;
|
uint8_t dev_test_mode;
|
||||||
uint32_t dev_remote_wakeup;
|
uint32_t dev_remote_wakeup;
|
||||||
|
|
||||||
USBD_SetupReqTypedef request;
|
USBD_SetupReqTypedef request;
|
||||||
USBD_DescriptorsTypeDef *pDesc;
|
USBD_DescriptorsTypeDef *pDesc;
|
||||||
USBD_ClassTypeDef *pClass;
|
USBD_ClassTypeDef *pClass;
|
||||||
void *pClassData;
|
/* This is stupid, any nice solution to handle multiple interfaces
|
||||||
void *pUserData;
|
* would be much apriciated. Or at least a flow how this should be rewritten instead.
|
||||||
void *pData;
|
*/
|
||||||
|
void *pCDC_ClassData;
|
||||||
|
void *pCDC_UserData;
|
||||||
|
void *pHID_ClassData;
|
||||||
|
void *pHID_UserData;
|
||||||
|
void *pMSC_ClassData;
|
||||||
|
void *pMSC_UserData;
|
||||||
|
void *pData;
|
||||||
} USBD_HandleTypeDef;
|
} USBD_HandleTypeDef;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_DEF_Exported_Macros
|
/** @defgroup USBD_DEF_Exported_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
#define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \
|
#define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \
|
||||||
(((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8))
|
(((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8))
|
||||||
|
|
||||||
#define LOBYTE(x) ((uint8_t)(x & 0x00FF))
|
#define LOBYTE(x) ((uint8_t)(x & 0x00FF))
|
||||||
#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8))
|
#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8))
|
||||||
|
#ifndef MIN
|
||||||
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
|
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
|
||||||
|
#endif
|
||||||
|
#ifndef MAX
|
||||||
#define MAX(a, b) (((a) > (b)) ? (a) : (b))
|
#define MAX(a, b) (((a) > (b)) ? (a) : (b))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if defined ( __GNUC__ )
|
#if defined ( __GNUC__ )
|
||||||
|
@ -277,42 +288,42 @@ typedef struct _USBD_HandleTypeDef
|
||||||
|
|
||||||
|
|
||||||
/* In HS mode and when the DMA is used, all variables and data structures dealing
|
/* 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 */
|
with the DMA during the transaction process should be 4-bytes aligned */
|
||||||
|
|
||||||
#if defined (__GNUC__) /* GNU Compiler */
|
#if defined (__GNUC__) /* GNU Compiler */
|
||||||
#define __ALIGN_END __attribute__ ((aligned (4)))
|
#define __ALIGN_END __attribute__ ((aligned (4)))
|
||||||
#define __ALIGN_BEGIN
|
#define __ALIGN_BEGIN
|
||||||
#else
|
#else
|
||||||
#define __ALIGN_END
|
#define __ALIGN_END
|
||||||
#if defined (__CC_ARM) /* ARM Compiler */
|
#if defined (__CC_ARM) /* ARM Compiler */
|
||||||
#define __ALIGN_BEGIN __align(4)
|
#define __ALIGN_BEGIN __align(4)
|
||||||
#elif defined (__ICCARM__) /* IAR Compiler */
|
#elif defined (__ICCARM__) /* IAR Compiler */
|
||||||
#define __ALIGN_BEGIN
|
#define __ALIGN_BEGIN
|
||||||
#elif defined (__TASKING__) /* TASKING Compiler */
|
#elif defined (__TASKING__) /* TASKING Compiler */
|
||||||
#define __ALIGN_BEGIN __align(4)
|
#define __ALIGN_BEGIN __align(4)
|
||||||
#endif /* __CC_ARM */
|
#endif /* __CC_ARM */
|
||||||
#endif /* __GNUC__ */
|
#endif /* __GNUC__ */
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_DEF_Exported_Variables
|
/** @defgroup USBD_DEF_Exported_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_DEF_Exported_FunctionsPrototype
|
/** @defgroup USBD_DEF_Exported_FunctionsPrototype
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
@ -322,9 +333,9 @@ typedef struct _USBD_HandleTypeDef
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -16,14 +16,14 @@
|
||||||
*
|
*
|
||||||
* http://www.st.com/software_license_agreement_liberty_v2
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
*
|
*
|
||||||
* Unless required by applicable law or agreed to in writing, software
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
* See the License for the specific language governing permissions and
|
* See the License for the specific language governing permissions and
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
#include "usbd_core.h"
|
#include "usbd_core.h"
|
||||||
|
@ -33,57 +33,57 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_CORE
|
/** @defgroup USBD_CORE
|
||||||
* @brief usbd core module
|
* @brief usbd core module
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Private_TypesDefinitions
|
/** @defgroup USBD_CORE_Private_TypesDefinitions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Private_Defines
|
/** @defgroup USBD_CORE_Private_Defines
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Private_Macros
|
/** @defgroup USBD_CORE_Private_Macros
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Private_FunctionPrototypes
|
/** @defgroup USBD_CORE_Private_FunctionPrototypes
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Private_Variables
|
/** @defgroup USBD_CORE_Private_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/** @defgroup USBD_CORE_Private_Functions
|
/** @defgroup USBD_CORE_Private_Functions
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_Init
|
* @brief USBD_Init
|
||||||
|
@ -99,32 +99,32 @@ USBD_StatusTypeDef USBD_Init(USBD_HandleTypeDef *pdev, USBD_DescriptorsTypeDef *
|
||||||
if(pdev == NULL)
|
if(pdev == NULL)
|
||||||
{
|
{
|
||||||
USBD_ErrLog("Invalid Device handle");
|
USBD_ErrLog("Invalid Device handle");
|
||||||
return USBD_FAIL;
|
return USBD_FAIL;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Unlink previous class*/
|
/* Unlink previous class*/
|
||||||
if(pdev->pClass != NULL)
|
if(pdev->pClass != NULL)
|
||||||
{
|
{
|
||||||
pdev->pClass = NULL;
|
pdev->pClass = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Assign USBD Descriptors */
|
/* Assign USBD Descriptors */
|
||||||
if(pdesc != NULL)
|
if(pdesc != NULL)
|
||||||
{
|
{
|
||||||
pdev->pDesc = pdesc;
|
pdev->pDesc = pdesc;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Set Device initial State */
|
/* Set Device initial State */
|
||||||
pdev->dev_state = USBD_STATE_DEFAULT;
|
pdev->dev_state = USBD_STATE_DEFAULT;
|
||||||
pdev->id = id;
|
pdev->id = id;
|
||||||
/* Initialize low level driver */
|
/* Initialize low level driver */
|
||||||
USBD_LL_Init(pdev);
|
USBD_LL_Init(pdev);
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_DeInit
|
* @brief USBD_DeInit
|
||||||
* Re-Initialize th device library
|
* Re-Initialize th device library
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status: status
|
* @retval status: status
|
||||||
|
@ -133,22 +133,22 @@ USBD_StatusTypeDef USBD_DeInit(USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
/* Set Default State */
|
/* Set Default State */
|
||||||
pdev->dev_state = USBD_STATE_DEFAULT;
|
pdev->dev_state = USBD_STATE_DEFAULT;
|
||||||
|
|
||||||
/* Free Class Resources */
|
/* Free Class Resources */
|
||||||
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
||||||
|
|
||||||
/* Stop the low level driver */
|
/* Stop the low level driver */
|
||||||
USBD_LL_Stop(pdev);
|
USBD_LL_Stop(pdev);
|
||||||
|
|
||||||
/* Initialize low level driver */
|
/* Initialize low level driver */
|
||||||
USBD_LL_DeInit(pdev);
|
USBD_LL_DeInit(pdev);
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_RegisterClass
|
* @brief USBD_RegisterClass
|
||||||
* Link class driver to Device Core.
|
* Link class driver to Device Core.
|
||||||
* @param pDevice : Device Handle
|
* @param pDevice : Device Handle
|
||||||
* @param pclass: Class handle
|
* @param pclass: Class handle
|
||||||
|
@ -166,29 +166,29 @@ USBD_StatusTypeDef USBD_RegisterClass(USBD_HandleTypeDef *pdev, USBD_ClassTypeD
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
USBD_ErrLog("Invalid Class handle");
|
USBD_ErrLog("Invalid Class handle");
|
||||||
status = USBD_FAIL;
|
status = USBD_FAIL;
|
||||||
}
|
}
|
||||||
|
|
||||||
return status;
|
return status;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_Start
|
* @brief USBD_Start
|
||||||
* Start the USB Device Core.
|
* Start the USB Device Core.
|
||||||
* @param pdev: Device Handle
|
* @param pdev: Device Handle
|
||||||
* @retval USBD Status
|
* @retval USBD Status
|
||||||
*/
|
*/
|
||||||
USBD_StatusTypeDef USBD_Start (USBD_HandleTypeDef *pdev)
|
USBD_StatusTypeDef USBD_Start (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
|
|
||||||
/* Start the low level driver */
|
/* Start the low level driver */
|
||||||
USBD_LL_Start(pdev);
|
USBD_LL_Start(pdev);
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_Stop
|
* @brief USBD_Stop
|
||||||
* Stop the USB Device Core.
|
* Stop the USB Device Core.
|
||||||
* @param pdev: Device Handle
|
* @param pdev: Device Handle
|
||||||
* @retval USBD Status
|
* @retval USBD Status
|
||||||
|
@ -196,21 +196,21 @@ USBD_StatusTypeDef USBD_Start (USBD_HandleTypeDef *pdev)
|
||||||
USBD_StatusTypeDef USBD_Stop (USBD_HandleTypeDef *pdev)
|
USBD_StatusTypeDef USBD_Stop (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
/* Free Class Resources */
|
/* Free Class Resources */
|
||||||
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
||||||
|
|
||||||
/* Stop the low level driver */
|
/* Stop the low level driver */
|
||||||
USBD_LL_Stop(pdev);
|
USBD_LL_Stop(pdev);
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_RunTestMode
|
* @brief USBD_RunTestMode
|
||||||
* Launch test mode process
|
* Launch test mode process
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
*/
|
*/
|
||||||
USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
|
USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
(void)pdev;
|
(void)pdev;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
|
@ -218,7 +218,7 @@ USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_SetClassConfig
|
* @brief USBD_SetClassConfig
|
||||||
* Configure device and start the interface
|
* Configure device and start the interface
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @param cfgidx: configuration index
|
* @param cfgidx: configuration index
|
||||||
|
@ -228,7 +228,7 @@ USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
|
||||||
USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
|
USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
USBD_StatusTypeDef ret = USBD_FAIL;
|
USBD_StatusTypeDef ret = USBD_FAIL;
|
||||||
|
|
||||||
if(pdev->pClass != NULL)
|
if(pdev->pClass != NULL)
|
||||||
{
|
{
|
||||||
/* Set configuration and Start the Class*/
|
/* Set configuration and Start the Class*/
|
||||||
|
@ -237,11 +237,11 @@ USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx
|
||||||
ret = USBD_OK;
|
ret = USBD_OK;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_ClrClassConfig
|
* @brief USBD_ClrClassConfig
|
||||||
* Clear current configuration
|
* Clear current configuration
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @param cfgidx: configuration index
|
* @param cfgidx: configuration index
|
||||||
|
@ -250,13 +250,13 @@ USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx
|
||||||
USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
|
USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
/* Clear configuration and De-initialize the Class process*/
|
/* Clear configuration and De-initialize the Class process*/
|
||||||
pdev->pClass->DeInit(pdev, cfgidx);
|
pdev->pClass->DeInit(pdev, cfgidx);
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_SetupStage
|
* @brief USBD_SetupStage
|
||||||
* Handle the setup stage
|
* Handle the setup stage
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -265,33 +265,33 @@ USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup)
|
||||||
{
|
{
|
||||||
|
|
||||||
USBD_ParseSetupRequest(&pdev->request, psetup);
|
USBD_ParseSetupRequest(&pdev->request, psetup);
|
||||||
|
|
||||||
pdev->ep0_state = USBD_EP0_SETUP;
|
pdev->ep0_state = USBD_EP0_SETUP;
|
||||||
pdev->ep0_data_len = pdev->request.wLength;
|
pdev->ep0_data_len = pdev->request.wLength;
|
||||||
|
|
||||||
switch (pdev->request.bmRequest & 0x1F)
|
switch (pdev->request.bmRequest & 0x1F)
|
||||||
{
|
{
|
||||||
case USB_REQ_RECIPIENT_DEVICE:
|
case USB_REQ_RECIPIENT_DEVICE:
|
||||||
USBD_StdDevReq (pdev, &pdev->request);
|
USBD_StdDevReq (pdev, &pdev->request);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_RECIPIENT_INTERFACE:
|
case USB_REQ_RECIPIENT_INTERFACE:
|
||||||
USBD_StdItfReq(pdev, &pdev->request);
|
USBD_StdItfReq(pdev, &pdev->request);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case USB_REQ_RECIPIENT_ENDPOINT:
|
case USB_REQ_RECIPIENT_ENDPOINT:
|
||||||
USBD_StdEPReq(pdev, &pdev->request);
|
USBD_StdEPReq(pdev, &pdev->request);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
USBD_LL_StallEP(pdev , pdev->request.bmRequest & 0x80);
|
USBD_LL_StallEP(pdev , pdev->request.bmRequest & 0x80);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_DataOutStage
|
* @brief USBD_DataOutStage
|
||||||
* Handle data OUT stage
|
* Handle data OUT stage
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
|
@ -300,18 +300,18 @@ USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup)
|
||||||
USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum, uint8_t *pdata)
|
USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum, uint8_t *pdata)
|
||||||
{
|
{
|
||||||
USBD_EndpointTypeDef *pep;
|
USBD_EndpointTypeDef *pep;
|
||||||
|
|
||||||
if(epnum == 0)
|
if(epnum == 0)
|
||||||
{
|
{
|
||||||
pep = &pdev->ep_out[0];
|
pep = &pdev->ep_out[0];
|
||||||
|
|
||||||
if ( pdev->ep0_state == USBD_EP0_DATA_OUT)
|
if ( pdev->ep0_state == USBD_EP0_DATA_OUT)
|
||||||
{
|
{
|
||||||
if(pep->rem_length > pep->maxpacket)
|
if(pep->rem_length > pep->maxpacket)
|
||||||
{
|
{
|
||||||
pep->rem_length -= pep->maxpacket;
|
pep->rem_length -= pep->maxpacket;
|
||||||
|
|
||||||
USBD_CtlContinueRx (pdev,
|
USBD_CtlContinueRx (pdev,
|
||||||
pdata,
|
pdata,
|
||||||
MIN(pep->rem_length ,pep->maxpacket));
|
MIN(pep->rem_length ,pep->maxpacket));
|
||||||
}
|
}
|
||||||
|
@ -320,7 +320,7 @@ USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum
|
||||||
if((pdev->pClass->EP0_RxReady != NULL)&&
|
if((pdev->pClass->EP0_RxReady != NULL)&&
|
||||||
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
||||||
{
|
{
|
||||||
pdev->pClass->EP0_RxReady(pdev);
|
pdev->pClass->EP0_RxReady(pdev);
|
||||||
}
|
}
|
||||||
USBD_CtlSendStatus(pdev);
|
USBD_CtlSendStatus(pdev);
|
||||||
}
|
}
|
||||||
|
@ -329,13 +329,13 @@ USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum
|
||||||
else if((pdev->pClass->DataOut != NULL)&&
|
else if((pdev->pClass->DataOut != NULL)&&
|
||||||
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
||||||
{
|
{
|
||||||
pdev->pClass->DataOut(pdev, epnum);
|
pdev->pClass->DataOut(pdev, epnum);
|
||||||
}
|
}
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_DataInStage
|
* @brief USBD_DataInStage
|
||||||
* Handle data in stage
|
* Handle data in stage
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @param epnum: endpoint index
|
* @param epnum: endpoint index
|
||||||
|
@ -344,26 +344,26 @@ USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum
|
||||||
USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum, uint8_t *pdata)
|
USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum, uint8_t *pdata)
|
||||||
{
|
{
|
||||||
USBD_EndpointTypeDef *pep;
|
USBD_EndpointTypeDef *pep;
|
||||||
|
|
||||||
if(epnum == 0)
|
if(epnum == 0)
|
||||||
{
|
{
|
||||||
pep = &pdev->ep_in[0];
|
pep = &pdev->ep_in[0];
|
||||||
|
|
||||||
if ( pdev->ep0_state == USBD_EP0_DATA_IN)
|
if ( pdev->ep0_state == USBD_EP0_DATA_IN)
|
||||||
{
|
{
|
||||||
if(pep->rem_length > pep->maxpacket)
|
if(pep->rem_length > pep->maxpacket)
|
||||||
{
|
{
|
||||||
pep->rem_length -= pep->maxpacket;
|
pep->rem_length -= pep->maxpacket;
|
||||||
|
|
||||||
USBD_CtlContinueSendData (pdev,
|
USBD_CtlContinueSendData (pdev,
|
||||||
pdata,
|
pdata,
|
||||||
pep->rem_length);
|
pep->rem_length);
|
||||||
|
|
||||||
/* Prepare endpoint for premature end of transfer */
|
/* Prepare endpoint for premature end of transfer */
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
0,
|
0,
|
||||||
NULL,
|
NULL,
|
||||||
0);
|
0);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{ /* last packet is MPS multiple, so send ZLP packet */
|
{ /* last packet is MPS multiple, so send ZLP packet */
|
||||||
|
@ -371,10 +371,10 @@ USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum,
|
||||||
(pep->total_length >= pep->maxpacket) &&
|
(pep->total_length >= pep->maxpacket) &&
|
||||||
(pep->total_length < pdev->ep0_data_len ))
|
(pep->total_length < pdev->ep0_data_len ))
|
||||||
{
|
{
|
||||||
|
|
||||||
USBD_CtlContinueSendData(pdev , NULL, 0);
|
USBD_CtlContinueSendData(pdev , NULL, 0);
|
||||||
pdev->ep0_data_len = 0;
|
pdev->ep0_data_len = 0;
|
||||||
|
|
||||||
/* Prepare endpoint for premature end of transfer */
|
/* Prepare endpoint for premature end of transfer */
|
||||||
USBD_LL_PrepareReceive (pdev,
|
USBD_LL_PrepareReceive (pdev,
|
||||||
0,
|
0,
|
||||||
|
@ -386,28 +386,28 @@ USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum,
|
||||||
if((pdev->pClass->EP0_TxSent != NULL)&&
|
if((pdev->pClass->EP0_TxSent != NULL)&&
|
||||||
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
||||||
{
|
{
|
||||||
pdev->pClass->EP0_TxSent(pdev);
|
pdev->pClass->EP0_TxSent(pdev);
|
||||||
}
|
}
|
||||||
USBD_CtlReceiveStatus(pdev);
|
USBD_CtlReceiveStatus(pdev);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (pdev->dev_test_mode == 1)
|
if (pdev->dev_test_mode == 1)
|
||||||
{
|
{
|
||||||
USBD_RunTestMode(pdev);
|
USBD_RunTestMode(pdev);
|
||||||
pdev->dev_test_mode = 0;
|
pdev->dev_test_mode = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else if((pdev->pClass->DataIn != NULL)&&
|
else if((pdev->pClass->DataIn != NULL)&&
|
||||||
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
(pdev->dev_state == USBD_STATE_CONFIGURED))
|
||||||
{
|
{
|
||||||
pdev->pClass->DataIn(pdev, epnum);
|
pdev->pClass->DataIn(pdev, epnum);
|
||||||
}
|
}
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_LL_Reset
|
* @brief USBD_LL_Reset
|
||||||
* Handle Reset event
|
* Handle Reset event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -420,23 +420,23 @@ USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev)
|
||||||
0x00,
|
0x00,
|
||||||
USBD_EP_TYPE_CTRL,
|
USBD_EP_TYPE_CTRL,
|
||||||
USB_MAX_EP0_SIZE);
|
USB_MAX_EP0_SIZE);
|
||||||
|
|
||||||
pdev->ep_out[0].maxpacket = USB_MAX_EP0_SIZE;
|
pdev->ep_out[0].maxpacket = USB_MAX_EP0_SIZE;
|
||||||
|
|
||||||
/* Open EP0 IN */
|
/* Open EP0 IN */
|
||||||
USBD_LL_OpenEP(pdev,
|
USBD_LL_OpenEP(pdev,
|
||||||
0x80,
|
0x80,
|
||||||
USBD_EP_TYPE_CTRL,
|
USBD_EP_TYPE_CTRL,
|
||||||
USB_MAX_EP0_SIZE);
|
USB_MAX_EP0_SIZE);
|
||||||
|
|
||||||
pdev->ep_in[0].maxpacket = USB_MAX_EP0_SIZE;
|
pdev->ep_in[0].maxpacket = USB_MAX_EP0_SIZE;
|
||||||
/* Upon Reset call user call back */
|
/* Upon Reset call user call back */
|
||||||
pdev->dev_state = USBD_STATE_DEFAULT;
|
pdev->dev_state = USBD_STATE_DEFAULT;
|
||||||
|
|
||||||
if (pdev->pClassData)
|
if (pdev->pCDC_ClassData || pdev->pHID_ClassData || pdev->pMSC_ClassData)
|
||||||
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
||||||
|
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -444,7 +444,7 @@ USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev)
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_LL_Reset
|
* @brief USBD_LL_Reset
|
||||||
* Handle Reset event
|
* Handle Reset event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -456,7 +456,7 @@ USBD_StatusTypeDef USBD_LL_SetSpeed(USBD_HandleTypeDef *pdev, USBD_SpeedTypeDef
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_Suspend
|
* @brief USBD_Suspend
|
||||||
* Handle Suspend event
|
* Handle Suspend event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -470,7 +470,7 @@ USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev)
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_Resume
|
* @brief USBD_Resume
|
||||||
* Handle Resume event
|
* Handle Resume event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -478,12 +478,12 @@ USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev)
|
||||||
|
|
||||||
USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev)
|
USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
pdev->dev_state = pdev->dev_old_state;
|
pdev->dev_state = pdev->dev_old_state;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_SOF
|
* @brief USBD_SOF
|
||||||
* Handle SOF event
|
* Handle SOF event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -502,7 +502,7 @@ USBD_StatusTypeDef USBD_LL_SOF(USBD_HandleTypeDef *pdev)
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_IsoINIncomplete
|
* @brief USBD_IsoINIncomplete
|
||||||
* Handle iso in incomplete event
|
* Handle iso in incomplete event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -516,7 +516,7 @@ USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t ep
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_IsoOUTIncomplete
|
* @brief USBD_IsoOUTIncomplete
|
||||||
* Handle iso out incomplete event
|
* Handle iso out incomplete event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -530,7 +530,7 @@ USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t e
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_DevConnected
|
* @brief USBD_DevConnected
|
||||||
* Handle device connection event
|
* Handle device connection event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -542,7 +542,7 @@ USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev)
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief USBD_DevDisconnected
|
* @brief USBD_DevDisconnected
|
||||||
* Handle device disconnection event
|
* Handle device disconnection event
|
||||||
* @param pdev: device instance
|
* @param pdev: device instance
|
||||||
* @retval status
|
* @retval status
|
||||||
|
@ -551,23 +551,23 @@ USBD_StatusTypeDef USBD_LL_DevDisconnected(USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
/* Free Class Resources */
|
/* Free Class Resources */
|
||||||
pdev->dev_state = USBD_STATE_DEFAULT;
|
pdev->dev_state = USBD_STATE_DEFAULT;
|
||||||
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
pdev->pClass->DeInit(pdev, pdev->dev_config);
|
||||||
|
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
||||||
|
|
|
@ -82,11 +82,25 @@ USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
|
||||||
EXCLUDES = usbd_cdc_if_template.c
|
EXCLUDES = usbd_cdc_if_template.c
|
||||||
USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
|
USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
|
||||||
|
|
||||||
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src
|
USBHID_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID
|
||||||
|
USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/Src/*.c))
|
||||||
|
|
||||||
|
USBHIDCDC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_HID
|
||||||
|
USBHIDCDC_SRC = $(notdir $(wildcard $(USBHIDCDC_DIR)/Src/*.c))
|
||||||
|
|
||||||
|
USBMSC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
|
||||||
|
USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c))
|
||||||
|
EXCLUDES = usbd_msc_storage_template.c
|
||||||
|
USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC))
|
||||||
|
|
||||||
|
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBHIDCDC_DIR)/Src:$(USBMSC_DIR)/Src
|
||||||
|
|
||||||
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
|
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
|
||||||
$(USBCORE_SRC) \
|
$(USBCORE_SRC) \
|
||||||
$(USBCDC_SRC)
|
$(USBCDC_SRC) \
|
||||||
|
$(USBHID_SRC) \
|
||||||
|
$(USBHIDCDC_SRC) \
|
||||||
|
$(USBMSC_SRC)
|
||||||
|
|
||||||
#CMSIS
|
#CMSIS
|
||||||
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx
|
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx
|
||||||
|
@ -96,6 +110,9 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(STDPERIPH_DIR)/Inc \
|
$(STDPERIPH_DIR)/Inc \
|
||||||
$(USBCORE_DIR)/Inc \
|
$(USBCORE_DIR)/Inc \
|
||||||
$(USBCDC_DIR)/Inc \
|
$(USBCDC_DIR)/Inc \
|
||||||
|
$(USBHID_DIR)/Inc \
|
||||||
|
$(USBHIDCDC_DIR)/Inc \
|
||||||
|
$(USBMSC_DIR)/Inc \
|
||||||
$(CMSIS_DIR)/Core/Include \
|
$(CMSIS_DIR)/Core/Include \
|
||||||
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
|
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
|
||||||
$(ROOT)/src/main/vcp_hal
|
$(ROOT)/src/main/vcp_hal
|
||||||
|
|
|
@ -39,6 +39,11 @@
|
||||||
#elif defined(STM32F7)
|
#elif defined(STM32F7)
|
||||||
#include "vcp_hal/usbd_cdc_interface.h"
|
#include "vcp_hal/usbd_cdc_interface.h"
|
||||||
#include "usb_io.h"
|
#include "usb_io.h"
|
||||||
|
#ifdef USE_USB_CDC_HID
|
||||||
|
#include "usbd_cdc_hid.h"
|
||||||
|
#include "pg/pg.h"
|
||||||
|
#include "pg/usb.h"
|
||||||
|
#endif
|
||||||
USBD_HandleTypeDef USBD_Device;
|
USBD_HandleTypeDef USBD_Device;
|
||||||
#else
|
#else
|
||||||
#include "usb_core.h"
|
#include "usb_core.h"
|
||||||
|
@ -234,8 +239,16 @@ serialPort_t *usbVcpOpen(void)
|
||||||
USBD_Init(&USBD_Device, &VCP_Desc, 0);
|
USBD_Init(&USBD_Device, &VCP_Desc, 0);
|
||||||
|
|
||||||
/* Add Supported Class */
|
/* Add Supported Class */
|
||||||
USBD_RegisterClass(&USBD_Device, USBD_CDC_CLASS);
|
#ifdef USE_USB_CDC_HID
|
||||||
|
if (usbDevConfig()->type == COMPOSITE) {
|
||||||
|
USBD_RegisterClass(&USBD_Device, USBD_HID_CDC_CLASS);
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
USBD_RegisterClass(&USBD_Device, USBD_CDC_CLASS);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* HID Interface doesn't have any callbacks... */
|
||||||
/* Add CDC Interface Class */
|
/* Add CDC Interface Class */
|
||||||
USBD_CDC_RegisterInterface(&USBD_Device, &USBD_CDC_fops);
|
USBD_CDC_RegisterInterface(&USBD_Device, &USBD_CDC_fops);
|
||||||
|
|
||||||
|
|
|
@ -87,8 +87,13 @@
|
||||||
|
|
||||||
#ifdef USE_USB_CDC_HID
|
#ifdef USE_USB_CDC_HID
|
||||||
//TODO: Make it platform independent in the future
|
//TODO: Make it platform independent in the future
|
||||||
|
#ifdef STM32F4
|
||||||
#include "vcpf4/usbd_cdc_vcp.h"
|
#include "vcpf4/usbd_cdc_vcp.h"
|
||||||
#include "usbd_hid_core.h"
|
#include "usbd_hid_core.h"
|
||||||
|
#elif defined(STM32F7)
|
||||||
|
#include "usbd_cdc_interface.h"
|
||||||
|
#include "usbd_hid.h"
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
|
@ -151,7 +156,12 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
|
||||||
for (int i = 0; i < 8; i++) {
|
for (int i = 0; i < 8; i++) {
|
||||||
report[i] = scaleRange(constrain(rcData[i], 1000, 2000), 1000, 2000, -127, 127);
|
report[i] = scaleRange(constrain(rcData[i], 1000, 2000), 1000, 2000, -127, 127);
|
||||||
}
|
}
|
||||||
|
#ifdef STM32F4
|
||||||
USBD_HID_SendReport(&USB_OTG_dev, (uint8_t*)report, sizeof(report));
|
USBD_HID_SendReport(&USB_OTG_dev, (uint8_t*)report, sizeof(report));
|
||||||
|
#elif defined(STM32F7)
|
||||||
|
extern USBD_HandleTypeDef USBD_Device;
|
||||||
|
USBD_HID_SendReport(&USBD_Device, (uint8_t*)report, sizeof(report));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -107,6 +107,10 @@
|
||||||
#undef USE_USB_MSC
|
#undef USE_USB_MSC
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_VCP)
|
||||||
|
#undef USE_USB_CDC_HID
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
|
#if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
|
||||||
#define USE_USB_ADVANCED_PROFILES
|
#define USE_USB_ADVANCED_PROFILES
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -69,6 +69,7 @@
|
||||||
#define USE_GYRO_DATA_ANALYSE
|
#define USE_GYRO_DATA_ANALYSE
|
||||||
#define USE_OVERCLOCK
|
#define USE_OVERCLOCK
|
||||||
#define USE_ADC_INTERNAL
|
#define USE_ADC_INTERNAL
|
||||||
|
#define USE_USB_CDC_HID
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F4) || defined(STM32F7)
|
||||||
|
|
|
@ -379,7 +379,7 @@ uint32_t CDC_Send_FreeBytes(void)
|
||||||
*/
|
*/
|
||||||
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
|
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
|
||||||
{
|
{
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
|
||||||
while (hcdc->TxState != 0);
|
while (hcdc->TxState != 0);
|
||||||
|
|
||||||
for (uint32_t i = 0; i < sendLength; i++)
|
for (uint32_t i = 0; i < sendLength; i++)
|
||||||
|
|
|
@ -53,6 +53,10 @@
|
||||||
#include "usbd_conf.h"
|
#include "usbd_conf.h"
|
||||||
#include "usbd_cdc_interface.h"
|
#include "usbd_cdc_interface.h"
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
#include "pg/pg.h"
|
||||||
|
#include "pg/usb.h"
|
||||||
|
|
||||||
/* Private typedef -----------------------------------------------------------*/
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
/* Private define ------------------------------------------------------------*/
|
/* Private define ------------------------------------------------------------*/
|
||||||
/* Private macro -------------------------------------------------------------*/
|
/* Private macro -------------------------------------------------------------*/
|
||||||
|
@ -402,9 +406,21 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev)
|
||||||
/* Initialize LL Driver */
|
/* Initialize LL Driver */
|
||||||
HAL_PCD_Init(&hpcd);
|
HAL_PCD_Init(&hpcd);
|
||||||
|
|
||||||
|
#ifdef USE_USB_CDC_HID
|
||||||
|
if (usbDevConfig()->type == COMPOSITE) {
|
||||||
|
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
|
||||||
|
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x20);
|
||||||
|
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x40);
|
||||||
|
HAL_PCDEx_SetTxFiFo(&hpcd, 2, 0x20);
|
||||||
|
HAL_PCDEx_SetTxFiFo(&hpcd, 3, 0x40);
|
||||||
|
} else {
|
||||||
|
#endif /* CDC_HID */
|
||||||
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
|
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
|
||||||
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x40);
|
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x40);
|
||||||
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x80);
|
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x80);
|
||||||
|
#ifdef USE_USB_CDC_HID
|
||||||
|
}
|
||||||
|
#endif /* CDC_HID */
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_USB_HS
|
#ifdef USE_USB_HS
|
||||||
|
|
|
@ -60,12 +60,13 @@
|
||||||
/* Exported types ------------------------------------------------------------*/
|
/* Exported types ------------------------------------------------------------*/
|
||||||
/* Exported constants --------------------------------------------------------*/
|
/* Exported constants --------------------------------------------------------*/
|
||||||
/* Common Config */
|
/* Common Config */
|
||||||
#define USBD_MAX_NUM_INTERFACES 0
|
#define USBD_MAX_NUM_INTERFACES 3
|
||||||
#define USBD_MAX_NUM_CONFIGURATION 1
|
#define USBD_MAX_NUM_CONFIGURATION 1
|
||||||
#define USBD_MAX_STR_DESC_SIZ 0x100
|
#define USBD_MAX_STR_DESC_SIZ 0x100
|
||||||
#define USBD_SUPPORT_USER_STRING 0
|
#define USBD_SUPPORT_USER_STRING 0
|
||||||
#define USBD_SELF_POWERED 1
|
#define USBD_SELF_POWERED 1
|
||||||
#define USBD_DEBUG_LEVEL 0
|
#define USBD_DEBUG_LEVEL 0
|
||||||
|
#define MSC_MEDIA_PACKET 512
|
||||||
#define USE_USB_FS
|
#define USE_USB_FS
|
||||||
|
|
||||||
/* Exported macro ------------------------------------------------------------*/
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
|
|
@ -52,6 +52,8 @@
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
#include "build/version.h"
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#include "pg/pg.h"
|
||||||
|
#include "pg/usb.h"
|
||||||
/* Private typedef -----------------------------------------------------------*/
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
/* Private define ------------------------------------------------------------*/
|
/* Private define ------------------------------------------------------------*/
|
||||||
#define USBD_VID 0x0483
|
#define USBD_VID 0x0483
|
||||||
|
@ -114,6 +116,10 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
|
||||||
USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */
|
USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */
|
||||||
}; /* USB_DeviceDescriptor */
|
}; /* USB_DeviceDescriptor */
|
||||||
|
|
||||||
|
#ifdef USE_USB_CDC_HID
|
||||||
|
extern uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC];
|
||||||
|
#endif
|
||||||
|
|
||||||
/* USB Standard Device Descriptor */
|
/* USB Standard Device Descriptor */
|
||||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||||
#pragma data_alignment=4
|
#pragma data_alignment=4
|
||||||
|
@ -149,6 +155,12 @@ static void Get_SerialNum(void);
|
||||||
uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||||
{
|
{
|
||||||
(void)speed;
|
(void)speed;
|
||||||
|
#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);
|
*length = sizeof(USBD_DeviceDesc);
|
||||||
return (uint8_t*)USBD_DeviceDesc;
|
return (uint8_t*)USBD_DeviceDesc;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue