HAL_F4Light: removed ST licensed files from HAL_F4Light

This commit is contained in:
Andrew Tridgell 2018-06-14 16:13:07 +10:00
parent c0bfc77701
commit 5d20699975
46 changed files with 0 additions and 13889 deletions

View File

@ -1 +0,0 @@
this is NOT generic driver from ST, but fixed two bugs

View File

@ -1,20 +0,0 @@
#pragma once
/*
* IAR specific functions for IRQ disable/enable
*/
typedef __istate_t atomic_t;
static inline atomic_t atomic_begin(void)
{
__istate_t a = __get_interrupt_state();
__disable_interrupt();
return a;
}
static inline void atomic_end(atomic_t a)
{
__set_interrupt_state(a);
}

View File

@ -1,4 +0,0 @@
#pragma once
#define MIN_(a, b) (a) < (b) ? (a) : (b)
#define MAX_(a, b) (a) > (b) ? (a) : (b)

View File

@ -1,54 +0,0 @@
#pragma once
/*
* Ring buffer implementation helpers
*/
/* Wrap up buffer index */
static inline unsigned ring_wrap(unsigned size, unsigned idx)
{
return idx >= size ? idx - size : idx;
}
/* Returns the number of bytes available in buffer */
static inline unsigned ring_data_avail(unsigned size, unsigned head, unsigned tail)
{
if (head >= tail)
return head - tail;
else
return size + head - tail;
}
/* Returns the amount of free space available in buffer */
static inline unsigned ring_space_avail(unsigned size, unsigned head, unsigned tail)
{
return size - ring_data_avail(size, head, tail) - 1;
}
/* Returns the number of contiguous data bytes available in buffer */
static inline unsigned ring_data_contig(unsigned size, unsigned head, unsigned tail)
{
if (head >= tail)
return head - tail;
else
return size - tail;
}
/* Returns the amount of contiguous space available in buffer */
static inline unsigned ring_space_contig(unsigned size, unsigned head, unsigned tail)
{
if (head >= tail)
return (tail ? size : size - 1) - head;
else
return tail - head - 1;
}
/* Returns the amount of free space available after wrapping up the head */
static inline unsigned ring_space_wrapped(unsigned size, unsigned head, unsigned tail)
{
if (head < tail || !tail)
return 0;
else
return tail - 1;
}

View File

@ -1,42 +0,0 @@
# Standard things
sp := $(sp).x
dirstack_$(sp) := $(d)
d := $(dir)
BUILDDIRS += $(BUILD_PATH)/$(d)
LIBRARY_INCLUDES += -I$(STM32USB_PATH)
# Local flags
CFLAGS_$(d) =
STM_DIR := AP_HAL_F4Light/hardware/STM32_USB_Driver
# Local rules and targets
cSRCS_$(d) :=
cSRCS_$(d) += $(STM_DIR)/usb_core.c
cSRCS_$(d) += $(STM_DIR)/usb_dcd.c
cSRCS_$(d) += $(STM_DIR)/usb_dcd_int.c
cSRCS_$(d) += $(STM_DIR)/usbd_cdc_core.c
cSRCS_$(d) += $(STM_DIR)/usbd_core.c
cSRCS_$(d) += $(STM_DIR)/usbd_ioreq.c
cSRCS_$(d) += $(STM_DIR)/usbd_req.c
sSRCS_$(d) :=
cppSRCS_$(d) :=
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
OBJS_$(d) := $(cFILES_$(d):%.c=$(LIBRARIES_PATH)/%.o)
OBJS_$(d) += $(sFILES_$(d):%.s=$(LIBRARIES_PATH)/%.o)
DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
$(OBJS_$(d)): TGT_ASFLAGS :=
TGT_BIN += $(OBJS_$(d))
# Standard things
-include $(DEPS_$(d))
d := $(dirstack_$(sp))
sp := $(basename $(sp))

View File

@ -1,103 +0,0 @@
/**
******************************************************************************
* @file usb_bsp.h
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Specific api's relative to the used hardware platform
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_BSP__H__
#define __USB_BSP__H__
/* Includes ------------------------------------------------------------------*/
#include "usb_core.h"
#include "usb_conf.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_BSP
* @brief This file is the
* @{
*/
/** @defgroup USB_BSP_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_BSP_Exported_FunctionsPrototype
* @{
*/
void BSP_Init(void);
void USB_OTG_BSP_Init (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_BSP_uDelay (const uint32_t usec);
void USB_OTG_BSP_mDelay (const uint32_t msec);
void USB_OTG_BSP_EnableInterrupt (USB_OTG_CORE_HANDLE *pdev);
#ifdef USE_HOST_MODE
void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state);
#endif
/**
* @}
*/
#endif //__USB_BSP__H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

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

File diff suppressed because it is too large Load Diff

View File

@ -1,417 +0,0 @@
/**
******************************************************************************
* @file usb_core.h
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Header of the Core Layer
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CORE_H__
#define __USB_CORE_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
#include "usb_regs.h"
#include "usb_defines.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_CORE
* @brief usb otg driver core layer
* @{
*/
/** @defgroup USB_CORE_Exported_Defines
* @{
*/
#define USB_OTG_EP0_IDLE 0
#define USB_OTG_EP0_SETUP 1
#define USB_OTG_EP0_DATA_IN 2
#define USB_OTG_EP0_DATA_OUT 3
#define USB_OTG_EP0_STATUS_IN 4
#define USB_OTG_EP0_STATUS_OUT 5
#define USB_OTG_EP0_STALL 6
#define USB_OTG_EP_TX_DIS 0x0000
#define USB_OTG_EP_TX_STALL 0x0010
#define USB_OTG_EP_TX_NAK 0x0020
#define USB_OTG_EP_TX_VALID 0x0030
#define USB_OTG_EP_RX_DIS 0x0000
#define USB_OTG_EP_RX_STALL 0x1000
#define USB_OTG_EP_RX_NAK 0x2000
#define USB_OTG_EP_RX_VALID 0x3000
/**
* @}
*/
#define MAX_DATA_LENGTH 0x200
/** @defgroup USB_CORE_Exported_Types
* @{
*/
typedef enum {
USB_OTG_OK = 0,
USB_OTG_FAIL
}USB_OTG_STS;
typedef enum {
HC_IDLE = 0,
HC_XFRC,
HC_HALTED,
HC_NAK,
HC_NYET,
HC_STALL,
HC_XACTERR,
HC_BBLERR,
HC_DATATGLERR,
}HC_STATUS;
typedef enum {
URB_IDLE = 0,
URB_DONE,
URB_NOTREADY,
URB_ERROR,
URB_STALL
}URB_STATE;
typedef enum {
CTRL_START = 0,
CTRL_XFRC,
CTRL_HALTED,
CTRL_NAK,
CTRL_STALL,
CTRL_XACTERR,
CTRL_BBLERR,
CTRL_DATATGLERR,
CTRL_FAIL
}CTRL_STATUS;
typedef struct USB_OTG_hc
{
uint8_t dev_addr ;
uint8_t ep_num;
uint8_t ep_is_in;
uint8_t speed;
uint8_t do_ping;
uint8_t ep_type;
uint16_t max_packet;
uint8_t data_pid;
uint8_t *xfer_buff;
uint32_t xfer_len;
uint32_t xfer_count;
uint8_t toggle_in;
uint8_t toggle_out;
uint32_t dma_addr;
}
USB_OTG_HC , *PUSB_OTG_HC;
typedef struct USB_OTG_ep
{
uint8_t num;
uint8_t is_in;
uint8_t is_stall;
uint8_t type;
uint8_t data_pid_start;
uint8_t even_odd_frame;
uint16_t tx_fifo_num;
uint32_t maxpacket;
/* transaction level variables*/
uint8_t *xfer_buff;
uint32_t dma_addr;
uint32_t xfer_len;
uint32_t xfer_count;
/* Transfer level variables*/
uint32_t rem_data_len;
uint32_t total_data_len;
uint32_t ctl_data_len;
}
USB_OTG_EP , *PUSB_OTG_EP;
typedef struct USB_OTG_core_cfg
{
uint8_t host_channels;
uint8_t dev_endpoints;
uint8_t speed;
uint8_t dma_enable;
uint16_t mps;
uint16_t TotalFifoSize;
uint8_t phy_itface;
uint8_t Sof_output;
uint8_t low_power;
uint8_t coreID;
}
USB_OTG_CORE_CFGS, *PUSB_OTG_CORE_CFGS;
typedef struct usb_setup_req {
uint8_t bmRequest;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} USB_SETUP_REQ;
typedef struct _Device_TypeDef
{
uint8_t *(*GetDeviceDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetLangIDStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetManufacturerStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetProductStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetSerialStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetConfigurationStrDescriptor)( uint8_t speed , uint16_t *length);
uint8_t *(*GetInterfaceStrDescriptor)( uint8_t speed , uint16_t *length);
} USBD_DEVICE, *pUSBD_DEVICE;
//typedef struct USB_OTG_hPort
//{
// void (*Disconnect) (void *phost);
// void (*Connect) (void *phost);
// uint8_t ConnStatus;
// uint8_t DisconnStatus;
// uint8_t ConnHandled;
// uint8_t DisconnHandled;
//} USB_OTG_hPort_TypeDef;
typedef struct _Device_cb
{
uint8_t (*Init) (void *pdev , uint8_t cfgidx);
uint8_t (*DeInit) (void *pdev , uint8_t cfgidx);
/* Control Endpoints*/
uint8_t (*Setup) (void *pdev , USB_SETUP_REQ *req);
uint8_t (*EP0_TxSent) (void *pdev );
uint8_t (*EP0_RxReady) (void *pdev );
/* Class Specific Endpoints*/
uint8_t (*DataIn) (void *pdev , uint8_t epnum);
uint8_t (*DataOut) (void *pdev , uint8_t epnum);
uint8_t (*SOF) (void *pdev);
uint8_t (*IsoINIncomplete) (void *pdev);
uint8_t (*IsoOUTIncomplete) (void *pdev);
uint8_t *(*GetConfigDescriptor)( uint8_t speed , uint16_t *length);
#ifdef USB_OTG_HS_CORE
uint8_t *(*GetOtherConfigDescriptor)( uint8_t speed , uint16_t *length);
#endif
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t *(*GetUsrStrDescriptor)( uint8_t speed ,uint8_t index, uint16_t *length);
#endif
} USBD_Class_cb_TypeDef;
typedef struct _USBD_USR_PROP
{
void (*Init)(void);
void (*DeviceReset)(uint8_t speed);
void (*DeviceConfigured)(void);
void (*DeviceSuspended)(void);
void (*DeviceResumed)(void);
void (*DeviceConnected)(void);
void (*DeviceDisconnected)(void);
}
USBD_Usr_cb_TypeDef;
typedef struct _DCD
{
uint8_t device_config;
uint8_t device_state;
uint8_t device_status;
uint8_t device_old_status;
uint8_t device_address;
uint8_t connection_status;
uint8_t test_mode;
uint32_t DevRemoteWakeup;
USB_OTG_EP in_ep [USB_OTG_MAX_TX_FIFOS];
USB_OTG_EP out_ep [USB_OTG_MAX_TX_FIFOS];
uint8_t setup_packet [8*3];
const USBD_Class_cb_TypeDef *class_cb;
const USBD_Usr_cb_TypeDef *usr_cb;
const USBD_DEVICE *usr_device;
uint8_t *pConfig_descriptor;
}
DCD_DEV , *DCD_PDEV;
typedef struct _HCD
{
uint8_t Rx_Buffer [MAX_DATA_LENGTH];
__IO uint32_t ConnSts;
__IO uint32_t ErrCnt[USB_OTG_MAX_TX_FIFOS];
__IO uint32_t XferCnt[USB_OTG_MAX_TX_FIFOS];
__IO HC_STATUS HC_Status[USB_OTG_MAX_TX_FIFOS];
__IO URB_STATE URB_State[USB_OTG_MAX_TX_FIFOS];
USB_OTG_HC hc [USB_OTG_MAX_TX_FIFOS];
uint16_t channel [USB_OTG_MAX_TX_FIFOS];
// USB_OTG_hPort_TypeDef *port_cb;
}
HCD_DEV , *USB_OTG_USBH_PDEV;
typedef struct _OTG
{
uint8_t OTG_State;
uint8_t OTG_PrevState;
uint8_t OTG_Mode;
}
OTG_DEV , *USB_OTG_USBO_PDEV;
typedef struct USB_OTG_handle
{
USB_OTG_CORE_CFGS cfg;
USB_OTG_CORE_REGS regs;
#ifdef USE_DEVICE_MODE
DCD_DEV dev;
#endif
#ifdef USE_HOST_MODE
HCD_DEV host;
#endif
#ifdef USE_OTG_MODE
OTG_DEV otg;
#endif
}
USB_OTG_CORE_HANDLE , *PUSB_OTG_CORE_HANDLE;
/**
* @}
*/
/** @defgroup USB_CORE_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CORE_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CORE_Exported_FunctionsPrototype
* @{
*/
USB_OTG_STS USB_OTG_CoreInit (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_SelectCore (USB_OTG_CORE_HANDLE *pdev,
const USB_OTG_CORE_ID_TypeDef coreID);
USB_OTG_STS USB_OTG_EnableGlobalInt (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_DisableGlobalInt(USB_OTG_CORE_HANDLE *pdev);
void* USB_OTG_ReadPacket (USB_OTG_CORE_HANDLE *pdev ,
uint8_t *dest,
uint16_t len);
USB_OTG_STS USB_OTG_WritePacket (USB_OTG_CORE_HANDLE *pdev ,
const uint8_t *src,
uint8_t ch_ep_num,
uint16_t len);
USB_OTG_STS USB_OTG_FlushTxFifo (USB_OTG_CORE_HANDLE *pdev , uint32_t num);
USB_OTG_STS USB_OTG_FlushRxFifo (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadCoreItr (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadOtgItr (USB_OTG_CORE_HANDLE *pdev);
uint8_t USB_OTG_IsHostMode (USB_OTG_CORE_HANDLE *pdev);
uint8_t USB_OTG_IsDeviceMode (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_GetMode (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_PhyInit (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_SetCurrentMode (USB_OTG_CORE_HANDLE *pdev,
uint8_t mode);
/*********************** HOST APIs ********************************************/
#ifdef USE_HOST_MODE
USB_OTG_STS USB_OTG_CoreInitHost (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EnableHostInt (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_HC_Init (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
USB_OTG_STS USB_OTG_HC_Halt (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
USB_OTG_STS USB_OTG_HC_StartXfer (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
USB_OTG_STS USB_OTG_HC_DoPing (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num);
uint32_t USB_OTG_ReadHostAllChannels_intr (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ResetPort (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadHPRT0 (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_DriveVbus (USB_OTG_CORE_HANDLE *pdev, uint8_t state);
void USB_OTG_InitFSLSPClkSel (USB_OTG_CORE_HANDLE *pdev ,uint8_t freq);
uint8_t USB_OTG_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev) ;
void USB_OTG_StopHost (USB_OTG_CORE_HANDLE *pdev);
#endif
/********************* DEVICE APIs ********************************************/
#ifdef USE_DEVICE_MODE
USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EnableDevInt (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadDevAllInEPItr (USB_OTG_CORE_HANDLE *pdev);
enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed(USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EP0Activate (USB_OTG_CORE_HANDLE *pdev);
USB_OTG_STS USB_OTG_EPActivate (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPDeactivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPStartXfer (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EP0StartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPSetStall (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
USB_OTG_STS USB_OTG_EPClearStall (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
uint32_t USB_OTG_ReadDevAllOutEp_itr (USB_OTG_CORE_HANDLE *pdev);
uint32_t USB_OTG_ReadDevOutEP_itr (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
uint32_t USB_OTG_ReadDevAllInEPItr (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_InitDevSpeed (USB_OTG_CORE_HANDLE *pdev , uint8_t speed);
uint8_t USBH_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_EP0_OutStart(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_ActiveRemoteWakeup(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_UngateClock(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev);
void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t Status);
uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep);
#endif
/**
* @}
*/
#endif /* __USB_CORE_H__ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,478 +0,0 @@
/**
******************************************************************************
* @file usb_dcd.c
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Peripheral Device Interface Layer
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd.h"
#include "usb_bsp.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD
* @brief This file is the interface between EFSL ans Host mass-storage class
* @{
*/
/** @defgroup USB_DCD_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Private_Functions
* @{
*/
void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
USB_OTG_CORE_ID_TypeDef coreID)
{
uint32_t i;
USB_OTG_EP *ep;
USB_OTG_SelectCore (pdev , coreID);
pdev->dev.device_status = USB_OTG_DEFAULT;
pdev->dev.device_address = 0;
/* Init ep structure */
for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
{
ep = &pdev->dev.in_ep[i];
/* Init ep structure */
ep->is_in = 1;
ep->num = i;
ep->tx_fifo_num = i;
/* Control until ep is actvated */
ep->type = EP_TYPE_CTRL;
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
ep->xfer_buff = 0;
ep->xfer_len = 0;
}
for (i = 0; i < pdev->cfg.dev_endpoints; i++)
{
ep = &pdev->dev.out_ep[i];
/* Init ep structure */
ep->is_in = 0;
ep->num = i;
ep->tx_fifo_num = i;
/* Control until ep is activated */
ep->type = EP_TYPE_CTRL;
ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
ep->xfer_buff = 0;
ep->xfer_len = 0;
}
USB_OTG_DisableGlobalInt(pdev);
/*Init the Core (common init.) */
USB_OTG_CoreInit(pdev);
/* Force Device Mode*/
USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
/* Init Device */
USB_OTG_CoreInitDev(pdev);
/* Enable USB Global interrupt */
USB_OTG_EnableGlobalInt(pdev);
}
/**
* @brief Configure an EP
* @param pdev : Device instance
* @param epdesc : Endpoint Descriptor
* @retval : status
*/
uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev ,
uint8_t ep_addr,
uint16_t ep_mps,
uint8_t ep_type)
{
USB_OTG_EP *ep;
if ((ep_addr & 0x80) == 0x80)
{
ep = &pdev->dev.in_ep[ep_addr & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[ep_addr & 0x7F];
}
ep->num = ep_addr & 0x7F;
ep->is_in = (0x80 & ep_addr) != 0;
ep->maxpacket = ep_mps;
ep->type = ep_type;
if (ep->is_in)
{
/* Assign a Tx FIFO */
ep->tx_fifo_num = ep->num;
}
/* Set initial data PID. */
if (ep_type == USB_OTG_EP_BULK )
{
ep->data_pid_start = 0;
}
USB_OTG_EPActivate(pdev , ep );
return 0;
}
/**
* @brief called when an EP is disabled
* @param pdev: device instance
* @param ep_addr: endpoint address
* @retval : status
*/
uint32_t DCD_EP_Close(USB_OTG_CORE_HANDLE *pdev , uint8_t ep_addr)
{
USB_OTG_EP *ep;
if ((ep_addr&0x80) == 0x80)
{
ep = &pdev->dev.in_ep[ep_addr & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[ep_addr & 0x7F];
}
ep->num = ep_addr & 0x7F;
ep->is_in = (0x80 & ep_addr) != 0;
USB_OTG_EPDeactivate(pdev , ep );
return 0;
}
/**
* @brief DCD_EP_PrepareRx
* @param pdev: device instance
* @param ep_addr: endpoint address
* @param pbuf: pointer to Rx buffer
* @param buf_len: data length
* @retval : status
*/
uint32_t DCD_EP_PrepareRx(USB_OTG_CORE_HANDLE *pdev,
uint8_t ep_addr,
uint8_t *pbuf,
uint16_t buf_len)
{
USB_OTG_EP *ep;
ep = &pdev->dev.out_ep[ep_addr & 0x7F];
/*setup and start the Xfer */
ep->xfer_buff = pbuf;
ep->xfer_len = buf_len;
ep->xfer_count = 0;
ep->is_in = 0;
ep->num = ep_addr & 0x7F;
if (pdev->cfg.dma_enable == 1)
{
ep->dma_addr = (uint32_t)pbuf;
}
if ( ep->num == 0 )
{
USB_OTG_EP0StartXfer(pdev , ep);
}
else
{
USB_OTG_EPStartXfer(pdev, ep );
}
return 0;
}
/**
* @brief Transmit data over USB
* @param pdev: device instance
* @param ep_addr: endpoint address
* @param pbuf: pointer to Tx buffer
* @param buf_len: data length
* @retval : status
*/
uint32_t DCD_EP_Tx (USB_OTG_CORE_HANDLE *pdev,
uint8_t ep_addr,
uint8_t *pbuf,
uint32_t buf_len)
{
USB_OTG_EP *ep;
ep = &pdev->dev.in_ep[ep_addr & 0x7F];
/* Setup and start the Transfer */
ep->is_in = 1;
ep->num = ep_addr & 0x7F;
ep->xfer_buff = pbuf;
ep->dma_addr = (uint32_t)pbuf;
ep->xfer_count = 0;
ep->xfer_len = buf_len;
if ( ep->num == 0 )
{
USB_OTG_EP0StartXfer(pdev , ep);
}
else
{
USB_OTG_EPStartXfer(pdev, ep );
}
return 0;
}
/**
* @brief Stall an endpoint.
* @param pdev: device instance
* @param epnum: endpoint address
* @retval : status
*/
uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
USB_OTG_EP *ep;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
ep->is_stall = 1;
ep->num = epnum & 0x7F;
ep->is_in = ((epnum & 0x80) == 0x80);
USB_OTG_EPSetStall(pdev , ep);
return (0);
}
/**
* @brief Clear stall condition on endpoints.
* @param pdev: device instance
* @param epnum: endpoint address
* @retval : status
*/
uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
USB_OTG_EP *ep;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
ep->is_stall = 0;
ep->num = epnum & 0x7F;
ep->is_in = ((epnum & 0x80) == 0x80);
USB_OTG_EPClearStall(pdev , ep);
return (0);
}
/**
* @brief This Function flushes the FIFOs.
* @param pdev: device instance
* @param epnum: endpoint address
* @retval : status
*/
uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
{
if ((epnum & 0x80) == 0x80)
{
USB_OTG_FlushTxFifo(pdev, epnum & 0x7F);
}
else
{
USB_OTG_FlushRxFifo(pdev);
}
return (0);
}
/**
* @brief This Function set USB device address
* @param pdev: device instance
* @param address: new device address
* @retval : status
*/
void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev, uint8_t address)
{
USB_OTG_DCFG_TypeDef dcfg;
dcfg.d32 = 0;
dcfg.b.devaddr = address;
USB_OTG_MODIFY_REG32( &pdev->regs.DREGS->DCFG, 0, dcfg.d32);
}
/**
* @brief Connect device (enable internal pull-up)
* @param pdev: device instance
* @retval : None
*/
void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev)
{
#ifndef USE_OTG_MODE
USB_OTG_DCTL_TypeDef dctl;
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
/* Connect device */
dctl.b.sftdiscon = 0;
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
USB_OTG_BSP_mDelay(3);
#endif
}
/**
* @brief Disconnect device (disable internal pull-up)
* @param pdev: device instance
* @retval : None
*/
void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev)
{
#ifndef USE_OTG_MODE
USB_OTG_DCTL_TypeDef dctl;
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
/* Disconnect device for 3ms */
dctl.b.sftdiscon = 1;
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
USB_OTG_BSP_mDelay(3);
#endif
}
/**
* @brief returns the EP Status
* @param pdev : Selected device
* epnum : endpoint address
* @retval : EP status
*/
uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,uint8_t epnum)
{
USB_OTG_EP *ep;
uint32_t Status = 0;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
Status = USB_OTG_GetEPStatus(pdev ,ep);
/* Return the current status */
return Status;
}
/**
* @brief Set the EP Status
* @param pdev : Selected device
* Status : new Status
* epnum : EP address
* @retval : None
*/
void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Status)
{
USB_OTG_EP *ep;
if ((0x80 & epnum) == 0x80)
{
ep = &pdev->dev.in_ep[epnum & 0x7F];
}
else
{
ep = &pdev->dev.out_ep[epnum];
}
USB_OTG_SetEPStatus(pdev ,ep , Status);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,164 +0,0 @@
/**
******************************************************************************
* @file usb_dcd.h
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Peripheral Driver Header file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __DCD_H__
#define __DCD_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_core.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD
* @brief This file is the
* @{
*/
/** @defgroup USB_DCD_Exported_Defines
* @{
*/
#define USB_OTG_EP_CONTROL 0
#define USB_OTG_EP_ISOC 1
#define USB_OTG_EP_BULK 2
#define USB_OTG_EP_INT 3
#define USB_OTG_EP_MASK 3
/* Device Status */
#define USB_OTG_DEFAULT 1
#define USB_OTG_ADDRESSED 2
#define USB_OTG_CONFIGURED 3
#define USB_OTG_SUSPENDED 4
/**
* @}
*/
/** @defgroup USB_DCD_Exported_Types
* @{
*/
/********************************************************************************
Data structure type
********************************************************************************/
typedef struct
{
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint16_t wMaxPacketSize;
uint8_t bInterval;
}
EP_DESCRIPTOR , *PEP_DESCRIPTOR;
/**
* @}
*/
/** @defgroup USB_DCD_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_Exported_FunctionsPrototype
* @{
*/
/********************************************************************************
EXPORTED FUNCTION FROM THE USB-OTG LAYER
********************************************************************************/
void DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
USB_OTG_CORE_ID_TypeDef coreID);
void DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev);
void DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev);
void DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev,
uint8_t address);
uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev ,
uint8_t ep_addr,
uint16_t ep_mps,
uint8_t ep_type);
uint32_t DCD_EP_Close (USB_OTG_CORE_HANDLE *pdev,
uint8_t ep_addr);
uint32_t DCD_EP_PrepareRx (USB_OTG_CORE_HANDLE *pdev,
uint8_t ep_addr,
uint8_t *pbuf,
uint16_t buf_len);
uint32_t DCD_EP_Tx (USB_OTG_CORE_HANDLE *pdev,
uint8_t ep_addr,
uint8_t *pbuf,
uint32_t buf_len);
uint32_t DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
uint32_t DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
uint32_t DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
uint32_t DCD_Handle_ISR(USB_OTG_CORE_HANDLE *pdev);
uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,
uint8_t epnum);
void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev ,
uint8_t epnum ,
uint32_t Status);
/**
* @}
*/
#endif //__DCD_H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,904 +0,0 @@
/**
******************************************************************************
* @file usb_dcd_int.c
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Peripheral Device interrupt subroutines
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
//#pragma GCC optimize ("Og")
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd_int.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD_INT
* @brief This file contains the interrupt subroutines for the Device mode.
* @{
*/
/** @defgroup USB_DCD_INT_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_FunctionPrototypes
* @{
*/
/* static functions */
static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum);
/* Interrupt Handlers */
static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev , uint32_t epnum);
static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
#ifdef VBUS_SENSING_ENABLED
static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev);
#endif
/**
* @}
*/
/** @defgroup USB_DCD_INT_Private_Functions
* @{
*/
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
/**
* @brief USBD_OTG_EP1OUT_ISR_Handler
* handles all USB Interrupts
* @param pdev: device instance
* @retval status
*/
uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DOEPINTn_TypeDef doepint;
USB_OTG_DEPXFRSIZ_TypeDef deptsiz;
doepint.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[1]->DOEPINT);
doepint.d32&= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOUTEP1MSK);
/* Transfer complete */
if ( doepint.b.xfercompl )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(1, xfercompl);
if (pdev->cfg.dma_enable == 1)
{
deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[1]->DOEPTSIZ));
/*ToDo : handle more than one single MPS size packet */
pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].maxpacket - \
deptsiz.b.xfersize;
}
/* Inform upper layer: data ready */
/* RX COMPLETE */
USBD_DCD_INT_fops->DataOutStage(pdev , 1);
}
/* Endpoint disable */
if ( doepint.b.epdisabled )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(1, epdisabled);
}
return 1;
}
/**
* @brief USBD_OTG_EP1IN_ISR_Handler
* handles all USB Interrupts
* @param pdev: device instance
* @retval status
*/
uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DIEPINTn_TypeDef diepint;
uint32_t fifoemptymsk, msk, emp;
msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DINEP1MSK);
emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
msk |= ((emp >> 1 ) & 0x1) << 7;
diepint.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[1]->DIEPINT) & msk;
if ( diepint.b.xfercompl )
{
fifoemptymsk = 0x1 << 1;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
CLEAR_IN_EP_INTR(1, xfercompl);
/* TX COMPLETE */
USBD_DCD_INT_fops->DataInStage(pdev , 1);
}
if ( diepint.b.epdisabled )
{
CLEAR_IN_EP_INTR(1, epdisabled);
}
if ( diepint.b.timeout )
{
CLEAR_IN_EP_INTR(1, timeout);
}
if (diepint.b.intktxfemp)
{
CLEAR_IN_EP_INTR(1, intktxfemp);
}
if (diepint.b.inepnakeff)
{
CLEAR_IN_EP_INTR(1, inepnakeff);
}
if (diepint.b.emptyintr)
{
DCD_WriteEmptyTxFifo(pdev , 1);
CLEAR_IN_EP_INTR(1, emptyintr);
}
return 1;
}
#endif
/**
* @brief STM32_USBF_OTG_ISR_Handler
* handles all USB Interrupts
* @param pdev: device instance
* @retval status
*/
uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintr_status;
uint32_t retval = 0;
if (USB_OTG_IsDeviceMode(pdev)) { /* ensure that we are in device mode */
gintr_status.d32 = USB_OTG_ReadCoreItr(pdev);
//40000
if (!gintr_status.d32) /* avoid spurious interrupt */
{
return 0;
}
if (gintr_status.b.outepintr)
{
retval |= DCD_HandleOutEP_ISR(pdev);
}
if (gintr_status.b.inepint)
{
retval |= DCD_HandleInEP_ISR(pdev);
}
if (gintr_status.b.modemismatch)
{
USB_OTG_GINTSTS_TypeDef gintsts;
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.modemismatch = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
}
if (gintr_status.b.wkupintr)
{
retval |= DCD_HandleResume_ISR(pdev);
}
if (gintr_status.b.usbsuspend)
{
retval |= DCD_HandleUSBSuspend_ISR(pdev);
}
if (gintr_status.b.sofintr)
{
retval |= DCD_HandleSof_ISR(pdev);
}
if (gintr_status.b.rxstsqlvl)
{
retval |= DCD_HandleRxStatusQueueLevel_ISR(pdev);
}
if (gintr_status.b.usbreset)
{
retval |= DCD_HandleUsbReset_ISR(pdev);
}
if (gintr_status.b.enumdone)
{
retval |= DCD_HandleEnumDone_ISR(pdev);
}
if (gintr_status.b.incomplisoin)
{
retval |= DCD_IsoINIncomplete_ISR(pdev);
}
if (gintr_status.b.incomplisoout)
{
retval |= DCD_IsoOUTIncomplete_ISR(pdev);
}
#ifdef VBUS_SENSING_ENABLED
if (gintr_status.b.sessreqintr)
{
retval |= DCD_SessionRequest_ISR(pdev);
}
if (gintr_status.b.otgintr)
{
retval |= DCD_OTG_ISR(pdev);
}
#endif
} // not device mode - don't do anything BUGBUGBUG!!! We MUST clear all available sources of interrupt or program will hang
else { //[ @NG
#define USB_OTG_GAHBCFG_GINT_Pos (0U)
#define USB_OTG_GAHBCFG_GINT_Msk (0x1U << USB_OTG_GAHBCFG_GINT_Pos) /*!< 0x00000001 */
#define USB_OTG_GAHBCFG_GINT USB_OTG_GAHBCFG_GINT_Msk /*!< Global interrupt mask */
*(__IO uint32_t *)(&pdev->regs.GREGS->GAHBCFG) &= USB_OTG_GAHBCFG_GINT; // disable global interrupt - from F4 Arduino
/* Clear ALL interrupts */
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, 0xffffffff);
/*
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, 0xffffffff);
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DAINT, 0xffffffff);
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DEACHINT, 0xffffffff);
USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 0xffffffff);
uint8_t i;
for(i=0;i<USB_OTG_MAX_TX_FIFOS; i++){
USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[i]->DIEPINT, 0xffffffff);
USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xffffffff);
USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[i]->HCINT, 0xffffffff);
}
*/
} //]
return retval;
}
#ifdef VBUS_SENSING_ENABLED
/**
* @brief DCD_SessionRequest_ISR
* Indicates that the USB_OTG controller has detected a connection
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USBD_DCD_INT_fops->DevConnected (pdev);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.sessreqintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief DCD_OTG_ISR
* Indicates that the USB_OTG controller has detected an OTG event:
* used to detect the end of session i.e. disconnection
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GOTGINT_TypeDef gotgint;
gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
if (gotgint.b.sesenddet)
{
USBD_DCD_INT_fops->DevDisconnected (pdev);
}
/* Clear OTG interrupt */
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32);
return 1;
}
#endif
/**
* @brief DCD_HandleResume_ISR
* Indicates that the USB_OTG controller has detected a resume or
* remote Wake-up sequence
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_DCTL_TypeDef devctl;
USB_OTG_PCGCCTL_TypeDef power;
if(pdev->cfg.low_power)
{
/* un-gate USB Core clock */
power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL);
power.b.gatehclk = 0;
power.b.stoppclk = 0;
USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32);
}
/* Clear the Remote Wake-up Signaling */
devctl.d32 = 0;
devctl.b.rmtwkupsig = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, devctl.d32, 0);
/* Inform upper layer by the Resume Event */
USBD_DCD_INT_fops->Resume (pdev);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.wkupintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief USB_OTG_HandleUSBSuspend_ISR
* Indicates that SUSPEND state has been detected on the USB
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_PCGCCTL_TypeDef power;
USB_OTG_DSTS_TypeDef dsts;
__IO uint8_t prev_status = 0;
prev_status = pdev->dev.device_status;
USBD_DCD_INT_fops->Suspend (pdev);
dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.usbsuspend = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
if((pdev->cfg.low_power) && (dsts.b.suspsts == 1) &&
(pdev->dev.connection_status == 1) &&
(prev_status == USB_OTG_CONFIGURED))
{
/* switch-off the clocks */
power.d32 = 0;
power.b.stoppclk = 1;
USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
power.b.gatehclk = 1;
USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
/* Request to enter Sleep mode after exit from current ISR */
SCB->SCR |= (SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk);
}
return 1;
}
/**
* @brief DCD_HandleInEP_ISR
* Indicates that an IN EP has a pending Interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DIEPINTn_TypeDef diepint;
uint32_t ep_intr;
uint32_t epnum = 0;
uint32_t fifoemptymsk;
diepint.d32 = 0;
ep_intr = USB_OTG_ReadDevAllInEPItr(pdev);
while ( ep_intr )
{
if (ep_intr&0x1) /* In ITR */
{
diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */
if ( diepint.b.xfercompl )
{
fifoemptymsk = 0x1 << epnum;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
CLEAR_IN_EP_INTR(epnum, xfercompl);
/* TX COMPLETE */
USBD_DCD_INT_fops->DataInStage(pdev , epnum);
if (pdev->cfg.dma_enable == 1)
{
if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_IN))
{
/* prepare to rx more setup packets */
USB_OTG_EP0_OutStart(pdev);
}
}
}
if ( diepint.b.timeout )
{
CLEAR_IN_EP_INTR(epnum, timeout);
}
if (diepint.b.intktxfemp)
{
CLEAR_IN_EP_INTR(epnum, intktxfemp);
}
if (diepint.b.inepnakeff)
{
CLEAR_IN_EP_INTR(epnum, inepnakeff);
}
if ( diepint.b.epdisabled )
{
CLEAR_IN_EP_INTR(epnum, epdisabled);
}
if (diepint.b.emptyintr)
{
DCD_WriteEmptyTxFifo(pdev , epnum);
CLEAR_IN_EP_INTR(epnum, emptyintr);
}
}
epnum++;
ep_intr >>= 1;
}
return 1;
}
/**
* @brief DCD_HandleOutEP_ISR
* Indicates that an OUT EP has a pending Interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev)
{
uint32_t ep_intr;
USB_OTG_DOEPINTn_TypeDef doepint;
USB_OTG_DEPXFRSIZ_TypeDef deptsiz;
uint32_t epnum = 0;
doepint.d32 = 0;
/* Read in the device interrupt bits */
ep_intr = USB_OTG_ReadDevAllOutEp_itr(pdev);
while ( ep_intr )
{
if (ep_intr&0x1)
{
doepint.d32 = USB_OTG_ReadDevOutEP_itr(pdev, epnum);
/* Transfer complete */
if ( doepint.b.xfercompl )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(epnum, xfercompl);
if (pdev->cfg.dma_enable == 1)
{
deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[epnum]->DOEPTSIZ));
/*ToDo : handle more than one single MPS size packet */
pdev->dev.out_ep[epnum].xfer_count = pdev->dev.out_ep[epnum].maxpacket - \
deptsiz.b.xfersize;
}
/* Inform upper layer: data ready */
/* RX COMPLETE */
USBD_DCD_INT_fops->DataOutStage(pdev , epnum);
if (pdev->cfg.dma_enable == 1)
{
if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_OUT))
{
/* prepare to rx more setup packets */
USB_OTG_EP0_OutStart(pdev);
}
}
}
/* Endpoint disable */
if ( doepint.b.epdisabled )
{
/* Clear the bit in DOEPINTn for this interrupt */
CLEAR_OUT_EP_INTR(epnum, epdisabled);
}
/* Setup Phase Done (control EPs) */
if ( doepint.b.setup )
{
/* inform the upper layer that a setup packet is available */
/* SETUP COMPLETE */
USBD_DCD_INT_fops->SetupStage(pdev);
CLEAR_OUT_EP_INTR(epnum, setup);
}
}
epnum++;
ep_intr >>= 1;
}
return 1;
}
/**
* @brief DCD_HandleSof_ISR
* Handles the SOF Interrupts
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef GINTSTS;
USBD_DCD_INT_fops->SOF(pdev);
/* Clear interrupt */
GINTSTS.d32 = 0;
GINTSTS.b.sofintr = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, GINTSTS.d32);
return 1;
}
/**
* @brief DCD_HandleRxStatusQueueLevel_ISR
* Handles the Rx Status Queue Level Interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTMSK_TypeDef int_mask;
USB_OTG_DRXSTS_TypeDef status;
USB_OTG_EP *ep;
/* Disable the Rx Status Queue Level interrupt */
int_mask.d32 = 0;
int_mask.b.rxstsqlvl = 1;
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32, 0);
/* Get the Status from the top of the FIFO */
status.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRXSTSP );
ep = &pdev->dev.out_ep[status.b.epnum];
switch (status.b.pktsts)
{
case STS_GOUT_NAK:
break;
case STS_DATA_UPDT:
if (status.b.bcnt)
{
USB_OTG_ReadPacket(pdev,ep->xfer_buff, status.b.bcnt);
ep->xfer_buff += status.b.bcnt;
ep->xfer_count += status.b.bcnt;
}
break;
case STS_XFER_COMP:
break;
case STS_SETUP_COMP:
break;
case STS_SETUP_UPDT:
/* Copy the setup packet received in FIFO into the setup buffer in RAM */
USB_OTG_ReadPacket(pdev , pdev->dev.setup_packet, 8);
ep->xfer_count += status.b.bcnt;
break;
default:
break;
}
/* Enable the Rx Status Queue Level interrupt */
USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, int_mask.d32);
return 1;
}
/**
* @brief DCD_WriteEmptyTxFifo
* check FIFO for the next packet to be loaded
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
{
USB_OTG_DTXFSTSn_TypeDef txstatus;
USB_OTG_EP *ep;
uint32_t len = 0;
uint32_t len32b;
txstatus.d32 = 0;
ep = &pdev->dev.in_ep[epnum];
len = ep->xfer_len - ep->xfer_count;
if (len > ep->maxpacket)
{
len = ep->maxpacket;
}
len32b = (len + 3) / 4;
txstatus.d32 = USB_OTG_READ_REG32( &pdev->regs.INEP_REGS[epnum]->DTXFSTS);
while (txstatus.b.txfspcavail > len32b &&
ep->xfer_count < ep->xfer_len &&
ep->xfer_len != 0)
{
/* Write the FIFO */
len = ep->xfer_len - ep->xfer_count;
if (len > ep->maxpacket)
{
len = ep->maxpacket;
}
len32b = (len + 3) / 4;
USB_OTG_WritePacket (pdev , ep->xfer_buff, epnum, len);
ep->xfer_buff += len;
ep->xfer_count += len;
if( ep->xfer_count >= ep->xfer_len) {
uint32_t fifoemptymsk = 1 << ep->num;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
break;
}
txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS);
}
return 1;
}
/**
* @brief DCD_HandleUsbReset_ISR
* This interrupt occurs when a USB Reset is detected
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_DAINT_TypeDef daintmsk;
USB_OTG_DOEPMSK_TypeDef doepmsk;
USB_OTG_DIEPMSK_TypeDef diepmsk;
USB_OTG_DCFG_TypeDef dcfg;
USB_OTG_DCTL_TypeDef dctl;
USB_OTG_GINTSTS_TypeDef gintsts;
uint32_t i;
dctl.d32 = 0;
daintmsk.d32 = 0;
doepmsk.d32 = 0;
diepmsk.d32 = 0;
dcfg.d32 = 0;
gintsts.d32 = 0;
/* Clear the Remote Wake-up Signaling */
dctl.b.rmtwkupsig = 1;
USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 );
/* Flush the Tx FIFO */
USB_OTG_FlushTxFifo(pdev , 0 );
for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
{
USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF);
USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF);
}
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF );
daintmsk.ep.in = 1;
daintmsk.ep.out = 1;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, daintmsk.d32 );
doepmsk.b.setup = 1;
doepmsk.b.xfercompl = 1;
doepmsk.b.epdisabled = 1;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, doepmsk.d32 );
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOUTEP1MSK, doepmsk.d32 );
#endif
diepmsk.b.xfercompl = 1;
diepmsk.b.timeout = 1;
diepmsk.b.epdisabled = 1;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, diepmsk.d32 );
#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DINEP1MSK, diepmsk.d32 );
#endif
/* Reset Device Address */
dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG);
dcfg.b.devaddr = 0;
USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32);
/* setup EP0 to receive SETUP packets */
USB_OTG_EP0_OutStart(pdev);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.usbreset = 1;
USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
/*Reset internal state machine */
USBD_DCD_INT_fops->Reset(pdev);
return 1;
}
/**
* @brief DCD_HandleEnumDone_ISR
* Read the device status register and set the device speed
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
USB_OTG_GUSBCFG_TypeDef gusbcfg;
USB_OTG_EP0Activate(pdev);
/* Set USB turn-around time based on device speed and PHY interface. */
gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
/* Full or High speed */
if ( USB_OTG_GetDeviceSpeed(pdev) == USB_SPEED_HIGH)
{
pdev->cfg.speed = USB_OTG_SPEED_HIGH;
pdev->cfg.mps = USB_OTG_HS_MAX_PACKET_SIZE ;
gusbcfg.b.usbtrdtim = 9;
}
else
{
pdev->cfg.speed = USB_OTG_SPEED_FULL;
pdev->cfg.mps = USB_OTG_FS_MAX_PACKET_SIZE ;
gusbcfg.b.usbtrdtim = 5;
}
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
/* Clear interrupt */
gintsts.d32 = 0;
gintsts.b.enumdone = 1;
USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, gintsts.d32 );
return 1;
}
/**
* @brief DCD_IsoINIncomplete_ISR
* handle the ISO IN incomplete interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0;
USBD_DCD_INT_fops->IsoINIncomplete (pdev);
/* Clear interrupt */
gintsts.b.incomplisoin = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief DCD_IsoOUTIncomplete_ISR
* handle the ISO OUT incomplete interrupt
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_GINTSTS_TypeDef gintsts;
gintsts.d32 = 0;
USBD_DCD_INT_fops->IsoOUTIncomplete (pdev);
/* Clear interrupt */
gintsts.b.incomplisoout = 1;
USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
return 1;
}
/**
* @brief DCD_ReadDevInEP
* Reads ep flags
* @param pdev: device instance
* @retval status
*/
static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
uint32_t v, msk, emp;
msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPMSK);
emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
msk |= ((emp >> epnum) & 0x1) << 7;
v = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT) & msk;
return v;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,127 +0,0 @@
/**
******************************************************************************
* @file usb_dcd_int.h
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Peripheral Device Interface Layer
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef USB_DCD_INT_H__
#define USB_DCD_INT_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DCD_INT
* @brief This file is the
* @{
*/
/** @defgroup USB_DCD_INT_Exported_Defines
* @{
*/
typedef struct _USBD_DCD_INT
{
uint8_t (* DataOutStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
uint8_t (* DataInStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
uint8_t (* SetupStage) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* Reset) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* Suspend) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* Resume) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* IsoINIncomplete) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* IsoOUTIncomplete) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev);
uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev);
}USBD_DCD_INT_cb_TypeDef;
extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops;
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_Macros
* @{
*/
#define CLEAR_IN_EP_INTR(epnum,intr) \
diepint.d32=0; \
diepint.b.intr = 1; \
USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT,diepint.d32);
#define CLEAR_OUT_EP_INTR(epnum,intr) \
doepint.d32=0; \
doepint.b.intr = 1; \
USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[epnum]->DOEPINT,doepint.d32);
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DCD_INT_Exported_FunctionsPrototype
* @{
*/
uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
#endif // USB_DCD_INT_H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,247 +0,0 @@
/**
******************************************************************************
* @file usb_defines.h
* @author MCD Application Team
* @version V2.1.0
* @date 19-March-2012
* @brief Header of the Core Layer
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DEF_H__
#define __USB_DEF_H__
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_DEFINES
* @brief This file is the
* @{
*/
/** @defgroup USB_DEFINES_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup _CORE_DEFINES_
* @{
*/
#define USB_OTG_SPEED_PARAM_HIGH 0
#define USB_OTG_SPEED_PARAM_HIGH_IN_FULL 1
#define USB_OTG_SPEED_PARAM_FULL 3
#define USB_OTG_SPEED_HIGH 0
#define USB_OTG_SPEED_FULL 1
#define USB_OTG_ULPI_PHY 1
#define USB_OTG_EMBEDDED_PHY 2
/**
* @}
*/
/** @defgroup _GLOBAL_DEFINES_
* @{
*/
#define GAHBCFG_TXFEMPTYLVL_EMPTY 1
#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY 0
#define GAHBCFG_GLBINT_ENABLE 1
#define GAHBCFG_INT_DMA_BURST_SINGLE 0
#define GAHBCFG_INT_DMA_BURST_INCR 1
#define GAHBCFG_INT_DMA_BURST_INCR4 3
#define GAHBCFG_INT_DMA_BURST_INCR8 5
#define GAHBCFG_INT_DMA_BURST_INCR16 7
#define GAHBCFG_DMAENABLE 1
#define GAHBCFG_TXFEMPTYLVL_EMPTY 1
#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY 0
#define GRXSTS_PKTSTS_IN 2
#define GRXSTS_PKTSTS_IN_XFER_COMP 3
#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5
#define GRXSTS_PKTSTS_CH_HALTED 7
/**
* @}
*/
/** @defgroup _OnTheGo_DEFINES_
* @{
*/
#define MODE_HNP_SRP_CAPABLE 0
#define MODE_SRP_ONLY_CAPABLE 1
#define MODE_NO_HNP_SRP_CAPABLE 2
#define MODE_SRP_CAPABLE_DEVICE 3
#define MODE_NO_SRP_CAPABLE_DEVICE 4
#define MODE_SRP_CAPABLE_HOST 5
#define MODE_NO_SRP_CAPABLE_HOST 6
#define A_HOST 1
#define A_SUSPEND 2
#define A_PERIPHERAL 3
#define B_PERIPHERAL 4
#define B_HOST 5
#define DEVICE_MODE 0
#define HOST_MODE 1
#define OTG_MODE 2
/**
* @}
*/
/** @defgroup __DEVICE_DEFINES_
* @{
*/
#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ 0
#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ 1
#define DSTS_ENUMSPD_LS_PHY_6MHZ 2
#define DSTS_ENUMSPD_FS_PHY_48MHZ 3
#define DCFG_FRAME_INTERVAL_80 0
#define DCFG_FRAME_INTERVAL_85 1
#define DCFG_FRAME_INTERVAL_90 2
#define DCFG_FRAME_INTERVAL_95 3
#define DEP0CTL_MPS_64 0
#define DEP0CTL_MPS_32 1
#define DEP0CTL_MPS_16 2
#define DEP0CTL_MPS_8 3
#define EP_SPEED_LOW 0
#define EP_SPEED_FULL 1
#define EP_SPEED_HIGH 2
#define EP_TYPE_CTRL 0
#define EP_TYPE_ISOC 1
#define EP_TYPE_BULK 2
#define EP_TYPE_INTR 3
#define EP_TYPE_MSK 3
#define STS_GOUT_NAK 1
#define STS_DATA_UPDT 2
#define STS_XFER_COMP 3
#define STS_SETUP_COMP 4
#define STS_SETUP_UPDT 6
/**
* @}
*/
/** @defgroup __HOST_DEFINES_
* @{
*/
#define HC_PID_DATA0 0
#define HC_PID_DATA2 1
#define HC_PID_DATA1 2
#define HC_PID_SETUP 3
#define HPRT0_PRTSPD_HIGH_SPEED 0
#define HPRT0_PRTSPD_FULL_SPEED 1
#define HPRT0_PRTSPD_LOW_SPEED 2
#define HCFG_30_60_MHZ 0
#define HCFG_48_MHZ 1
#define HCFG_6_MHZ 2
#define HCCHAR_CTRL 0
#define HCCHAR_ISOC 1
#define HCCHAR_BULK 2
#define HCCHAR_INTR 3
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_Types
* @{
*/
typedef enum
{
USB_OTG_HS_CORE_ID = 0,
USB_OTG_FS_CORE_ID = 1
}USB_OTG_CORE_ID_TypeDef;
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_DEFINES_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
/** @defgroup Internal_Macro's
* @{
*/
#define USB_OTG_READ_REG32(reg) (*(__IO uint32_t *)reg)
#define USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)reg = value)
#define USB_OTG_MODIFY_REG32(reg,clear_mask,set_mask) \
USB_OTG_WRITE_REG32(reg, (((USB_OTG_READ_REG32(reg)) & ~clear_mask) | set_mask ) )
/********************************************************************************
ENUMERATION TYPE
********************************************************************************/
enum USB_OTG_SPEED {
USB_SPEED_UNKNOWN = 0,
USB_SPEED_LOW,
USB_SPEED_FULL,
USB_SPEED_HIGH
};
#endif //__USB_DEFINES__H__
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -1,813 +0,0 @@
/**
******************************************************************************
* @file usbd_cdc_core.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides the high layer firmware functions to manage the
* following functionalities of the USB CDC Class:
* - Initialization and Configuration of high and low layer
* - Enumeration as CDC Device (and enumeration for each implemented memory interface)
* - OUT/IN data transfer
* - Command IN transfer (class requests management)
* - Error management
*
* @verbatim
*
* ===================================================================
* CDC Class Driver Description
* ===================================================================
* This driver manages the "Universal Serial Bus Class Definitions for Communications Devices
* Revision 1.2 November 16, 2007" and the sub-protocol specification of "Universal Serial Bus
* Communications Class Subclass Specification for PSTN Devices Revision 1.2 February 9, 2007"
* This driver implements the following aspects of the specification:
* - Device descriptor management
* - Configuration descriptor management
* - Enumeration as CDC device with 2 data endpoints (IN and OUT) and 1 command endpoint (IN)
* - Requests management (as described in section 6.2 in specification)
* - Abstract Control Model compliant
* - Union Functional collection (using 1 IN endpoint for control)
* - Data interface class
* @note
* For the Abstract Control Model, this core allows only transmitting the requests to
* lower layer dispatcher (ie. usbd_cdc_vcp.c/.h) which should manage each request and
* perform relative actions.
*
* These aspects may be enriched or modified for a specific user application.
*
* This driver doesn't implement the following aspects of the specification
* (but it is possible to manage these features with some modifications on this driver):
* - Any class-specific aspect relative to communication classes should be managed by user application.
* - All communication classes other than PSTN are not managed
*
* @endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_cdc_core.h"
#include "usbd_desc.h"
#include "usbd_req.h"
#include "ring_buff.h"
#include "min_max.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup usbd_cdc
* @brief usbd core module
* @{
*/
/** @defgroup usbd_cdc_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup usbd_cdc_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup usbd_cdc_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup usbd_cdc_Private_FunctionPrototypes
* @{
*/
/*********************************************
CDC Device library callbacks
*********************************************/
static uint8_t usbd_cdc_Init (void *pdev, uint8_t cfgidx);
static uint8_t usbd_cdc_DeInit (void *pdev, uint8_t cfgidx);
static uint8_t usbd_cdc_Setup (void *pdev, USB_SETUP_REQ *req);
static uint8_t usbd_cdc_EP0_RxReady (void *pdev);
static uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum);
static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum);
static uint8_t usbd_cdc_SOF (void *pdev);
/*********************************************
CDC specific management functions
*********************************************/
static uint8_t *USBD_cdc_GetCfgDesc (uint8_t speed, uint16_t *length);
#ifdef USE_USB_OTG_HS
static uint8_t *USBD_cdc_GetOtherCfgDesc (uint8_t speed, uint16_t *length);
#endif
/**
* @}
*/
/** @defgroup usbd_cdc_Private_Variables
* @{
*/
extern CDC_IF_Prop_TypeDef APP_FOPS;
extern const uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC];
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t const usbd_cdc_CfgDesc [USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END ;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t usbd_cdc_OtherCfgDesc [USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END ;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN static __IO uint32_t usbd_cdc_AltSet __ALIGN_END = 0;
/* OUT ring buffer */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t USB_Rx_Buffer [USB_RX_BUFF_SIZE] __ALIGN_END ;
uint32_t USB_Rx_buff_head = 0;
uint32_t USB_Rx_buff_tail = 0;
uint32_t USB_Rx_buff_size = USB_RX_BUFF_SIZE;
uint32_t USB_Rx_total_bytes = 0;
/* IN ring buffer */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t USB_Tx_Buffer [USB_TX_BUFF_SIZE] __ALIGN_END ;
uint32_t USB_Tx_buff_head = 0;
uint32_t USB_Tx_buff_tail = 0;
uint32_t USB_Tx_total_bytes = 0;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t CmdBuff[CDC_CMD_PACKET_SZE] __ALIGN_END ;
uint8_t USB_Tx_Active = 0; /* IN endpoint is transmitting */
uint8_t USB_Rx_Active = 0; /* OUT endpoint is receiving */
static uint32_t cdcCmd = 0xFF;
static uint32_t cdcLen = 0;
/* CDC interface class callbacks structure */
USBD_Class_cb_TypeDef const USBD_CDC_cb =
{
usbd_cdc_Init,
usbd_cdc_DeInit,
usbd_cdc_Setup,
NULL, /* EP0_TxSent, */
usbd_cdc_EP0_RxReady,
usbd_cdc_DataIn,
usbd_cdc_DataOut,
usbd_cdc_SOF,
NULL,
NULL,
USBD_cdc_GetCfgDesc,
#ifdef USE_USB_OTG_HS
USBD_cdc_GetOtherCfgDesc, /* use same config as per FS */
#endif /* USE_USB_OTG_HS */
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB CDC device Configuration Descriptor */
__ALIGN_BEGIN uint8_t const usbd_cdc_CfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
{
/*Configuration Descriptor*/
0x09, /* bLength: Configuration Descriptor size */
USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */
USB_CDC_CONFIG_DESC_SIZ, /* wTotalLength:no of returned bytes */
0x00,
0x02, /* bNumInterfaces: 2 interface */
0x01, /* bConfigurationValue: Configuration value */
0x00, /* iConfiguration: Index of string descriptor describing the configuration */
0xC0, /* bmAttributes: self powered */
0x32, /* MaxPower 0 mA */
/*---------------------------------------------------------------------------*/
/*Interface Descriptor */
0x09, /* bLength: Interface Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: Interface */
/* Interface descriptor type */
0x00, /* 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 */
0x01, /* bDataInterface: 1 */
/*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 */
0x00, /* bMasterInterface: Communication class interface */
0x01, /* bSlaveInterface0: Data Class Interface */
/*Endpoint 2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
CDC_CMD_EP, /* bEndpointAddress */
0x03, /* bmAttributes: Interrupt */
LOBYTE(CDC_CMD_PACKET_SZE), /* wMaxPacketSize: */
HIBYTE(CDC_CMD_PACKET_SZE),
#ifdef USE_USB_OTG_HS
0x10, /* bInterval: */
#else
0xFF, /* bInterval: */
#endif /* USE_USB_OTG_HS */
/*---------------------------------------------------------------------------*/
/*Data class interface descriptor*/
0x09, /* bLength: Endpoint Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: */
0x01, /* 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_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
CDC_OUT_EP, /* bEndpointAddress */
0x02, /* bmAttributes: Bulk */
LOBYTE(CDC_DATA_MAX_PACKET_SIZE), /* wMaxPacketSize: */
HIBYTE(CDC_DATA_MAX_PACKET_SIZE),
0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint IN Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
CDC_IN_EP, /* bEndpointAddress */
0x02, /* bmAttributes: Bulk */
LOBYTE(CDC_DATA_MAX_PACKET_SIZE), /* wMaxPacketSize: */
HIBYTE(CDC_DATA_MAX_PACKET_SIZE),
0x00 /* bInterval: ignore for Bulk transfer */
} ;
#ifdef USE_USB_OTG_HS
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t const usbd_cdc_OtherCfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
{
0x09, /* bLength: Configuation Descriptor size */
USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
USB_CDC_CONFIG_DESC_SIZ,
0x00,
0x02, /* bNumInterfaces: 2 interfaces */
0x01, /* bConfigurationValue: */
0x04, /* iConfiguration: */
0xC0, /* bmAttributes: */
0x32, /* MaxPower 100 mA */
/*Interface Descriptor */
0x09, /* bLength: Interface Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: Interface */
/* Interface descriptor type */
0x00, /* 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 */
0x01, /* bDataInterface: 1 */
/*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 */
0x00, /* bMasterInterface: Communication class interface */
0x01, /* bSlaveInterface0: Data Class Interface */
/*Endpoint 2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
CDC_CMD_EP, /* bEndpointAddress */
0x03, /* bmAttributes: Interrupt */
LOBYTE(CDC_CMD_PACKET_SZE), /* wMaxPacketSize: */
HIBYTE(CDC_CMD_PACKET_SZE),
0xFF, /* bInterval: */
/*---------------------------------------------------------------------------*/
/*Data class interface descriptor*/
0x09, /* bLength: Endpoint Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: */
0x01, /* 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_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
CDC_OUT_EP, /* bEndpointAddress */
0x02, /* bmAttributes: Bulk */
0x40, /* wMaxPacketSize: */
0x00,
0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint IN Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
CDC_IN_EP, /* bEndpointAddress */
0x02, /* bmAttributes: Bulk */
0x40, /* wMaxPacketSize: */
0x00,
0x00 /* bInterval */
};
#endif /* USE_USB_OTG_HS */
/**
* @}
*/
/** @defgroup usbd_cdc_Private_Functions
* @{
*/
/**
* @brief usbd_cdc_Init
* Initilaize the CDC interface
* @param pdev: device instance
* @param cfgidx: Configuration index
* @retval status
*/
static uint8_t usbd_cdc_Init (void *pdev,
uint8_t cfgidx)
{
uint8_t *pbuf;
/* Open EP IN */
DCD_EP_Open(pdev,
CDC_IN_EP,
CDC_DATA_IN_PACKET_SIZE,
USB_OTG_EP_BULK);
/* Open EP OUT */
DCD_EP_Open(pdev,
CDC_OUT_EP,
CDC_DATA_OUT_PACKET_SIZE,
USB_OTG_EP_BULK);
/* Open Command IN EP */
DCD_EP_Open(pdev,
CDC_CMD_EP,
CDC_CMD_PACKET_SZE,
USB_OTG_EP_INT);
pbuf = (uint8_t *)USBD_DeviceDesc;
pbuf[4] = DEVICE_CLASS_CDC;
pbuf[5] = DEVICE_SUBCLASS_CDC;
/* Initialize the Interface physical components */
APP_FOPS.pIf_Init();
USB_Rx_Active = 1;
/* Prepare Out endpoint to receive next packet */
DCD_EP_PrepareRx(pdev,
CDC_OUT_EP,
USB_Rx_Buffer,
CDC_DATA_OUT_PACKET_SIZE);
return USBD_OK;
}
/**
* @brief usbd_cdc_Init
* DeInitialize the CDC layer
* @param pdev: device instance
* @param cfgidx: Configuration index
* @retval status
*/
static uint8_t usbd_cdc_DeInit (void *pdev,
uint8_t cfgidx)
{
/* Open EP IN */
DCD_EP_Close(pdev,
CDC_IN_EP);
/* Open EP OUT */
DCD_EP_Close(pdev,
CDC_OUT_EP);
/* Open Command IN EP */
DCD_EP_Close(pdev,
CDC_CMD_EP);
/* Restore default state of the Interface physical components */
APP_FOPS.pIf_DeInit();
return USBD_OK;
}
/**
* @brief usbd_cdc_Setup
* Handle the CDC specific requests
* @param pdev: instance
* @param req: usb requests
* @retval status
*/
static uint8_t usbd_cdc_Setup (void *pdev,
USB_SETUP_REQ *req)
{
uint16_t len=USB_CDC_DESC_SIZ;
uint8_t const *pbuf=usbd_cdc_CfgDesc + 9;
switch (req->bmRequest & USB_REQ_TYPE_MASK)
{
/* CDC Class Requests -------------------------------*/
case USB_REQ_TYPE_CLASS :
/* Check if the request is a data setup packet */
if (req->wLength)
{
/* Check if the request is Device-to-Host */
if (req->bmRequest & 0x80)
{
/* Get the data to be sent to Host from interface layer */
APP_FOPS.pIf_Ctrl(req->bRequest, CmdBuff, req->wLength);
/* Send the data to the host */
USBD_CtlSendData (pdev,
CmdBuff,
req->wLength);
}
else /* Host-to-Device requeset */
{
/* Set the value of the current command to be processed */
cdcCmd = req->bRequest;
cdcLen = req->wLength;
/* Prepare the reception of the buffer over EP0
Next step: the received data will be managed in usbd_cdc_EP0_TxSent()
function. */
USBD_CtlPrepareRx (pdev,
CmdBuff,
req->wLength);
}
}
else /* No Data request */
{
/* Transfer the command to the interface layer */
APP_FOPS.pIf_Ctrl(req->bRequest, NULL, 0);
}
return USBD_OK;
default:
USBD_CtlError (pdev, req);
return USBD_FAIL;
/* Standard Requests -------------------------------*/
case USB_REQ_TYPE_STANDARD:
switch (req->bRequest)
{
case USB_REQ_GET_DESCRIPTOR:
if( (req->wValue >> 8) == CDC_DESCRIPTOR_TYPE)
{
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
pbuf = usbd_cdc_Desc;
#else
pbuf = usbd_cdc_CfgDesc + 9 + (9 * USBD_ITF_MAX_NUM);
#endif
len = MIN(USB_CDC_DESC_SIZ , req->wLength);
}
USBD_CtlSendData (pdev,
pbuf,
len);
break;
case USB_REQ_GET_INTERFACE :
USBD_CtlSendData (pdev,
(uint8_t *)&usbd_cdc_AltSet,
1);
break;
case USB_REQ_SET_INTERFACE :
if ((uint8_t)(req->wValue) < USBD_ITF_MAX_NUM)
{
usbd_cdc_AltSet = (uint8_t)(req->wValue);
}
else
{
/* Call the error management function (command will be nacked */
USBD_CtlError (pdev, req);
}
break;
}
}
return USBD_OK;
}
/**
* @brief usbd_cdc_EP0_RxReady
* Data received on control endpoint
* @param pdev: device device instance
* @retval status
*/
static uint8_t usbd_cdc_EP0_RxReady (void *pdev)
{
if (cdcCmd != NO_CMD)
{
/* Process the data */
APP_FOPS.pIf_Ctrl(cdcCmd, CmdBuff, cdcLen);
/* Reset the command variable to default value */
cdcCmd = NO_CMD;
}
return USBD_OK;
}
static inline uint32_t last_tx_packet_size(void *pdev, uint8_t epnum)
{
return ((USB_OTG_CORE_HANDLE*)pdev)->dev.in_ep[epnum].xfer_len;
}
static inline uint32_t last_rx_data_size(void *pdev, uint8_t epnum)
{
return ((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].xfer_count;
}
/**
* @brief usbd_audio_DataIn
* Data sent on non-control IN endpoint
* @param pdev: device instance
* @param epnum: endpoint number
* @retval status
*/
static uint8_t usbd_cdc_DataIn (void *pdev, uint8_t epnum)
{
uint16_t USB_Tx_length;
if (!USB_Tx_Active)
return USBD_OK;
USB_Tx_length = ring_data_contig(USB_TX_BUFF_SIZE, USB_Tx_buff_head, USB_Tx_buff_tail);
if (USB_Tx_length) {
USB_Tx_length = MIN_(USB_Tx_length, CDC_DATA_IN_PACKET_SIZE);
} else if (last_tx_packet_size(pdev, epnum) != CDC_DATA_IN_PACKET_SIZE) {
USB_Tx_Active = 0;
return USBD_OK;
}
/* Send the available data buffer on IN endpoint or ZLP to indicate the end of data stream */
DCD_EP_Tx(
pdev,
CDC_IN_EP,
(uint8_t*)&USB_Tx_Buffer[USB_Tx_buff_tail],
USB_Tx_length
);
USB_Tx_buff_tail = ring_wrap(USB_TX_BUFF_SIZE, USB_Tx_buff_tail + USB_Tx_length);
USB_Tx_total_bytes += USB_Tx_length;
return USBD_OK;
}
static inline int try_start_rx(void *pdev)
{
uint32_t space_avail;
if (USB_Rx_buff_head >= USB_Rx_buff_tail)
USB_Rx_buff_size = USB_RX_BUFF_SIZE;
space_avail= ring_space_contig(USB_Rx_buff_size, USB_Rx_buff_head, USB_Rx_buff_tail);
if (space_avail < CDC_DATA_OUT_PACKET_SIZE) {
space_avail = ring_space_wrapped(USB_Rx_buff_size, USB_Rx_buff_head, USB_Rx_buff_tail);
if (space_avail < CDC_DATA_OUT_PACKET_SIZE) {
if (USB_Rx_Active) {
USB_Rx_Active = 0;
DCD_SetEPStatus(pdev, CDC_OUT_EP, USB_OTG_EP_TX_NAK);
}
return 0;
}
USB_Rx_buff_size = USB_Rx_buff_head;
USB_Rx_buff_head = 0;
if (USB_Rx_buff_tail == USB_Rx_buff_size)
USB_Rx_buff_tail = 0;
}
if (!USB_Rx_Active) {
USB_Rx_Active = 1;
DCD_SetEPStatus(pdev, CDC_OUT_EP, USB_OTG_EP_TX_VALID);
}
/* Prepare Out endpoint to receive next packet */
DCD_EP_PrepareRx(
pdev,
CDC_OUT_EP,
USB_Rx_Buffer + USB_Rx_buff_head,
CDC_DATA_OUT_PACKET_SIZE
);
return 1;
}
/**
* @brief usbd_cdc_DataOut
* Data received on non-control Out endpoint
* @param pdev: device instance
* @param epnum: endpoint number
* @retval status
*/
static uint8_t usbd_cdc_DataOut (void *pdev, uint8_t epnum)
{
uint32_t USB_Rx_Cnt = last_rx_data_size(pdev, epnum);
USB_Rx_buff_head = ring_wrap(USB_Rx_buff_size, USB_Rx_buff_head + USB_Rx_Cnt);
USB_Rx_total_bytes += USB_Rx_Cnt;
try_start_rx(pdev);
return USBD_OK;
}
static void schedule_cdc_out(void *pdev)
{
if (!USB_Rx_Active)
try_start_rx(pdev);
}
static void schedule_cdc_in(void *pdev)
{
uint16_t USB_Tx_length;
if (USB_Tx_Active)
return;
USB_Tx_length = ring_data_contig(USB_TX_BUFF_SIZE, USB_Tx_buff_head, USB_Tx_buff_tail);
if (!USB_Tx_length)
return;
USB_Tx_Active = 1;
USB_Tx_length = MIN_(USB_Tx_length, CDC_DATA_IN_PACKET_SIZE);
/* Send the available data buffer on IN endpoint */
DCD_EP_Tx(
pdev,
CDC_IN_EP,
(uint8_t*)&USB_Tx_Buffer[USB_Tx_buff_tail],
USB_Tx_length
);
USB_Tx_buff_tail = ring_wrap(USB_TX_BUFF_SIZE, USB_Tx_buff_tail + USB_Tx_length);
USB_Tx_total_bytes += USB_Tx_length;
}
/**
* @brief usbd_audio_SOF
* Start Of Frame event management
* @param pdev: instance
* @param epnum: endpoint number
* @retval status
*/
static uint8_t usbd_cdc_SOF (void *pdev)
{
static uint32_t FrameCount = 0;
if (FrameCount++ == CDC_IN_FRAME_INTERVAL)
{
/* Reset the frame counter */
FrameCount = 0;
/* Check the data to be sent through IN pipe */
schedule_cdc_in(pdev);
/* Check we can start receiving through OUT pipe */
schedule_cdc_out(pdev);
}
return USBD_OK;
}
/**
* @brief USBD_cdc_GetCfgDesc
* Return configuration descriptor
* @param speed : current device speed
* @param length : pointer data length
* @retval pointer to descriptor buffer
*/
static uint8_t *USBD_cdc_GetCfgDesc (uint8_t speed, uint16_t *length)
{
*length = sizeof (usbd_cdc_CfgDesc);
return usbd_cdc_CfgDesc;
}
/**
* @brief USBD_cdc_GetCfgDesc
* Return configuration descriptor
* @param speed : current device speed
* @param length : pointer data length
* @retval pointer to descriptor buffer
*/
#ifdef USE_USB_OTG_HS
static uint8_t *USBD_cdc_GetOtherCfgDesc (uint8_t speed, uint16_t *length)
{
*length = sizeof (usbd_cdc_OtherCfgDesc);
return usbd_cdc_OtherCfgDesc;
}
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,167 +0,0 @@
/**
******************************************************************************
* @file usbd_cdc_core.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header file for the usbd_cdc_core.c file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#ifndef __USB_CDC_CORE_H_
#define __USB_CDC_CORE_H_
#include "usbd_ioreq.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup usbd_cdc
* @brief This file is the Header file for USBD_cdc.c
* @{
*/
/** @defgroup usbd_cdc_Exported_Defines
* @{
*/
#define USB_CDC_CONFIG_DESC_SIZ (67)
#define USB_CDC_DESC_SIZ (67-9)
#define CDC_DESCRIPTOR_TYPE 0x21
#define DEVICE_CLASS_CDC 0x02
#define DEVICE_SUBCLASS_CDC 0x00
#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
#define USB_STRING_DESCRIPTOR_TYPE 0x03
#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
#define STANDARD_ENDPOINT_DESC_SIZE 0x09
#define CDC_DATA_IN_PACKET_SIZE CDC_DATA_MAX_PACKET_SIZE
#define CDC_DATA_OUT_PACKET_SIZE CDC_DATA_MAX_PACKET_SIZE
/*---------------------------------------------------------------------*/
/* CDC definitions */
/*---------------------------------------------------------------------*/
/**************************************************/
/* CDC Requests */
/**************************************************/
#define SEND_ENCAPSULATED_COMMAND 0x00
#define GET_ENCAPSULATED_RESPONSE 0x01
#define SET_COMM_FEATURE 0x02
#define GET_COMM_FEATURE 0x03
#define CLEAR_COMM_FEATURE 0x04
#define SET_LINE_CODING 0x20
#define GET_LINE_CODING 0x21
#define SET_CONTROL_LINE_STATE 0x22
#define SEND_BREAK 0x23
#define NO_CMD 0xFF
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_TypesDefinitions
* @{
*/
typedef struct _CDC_IF_PROP
{
uint16_t (*pIf_Init) (void);
uint16_t (*pIf_DeInit) (void);
uint16_t (*pIf_Ctrl) (uint32_t Cmd, uint8_t* Buf, uint32_t Len);
uint16_t (*pIf_DataTx) (const uint8_t* Buf, uint32_t Len);
uint16_t (*pIf_DataRx) (uint8_t* Buf, uint32_t Len);
}
CDC_IF_Prop_TypeDef;
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_Variables
* @{
*/
extern const USBD_Class_cb_TypeDef USBD_CDC_cb;
/**
* @}
*/
/** @defgroup USB_CORE_Exported_Functions
* @{
*/
/**
* @}
*/
/*
* CDC data buffers
*/
#ifndef USB_TX_BUFF_SIZE
#define USB_TX_BUFF_SIZE 512
#define USB_RX_BUFF_SIZE 1024
#endif
/*
* IN ring endpoint buffer (data to be sent to host)
*/
extern uint8_t USB_Tx_Buffer[];
extern uint32_t USB_Tx_buff_head;
extern uint32_t USB_Tx_buff_tail;
/*
* OUT endpoint ring buffer (data received from host)
*/
extern uint8_t USB_Rx_Buffer[];
extern uint32_t USB_Rx_buff_head;
extern uint32_t USB_Rx_buff_tail;
extern uint32_t USB_Rx_buff_size;
#endif // __USB_CDC_CORE_H_
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,147 +0,0 @@
/**
******************************************************************************
* @file usbd_conf.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief USB Device configuration file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_CONF__H__
#define __USBD_CONF__H__
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/** @defgroup USB_CONF_Exported_Defines
* @{
*/
#define USBD_CFG_MAX_NUM 1
#define USBD_ITF_MAX_NUM 1
#define USBD_SELF_POWERED
#define USB_MAX_STR_DESC_SIZ 255
/** @defgroup USB_VCP_Class_Layer_Parameter
* @{
*/
#define CDC_IN_EP 0x81 /* EP1 for data IN */
#define CDC_OUT_EP 0x01 /* EP1 for data OUT */
#define CDC_CMD_EP 0x82 /* EP2 for CDC commands */
/* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */
#ifdef USE_USB_OTG_HS
#define CDC_DATA_MAX_PACKET_SIZE 512 /* Endpoint IN & OUT Packet size */
#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */
#define CDC_IN_FRAME_INTERVAL 40 /* Number of micro-frames between IN transfers */
#define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer:
APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL*8 */
#else
#define CDC_DATA_MAX_PACKET_SIZE 64 /* Endpoint IN & OUT Packet size */
#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */
#define CDC_IN_FRAME_INTERVAL 5 /* Number of frames between IN transfers */
#define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer:
APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL */
#endif /* USE_USB_OTG_HS */
#define APP_FOPS VCP_fops
//[ for MSC
//#define USBD_CFG_MAX_NUM 1
//#define USBD_ITF_MAX_NUM 1
//#define USB_MAX_STR_DESC_SIZ 64
//#define USBD_SELF_POWERED
/* Class Layer Parameter */
#define MSC_IN_EP 0x81
#define MSC_OUT_EP 0x01
#ifdef USE_USB_OTG_HS
#ifdef USE_ULPI_PHY
#define MSC_MAX_PACKET 512
#else
#define MSC_MAX_PACKET 64
#endif
#else /*USE_USB_OTG_FS*/
#define MSC_MAX_PACKET 64
#endif
#define MSC_MEDIA_PACKET 4096
//]
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USB_CONF_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif //__USBD_CONF__H__
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,506 +0,0 @@
/**
******************************************************************************
* @file usbd_core.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides all the USBD core functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_core.h"
#include "usbd_req.h"
#include "usbd_ioreq.h"
#include "usb_dcd_int.h"
#include "usb_bsp.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_CORE
* @brief usbd core module
* @{
*/
/** @defgroup USBD_CORE_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Private_FunctionPrototypes
* @{
*/
static uint8_t USBD_SetupStage(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
static uint8_t USBD_SOF(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_Reset(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE *pdev);
#ifdef VBUS_SENSING_ENABLED
static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev);
#endif
static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev);
static uint8_t USBD_RunTestMode (USB_OTG_CORE_HANDLE *pdev) ;
/**
* @}
*/
/** @defgroup USBD_CORE_Private_Variables
* @{
*/
__IO USB_OTG_DCTL_TypeDef SET_TEST_MODE;
USBD_DCD_INT_cb_TypeDef USBD_DCD_INT_cb =
{
USBD_DataOutStage,
USBD_DataInStage,
USBD_SetupStage,
USBD_SOF,
USBD_Reset,
USBD_Suspend,
USBD_Resume,
USBD_IsoINIncomplete,
USBD_IsoOUTIncomplete,
#ifdef VBUS_SENSING_ENABLED
USBD_DevConnected,
USBD_DevDisconnected,
#endif
};
USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops = &USBD_DCD_INT_cb;
/**
* @}
*/
/** @defgroup USBD_CORE_Private_Functions
* @{
*/
/**
* @brief USBD_Init
* Initailizes the device stack and load the class driver
* @param pdev: device instance
* @param core_address: USB OTG core ID
* @param class_cb: Class callback structure address
* @param usr_cb: User callback structure address
* @retval None
*/
void USBD_Init(USB_OTG_CORE_HANDLE *pdev,
const USB_OTG_CORE_ID_TypeDef coreID,
const USBD_DEVICE *pDevice,
const USBD_Class_cb_TypeDef *class_cb,
const USBD_Usr_cb_TypeDef *usr_cb)
{
/* Hardware Init */
USB_OTG_BSP_Init(pdev);
USBD_DeInit(pdev);
/*Register class and user callbacks */
pdev->dev.class_cb = class_cb;
pdev->dev.usr_cb = usr_cb;
pdev->dev.usr_device = pDevice;
/* set USB OTG core params */
DCD_Init(pdev , coreID);
/* Upon Init call usr callback */
pdev->dev.usr_cb->Init();
/* Enable Interrupts */
USB_OTG_BSP_EnableInterrupt(pdev);
}
/**
* @brief USBD_DeInit
* Re-Initialize th device library
* @param pdev: device instance
* @retval status: status
*/
USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev)
{
/* Software Init */
return USBD_OK;
}
/**
* @brief USBD_SetupStage
* Handle the setup stage
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_SetupStage(USB_OTG_CORE_HANDLE *pdev)
{
USB_SETUP_REQ req;
USBD_ParseSetupRequest(pdev , &req);
switch (req.bmRequest & 0x1F)
{
case USB_REQ_RECIPIENT_DEVICE:
USBD_StdDevReq (pdev, &req);
break;
case USB_REQ_RECIPIENT_INTERFACE:
USBD_StdItfReq(pdev, &req);
break;
case USB_REQ_RECIPIENT_ENDPOINT:
USBD_StdEPReq(pdev, &req);
break;
default:
DCD_EP_Stall(pdev , req.bmRequest & 0x80);
break;
}
return USBD_OK;
}
/**
* @brief USBD_DataOutStage
* Handle data out stage
* @param pdev: device instance
* @param epnum: endpoint index
* @retval status
*/
static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
{
USB_OTG_EP *ep;
if(epnum == 0)
{
ep = &pdev->dev.out_ep[0];
if ( pdev->dev.device_state == USB_OTG_EP0_DATA_OUT)
{
if(ep->rem_data_len > ep->maxpacket)
{
ep->rem_data_len -= ep->maxpacket;
if(pdev->cfg.dma_enable == 1)
{
/* in slave mode this, is handled by the RxSTSQLvl ISR */
ep->xfer_buff += ep->maxpacket;
}
USBD_CtlContinueRx (pdev,
ep->xfer_buff,
MIN(ep->rem_data_len ,ep->maxpacket));
}
else
{
if((pdev->dev.class_cb->EP0_RxReady != NULL)&&
(pdev->dev.device_status == USB_OTG_CONFIGURED))
{
pdev->dev.class_cb->EP0_RxReady(pdev);
}
USBD_CtlSendStatus(pdev);
}
}
}
else if((pdev->dev.class_cb->DataOut != NULL)&&
(pdev->dev.device_status == USB_OTG_CONFIGURED))
{
pdev->dev.class_cb->DataOut(pdev, epnum);
}
return USBD_OK;
}
/**
* @brief USBD_DataInStage
* Handle data in stage
* @param pdev: device instance
* @param epnum: endpoint index
* @retval status
*/
static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
{
USB_OTG_EP *ep;
if(epnum == 0)
{
ep = &pdev->dev.in_ep[0];
if ( pdev->dev.device_state == USB_OTG_EP0_DATA_IN)
{
if(ep->rem_data_len > ep->maxpacket)
{
ep->rem_data_len -= ep->maxpacket;
if(pdev->cfg.dma_enable == 1)
{
/* in slave mode this, is handled by the TxFifoEmpty ISR */
ep->xfer_buff += ep->maxpacket;
}
USBD_CtlContinueSendData (pdev,
ep->xfer_buff,
ep->rem_data_len);
}
else
{ /* last packet is MPS multiple, so send ZLP packet */
if((ep->total_data_len % ep->maxpacket == 0) &&
(ep->total_data_len >= ep->maxpacket) &&
(ep->total_data_len < ep->ctl_data_len ))
{
USBD_CtlContinueSendData(pdev , NULL, 0);
ep->ctl_data_len = 0;
}
else
{
if((pdev->dev.class_cb->EP0_TxSent != NULL)&&
(pdev->dev.device_status == USB_OTG_CONFIGURED))
{
pdev->dev.class_cb->EP0_TxSent(pdev);
}
USBD_CtlReceiveStatus(pdev);
}
}
}
if (pdev->dev.test_mode == 1)
{
USBD_RunTestMode(pdev);
pdev->dev.test_mode = 0;
}
}
else if((pdev->dev.class_cb->DataIn != NULL)&&
(pdev->dev.device_status == USB_OTG_CONFIGURED))
{
pdev->dev.class_cb->DataIn(pdev, epnum);
}
return USBD_OK;
}
/**
* @brief USBD_RunTestMode
* Launch test mode process
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_RunTestMode (USB_OTG_CORE_HANDLE *pdev)
{
USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, SET_TEST_MODE.d32);
return USBD_OK;
}
/**
* @brief USBD_Reset
* Handle Reset event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_Reset(USB_OTG_CORE_HANDLE *pdev)
{
/* Open EP0 OUT */
DCD_EP_Open(pdev,
0x00,
USB_OTG_MAX_EP0_SIZE,
EP_TYPE_CTRL);
/* Open EP0 IN */
DCD_EP_Open(pdev,
0x80,
USB_OTG_MAX_EP0_SIZE,
EP_TYPE_CTRL);
/* Upon Reset call usr call back */
pdev->dev.device_status = USB_OTG_DEFAULT;
pdev->dev.usr_cb->DeviceReset(pdev->cfg.speed);
return USBD_OK;
}
/**
* @brief USBD_Resume
* Handle Resume event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE *pdev)
{
/* Upon Resume call usr call back */
pdev->dev.usr_cb->DeviceResumed();
pdev->dev.device_status = pdev->dev.device_old_status;
pdev->dev.device_status = USB_OTG_CONFIGURED;
return USBD_OK;
}
/**
* @brief USBD_Suspend
* Handle Suspend event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE *pdev)
{
pdev->dev.device_old_status = pdev->dev.device_status;
pdev->dev.device_status = USB_OTG_SUSPENDED;
/* Upon Resume call usr call back */
pdev->dev.usr_cb->DeviceSuspended();
return USBD_OK;
}
/**
* @brief USBD_SOF
* Handle SOF event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_SOF(USB_OTG_CORE_HANDLE *pdev)
{
if(pdev->dev.class_cb->SOF)
{
pdev->dev.class_cb->SOF(pdev);
}
return USBD_OK;
}
/**
* @brief USBD_SetCfg
* Configure device and start the interface
* @param pdev: device instance
* @param cfgidx: configuration index
* @retval status
*/
USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx)
{
pdev->dev.class_cb->Init(pdev, cfgidx);
/* Upon set config call usr call back */
pdev->dev.usr_cb->DeviceConfigured();
return USBD_OK;
}
/**
* @brief USBD_ClrCfg
* Clear current configuration
* @param pdev: device instance
* @param cfgidx: configuration index
* @retval status: USBD_Status
*/
USBD_Status USBD_ClrCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx)
{
pdev->dev.class_cb->DeInit(pdev, cfgidx);
return USBD_OK;
}
/**
* @brief USBD_IsoINIncomplete
* Handle iso in incomplete event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE *pdev)
{
pdev->dev.class_cb->IsoINIncomplete(pdev);
return USBD_OK;
}
/**
* @brief USBD_IsoOUTIncomplete
* Handle iso out incomplete event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE *pdev)
{
pdev->dev.class_cb->IsoOUTIncomplete(pdev);
return USBD_OK;
}
#ifdef VBUS_SENSING_ENABLED
/**
* @brief USBD_DevConnected
* Handle device connection event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE *pdev)
{
pdev->dev.usr_cb->DeviceConnected();
pdev->dev.connection_status = 1;
return USBD_OK;
}
/**
* @brief USBD_DevDisconnected
* Handle device disconnection event
* @param pdev: device instance
* @retval status
*/
static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE *pdev)
{
pdev->dev.usr_cb->DeviceDisconnected();
pdev->dev.class_cb->DeInit(pdev, 0);
pdev->dev.connection_status = 0;
return USBD_OK;
}
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,120 +0,0 @@
/**
******************************************************************************
* @file usbd_core.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief Header file for usbd_core.c
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_CORE_H
#define __USBD_CORE_H
/* Includes ------------------------------------------------------------------*/
#include "usb_dcd.h"
#include "usbd_def.h"
#include "usbd_conf.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_CORE
* @brief This file is the Header file for usbd_core.c file
* @{
*/
/** @defgroup USBD_CORE_Exported_Defines
* @{
*/
typedef enum {
USBD_OK = 0,
USBD_BUSY,
USBD_FAIL,
}USBD_Status;
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_FunctionsPrototype
* @{
*/
void USBD_Init(USB_OTG_CORE_HANDLE *pdev,
const USB_OTG_CORE_ID_TypeDef coreID,
const USBD_DEVICE *pDevice,
const USBD_Class_cb_TypeDef *class_cb,
const USBD_Usr_cb_TypeDef *usr_cb);
USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev);
USBD_Status USBD_ClrCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx);
USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE *pdev, uint8_t cfgidx);
/**
* @}
*/
#endif /* __USBD_CORE_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,156 +0,0 @@
/**
******************************************************************************
* @file usbd_def.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief general defines for the usb device library
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_DEF_H
#define __USBD_DEF_H
/* Includes ------------------------------------------------------------------*/
#include "usbd_conf.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USB_DEF
* @brief general defines for the usb device library file
* @{
*/
/** @defgroup USB_DEF_Exported_Defines
* @{
*/
#ifndef NULL
#define NULL 0
#endif
#define USB_LEN_DEV_QUALIFIER_DESC 0x0A
#define USB_LEN_DEV_DESC 0x12
#define USB_LEN_CFG_DESC 0x09
#define USB_LEN_IF_DESC 0x09
#define USB_LEN_EP_DESC 0x07
#define USB_LEN_OTG_DESC 0x03
#define USBD_IDX_LANGID_STR 0x00
#define USBD_IDX_MFC_STR 0x01
#define USBD_IDX_PRODUCT_STR 0x02
#define USBD_IDX_SERIAL_STR 0x03
#define USBD_IDX_CONFIG_STR 0x04
#define USBD_IDX_INTERFACE_STR 0x05
#define USB_REQ_TYPE_STANDARD 0x00
#define USB_REQ_TYPE_CLASS 0x20
#define USB_REQ_TYPE_VENDOR 0x40
#define USB_REQ_TYPE_MASK 0x60
#define USB_REQ_RECIPIENT_DEVICE 0x00
#define USB_REQ_RECIPIENT_INTERFACE 0x01
#define USB_REQ_RECIPIENT_ENDPOINT 0x02
#define USB_REQ_RECIPIENT_MASK 0x03
#define USB_REQ_GET_STATUS 0x00
#define USB_REQ_CLEAR_FEATURE 0x01
#define USB_REQ_SET_FEATURE 0x03
#define USB_REQ_SET_ADDRESS 0x05
#define USB_REQ_GET_DESCRIPTOR 0x06
#define USB_REQ_SET_DESCRIPTOR 0x07
#define USB_REQ_GET_CONFIGURATION 0x08
#define USB_REQ_SET_CONFIGURATION 0x09
#define USB_REQ_GET_INTERFACE 0x0A
#define USB_REQ_SET_INTERFACE 0x0B
#define USB_REQ_SYNCH_FRAME 0x0C
#define USB_DESC_TYPE_DEVICE 1
#define USB_DESC_TYPE_CONFIGURATION 2
#define USB_DESC_TYPE_STRING 3
#define USB_DESC_TYPE_INTERFACE 4
#define USB_DESC_TYPE_ENDPOINT 5
#define USB_DESC_TYPE_DEVICE_QUALIFIER 6
#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 7
#define USB_CONFIG_REMOTE_WAKEUP 2
#define USB_CONFIG_SELF_POWERED 1
#define USB_FEATURE_EP_HALT 0
#define USB_FEATURE_REMOTE_WAKEUP 1
#define USB_FEATURE_TEST_MODE 2
/**
* @}
*/
/** @defgroup USBD_DEF_Exported_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DEF_Exported_Macros
* @{
*/
#define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \
(((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8))
#define LOBYTE(x) ((uint8_t)(x & 0x00FF))
#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8))
/**
* @}
*/
/** @defgroup USBD_DEF_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DEF_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif /* __USBD_DEF_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,122 +0,0 @@
/**
******************************************************************************
* @file usbd_desc.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header file for the usbd_desc.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DESC_H
#define __USB_DESC_H
/* Includes ------------------------------------------------------------------*/
#include "usbd_def.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USB_DESC
* @brief general defines for the usb device library file
* @{
*/
/** @defgroup USB_DESC_Exported_Defines
* @{
*/
#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
#define USB_STRING_DESCRIPTOR_TYPE 0x03
#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
#define USB_SIZ_DEVICE_DESC 18
#define USB_SIZ_STRING_LANGID 4
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_Variables
* @{
*/
extern const uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC];
extern const uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC];
extern const uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC];
extern const uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID];
extern const USBD_DEVICE USR_desc;
extern uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ];
/**
* @}
*/
/** @defgroup USBD_DESC_Exported_FunctionsPrototype
* @{
*/
uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_ProductStrDescriptor ( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
/**
* @}
*/
#endif /* __USBD_DESC_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,244 +0,0 @@
/**
******************************************************************************
* @file usbd_ioreq.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides the IO requests APIs for control endpoints.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_ioreq.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_IOREQ
* @brief control I/O requests module
* @{
*/
/** @defgroup USBD_IOREQ_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Private_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Private_Functions
* @{
*/
/**
* @brief USBD_CtlSendData
* send data on the ctl pipe
* @param pdev: device instance
* @param buff: pointer to data buffer
* @param len: length of data to be sent
* @retval status
*/
USBD_Status USBD_CtlSendData (USB_OTG_CORE_HANDLE *pdev,
const uint8_t *pbuf,
uint16_t len)
{
USBD_Status ret = USBD_OK;
pdev->dev.in_ep[0].total_data_len = len;
pdev->dev.in_ep[0].rem_data_len = len;
pdev->dev.device_state = USB_OTG_EP0_DATA_IN;
DCD_EP_Tx (pdev, 0, pbuf, len);
return ret;
}
/**
* @brief USBD_CtlContinueSendData
* continue sending data on the ctl pipe
* @param pdev: device instance
* @param buff: pointer to data buffer
* @param len: length of data to be sent
* @retval status
*/
USBD_Status USBD_CtlContinueSendData (USB_OTG_CORE_HANDLE *pdev,
uint8_t *pbuf,
uint16_t len)
{
USBD_Status ret = USBD_OK;
DCD_EP_Tx (pdev, 0, pbuf, len);
return ret;
}
/**
* @brief USBD_CtlPrepareRx
* receive data on the ctl pipe
* @param pdev: USB OTG device instance
* @param buff: pointer to data buffer
* @param len: length of data to be received
* @retval status
*/
USBD_Status USBD_CtlPrepareRx (USB_OTG_CORE_HANDLE *pdev,
uint8_t *pbuf,
uint16_t len)
{
USBD_Status ret = USBD_OK;
pdev->dev.out_ep[0].total_data_len = len;
pdev->dev.out_ep[0].rem_data_len = len;
pdev->dev.device_state = USB_OTG_EP0_DATA_OUT;
DCD_EP_PrepareRx (pdev,
0,
pbuf,
len);
return ret;
}
/**
* @brief USBD_CtlContinueRx
* continue receive data on the ctl pipe
* @param pdev: USB OTG device instance
* @param buff: pointer to data buffer
* @param len: length of data to be received
* @retval status
*/
USBD_Status USBD_CtlContinueRx (USB_OTG_CORE_HANDLE *pdev,
uint8_t *pbuf,
uint16_t len)
{
USBD_Status ret = USBD_OK;
DCD_EP_PrepareRx (pdev,
0,
pbuf,
len);
return ret;
}
/**
* @brief USBD_CtlSendStatus
* send zero lzngth packet on the ctl pipe
* @param pdev: USB OTG device instance
* @retval status
*/
USBD_Status USBD_CtlSendStatus (USB_OTG_CORE_HANDLE *pdev)
{
USBD_Status ret = USBD_OK;
pdev->dev.device_state = USB_OTG_EP0_STATUS_IN;
DCD_EP_Tx (pdev,
0,
NULL,
0);
USB_OTG_EP0_OutStart(pdev);
return ret;
}
/**
* @brief USBD_CtlReceiveStatus
* receive zero lzngth packet on the ctl pipe
* @param pdev: USB OTG device instance
* @retval status
*/
USBD_Status USBD_CtlReceiveStatus (USB_OTG_CORE_HANDLE *pdev)
{
USBD_Status ret = USBD_OK;
pdev->dev.device_state = USB_OTG_EP0_STATUS_OUT;
DCD_EP_PrepareRx ( pdev,
0,
NULL,
0);
USB_OTG_EP0_OutStart(pdev);
return ret;
}
/**
* @brief USBD_GetRxCount
* returns the received data length
* @param pdev: USB OTG device instance
* epnum: endpoint index
* @retval Rx Data blength
*/
uint16_t USBD_GetRxCount (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
{
return pdev->dev.out_ep[epnum].xfer_count;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,121 +0,0 @@
/**
******************************************************************************
* @file usbd_ioreq.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header file for the usbd_ioreq.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_IOREQ_H_
#define __USBD_IOREQ_H_
/* Includes ------------------------------------------------------------------*/
#include "usbd_def.h"
#include "usbd_core.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_IOREQ
* @brief header file for the usbd_ioreq.c file
* @{
*/
/** @defgroup USBD_IOREQ_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBD_IOREQ_Exported_FunctionsPrototype
* @{
*/
USBD_Status USBD_CtlSendData (USB_OTG_CORE_HANDLE *pdev,
const uint8_t *buf,
uint16_t len);
USBD_Status USBD_CtlContinueSendData (USB_OTG_CORE_HANDLE *pdev,
uint8_t *pbuf,
uint16_t len);
USBD_Status USBD_CtlPrepareRx (USB_OTG_CORE_HANDLE *pdev,
uint8_t *pbuf,
uint16_t len);
USBD_Status USBD_CtlContinueRx (USB_OTG_CORE_HANDLE *pdev,
uint8_t *pbuf,
uint16_t len);
USBD_Status USBD_CtlSendStatus (USB_OTG_CORE_HANDLE *pdev);
USBD_Status USBD_CtlReceiveStatus (USB_OTG_CORE_HANDLE *pdev);
uint16_t USBD_GetRxCount (USB_OTG_CORE_HANDLE *pdev ,
uint8_t epnum);
/**
* @}
*/
#endif /* __USBD_IOREQ_H_ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,866 +0,0 @@
/**
******************************************************************************
* @file usbd_req.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides the standard USB requests following chapter 9.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_req.h"
#include "usbd_ioreq.h"
#include "usbd_desc.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_REQ
* @brief USB standard requests module
* @{
*/
/** @defgroup USBD_REQ_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Private_Variables
* @{
*/
extern __IO USB_OTG_DCTL_TypeDef SET_TEST_MODE;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint32_t USBD_ep_status __ALIGN_END = 0;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint32_t USBD_default_cfg __ALIGN_END = 0;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint32_t USBD_cfg_status __ALIGN_END = 0;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ] __ALIGN_END ; // work buffer
/**
* @}
*/
/** @defgroup USBD_REQ_Private_FunctionPrototypes
* @{
*/
static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static void USBD_SetAddress(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static void USBD_SetConfig(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static void USBD_GetConfig(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static void USBD_GetStatus(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static void USBD_SetFeature(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static void USBD_ClrFeature(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
static uint8_t USBD_GetLen(const uint8_t *buf);
/**
* @}
*/
/** @defgroup USBD_REQ_Private_Functions
* @{
*/
/**
* @brief USBD_StdDevReq
* Handle standard usb device requests
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
USBD_Status USBD_StdDevReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req)
{
USBD_Status ret = USBD_OK;
switch (req->bRequest)
{
case USB_REQ_GET_DESCRIPTOR:
USBD_GetDescriptor (pdev, req) ;
break;
case USB_REQ_SET_ADDRESS:
USBD_SetAddress(pdev, req);
break;
case USB_REQ_SET_CONFIGURATION:
USBD_SetConfig (pdev , req);
break;
case USB_REQ_GET_CONFIGURATION:
USBD_GetConfig (pdev , req);
break;
case USB_REQ_GET_STATUS:
USBD_GetStatus (pdev , req);
break;
case USB_REQ_SET_FEATURE:
USBD_SetFeature (pdev , req);
break;
case USB_REQ_CLEAR_FEATURE:
USBD_ClrFeature (pdev , req);
break;
default:
USBD_CtlError(pdev , req);
break;
}
return ret;
}
/**
* @brief USBD_StdItfReq
* Handle standard usb interface requests
* @param pdev: USB OTG device instance
* @param req: usb request
* @retval status
*/
USBD_Status USBD_StdItfReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req)
{
USBD_Status ret = USBD_OK;
switch (pdev->dev.device_status)
{
case USB_OTG_CONFIGURED:
if (LOBYTE(req->wIndex) <= USBD_ITF_MAX_NUM)
{
pdev->dev.class_cb->Setup (pdev, req);
if((req->wLength == 0)&& (ret == USBD_OK))
{
USBD_CtlSendStatus(pdev);
}
}
else
{
USBD_CtlError(pdev , req);
}
break;
default:
USBD_CtlError(pdev , req);
break;
}
return ret;
}
/**
* @brief USBD_StdEPReq
* Handle standard usb endpoint requests
* @param pdev: USB OTG device instance
* @param req: usb request
* @retval status
*/
USBD_Status USBD_StdEPReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req)
{
uint8_t ep_addr;
USBD_Status ret = USBD_OK;
ep_addr = LOBYTE(req->wIndex);
switch (req->bRequest)
{
case USB_REQ_SET_FEATURE :
switch (pdev->dev.device_status)
{
case USB_OTG_ADDRESSED:
if ((ep_addr != 0x00) && (ep_addr != 0x80))
{
DCD_EP_Stall(pdev , ep_addr);
}
break;
case USB_OTG_CONFIGURED:
if (req->wValue == USB_FEATURE_EP_HALT)
{
if ((ep_addr != 0x00) && (ep_addr != 0x80))
{
DCD_EP_Stall(pdev , ep_addr);
}
}
pdev->dev.class_cb->Setup (pdev, req);
USBD_CtlSendStatus(pdev);
break;
default:
USBD_CtlError(pdev , req);
break;
}
break;
case USB_REQ_CLEAR_FEATURE :
switch (pdev->dev.device_status)
{
case USB_OTG_ADDRESSED:
if ((ep_addr != 0x00) && (ep_addr != 0x80))
{
DCD_EP_Stall(pdev , ep_addr);
}
break;
case USB_OTG_CONFIGURED:
if (req->wValue == USB_FEATURE_EP_HALT)
{
if ((ep_addr != 0x00) && (ep_addr != 0x80))
{
DCD_EP_ClrStall(pdev , ep_addr);
pdev->dev.class_cb->Setup (pdev, req);
}
USBD_CtlSendStatus(pdev);
}
break;
default:
USBD_CtlError(pdev , req);
break;
}
break;
case USB_REQ_GET_STATUS:
switch (pdev->dev.device_status)
{
case USB_OTG_ADDRESSED:
if ((ep_addr != 0x00) && (ep_addr != 0x80))
{
DCD_EP_Stall(pdev , ep_addr);
}
break;
case USB_OTG_CONFIGURED:
if ((ep_addr & 0x80)== 0x80)
{
if(pdev->dev.in_ep[ep_addr & 0x7F].is_stall)
{
USBD_ep_status = 0x0001;
}
else
{
USBD_ep_status = 0x0000;
}
}
else if ((ep_addr & 0x80)== 0x00)
{
if(pdev->dev.out_ep[ep_addr].is_stall)
{
USBD_ep_status = 0x0001;
}
else
{
USBD_ep_status = 0x0000;
}
}
USBD_CtlSendData (pdev,
(uint8_t *)&USBD_ep_status,
2);
break;
default:
USBD_CtlError(pdev , req);
break;
}
break;
default:
break;
}
return ret;
}
/**
* @brief USBD_GetDescriptor
* Handle Get Descriptor requests
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
uint16_t len;
uint8_t *pbuf;
switch (req->wValue >> 8)
{
case USB_DESC_TYPE_DEVICE:
pbuf = pdev->dev.usr_device->GetDeviceDescriptor(pdev->cfg.speed, &len);
if ((req->wLength == 64) ||( pdev->dev.device_status == USB_OTG_DEFAULT))
{
len = 8;
}
break;
case USB_DESC_TYPE_CONFIGURATION:
pbuf = (uint8_t *)pdev->dev.class_cb->GetConfigDescriptor(pdev->cfg.speed, &len);
#ifdef USB_OTG_HS_CORE
if((pdev->cfg.speed == USB_OTG_SPEED_FULL )&&
(pdev->cfg.phy_itface == USB_OTG_ULPI_PHY))
{
pbuf = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len);
}
#endif
pbuf[1] = USB_DESC_TYPE_CONFIGURATION;
pdev->dev.pConfig_descriptor = pbuf;
break;
case USB_DESC_TYPE_STRING:
switch ((uint8_t)(req->wValue))
{
case USBD_IDX_LANGID_STR:
pbuf = pdev->dev.usr_device->GetLangIDStrDescriptor(pdev->cfg.speed, &len);
break;
case USBD_IDX_MFC_STR:
pbuf = pdev->dev.usr_device->GetManufacturerStrDescriptor(pdev->cfg.speed, &len);
break;
case USBD_IDX_PRODUCT_STR:
pbuf = pdev->dev.usr_device->GetProductStrDescriptor(pdev->cfg.speed, &len);
break;
case USBD_IDX_SERIAL_STR:
pbuf = pdev->dev.usr_device->GetSerialStrDescriptor(pdev->cfg.speed, &len);
break;
case USBD_IDX_CONFIG_STR:
pbuf = pdev->dev.usr_device->GetConfigurationStrDescriptor(pdev->cfg.speed, &len);
break;
case USBD_IDX_INTERFACE_STR:
pbuf = pdev->dev.usr_device->GetInterfaceStrDescriptor(pdev->cfg.speed, &len);
break;
default:
#ifdef USB_SUPPORT_USER_STRING_DESC
pbuf = pdev->dev.class_cb->GetUsrStrDescriptor(pdev->cfg.speed, (req->wValue) , &len);
break;
#else
USBD_CtlError(pdev , req);
return;
#endif /* USBD_CtlError(pdev , req); */
}
break;
case USB_DESC_TYPE_DEVICE_QUALIFIER:
#ifdef USB_OTG_HS_CORE
if(pdev->cfg.speed == USB_OTG_SPEED_HIGH )
{
pbuf = (uint8_t *)pdev->dev.class_cb->GetConfigDescriptor(pdev->cfg.speed, &len);
USBD_DeviceQualifierDesc[4]= pbuf[14];
USBD_DeviceQualifierDesc[5]= pbuf[15];
USBD_DeviceQualifierDesc[6]= pbuf[16];
pbuf = USBD_DeviceQualifierDesc;
len = USB_LEN_DEV_QUALIFIER_DESC;
break;
}
else
{
USBD_CtlError(pdev , req);
return;
}
#else
USBD_CtlError(pdev , req);
return;
#endif
case USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION:
#ifdef USB_OTG_HS_CORE
if(pdev->cfg.speed == USB_OTG_SPEED_HIGH )
{
pbuf = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len);
pbuf[1] = USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION;
break;
}
else
{
USBD_CtlError(pdev , req);
return;
}
#else
USBD_CtlError(pdev , req);
return;
#endif
default:
USBD_CtlError(pdev , req);
return;
}
if((len != 0)&& (req->wLength != 0))
{
len = MIN(len , req->wLength);
USBD_CtlSendData (pdev,
pbuf,
len);
}
}
/**
* @brief USBD_SetAddress
* Set device address
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_SetAddress(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
uint8_t dev_addr;
if ((req->wIndex == 0) && (req->wLength == 0))
{
dev_addr = (uint8_t)(req->wValue) & 0x7F;
if (pdev->dev.device_status == USB_OTG_CONFIGURED)
{
USBD_CtlError(pdev , req);
}
else
{
pdev->dev.device_address = dev_addr;
DCD_EP_SetAddress(pdev, dev_addr);
USBD_CtlSendStatus(pdev);
if (dev_addr != 0)
{
pdev->dev.device_status = USB_OTG_ADDRESSED;
}
else
{
pdev->dev.device_status = USB_OTG_DEFAULT;
}
}
}
else
{
USBD_CtlError(pdev , req);
}
}
/**
* @brief USBD_SetConfig
* Handle Set device configuration request
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_SetConfig(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
static uint8_t cfgidx;
cfgidx = (uint8_t)(req->wValue);
if (cfgidx > USBD_CFG_MAX_NUM )
{
USBD_CtlError(pdev , req);
}
else
{
switch (pdev->dev.device_status)
{
case USB_OTG_ADDRESSED:
if (cfgidx)
{
pdev->dev.device_config = cfgidx;
pdev->dev.device_status = USB_OTG_CONFIGURED;
USBD_SetCfg(pdev , cfgidx);
USBD_CtlSendStatus(pdev);
}
else
{
USBD_CtlSendStatus(pdev);
}
break;
case USB_OTG_CONFIGURED:
if (cfgidx == 0)
{
pdev->dev.device_status = USB_OTG_ADDRESSED;
pdev->dev.device_config = cfgidx;
USBD_ClrCfg(pdev , cfgidx);
USBD_CtlSendStatus(pdev);
}
else if (cfgidx != pdev->dev.device_config)
{
/* Clear old configuration */
USBD_ClrCfg(pdev , pdev->dev.device_config);
/* set new configuration */
pdev->dev.device_config = cfgidx;
USBD_SetCfg(pdev , cfgidx);
USBD_CtlSendStatus(pdev);
}
else
{
USBD_CtlSendStatus(pdev);
}
break;
default:
USBD_CtlError(pdev , req);
break;
}
}
}
/**
* @brief USBD_GetConfig
* Handle Get device configuration request
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_GetConfig(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
if (req->wLength != 1)
{
USBD_CtlError(pdev , req);
}
else
{
switch (pdev->dev.device_status )
{
case USB_OTG_ADDRESSED:
USBD_CtlSendData (pdev,
(uint8_t *)&USBD_default_cfg,
1);
break;
case USB_OTG_CONFIGURED:
USBD_CtlSendData (pdev,
&pdev->dev.device_config,
1);
break;
default:
USBD_CtlError(pdev , req);
break;
}
}
}
/**
* @brief USBD_GetStatus
* Handle Get Status request
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_GetStatus(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
switch (pdev->dev.device_status)
{
case USB_OTG_ADDRESSED:
case USB_OTG_CONFIGURED:
#ifdef USBD_SELF_POWERED
USBD_cfg_status = USB_CONFIG_SELF_POWERED;
#else
USBD_cfg_status = 0x00;
#endif
if (pdev->dev.DevRemoteWakeup)
{
USBD_cfg_status |= USB_CONFIG_REMOTE_WAKEUP;
}
USBD_CtlSendData (pdev,
(uint8_t *)&USBD_cfg_status,
2);
break;
default :
USBD_CtlError(pdev , req);
break;
}
}
/**
* @brief USBD_SetFeature
* Handle Set device feature request
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_SetFeature(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
USB_OTG_DCTL_TypeDef dctl;
uint8_t test_mode = 0;
if (req->wValue == USB_FEATURE_REMOTE_WAKEUP)
{
pdev->dev.DevRemoteWakeup = 1;
pdev->dev.class_cb->Setup (pdev, req);
USBD_CtlSendStatus(pdev);
}
else if ((req->wValue == USB_FEATURE_TEST_MODE) &&
((req->wIndex & 0xFF) == 0))
{
dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
test_mode = req->wIndex >> 8;
switch (test_mode)
{
case 1: // TEST_J
dctl.b.tstctl = 1;
break;
case 2: // TEST_K
dctl.b.tstctl = 2;
break;
case 3: // TEST_SE0_NAK
dctl.b.tstctl = 3;
break;
case 4: // TEST_PACKET
dctl.b.tstctl = 4;
break;
case 5: // TEST_FORCE_ENABLE
dctl.b.tstctl = 5;
break;
}
SET_TEST_MODE = dctl;
pdev->dev.test_mode = 1;
USBD_CtlSendStatus(pdev);
}
}
/**
* @brief USBD_ClrFeature
* Handle clear device feature request
* @param pdev: device instance
* @param req: usb request
* @retval status
*/
static void USBD_ClrFeature(USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
switch (pdev->dev.device_status)
{
case USB_OTG_ADDRESSED:
case USB_OTG_CONFIGURED:
if (req->wValue == USB_FEATURE_REMOTE_WAKEUP)
{
pdev->dev.DevRemoteWakeup = 0;
pdev->dev.class_cb->Setup (pdev, req);
USBD_CtlSendStatus(pdev);
}
break;
default :
USBD_CtlError(pdev , req);
break;
}
}
/**
* @brief USBD_ParseSetupRequest
* Copy buffer into setup structure
* @param pdev: device instance
* @param req: usb request
* @retval None
*/
void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
req->bmRequest = *(uint8_t *) (pdev->dev.setup_packet);
req->bRequest = *(uint8_t *) (pdev->dev.setup_packet + 1);
req->wValue = SWAPBYTE (pdev->dev.setup_packet + 2);
req->wIndex = SWAPBYTE (pdev->dev.setup_packet + 4);
req->wLength = SWAPBYTE (pdev->dev.setup_packet + 6);
pdev->dev.in_ep[0].ctl_data_len = req->wLength ;
pdev->dev.device_state = USB_OTG_EP0_SETUP;
}
/**
* @brief USBD_CtlError
* Handle USB low level Error
* @param pdev: device instance
* @param req: usb request
* @retval None
*/
void USBD_CtlError( USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req)
{
DCD_EP_Stall(pdev , 0x80);
DCD_EP_Stall(pdev , 0);
USB_OTG_EP0_OutStart(pdev);
}
/**
* @brief USBD_GetString
* Convert Ascii string into unicode one
* @param desc : descriptor buffer
* @param unicode : Formatted string buffer (unicode)
* @param len : descriptor length
* @retval None
*/
void USBD_GetString(const uint8_t *desc, uint8_t *unicode, uint16_t *len)
{
uint8_t idx = 0;
if (desc != NULL) {
*len = USBD_GetLen(desc) * 2 + 2;
unicode[idx++] = *len;
unicode[idx++] = USB_DESC_TYPE_STRING;
while (*desc != NULL) {
unicode[idx++] = *desc++;
unicode[idx++] = 0x00;
}
}
}
/**
* @brief USBD_GetLen
* return the string length
* @param buf : pointer to the ascii string buffer
* @retval string length
*/
static uint8_t USBD_GetLen(const uint8_t *buf)
{
uint8_t len = 0;
while (*buf != NULL) {
len++;
buf++;
}
return len;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,108 +0,0 @@
/**
******************************************************************************
* @file usbd_req.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header file for the usbd_req.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_REQUEST_H_
#define __USB_REQUEST_H_
/* Includes ------------------------------------------------------------------*/
#include "usbd_def.h"
#include "usbd_core.h"
#include "usbd_conf.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_REQ
* @brief header file for the usbd_ioreq.c file
* @{
*/
/** @defgroup USBD_REQ_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBD_REQ_Exported_FunctionsPrototype
* @{
*/
USBD_Status USBD_StdDevReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req);
USBD_Status USBD_StdItfReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req);
USBD_Status USBD_StdEPReq (USB_OTG_CORE_HANDLE *pdev, USB_SETUP_REQ *req);
void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
void USBD_CtlError( USB_OTG_CORE_HANDLE *pdev,
USB_SETUP_REQ *req);
void USBD_GetString(const uint8_t *desc, uint8_t *unicode, uint16_t *len);
/**
* @}
*/
#endif /* __USB_REQUEST_H_ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,141 +0,0 @@
/**
******************************************************************************
* @file usbd_usr.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief Header file for usbd_usr.c
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_USR_H__
#define __USBD_USR_H__
/* Includes ------------------------------------------------------------------*/
#include "usbd_core.h"
/** @addtogroup USBD_USER
* @{
*/
/** @addtogroup USBD_MSC_DEMO_USER_CALLBACKS
* @{
*/
/** @defgroup USBD_USR
* @brief This file is the Header file for usbd_usr.c
* @{
*/
/** @defgroup USBD_USR_Exported_Types
* @{
*/
extern const USBD_Usr_cb_TypeDef USR_cb;
extern const USBD_Usr_cb_TypeDef USR_FS_cb;
extern const USBD_Usr_cb_TypeDef USR_HS_cb;
/**
* @}
*/
/** @defgroup USBD_USR_Exported_Defines
* @{
*/
/**
* @}
*/
/** @defgroup USBD_USR_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_USR_Exported_Variables
* @{
*/
void USBD_USR_Init(void);
void USBD_USR_DeviceReset (uint8_t speed);
void USBD_USR_DeviceConfigured (void);
void USBD_USR_DeviceSuspended(void);
void USBD_USR_DeviceResumed(void);
void USBD_USR_DeviceConnected(void);
void USBD_USR_DeviceDisconnected(void);
void USBD_USR_FS_Init(void);
void USBD_USR_FS_DeviceReset (uint8_t speed);
void USBD_USR_FS_DeviceConfigured (void);
void USBD_USR_FS_DeviceSuspended(void);
void USBD_USR_FS_DeviceResumed(void);
void USBD_USR_FS_DeviceConnected(void);
void USBD_USR_FS_DeviceDisconnected(void);
void USBD_USR_HS_Init(void);
void USBD_USR_HS_DeviceReset (uint8_t speed);
void USBD_USR_HS_DeviceConfigured (void);
void USBD_USR_HS_DeviceSuspended(void);
void USBD_USR_HS_DeviceResumed(void);
void USBD_USR_HS_DeviceConnected(void);
void USBD_USR_HS_DeviceDisconnected(void);
/**
* @}
*/
/** @defgroup USBD_USR_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif /*__USBD_USR_H__*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,105 +0,0 @@
/*
(c) 2017 night_ghost@ykoctpa.ru
*/
#include "StorageMode.h"
// defines of disk status
#include "../sd/FatFs/diskio.h"
extern USB_OTG_CORE_HANDLE USB_OTG_dev;
const int8_t STORAGE_Inquirydata[] =
{
0x00, 0x80, 0x02, 0x02,
(USBD_STD_INQUIRY_LENGTH - 5),
0x00, 0x00, 0x00,
'R', 'E', 'V', 'O', ' ', '@', 'N', 'G', // Manufacturer : 8 bytes
'S', 'D', ' ', 'C', 'a', 'r', 'd', ' ', // Product : 16 Bytes
'R', 'e', 'a', 'd', 'e', 'r', ' ', ' ', //
'1', '.', '0' ,'0', // Version : 4 Bytes
};
int8_t STORAGE_Init(uint8_t lun)
{
return 0;
}
int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size)
{
if(lun>0) return 1;
*block_size = MAL_massBlockSize[lun];
*block_num = MAL_massBlockCount[lun];
return 0;
}
int8_t STORAGE_IsReady(uint8_t lun)
{
return usb_mass_mal_get_status(lun) & (STA_NODISK | STA_NOINIT);
}
int8_t STORAGE_IsWriteProtected(uint8_t lun)
{
return usb_mass_mal_get_status(lun) & STA_PROTECT;
}
int8_t STORAGE_Read(
uint8_t lun, // logical unit number
uint8_t *buf, // Pointer to the buffer to save data
uint32_t blk_addr, // address of 1st block to be read
uint16_t blk_len) // nmber of blocks to be read
{
return usb_mass_mal_read_memory(lun, buf, blk_addr, blk_len);
}
int8_t STORAGE_Write(uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len)
{
return usb_mass_mal_write_memory(lun, buf, blk_addr, blk_len);
}
inline int8_t STORAGE_GetMaxLun(void)
{
return (STORAGE_LUN_NBR - 1);
}
#ifdef USE_USB_OTG_FS
extern void systemInit(uint8_t oc);
void OTG_FS_WKUP_IRQHandler(void)
{
if(USB_OTG_dev.cfg.low_power)
{
*(uint32_t *)(0xE000ED10) &= 0xFFFFFFF9 ; // SCB_SCR reset bits 0x6, SLEEPDEEP & SLEEPONEXIT
systemInit(0);
USB_OTG_UngateClock(&USB_OTG_dev);
}
EXTI_ClearITPendingBit(EXTI_Line18);
}
#endif
const USBD_STORAGE_cb_TypeDef STORAGE_fops =
{
STORAGE_Init,
STORAGE_GetCapacity,
STORAGE_IsReady,
STORAGE_IsWriteProtected,
STORAGE_Read,
STORAGE_Write,
STORAGE_GetMaxLun,
(int8_t *)STORAGE_Inquirydata,
};
const USBD_STORAGE_cb_TypeDef * const USBD_STORAGE_fops = &STORAGE_fops;

View File

@ -1,20 +0,0 @@
#ifndef STORAGE_MODE_H
#define STORAGE_MODE_H
#include "msc/usbd_msc_mem.h"
#include <usb_dcd_int.h>
#include "usb_mass_mal.h"
int8_t STORAGE_Init(uint8_t lun);
int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size);
int8_t STORAGE_IsReady(uint8_t lun);
int8_t STORAGE_IsWriteProtected(uint8_t lun);
int8_t STORAGE_GetMaxLun(void);
void OTG_FS_WKUP_IRQHandler(void);
int8_t STORAGE_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
int8_t STORAGE_Write(uint8_t lun,uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
#endif

View File

@ -1,333 +0,0 @@
/**
(c) 2017 night_ghost@ykoctpa.ru
based on:
******************************************************************************
* @file usbd_desc.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides the USBD descriptors and string formating method.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_core.h"
#include "usbd_desc.h"
#include "usbd_req.h"
#include "usbd_conf.h"
#include "usb_regs.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_DESC
* @brief USBD descriptors module
* @{
*/
/** @defgroup USBD_DESC_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Private_Defines
* @{
*/
#define USBD_VID 0x0483
#define USBD_PID 0x5720
#define USBD_LANGID_STRING 0x409
#define USBD_MANUFACTURER_STRING "STMicroelectronics"
#define USBD_PRODUCT_HS_STRING "Mass Storage in HS Mode"
#define USBD_SERIALNUMBER_HS_STRING "00000000001A"
#define USBD_PRODUCT_FS_STRING "Mass Storage in FS Mode"
#define USBD_SERIALNUMBER_FS_STRING "00000000001B"
#define USBD_CONFIGURATION_HS_STRING "MSC Config"
#define USBD_INTERFACE_HS_STRING "MSC Interface"
#define USBD_CONFIGURATION_FS_STRING "MSC Config"
#define USBD_INTERFACE_FS_STRING "MSC Interface"
/**
* @}
*/
/** @defgroup USBD_DESC_Private_Macros
* @{
*/
/**
* @}
*/
uint8_t * USBD_MSC_DeviceDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_MSC_LangIDStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_MSC_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length);
uint8_t * USBD_MSC_ProductStrDescriptor ( uint8_t speed , uint16_t *length);
uint8_t * USBD_MSC_SerialStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_MSC_ConfigStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_MSC_InterfaceStrDescriptor( uint8_t speed , uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t * USBD_MSC_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
/** @defgroup USBD_DESC_Private_Variables
* @{
*/
const USBD_DEVICE USR_MSC_desc =
{
USBD_MSC_DeviceDescriptor,
USBD_MSC_LangIDStrDescriptor,
USBD_MSC_ManufacturerStrDescriptor,
USBD_MSC_ProductStrDescriptor,
USBD_MSC_SerialStrDescriptor,
USBD_MSC_ConfigStrDescriptor,
USBD_MSC_InterfaceStrDescriptor,
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
const __ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END =
{
0x12, /*bLength */
USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType*/
0x00, /*bcdUSB */
0x02,
0x00, /*bDeviceClass*/
0x00, /*bDeviceSubClass*/
0x00, /*bDeviceProtocol*/
USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/
LOBYTE(USBD_VID), /*idVendor*/
HIBYTE(USBD_VID), /*idVendor*/
LOBYTE(USBD_PID), /*idVendor*/
HIBYTE(USBD_PID), /*idVendor*/
0x00, /*bcdDevice rel. 2.00*/
0x02,
USBD_IDX_MFC_STR, /*Index of manufacturer string*/
USBD_IDX_PRODUCT_STR, /*Index of product string*/
USBD_IDX_SERIAL_STR, /*Index of serial number string*/
USBD_CFG_MAX_NUM /*bNumConfigurations*/
} ; /* USB_DeviceDescriptor */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_MSC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
{
USB_LEN_DEV_QUALIFIER_DESC,
USB_DESC_TYPE_DEVICE_QUALIFIER,
0x00,
0x02,
0x00,
0x00,
0x00,
0x40,
0x01,
0x00,
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
const __ALIGN_BEGIN uint8_t USBD_MSC_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END =
{
USB_SIZ_STRING_LANGID,
USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
};
/**
* @}
*/
/** @defgroup USBD_DESC_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup USBD_DESC_Private_Functions
* @{
*/
/**
* @brief USBD_MSC_DeviceDescriptor
* return the device descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_DeviceDescriptor( uint8_t speed , uint16_t *length)
{
*length = sizeof(USBD_MSC_DeviceDesc);
return (uint8_t *)USBD_MSC_DeviceDesc;
}
/**
* @brief USBD_MSC_LangIDStrDescriptor
* return the LangID string descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
{
*length = sizeof(USBD_MSC_LangIDDesc);
return (uint8_t *)USBD_MSC_LangIDDesc;
}
/**
* @brief USBD_MSC_ProductStrDescriptor
* return the product string descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_ProductStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == 0)
{
USBD_GetString ((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
}
else
{
USBD_GetString ((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
/**
* @brief USBD_MSC_ManufacturerStrDescriptor
* return the manufacturer string descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length)
{
USBD_GetString ((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
}
/**
* @brief USBD_MSC_SerialStrDescriptor
* return the serial number string descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_SerialStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == USB_OTG_SPEED_HIGH)
{
USBD_GetString ((uint8_t *)USBD_SERIALNUMBER_HS_STRING, USBD_StrDesc, length);
}
else
{
USBD_GetString ((uint8_t *)USBD_SERIALNUMBER_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
/**
* @brief USBD_MSC_ConfigStrDescriptor
* return the configuration string descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_ConfigStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == USB_OTG_SPEED_HIGH)
{
USBD_GetString ((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
}
else
{
USBD_GetString ((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
/**
* @brief USBD_MSC_InterfaceStrDescriptor
* return the interface string descriptor
* @param speed : current device speed
* @param length : pointer to data length variable
* @retval pointer to descriptor buffer
*/
uint8_t * USBD_MSC_InterfaceStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == 0)
{
USBD_GetString ((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length);
}
else
{
USBD_GetString ((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,91 +0,0 @@
/*
(c) 2017 night_ghost@ykoctpa.ru
*/
#include <AP_HAL_F4Light/AP_HAL_F4Light_Namespace.h>
#include "mass_storage.h"
#include "../sd/SD.h"
#include "../sd/Sd2Card.h"
#include <usb.h>
#include "usbMassStorage.h"
#ifdef USB_MASSSTORAGE
/*
also see https://habrahabr.ru/post/335018/ and https://habrahabr.ru/post/336968/
*/
uint32_t MAL_massBlockCount[STORAGE_LUN_NBR];
uint32_t MAL_massBlockSize[STORAGE_LUN_NBR];
extern USB_OTG_CORE_HANDLE USB_OTG_dev;
void MassStorage::setup() const {
usb_attr_t usb_attr;
usb_open();
usb_default_attr(&usb_attr);
usb_attr.preempt_prio = USB_INT_PRIORITY;
usb_attr.sub_prio = 0;
usb_attr.use_present_pin = 1;
usb_attr.present_port = PIN_MAP[BOARD_USB_SENSE].gpio_device;
usb_attr.present_pin = PIN_MAP[BOARD_USB_SENSE].gpio_bit;
usb_setParams(&usb_attr);
SdFatFs *fs = SD.getVolume();
MAL_massBlockSize[0] = fs->sectorSize();
MAL_massBlockCount[0] = fs->sectorCount(); // in blocks
SD.sync(); // consistent state
SCSI_Init(); // start USB IO task
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_MSC_desc, &USBD_MSC_cb, &USR_cb);
}
// The following methods are used by the USBMassStorage driver to read and write to the SDCard.
extern "C" {
uint16_t usb_mass_mal_get_status(uint8_t lun){
return Sd2Card::errorCode();
}
int8_t usb_mass_mal_write_memory(uint8_t lun,uint8_t *writebuff, uint32_t lba, uint16_t transferLength) {
if (lun != 0) {
return USB_MASS_MAL_FAIL;
}
if (Sd2Card::writeBlock(writebuff, lba, transferLength)) {
return USB_MASS_MAL_SUCCESS;
}
return USB_MASS_MAL_FAIL;
}
int8_t usb_mass_mal_read_memory(uint8_t lun, uint8_t *readbuff, uint32_t lba, uint16_t transferLength) {
if (lun != 0) {
return USB_MASS_MAL_FAIL;
}
if (Sd2Card::readBlock(readbuff, lba, transferLength)) {
return USB_MASS_MAL_SUCCESS;
}
return USB_MASS_MAL_FAIL;
}
} // extern C
#endif

View File

@ -1,23 +0,0 @@
#pragma once
#include <AP_HAL/HAL.h>
#include <stdbool.h>
#include "usb_mass_mal.h"
extern "C" {
extern int usb_close(void);
extern void SCSI_Init();
}
namespace F4Light {
class MassStorage {
public:
MassStorage() {}
void setup() const;
};
} // namespace

View File

@ -1,406 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_bot.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides all the BOT protocol core functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_msc_bot.h"
#include "usbd_msc_scsi.h"
#include "usbd_ioreq.h"
#include "usbd_msc_mem.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup MSC_BOT
* @brief BOT protocol module
* @{
*/
/** @defgroup MSC_BOT_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup MSC_BOT_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup MSC_BOT_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MSC_BOT_Private_Variables
* @{
*/
uint16_t MSC_BOT_DataLen;
uint8_t MSC_BOT_State;
uint8_t MSC_BOT_Status;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t MSC_BOT_Data[MSC_MEDIA_PACKET] __ALIGN_END ;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN MSC_BOT_CBW_TypeDef MSC_BOT_cbw __ALIGN_END ;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN MSC_BOT_CSW_TypeDef MSC_BOT_csw __ALIGN_END ;
/**
* @}
*/
/** @defgroup MSC_BOT_Private_FunctionPrototypes
* @{
*/
static void MSC_BOT_CBW_Decode (USB_OTG_CORE_HANDLE *pdev);
static void MSC_BOT_SendData (USB_OTG_CORE_HANDLE *pdev,
uint8_t* pbuf,
uint16_t len);
static void MSC_BOT_Abort(USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
/** @defgroup MSC_BOT_Private_Functions
* @{
*/
/**
* @brief MSC_BOT_Init
* Initialize the BOT Process
* @param pdev: device instance
* @retval None
*/
void MSC_BOT_Init (USB_OTG_CORE_HANDLE *pdev)
{
MSC_BOT_State = BOT_IDLE;
MSC_BOT_Status = BOT_STATE_NORMAL;
USBD_STORAGE_fops->Init(0);
DCD_EP_Flush(pdev, MSC_OUT_EP);
DCD_EP_Flush(pdev, MSC_IN_EP);
/* Prapare EP to Receive First BOT Cmd */
DCD_EP_PrepareRx (pdev,
MSC_OUT_EP,
(uint8_t *)&MSC_BOT_cbw,
BOT_CBW_LENGTH);
}
/**
* @brief MSC_BOT_Reset
* Reset the BOT Machine
* @param pdev: device instance
* @retval None
*/
void MSC_BOT_Reset (USB_OTG_CORE_HANDLE *pdev)
{
MSC_BOT_State = BOT_IDLE;
MSC_BOT_Status = BOT_STATE_RECOVERY;
/* Prapare EP to Receive First BOT Cmd */
DCD_EP_PrepareRx (pdev,
MSC_OUT_EP,
(uint8_t *)&MSC_BOT_cbw,
BOT_CBW_LENGTH);
}
/**
* @brief MSC_BOT_DeInit
* Uninitialize the BOT Machine
* @param pdev: device instance
* @retval None
*/
void MSC_BOT_DeInit (USB_OTG_CORE_HANDLE *pdev)
{
MSC_BOT_State = BOT_IDLE;
}
/**
* @brief MSC_BOT_DataIn
* Handle BOT IN data stage
* @param pdev: device instance
* @param epnum: endpoint index
* @retval None
*/
void MSC_BOT_DataIn (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum)
{
switch (MSC_BOT_State)
{
case BOT_DATA_IN:
if(SCSI_ProcessCmd(pdev,
MSC_BOT_cbw.bLUN,
&MSC_BOT_cbw.CB[0]) < 0)
{
MSC_BOT_SendCSW (pdev, CSW_CMD_FAILED);
}
break;
case BOT_SEND_DATA:
case BOT_LAST_DATA_IN:
MSC_BOT_SendCSW (pdev, CSW_CMD_PASSED);
break;
default:
break;
}
}
/**
* @brief MSC_BOT_DataOut
* Proccess MSC OUT data
* @param pdev: device instance
* @param epnum: endpoint index
* @retval None
*/
void MSC_BOT_DataOut (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum)
{
switch (MSC_BOT_State)
{
case BOT_IDLE:
MSC_BOT_CBW_Decode(pdev);
break;
case BOT_DATA_OUT:
if(SCSI_ProcessCmd(pdev,
MSC_BOT_cbw.bLUN,
&MSC_BOT_cbw.CB[0]) < 0)
{
MSC_BOT_SendCSW (pdev, CSW_CMD_FAILED);
}
break;
default:
break;
}
}
/**
* @brief MSC_BOT_CBW_Decode
* Decode the CBW command and set the BOT state machine accordingtly
* @param pdev: device instance
* @retval None
*/
static void MSC_BOT_CBW_Decode (USB_OTG_CORE_HANDLE *pdev)
{
MSC_BOT_csw.dTag = MSC_BOT_cbw.dTag;
MSC_BOT_csw.dDataResidue = MSC_BOT_cbw.dDataLength;
if ((USBD_GetRxCount (pdev ,MSC_OUT_EP) != BOT_CBW_LENGTH) ||
(MSC_BOT_cbw.dSignature != BOT_CBW_SIGNATURE)||
(MSC_BOT_cbw.bLUN > 1) ||
(MSC_BOT_cbw.bCBLength < 1) ||
(MSC_BOT_cbw.bCBLength > 16))
{
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
MSC_BOT_Status = BOT_STATE_ERROR;
MSC_BOT_Abort(pdev);
return;
}
if(SCSI_ProcessCmd(pdev, MSC_BOT_cbw.bLUN,
&MSC_BOT_cbw.CB[0]) < 0){
MSC_BOT_Abort(pdev);
return;
}
// MSC_BOT_CBW_finish(); moved out to SCSI task
}
void MSC_BOT_CBW_finish (USB_OTG_CORE_HANDLE *pdev){
/*Burst xfer handled internally*/
if ((MSC_BOT_State != BOT_DATA_IN) &&
(MSC_BOT_State != BOT_DATA_OUT) &&
(MSC_BOT_State != BOT_LAST_DATA_IN)) // idle or BOT_SEND_DATA
{
if (MSC_BOT_DataLen > 0) {
MSC_BOT_SendData(pdev,
MSC_BOT_Data,
MSC_BOT_DataLen);
MSC_BOT_DataLen=0;
} else if (MSC_BOT_DataLen == 0) {
MSC_BOT_SendCSW (pdev,
CSW_CMD_PASSED);
}
}
}
/**
* @brief MSC_BOT_SendData
* Send the requested data
* @param pdev: device instance
* @param buf: pointer to data buffer
* @param len: Data Length
* @retval None
*/
static void MSC_BOT_SendData(USB_OTG_CORE_HANDLE *pdev,
uint8_t* buf,
uint16_t len)
{
len = MIN (MSC_BOT_cbw.dDataLength, len);
MSC_BOT_csw.dDataResidue -= len;
MSC_BOT_csw.bStatus = CSW_CMD_PASSED;
MSC_BOT_State = BOT_SEND_DATA;
DCD_EP_Tx (pdev, MSC_IN_EP, buf, len);
}
/**
* @brief MSC_BOT_SendCSW
* Send the Command Status Wrapper
* @param pdev: device instance
* @param status : CSW status
* @retval None
*/
void MSC_BOT_SendCSW (USB_OTG_CORE_HANDLE *pdev,
uint8_t CSW_Status)
{
MSC_BOT_csw.dSignature = BOT_CSW_SIGNATURE;
MSC_BOT_csw.bStatus = CSW_Status;
MSC_BOT_State = BOT_IDLE;
DCD_EP_Tx (pdev,
MSC_IN_EP,
(uint8_t *)&MSC_BOT_csw,
BOT_CSW_LENGTH);
/* Prapare EP to Receive next Cmd */
DCD_EP_PrepareRx (pdev,
MSC_OUT_EP,
(uint8_t *)&MSC_BOT_cbw,
BOT_CBW_LENGTH);
}
/**
* @brief MSC_BOT_Abort
* Abort the current transfer
* @param pdev: device instance
* @retval status
*/
static void MSC_BOT_Abort (USB_OTG_CORE_HANDLE *pdev)
{
if ((MSC_BOT_cbw.bmFlags == 0) &&
(MSC_BOT_cbw.dDataLength != 0) &&
(MSC_BOT_Status == BOT_STATE_NORMAL) )
{
DCD_EP_Stall(pdev, MSC_OUT_EP );
}
DCD_EP_Stall(pdev, MSC_IN_EP);
if(MSC_BOT_Status == BOT_STATE_ERROR)
{
DCD_EP_PrepareRx (pdev,
MSC_OUT_EP,
(uint8_t *)&MSC_BOT_cbw,
BOT_CBW_LENGTH);
}
}
/**
* @brief MSC_BOT_CplClrFeature
* Complete the clear feature request
* @param pdev: device instance
* @param epnum: endpoint index
* @retval None
*/
void MSC_BOT_CplClrFeature (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
{
if(MSC_BOT_Status == BOT_STATE_ERROR )/* Bad CBW Signature */
{
DCD_EP_Stall(pdev, MSC_IN_EP);
MSC_BOT_Status = BOT_STATE_NORMAL;
}
else if(((epnum & 0x80) == 0x80) && ( MSC_BOT_Status != BOT_STATE_RECOVERY))
{
MSC_BOT_SendCSW (pdev, CSW_CMD_FAILED);
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,156 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_bot.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header for the usbd_msc_bot.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#include "usbd_core.h"
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_MSC_BOT_H
#define __USBD_MSC_BOT_H
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup MSC_BOT
* @brief This file is the Header file for usbd_bot.c
* @{
*/
/** @defgroup USBD_CORE_Exported_Defines
* @{
*/
enum BOT_STATE {
BOT_IDLE = 0, /* Idle state */
BOT_DATA_OUT = 1, /* Data Out state */
BOT_DATA_IN = 2, /* Data In state */
BOT_LAST_DATA_IN = 3, /* Last Data In Last */
BOT_SEND_DATA = 4, /* Send Immediate data */
};
#define BOT_CBW_SIGNATURE 0x43425355
#define BOT_CSW_SIGNATURE 0x53425355
#define BOT_CBW_LENGTH 31
#define BOT_CSW_LENGTH 13
/* CSW Status Definitions */
#define CSW_CMD_PASSED 0x00
#define CSW_CMD_FAILED 0x01
#define CSW_PHASE_ERROR 0x02
/* BOT Status */
#define BOT_STATE_NORMAL 0
#define BOT_STATE_RECOVERY 1
#define BOT_STATE_ERROR 2
#define DIR_IN 0
#define DIR_OUT 1
#define BOTH_DIR 2
/**
* @}
*/
/** @defgroup MSC_CORE_Private_TypesDefinitions
* @{
*/
typedef struct _MSC_BOT_CBW
{
uint32_t dSignature;
uint32_t dTag;
uint32_t dDataLength;
uint8_t bmFlags;
uint8_t bLUN;
uint8_t bCBLength;
uint8_t CB[16];
}
MSC_BOT_CBW_TypeDef;
typedef struct _MSC_BOT_CSW
{
uint32_t dSignature;
uint32_t dTag;
uint32_t dDataResidue;
uint8_t bStatus;
}
MSC_BOT_CSW_TypeDef;
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_Types
* @{
*/
extern uint8_t MSC_BOT_Data[];
extern uint16_t MSC_BOT_DataLen;
extern uint8_t MSC_BOT_State;
extern uint8_t MSC_BOT_BurstMode;
extern MSC_BOT_CBW_TypeDef MSC_BOT_cbw;
extern MSC_BOT_CSW_TypeDef MSC_BOT_csw;
/**
* @}
*/
/** @defgroup USBD_CORE_Exported_FunctionsPrototypes
* @{
*/
void MSC_BOT_Init (USB_OTG_CORE_HANDLE *pdev);
void MSC_BOT_Reset (USB_OTG_CORE_HANDLE *pdev);
void MSC_BOT_DeInit (USB_OTG_CORE_HANDLE *pdev);
void MSC_BOT_DataIn (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
void MSC_BOT_DataOut (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
void MSC_BOT_SendCSW (USB_OTG_CORE_HANDLE *pdev,
uint8_t CSW_Status);
void MSC_BOT_CplClrFeature (USB_OTG_CORE_HANDLE *pdev,
uint8_t epnum);
void MSC_BOT_CBW_finish (USB_OTG_CORE_HANDLE *pdev);
/**
* @}
*/
#endif /* __USBD_MSC_BOT_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,497 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_core.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides all the MSC core functions.
*
* @verbatim
*
* ===================================================================
* MSC Class Description
* ===================================================================
* This module manages the MSC class V1.0 following the "Universal
* Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0
* Sep. 31, 1999".
* This driver implements the following aspects of the specification:
* - Bulk-Only Transport protocol
* - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3))
*
* @endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_msc_mem.h"
#include "usbd_msc_core.h"
#include "usbd_msc_bot.h"
#include "usbd_req.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup MSC_CORE
* @brief Mass storage core module
* @{
*/
/** @defgroup MSC_CORE_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup MSC_CORE_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup MSC_CORE_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MSC_CORE_Private_FunctionPrototypes
* @{
*/
uint8_t USBD_MSC_Init (void *pdev,
uint8_t cfgidx);
uint8_t USBD_MSC_DeInit (void *pdev,
uint8_t cfgidx);
uint8_t USBD_MSC_Setup (void *pdev,
USB_SETUP_REQ *req);
uint8_t USBD_MSC_DataIn (void *pdev,
uint8_t epnum);
uint8_t USBD_MSC_DataOut (void *pdev,
uint8_t epnum);
uint8_t *USBD_MSC_GetCfgDesc (uint8_t speed,
uint16_t *length);
#ifdef USB_OTG_HS_CORE
uint8_t *USBD_MSC_GetOtherCfgDesc (uint8_t speed,
uint16_t *length);
#endif
const uint8_t USBD_MSC_CfgDesc[USB_MSC_CONFIG_DESC_SIZ];
/**
* @}
*/
/** @defgroup MSC_CORE_Private_Variables
* @{
*/
const USBD_Class_cb_TypeDef USBD_MSC_cb =
{
USBD_MSC_Init,
USBD_MSC_DeInit,
USBD_MSC_Setup,
NULL, /*EP0_TxSent*/
NULL, /*EP0_RxReady*/
USBD_MSC_DataIn,
USBD_MSC_DataOut,
NULL, /*SOF */
NULL,
NULL,
USBD_MSC_GetCfgDesc,
#ifdef USB_OTG_HS_CORE
USBD_MSC_GetOtherCfgDesc,
#endif
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Mass storage device Configuration Descriptor */
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
const __ALIGN_BEGIN uint8_t USBD_MSC_CfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
{
0x09, /* bLength: Configuation Descriptor size */
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
USB_MSC_CONFIG_DESC_SIZ,
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */
0x04, /* iConfiguration: */
0xC0, /* bmAttributes: */
0x32, /* MaxPower 100 mA */
/******************** Mass Storage interface ********************/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x02, /* bNumEndpoints*/
0x08, /* bInterfaceClass: MSC Class */
0x06, /* bInterfaceSubClass : SCSI transparent*/
0x50, /* nInterfaceProtocol : bulk only */
0x05, /* iInterface: */
/******************** Mass Storage Endpoints ********************/
0x07, /*Endpoint descriptor length = 7*/
0x05, /*Endpoint descriptor type */
MSC_IN_EP, /*Endpoint address (IN, address 1) */
0x02, /*Bulk endpoint type */
LOBYTE(MSC_MAX_PACKET),
HIBYTE(MSC_MAX_PACKET),
0x00, /*Polling interval in milliseconds */
0x07, /*Endpoint descriptor length = 7 */
0x05, /*Endpoint descriptor type */
MSC_OUT_EP, /*Endpoint address (OUT, address 1) */
0x02, /*Bulk endpoint type */
LOBYTE(MSC_MAX_PACKET),
HIBYTE(MSC_MAX_PACKET),
0x00 /*Polling interval in milliseconds*/
};
#ifdef USB_OTG_HS_CORE
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN uint8_t USBD_MSC_OtherCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
{
0x09, /* bLength: Configuation Descriptor size */
USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
USB_MSC_CONFIG_DESC_SIZ,
0x00,
0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */
0x04, /* iConfiguration: */
0xC0, /* bmAttributes: */
0x32, /* MaxPower 100 mA */
/******************** Mass Storage interface ********************/
0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x02, /* bNumEndpoints*/
0x08, /* bInterfaceClass: MSC Class */
0x06, /* bInterfaceSubClass : SCSI transparent command set*/
0x50, /* nInterfaceProtocol */
0x05, /* iInterface: */
/******************** Mass Storage Endpoints ********************/
0x07, /*Endpoint descriptor length = 7*/
0x05, /*Endpoint descriptor type */
MSC_IN_EP, /*Endpoint address (IN, address 1) */
0x02, /*Bulk endpoint type */
0x40,
0x00,
0x00, /*Polling interval in milliseconds */
0x07, /*Endpoint descriptor length = 7 */
0x05, /*Endpoint descriptor type */
MSC_OUT_EP, /*Endpoint address (OUT, address 1) */
0x02, /*Bulk endpoint type */
0x40,
0x00,
0x00 /*Polling interval in milliseconds*/
};
#endif
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN static uint8_t USBD_MSC_MaxLun __ALIGN_END = 0;
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
__ALIGN_BEGIN static uint8_t USBD_MSC_AltSet __ALIGN_END = 0;
/**
* @}
*/
/** @defgroup MSC_CORE_Private_Functions
* @{
*/
/**
* @brief USBD_MSC_Init
* Initialize the mass storage configuration
* @param pdev: device instance
* @param cfgidx: configuration index
* @retval status
*/
uint8_t USBD_MSC_Init (void *pdev,
uint8_t cfgidx)
{
USBD_MSC_DeInit(pdev , cfgidx );
/* Open EP IN */
DCD_EP_Open(pdev,
MSC_IN_EP,
MSC_EPIN_SIZE,
USB_OTG_EP_BULK);
/* Open EP OUT */
DCD_EP_Open(pdev,
MSC_OUT_EP,
MSC_EPOUT_SIZE,
USB_OTG_EP_BULK);
/* Init the BOT layer */
MSC_BOT_Init(pdev);
return USBD_OK;
}
/**
* @brief USBD_MSC_DeInit
* DeInitilaize the mass storage configuration
* @param pdev: device instance
* @param cfgidx: configuration index
* @retval status
*/
uint8_t USBD_MSC_DeInit (void *pdev,
uint8_t cfgidx)
{
/* Close MSC EPs */
DCD_EP_Close (pdev , MSC_IN_EP);
DCD_EP_Close (pdev , MSC_OUT_EP);
/* Un Init the BOT layer */
MSC_BOT_DeInit(pdev);
return USBD_OK;
}
/**
* @brief USBD_MSC_Setup
* Handle the MSC specific requests
* @param pdev: device instance
* @param req: USB request
* @retval status
*/
uint8_t USBD_MSC_Setup (void *pdev, USB_SETUP_REQ *req)
{
switch (req->bmRequest & USB_REQ_TYPE_MASK)
{
/* Class request */
case USB_REQ_TYPE_CLASS :
switch (req->bRequest)
{
case BOT_GET_MAX_LUN :
if((req->wValue == 0) &&
(req->wLength == 1) &&
((req->bmRequest & 0x80) == 0x80))
{
USBD_MSC_MaxLun = USBD_STORAGE_fops->GetMaxLun();
if(USBD_MSC_MaxLun > 0)
{
USBD_CtlSendData (pdev,
&USBD_MSC_MaxLun,
1);
}
else
{
USBD_CtlError(pdev , req);
return USBD_FAIL;
}
}
else
{
USBD_CtlError(pdev , req);
return USBD_FAIL;
}
break;
case BOT_RESET :
if((req->wValue == 0) &&
(req->wLength == 0) &&
((req->bmRequest & 0x80) != 0x80))
{
MSC_BOT_Reset(pdev);
}
else
{
USBD_CtlError(pdev , req);
return USBD_FAIL;
}
break;
default:
USBD_CtlError(pdev , req);
return USBD_FAIL;
}
break;
/* Interface & Endpoint request */
case USB_REQ_TYPE_STANDARD:
switch (req->bRequest)
{
case USB_REQ_GET_INTERFACE :
USBD_CtlSendData (pdev,
&USBD_MSC_AltSet,
1);
break;
case USB_REQ_SET_INTERFACE :
USBD_MSC_AltSet = (uint8_t)(req->wValue);
break;
case USB_REQ_CLEAR_FEATURE:
/* Flush the FIFO and Clear the stall status */
DCD_EP_Flush(pdev, (uint8_t)req->wIndex);
/* Re-activate the EP */
DCD_EP_Close (pdev , (uint8_t)req->wIndex);
if((((uint8_t)req->wIndex) & 0x80) == 0x80)
{
DCD_EP_Open(pdev,
((uint8_t)req->wIndex),
MSC_EPIN_SIZE,
USB_OTG_EP_BULK);
}
else
{
DCD_EP_Open(pdev,
((uint8_t)req->wIndex),
MSC_EPOUT_SIZE,
USB_OTG_EP_BULK);
}
/* Handle BOT error */
MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex);
break;
}
break;
default:
break;
}
return USBD_OK;
}
/**
* @brief USBD_MSC_DataIn
* handle data IN Stage
* @param pdev: device instance
* @param epnum: endpoint index
* @retval status
*/
uint8_t USBD_MSC_DataIn (void *pdev,
uint8_t epnum)
{
MSC_BOT_DataIn(pdev , epnum);
return USBD_OK;
}
/**
* @brief USBD_MSC_DataOut
* handle data OUT Stage
* @param pdev: device instance
* @param epnum: endpoint index
* @retval status
*/
uint8_t USBD_MSC_DataOut (void *pdev,
uint8_t epnum)
{
MSC_BOT_DataOut(pdev , epnum);
return USBD_OK;
}
/**
* @brief USBD_MSC_GetCfgDesc
* return configuration descriptor
* @param speed : current device speed
* @param length : pointer data length
* @retval pointer to descriptor buffer
*/
uint8_t *USBD_MSC_GetCfgDesc (uint8_t speed, uint16_t *length)
{
*length = sizeof (USBD_MSC_CfgDesc);
return (uint8_t *)USBD_MSC_CfgDesc;
}
/**
* @brief USBD_MSC_GetOtherCfgDesc
* return other speed configuration descriptor
* @param speed : current device speed
* @param length : pointer data length
* @retval pointer to descriptor buffer
*/
#ifdef USB_OTG_HS_CORE
uint8_t *USBD_MSC_GetOtherCfgDesc (uint8_t speed,
uint16_t *length)
{
*length = sizeof (USBD_MSC_OtherCfgDesc);
return USBD_MSC_OtherCfgDesc;
}
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,78 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_core.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header for the usbd_msc_core.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef _USB_MSC_CORE_H_
#define _USB_MSC_CORE_H_
#include "usbd_ioreq.h"
extern USBD_DEVICE USR_MSC_desc;
/** @addtogroup USBD_MSC_BOT
* @{
*/
/** @defgroup USBD_MSC
* @brief This file is the Header file for USBD_msc.c
* @{
*/
/** @defgroup USBD_BOT_Exported_Defines
* @{
*/
#define BOT_GET_MAX_LUN 0xFE
#define BOT_RESET 0xFF
#define USB_MSC_CONFIG_DESC_SIZ 32
#define MSC_EPIN_SIZE MSC_MAX_PACKET
#define MSC_EPOUT_SIZE MSC_MAX_PACKET
/**
* @}
*/
/** @defgroup USB_CORE_Exported_Types
* @{
*/
extern const USBD_Class_cb_TypeDef USBD_MSC_cb;
/**
* @}
*/
/**
* @}
*/
#endif // _USB_MSC_CORE_H_
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,134 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_data.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides all the vital inquiry pages and sense data.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_msc_data.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup MSC_DATA
* @brief Mass storage info/data module
* @{
*/
/** @defgroup MSC_DATA_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup MSC_DATA_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup MSC_DATA_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MSC_DATA_Private_Variables
* @{
*/
/* USB Mass storage Page 0 Inquiry Data */
const uint8_t MSC_Page00_Inquiry_Data[] = {//7
0x00,
0x00,
0x00,
(LENGTH_INQUIRY_PAGE00 - 4),
0x00,
0x80,
0x83
};
/* USB Mass storage sense 6 Data */
const uint8_t MSC_Mode_Sense6_data[] = {
0x00,
0x00,
0x00,
0x00,
0x00,
0x00,
0x00,
0x00
};
/* USB Mass storage sense 10 Data */
const uint8_t MSC_Mode_Sense10_data[] = {
0x00,
0x06,
0x00,
0x00,
0x00,
0x00,
0x00,
0x00
};
/**
* @}
*/
/** @defgroup MSC_DATA_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @defgroup MSC_DATA_Private_Functions
* @{
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,104 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_data.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header for the usbd_msc_data.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef _USBD_MSC_DATA_H_
#define _USBD_MSC_DATA_H_
/* Includes ------------------------------------------------------------------*/
#include "usbd_conf.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USB_INFO
* @brief general defines for the usb device library file
* @{
*/
/** @defgroup USB_INFO_Exported_Defines
* @{
*/
#define MODE_SENSE6_LEN 8
#define MODE_SENSE10_LEN 8
#define LENGTH_INQUIRY_PAGE00 7
#define LENGTH_FORMAT_CAPACITIES 20
/**
* @}
*/
/** @defgroup USBD_INFO_Exported_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup USBD_INFO_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_INFO_Exported_Variables
* @{
*/
extern const uint8_t MSC_Page00_Inquiry_Data[];
extern const uint8_t MSC_Mode_Sense6_data[];
extern const uint8_t MSC_Mode_Sense10_data[] ;
/**
* @}
*/
/** @defgroup USBD_INFO_Exported_FunctionsPrototype
* @{
*/
/**
* @}
*/
#endif /* _USBD_MSC_DATA_H_ */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,112 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_mem.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header for the STORAGE DISK file file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_MEM_H
#define __USBD_MEM_H
/* Includes ------------------------------------------------------------------*/
#include "usbd_def.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_MEM
* @brief header file for the storage disk file
* @{
*/
/** @defgroup USBD_MEM_Exported_Defines
* @{
*/
#define USBD_STD_INQUIRY_LENGTH 36
/**
* @}
*/
/** @defgroup USBD_MEM_Exported_TypesDefinitions
* @{
*/
typedef struct _USBD_STORAGE
{
int8_t (* Init) (uint8_t lun);
int8_t (* GetCapacity) (uint8_t lun, uint32_t *block_num, uint32_t *block_size);
int8_t (* IsReady) (uint8_t lun);
int8_t (* IsWriteProtected) (uint8_t lun);
int8_t (* Read) (uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
int8_t (* Write)(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
int8_t (* GetMaxLun)(void);
int8_t *pInquiry;
}USBD_STORAGE_cb_TypeDef;
/**
* @}
*/
/** @defgroup USBD_MEM_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_MEM_Exported_Variables
* @{
*/
/**
* @}
*/
/** @defgroup USBD_MEM_Exported_FunctionsPrototype
* @{
*/
extern const USBD_STORAGE_cb_TypeDef * const USBD_STORAGE_fops;
/**
* @}
*/
#endif /* __USBD_MEM_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,937 +0,0 @@
/**
(c) 2017 night_ghost@ykoctpa.ru
based on:
******************************************************************************
* @file usbd_msc_scsi.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides all the USBD SCSI layer functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_msc_bot.h"
#include "usbd_msc_scsi.h"
#include "usbd_msc_mem.h"
#include "usbd_msc_data.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup MSC_SCSI
* @brief Mass storage SCSI layer module
* @{
*/
/** @defgroup MSC_SCSI_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Variables
* @{
*/
SCSI_Sense_TypeDef SCSI_Sense [SENSE_LIST_DEEPTH];
uint8_t SCSI_Sense_Head;
uint8_t SCSI_Sense_Tail;
uint32_t SCSI_blk_size;
uint32_t SCSI_blk_nbr;
uint32_t SCSI_blk_addr;
uint32_t SCSI_blk_len;
USB_OTG_CORE_HANDLE *cdev;
/**
* @}
*/
//[ move out data transfer from ISR level to task
typedef void (*voidFuncPtr)(void);
typedef struct USB_REC {
void *pdev;
uint8_t lun;
bool is_write;
} USB_rec;
// this is not true queue because there is only one request at a time, but this allows to exclude disabling of interrupts
#define USB_QUEUE_SIZE 4
static USB_rec usb_queue[USB_QUEUE_SIZE+1];
static uint8_t usb_read_ptr, usb_write_ptr;
// HAL task management for USB
extern void hal_set_task_active(void * handle);
extern void hal_context_switch_isr();
extern void *hal_register_task(voidFuncPtr task, uint32_t stack);
extern void hal_set_task_priority(void * handle, uint8_t prio);
static void usb_task();
static void *task_handle;
void SCSI_Init() {
usb_read_ptr=0;
usb_write_ptr=0;
task_handle = hal_register_task(usb_task, 2048); // 2K stack
hal_set_task_priority(task_handle, 80); // very high
}
//]
//#define SCSI_DEBUG
//[ debug
#ifdef SCSI_DEBUG
#define SCSI_LOG_LEN 500
typedef struct SCSI_LOG {
enum SCSI_Commands cmd;
enum BOT_STATE state;
bool alt;
uint32_t addr;
uint32_t len;
uint8_t params[8];
int8_t ret;
uint8_t rdp;
uint8_t wrp;
} SCSI_log;
static uint16_t scsi_log_ptr=0;
static SCSI_log *curr_log;
static SCSI_log scsi_log[SCSI_LOG_LEN+1];
#endif
//]
/** @defgroup MSC_SCSI_Private_FunctionPrototypes
* @{
*/
static int8_t SCSI_TestUnitReady(uint8_t lun, uint8_t *params);
static int8_t SCSI_Inquiry(uint8_t lun, uint8_t *params);
static int8_t SCSI_ReadFormatCapacity(uint8_t lun, uint8_t *params);
static int8_t SCSI_ReadCapacity10(uint8_t lun, uint8_t *params);
static int8_t SCSI_RequestSense (uint8_t lun, uint8_t *params);
static int8_t SCSI_StartStopUnit(uint8_t lun, uint8_t *params);
static int8_t SCSI_ModeSense6 (uint8_t lun, uint8_t *params);
static int8_t SCSI_ModeSense10 (uint8_t lun, uint8_t *params);
static int8_t SCSI_Write10(uint8_t lun , uint8_t *params);
static int8_t SCSI_Read10(uint8_t lun , uint8_t *params);
static int8_t SCSI_Verify10(uint8_t lun, uint8_t *params);
static int8_t SCSI_CheckAddressRange (uint8_t lun ,
uint32_t blk_offset ,
uint16_t blk_nbr);
static int8_t SCSI_ProcessRead (uint8_t lun);
static int8_t SCSI_ProcessWrite (uint8_t lun);
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Functions
* @{
*/
/**
* @brief SCSI_ProcessCmd
* Process SCSI commands
* @param pdev: device instance
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
int8_t SCSI_ProcessCmd(USB_OTG_CORE_HANDLE *pdev,
uint8_t lun,
uint8_t *params)
{
cdev = pdev;
int8_t ret=-1;
// if(!task_handle) SCSI_Init(); can't be registered from ISR!
#ifdef SCSI_DEBUG
printf("\nSCSI cmd=%d ", params[0]);
SCSI_log *p = &scsi_log[scsi_log_ptr++];
if(scsi_log_ptr>=SCSI_LOG_LEN) scsi_log_ptr=0;
p->cmd = params[0];
p->state = MSC_BOT_State;
memmove(p->params,params+1,8);
p->ret=55;
p->alt = false;
p->addr=0;
p->len=0;
curr_log=p;
#endif
switch (params[0]) {
case SCSI_TEST_UNIT_READY:
ret=SCSI_TestUnitReady(lun, params);
break;
case SCSI_REQUEST_SENSE:
ret=SCSI_RequestSense (lun, params);
break;
case SCSI_INQUIRY:
ret= SCSI_Inquiry(lun, params);
break;
case SCSI_START_STOP_UNIT:
ret= SCSI_StartStopUnit(lun, params);
break;
case SCSI_ALLOW_MEDIUM_REMOVAL:
ret= SCSI_StartStopUnit(lun, params);
break;
case SCSI_MODE_SENSE6:
ret= SCSI_ModeSense6 (lun, params);
break;
case SCSI_MODE_SENSE10:
ret= SCSI_ModeSense10 (lun, params);
break;
case SCSI_READ_FORMAT_CAPACITIES:
ret= SCSI_ReadFormatCapacity(lun, params);
break;
case SCSI_READ_CAPACITY10:
ret= SCSI_ReadCapacity10(lun, params);
break;
case SCSI_READ10:
ret= SCSI_Read10(lun, params);
return ret; // without MSC_BOT_CBW_finish(p->pdev);
case SCSI_WRITE10:
ret= SCSI_Write10(lun, params);
return ret; // without MSC_BOT_CBW_finish(p->pdev);
case SCSI_VERIFY10:
ret=SCSI_Verify10(lun, params);
break;
default:
SCSI_SenseCode(lun,
ILLEGAL_REQUEST,
INVALID_CDB);
ret= -1;
break;
}
MSC_BOT_CBW_finish(pdev);
return ret;
}
/**
* @brief SCSI_TestUnitReady
* Process SCSI Test Unit Ready Command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_TestUnitReady(uint8_t lun, uint8_t *params)
{
/* case 9 : Hi > D0 */
if (MSC_BOT_cbw.dDataLength != 0) {
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
if(USBD_STORAGE_fops->IsReady(lun) !=0 ) {
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
MSC_BOT_DataLen = 0;
return 0;
}
/**
* @brief SCSI_Inquiry
* Process Inquiry command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Inquiry(uint8_t lun, uint8_t *params)
{
uint8_t* pPage;
uint16_t len;
if (params[1] & 0x01)/*Evpd is set*/
{
pPage = (uint8_t *)MSC_Page00_Inquiry_Data;
len = LENGTH_INQUIRY_PAGE00;
}
else
{
pPage = (uint8_t *)&USBD_STORAGE_fops->pInquiry[lun * USBD_STD_INQUIRY_LENGTH];
len = pPage[4] + 5;
if (params[4] <= len)
{
len = params[4];
}
}
MSC_BOT_DataLen = len;
while (len)
{
len--;
MSC_BOT_Data[len] = pPage[len];
}
return 0;
}
/**
* @brief SCSI_ReadCapacity10
* Process Read Capacity 10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ReadCapacity10(uint8_t lun, uint8_t *params)
{
if(USBD_STORAGE_fops->GetCapacity(lun, &SCSI_blk_nbr, &SCSI_blk_size) != 0)
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
else
{
MSC_BOT_Data[0] = (uint8_t)((SCSI_blk_nbr - 1) >> 24);
MSC_BOT_Data[1] = (uint8_t)((SCSI_blk_nbr - 1) >> 16);
MSC_BOT_Data[2] = (uint8_t)((SCSI_blk_nbr - 1) >> 8);
MSC_BOT_Data[3] = (uint8_t)((SCSI_blk_nbr - 1));
MSC_BOT_Data[4] = (uint8_t)(SCSI_blk_size >> 24);
MSC_BOT_Data[5] = (uint8_t)(SCSI_blk_size >> 16);
MSC_BOT_Data[6] = (uint8_t)(SCSI_blk_size >> 8);
MSC_BOT_Data[7] = (uint8_t)(SCSI_blk_size);
MSC_BOT_DataLen = 8;
return 0;
}
}
/**
* @brief SCSI_ReadFormatCapacity
* Process Read Format Capacity command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ReadFormatCapacity(uint8_t lun, uint8_t *params)
{
uint32_t blk_size;
uint32_t blk_nbr;
uint16_t i;
for(i=0 ; i < 12 ; i++)
{
MSC_BOT_Data[i] = 0;
}
if(USBD_STORAGE_fops->GetCapacity(lun, &blk_nbr, &blk_size) != 0)
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
else
{
MSC_BOT_Data[3] = 0x08;
MSC_BOT_Data[4] = (uint8_t)((blk_nbr - 1) >> 24);
MSC_BOT_Data[5] = (uint8_t)((blk_nbr - 1) >> 16);
MSC_BOT_Data[6] = (uint8_t)((blk_nbr - 1) >> 8);
MSC_BOT_Data[7] = (uint8_t)((blk_nbr - 1));
MSC_BOT_Data[8] = 0x02;
MSC_BOT_Data[9] = (uint8_t)(blk_size >> 16);
MSC_BOT_Data[10] = (uint8_t)(blk_size >> 8);
MSC_BOT_Data[11] = (uint8_t)(blk_size);
MSC_BOT_DataLen = 12;
return 0;
}
}
/**
* @brief SCSI_ModeSense6
* Process Mode Sense6 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ModeSense6 (uint8_t lun, uint8_t *params)
{
uint16_t len = 8 ;
MSC_BOT_DataLen = len;
while (len)
{
len--;
MSC_BOT_Data[len] = MSC_Mode_Sense6_data[len];
}
return 0;
}
/**
* @brief SCSI_ModeSense10
* Process Mode Sense10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ModeSense10 (uint8_t lun, uint8_t *params)
{
uint16_t len = 8;
MSC_BOT_DataLen = len;
while (len)
{
len--;
MSC_BOT_Data[len] = MSC_Mode_Sense10_data[len];
}
return 0;
}
/**
* @brief SCSI_RequestSense
* Process Request Sense command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_RequestSense (uint8_t lun, uint8_t *params)
{
uint8_t i;
for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++) {
MSC_BOT_Data[i] = 0;
}
MSC_BOT_Data[0] = 0x70;
MSC_BOT_Data[7] = REQUEST_SENSE_DATA_LEN - 6;
if((SCSI_Sense_Head != SCSI_Sense_Tail)) {
MSC_BOT_Data[2] = SCSI_Sense[SCSI_Sense_Head].Skey;
MSC_BOT_Data[12] = SCSI_Sense[SCSI_Sense_Head].w.b.ASCQ;
MSC_BOT_Data[13] = SCSI_Sense[SCSI_Sense_Head].w.b.ASC;
SCSI_Sense_Head++;
if (SCSI_Sense_Head == SENSE_LIST_DEEPTH) {
SCSI_Sense_Head = 0;
}
}
MSC_BOT_DataLen = REQUEST_SENSE_DATA_LEN;
if (params[4] <= REQUEST_SENSE_DATA_LEN) {
MSC_BOT_DataLen = params[4];
}
return 0;
}
/**
* @brief SCSI_SenseCode
* Load the last error code in the error list
* @param lun: Logical unit number
* @param sKey: Sense Key
* @param ASC: Additional Sense Key
* @retval none
*/
void SCSI_SenseCode(uint8_t lun, uint8_t sKey, uint8_t ASC)
{
SCSI_Sense[SCSI_Sense_Tail].Skey = sKey;
SCSI_Sense[SCSI_Sense_Tail].w.ASC = ASC << 8;
SCSI_Sense_Tail++;
if (SCSI_Sense_Tail == SENSE_LIST_DEEPTH)
{
SCSI_Sense_Tail = 0;
}
}
/**
* @brief SCSI_StartStopUnit
* Process Start Stop Unit command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_StartStopUnit(uint8_t lun, uint8_t *params)
{
MSC_BOT_DataLen = 0;
return 0;
}
/**
* @brief SCSI_Read10
* Process Read10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Read10(uint8_t lun , uint8_t *params)
{
if(MSC_BOT_State == BOT_IDLE) { /* Idle */
/* case 10 : Ho <> Di */
if ((MSC_BOT_cbw.bmFlags & 0x80) != 0x80) {
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
if(USBD_STORAGE_fops->IsReady(lun) !=0 ) {
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
SCSI_blk_addr = (params[2] << 24) | \
(params[3] << 16) | \
(params[4] << 8) | \
params[5];
SCSI_blk_len = (params[7] << 8) | \
params[8];
if( SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0){
return -1; /* error */
}
MSC_BOT_State = BOT_DATA_IN;
SCSI_blk_addr *= SCSI_blk_size;
SCSI_blk_len *= SCSI_blk_size;
/* cases 4,5 : Hi <> Dn */
if (MSC_BOT_cbw.dDataLength != SCSI_blk_len) {
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
}
#ifdef SCSI_DEBUG
curr_log->addr = SCSI_blk_addr;
curr_log->len = SCSI_blk_len;
curr_log->rdp = usb_read_ptr;
curr_log->wrp = usb_write_ptr;
#endif
#if 1
USB_rec *p = &usb_queue[usb_write_ptr];
uint16_t old_wp = usb_write_ptr++;
if(usb_write_ptr >= USB_QUEUE_SIZE) { // move write pointer
usb_write_ptr=0; // ring
}
if(usb_write_ptr == usb_read_ptr) { // buffer overflow
usb_write_ptr=old_wp; // not overwrite, just skip last data
} else {
p->pdev = cdev;
p->lun = lun;
p->is_write = false;
}
// printf("\nUSB: enqueue read blk=%ld\n", SCSI_blk_addr / SCSI_blk_size);
uint32_t fifoemptymsk = 0x1 << (MSC_IN_EP & 0x7F);
USB_OTG_MODIFY_REG32(&cdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0); // clear FIFO Empty mask until real data write to prevent interrupt
hal_set_task_active(task_handle); // resume task
hal_context_switch_isr(); // and reschedule tasks after interrupt
return 0;
#else // as it was before
MSC_BOT_DataLen = MSC_MEDIA_PACKET;
return SCSI_ProcessRead(lun);
#endif
}
/**
* @brief SCSI_Write10
* Process Write10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Write10 (uint8_t lun , uint8_t *params)
{
if (MSC_BOT_State == BOT_IDLE) { /* Idle */
/* case 8 : Hi <> Do */
if ((MSC_BOT_cbw.bmFlags & 0x80) == 0x80){
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
/* Check whether Media is ready */
if(USBD_STORAGE_fops->IsReady(lun) !=0 ){
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
/* Check If media is write-protected */
if(USBD_STORAGE_fops->IsWriteProtected(lun) !=0 ) {
SCSI_SenseCode(lun,
NOT_READY,
WRITE_PROTECTED);
return -1;
}
SCSI_blk_addr = (params[2] << 24) | \
(params[3] << 16) | \
(params[4] << 8) | \
params[5];
SCSI_blk_len = (params[7] << 8) | \
params[8];
/* check if LBA address is in the right range */
if(SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0) {
return -1; /* error */
}
SCSI_blk_addr *= SCSI_blk_size;
SCSI_blk_len *= SCSI_blk_size;
/* cases 3,11,13 : Hn,Ho <> D0 */
if (MSC_BOT_cbw.dDataLength != SCSI_blk_len) {
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
/* Prepare EP to receive first data packet */
MSC_BOT_State = BOT_DATA_OUT;
DCD_EP_PrepareRx (cdev,
MSC_OUT_EP,
MSC_BOT_Data,
MIN (SCSI_blk_len, MSC_MEDIA_PACKET));
#ifdef SCSI_DEBUG
curr_log->addr = SCSI_blk_addr;
curr_log->len = SCSI_blk_len;
curr_log->rdp = usb_read_ptr;
curr_log->wrp = usb_write_ptr;
#endif
return 0;
}
/* Write Process ongoing */
#ifdef SCSI_DEBUG
curr_log->addr = SCSI_blk_addr;
curr_log->len = SCSI_blk_len;
curr_log->rdp = usb_read_ptr;
curr_log->wrp = usb_write_ptr;
curr_log->alt = true;
#endif
#if 1
USB_rec *p = &usb_queue[usb_write_ptr];
uint16_t old_wp = usb_write_ptr++;
if(usb_write_ptr >= USB_QUEUE_SIZE) { // move write pointer
usb_write_ptr=0; // ring
}
if(usb_write_ptr == usb_read_ptr) { // buffer overflow
usb_write_ptr=old_wp; // not overwrite, just skip last data
} else {
p->pdev = cdev;
p->lun = lun;
p->is_write = true;
}
// printf("\nUSB: enqueue write blk=%ld\n", SCSI_blk_addr / SCSI_blk_size);
hal_set_task_active(task_handle); // resume task
hal_context_switch_isr(); // and reschedule tasks after interrupt
return 0;
#else // as it was before
return SCSI_ProcessWrite(lun);
#endif
}
//[ real data read/write executed as task
static void usb_task(){
while(usb_read_ptr != usb_write_ptr) { // there are samples
USB_rec *p = &usb_queue[usb_read_ptr++];
if(usb_read_ptr >= USB_QUEUE_SIZE) { // move write pointer
usb_read_ptr=0; // ring
}
#ifdef SCSI_DEBUG
SCSI_log *l = &scsi_log[scsi_log_ptr++];
if(scsi_log_ptr>=SCSI_LOG_LEN) scsi_log_ptr=0;
l->cmd = 100 + p->is_write;
l->state = MSC_BOT_State;
l->ret=0;
l->alt = true;
l->addr=SCSI_blk_addr;
l->len=SCSI_blk_len;
l->rdp = usb_read_ptr;
l->wrp = usb_write_ptr;
curr_log=l;
#endif
int8_t ret;
if(p->is_write){
// printf("\nUSB: do write blk=%ld\n", SCSI_blk_addr / SCSI_blk_size);
ret = SCSI_ProcessWrite(p->lun);
} else {
// printf("\nUSB: do read blk=%ld\n", SCSI_blk_addr / SCSI_blk_size);
MSC_BOT_DataLen = MSC_MEDIA_PACKET;
ret = SCSI_ProcessRead(p->lun);
uint32_t fifoemptymsk = 0x1 << (MSC_IN_EP & 0x7F);
USB_OTG_MODIFY_REG32(&cdev->regs.DREGS->DIEPEMPMSK, 0, fifoemptymsk); // Set FIFO Empty mask after real data write to allow next interrupt
}
MSC_BOT_CBW_finish(p->pdev);
if(ret<0) {
#ifdef SCSI_DEBUG
l->ret = ret;
#endif
MSC_BOT_SendCSW (p->pdev, CSW_CMD_FAILED);
} else {
#ifdef SCSI_DEBUG
l->ret = 1;
#endif
}
}
}
//]
/**
* @brief SCSI_Verify10
* Process Verify10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Verify10(uint8_t lun , uint8_t *params){
if ((params[1]& 0x02) == 0x02) {
SCSI_SenseCode (lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND);
return -1; /* Error, Verify Mode Not supported*/
}
if(SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0) {
return -1; /* error */
}
MSC_BOT_DataLen = 0;
return 0;
}
/**
* @brief SCSI_CheckAddressRange
* Check address range
* @param lun: Logical unit number
* @param blk_offset: first block address
* @param blk_nbr: number of block to be processed
* @retval status
*/
static int8_t SCSI_CheckAddressRange (uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr)
{
if ((blk_offset + blk_nbr) > SCSI_blk_nbr ) {
SCSI_SenseCode(lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE);
return -1;
}
return 0;
}
/**
* @brief SCSI_ProcessRead
* Handle Read Process
* @param lun: Logical unit number
* @retval status
*/
static int8_t SCSI_ProcessRead (uint8_t lun)
{
uint32_t len;
len = MIN(SCSI_blk_len , MSC_MEDIA_PACKET);
// read block from storage
if( USBD_STORAGE_fops->Read(lun ,
MSC_BOT_Data,
SCSI_blk_addr / SCSI_blk_size,
len / SCSI_blk_size) < 0) {
SCSI_SenseCode(lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR);
return -1;
}
// and setup TX
DCD_EP_Tx (cdev,
MSC_IN_EP,
MSC_BOT_Data,
len);
SCSI_blk_addr += len;
SCSI_blk_len -= len;
/* case 6 : Hi = Di */
MSC_BOT_csw.dDataResidue -= len;
if (SCSI_blk_len == 0) {
MSC_BOT_State = BOT_LAST_DATA_IN;
}
return 0;
}
/**
* @brief SCSI_ProcessWrite
* Handle Write Process
* @param lun: Logical unit number
* @retval status
*/
static int8_t SCSI_ProcessWrite (uint8_t lun)
{
uint32_t len;
len = MIN(SCSI_blk_len , MSC_MEDIA_PACKET);
if(USBD_STORAGE_fops->Write(lun ,
MSC_BOT_Data,
SCSI_blk_addr / SCSI_blk_size,
len / SCSI_blk_size) < 0) {
SCSI_SenseCode(lun, HARDWARE_ERROR, WRITE_FAULT);
return -1;
}
SCSI_blk_addr += len;
SCSI_blk_len -= len;
/* case 12 : Ho = Do */
MSC_BOT_csw.dDataResidue -= len;
if (SCSI_blk_len == 0) {
MSC_BOT_SendCSW (cdev, CSW_CMD_PASSED);
} else {
/* Prapare EP to Receive next packet */
DCD_EP_PrepareRx (cdev,
MSC_OUT_EP,
MSC_BOT_Data,
MIN (SCSI_blk_len, MSC_MEDIA_PACKET));
}
return 0;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,729 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_scsi.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief This file provides all the USBD SCSI layer functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_msc_bot.h"
#include "usbd_msc_scsi.h"
#include "usbd_msc_mem.h"
#include "usbd_msc_data.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup MSC_SCSI
* @brief Mass storage SCSI layer module
* @{
*/
/** @defgroup MSC_SCSI_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Defines
* @{
*/
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Variables
* @{
*/
SCSI_Sense_TypeDef SCSI_Sense [SENSE_LIST_DEEPTH];
uint8_t SCSI_Sense_Head;
uint8_t SCSI_Sense_Tail;
uint32_t SCSI_blk_size;
uint32_t SCSI_blk_nbr;
uint32_t SCSI_blk_addr;
uint32_t SCSI_blk_len;
USB_OTG_CORE_HANDLE *cdev;
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_FunctionPrototypes
* @{
*/
static int8_t SCSI_TestUnitReady(uint8_t lun, uint8_t *params);
static int8_t SCSI_Inquiry(uint8_t lun, uint8_t *params);
static int8_t SCSI_ReadFormatCapacity(uint8_t lun, uint8_t *params);
static int8_t SCSI_ReadCapacity10(uint8_t lun, uint8_t *params);
static int8_t SCSI_RequestSense (uint8_t lun, uint8_t *params);
static int8_t SCSI_StartStopUnit(uint8_t lun, uint8_t *params);
static int8_t SCSI_ModeSense6 (uint8_t lun, uint8_t *params);
static int8_t SCSI_ModeSense10 (uint8_t lun, uint8_t *params);
static int8_t SCSI_Write10(uint8_t lun , uint8_t *params);
static int8_t SCSI_Read10(uint8_t lun , uint8_t *params);
static int8_t SCSI_Verify10(uint8_t lun, uint8_t *params);
static int8_t SCSI_CheckAddressRange (uint8_t lun ,
uint32_t blk_offset ,
uint16_t blk_nbr);
static int8_t SCSI_ProcessRead (uint8_t lun);
static int8_t SCSI_ProcessWrite (uint8_t lun);
/**
* @}
*/
/** @defgroup MSC_SCSI_Private_Functions
* @{
*/
/**
* @brief SCSI_ProcessCmd
* Process SCSI commands
* @param pdev: device instance
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
int8_t SCSI_ProcessCmd(USB_OTG_CORE_HANDLE *pdev,
uint8_t lun,
uint8_t *params)
{
cdev = pdev;
switch (params[0])
{
case SCSI_TEST_UNIT_READY:
return SCSI_TestUnitReady(lun, params);
case SCSI_REQUEST_SENSE:
return SCSI_RequestSense (lun, params);
case SCSI_INQUIRY:
return SCSI_Inquiry(lun, params);
case SCSI_START_STOP_UNIT:
return SCSI_StartStopUnit(lun, params);
case SCSI_ALLOW_MEDIUM_REMOVAL:
return SCSI_StartStopUnit(lun, params);
case SCSI_MODE_SENSE6:
return SCSI_ModeSense6 (lun, params);
case SCSI_MODE_SENSE10:
return SCSI_ModeSense10 (lun, params);
case SCSI_READ_FORMAT_CAPACITIES:
return SCSI_ReadFormatCapacity(lun, params);
case SCSI_READ_CAPACITY10:
return SCSI_ReadCapacity10(lun, params);
case SCSI_READ10:
return SCSI_Read10(lun, params);
case SCSI_WRITE10:
return SCSI_Write10(lun, params);
case SCSI_VERIFY10:
return SCSI_Verify10(lun, params);
default:
SCSI_SenseCode(lun,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
}
/**
* @brief SCSI_TestUnitReady
* Process SCSI Test Unit Ready Command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_TestUnitReady(uint8_t lun, uint8_t *params)
{
/* case 9 : Hi > D0 */
if (MSC_BOT_cbw.dDataLength != 0)
{
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
if(USBD_STORAGE_fops->IsReady(lun) !=0 )
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
MSC_BOT_DataLen = 0;
return 0;
}
/**
* @brief SCSI_Inquiry
* Process Inquiry command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Inquiry(uint8_t lun, uint8_t *params)
{
uint8_t* pPage;
uint16_t len;
if (params[1] & 0x01)/*Evpd is set*/
{
pPage = (uint8_t *)MSC_Page00_Inquiry_Data;
len = LENGTH_INQUIRY_PAGE00;
}
else
{
pPage = (uint8_t *)&USBD_STORAGE_fops->pInquiry[lun * USBD_STD_INQUIRY_LENGTH];
len = pPage[4] + 5;
if (params[4] <= len)
{
len = params[4];
}
}
MSC_BOT_DataLen = len;
while (len)
{
len--;
MSC_BOT_Data[len] = pPage[len];
}
return 0;
}
/**
* @brief SCSI_ReadCapacity10
* Process Read Capacity 10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ReadCapacity10(uint8_t lun, uint8_t *params)
{
if(USBD_STORAGE_fops->GetCapacity(lun, &SCSI_blk_nbr, &SCSI_blk_size) != 0)
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
else
{
MSC_BOT_Data[0] = (uint8_t)((SCSI_blk_nbr - 1) >> 24);
MSC_BOT_Data[1] = (uint8_t)((SCSI_blk_nbr - 1) >> 16);
MSC_BOT_Data[2] = (uint8_t)((SCSI_blk_nbr - 1) >> 8);
MSC_BOT_Data[3] = (uint8_t)((SCSI_blk_nbr - 1));
MSC_BOT_Data[4] = (uint8_t)(SCSI_blk_size >> 24);
MSC_BOT_Data[5] = (uint8_t)(SCSI_blk_size >> 16);
MSC_BOT_Data[6] = (uint8_t)(SCSI_blk_size >> 8);
MSC_BOT_Data[7] = (uint8_t)(SCSI_blk_size);
MSC_BOT_DataLen = 8;
return 0;
}
}
/**
* @brief SCSI_ReadFormatCapacity
* Process Read Format Capacity command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ReadFormatCapacity(uint8_t lun, uint8_t *params)
{
uint32_t blk_size;
uint32_t blk_nbr;
uint16_t i;
for(i=0 ; i < 12 ; i++)
{
MSC_BOT_Data[i] = 0;
}
if(USBD_STORAGE_fops->GetCapacity(lun, &blk_nbr, &blk_size) != 0)
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
else
{
MSC_BOT_Data[3] = 0x08;
MSC_BOT_Data[4] = (uint8_t)((blk_nbr - 1) >> 24);
MSC_BOT_Data[5] = (uint8_t)((blk_nbr - 1) >> 16);
MSC_BOT_Data[6] = (uint8_t)((blk_nbr - 1) >> 8);
MSC_BOT_Data[7] = (uint8_t)((blk_nbr - 1));
MSC_BOT_Data[8] = 0x02;
MSC_BOT_Data[9] = (uint8_t)(blk_size >> 16);
MSC_BOT_Data[10] = (uint8_t)(blk_size >> 8);
MSC_BOT_Data[11] = (uint8_t)(blk_size);
MSC_BOT_DataLen = 12;
return 0;
}
}
/**
* @brief SCSI_ModeSense6
* Process Mode Sense6 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ModeSense6 (uint8_t lun, uint8_t *params)
{
uint16_t len = 8 ;
MSC_BOT_DataLen = len;
while (len)
{
len--;
MSC_BOT_Data[len] = MSC_Mode_Sense6_data[len];
}
return 0;
}
/**
* @brief SCSI_ModeSense10
* Process Mode Sense10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_ModeSense10 (uint8_t lun, uint8_t *params)
{
uint16_t len = 8;
MSC_BOT_DataLen = len;
while (len)
{
len--;
MSC_BOT_Data[len] = MSC_Mode_Sense10_data[len];
}
return 0;
}
/**
* @brief SCSI_RequestSense
* Process Request Sense command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_RequestSense (uint8_t lun, uint8_t *params)
{
uint8_t i;
for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++)
{
MSC_BOT_Data[i] = 0;
}
MSC_BOT_Data[0] = 0x70;
MSC_BOT_Data[7] = REQUEST_SENSE_DATA_LEN - 6;
if((SCSI_Sense_Head != SCSI_Sense_Tail)) {
MSC_BOT_Data[2] = SCSI_Sense[SCSI_Sense_Head].Skey;
MSC_BOT_Data[12] = SCSI_Sense[SCSI_Sense_Head].w.b.ASCQ;
MSC_BOT_Data[13] = SCSI_Sense[SCSI_Sense_Head].w.b.ASC;
SCSI_Sense_Head++;
if (SCSI_Sense_Head == SENSE_LIST_DEEPTH)
{
SCSI_Sense_Head = 0;
}
}
MSC_BOT_DataLen = REQUEST_SENSE_DATA_LEN;
if (params[4] <= REQUEST_SENSE_DATA_LEN)
{
MSC_BOT_DataLen = params[4];
}
return 0;
}
/**
* @brief SCSI_SenseCode
* Load the last error code in the error list
* @param lun: Logical unit number
* @param sKey: Sense Key
* @param ASC: Additional Sense Key
* @retval none
*/
void SCSI_SenseCode(uint8_t lun, uint8_t sKey, uint8_t ASC)
{
SCSI_Sense[SCSI_Sense_Tail].Skey = sKey;
SCSI_Sense[SCSI_Sense_Tail].w.ASC = ASC << 8;
SCSI_Sense_Tail++;
if (SCSI_Sense_Tail == SENSE_LIST_DEEPTH)
{
SCSI_Sense_Tail = 0;
}
}
/**
* @brief SCSI_StartStopUnit
* Process Start Stop Unit command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_StartStopUnit(uint8_t lun, uint8_t *params)
{
MSC_BOT_DataLen = 0;
return 0;
}
/**
* @brief SCSI_Read10
* Process Read10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Read10(uint8_t lun , uint8_t *params)
{
if(MSC_BOT_State == BOT_IDLE) /* Idle */
{
/* case 10 : Ho <> Di */
if ((MSC_BOT_cbw.bmFlags & 0x80) != 0x80)
{
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
if(USBD_STORAGE_fops->IsReady(lun) !=0 )
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
SCSI_blk_addr = (params[2] << 24) | \
(params[3] << 16) | \
(params[4] << 8) | \
params[5];
SCSI_blk_len = (params[7] << 8) | \
params[8];
if( SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0)
{
return -1; /* error */
}
MSC_BOT_State = BOT_DATA_IN;
SCSI_blk_addr *= SCSI_blk_size;
SCSI_blk_len *= SCSI_blk_size;
/* cases 4,5 : Hi <> Dn */
if (MSC_BOT_cbw.dDataLength != SCSI_blk_len)
{
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
}
MSC_BOT_DataLen = MSC_MEDIA_PACKET;
return SCSI_ProcessRead(lun);
}
/**
* @brief SCSI_Write10
* Process Write10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Write10 (uint8_t lun , uint8_t *params)
{
if (MSC_BOT_State == BOT_IDLE) /* Idle */
{
/* case 8 : Hi <> Do */
if ((MSC_BOT_cbw.bmFlags & 0x80) == 0x80)
{
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
/* Check whether Media is ready */
if(USBD_STORAGE_fops->IsReady(lun) !=0 )
{
SCSI_SenseCode(lun,
NOT_READY,
MEDIUM_NOT_PRESENT);
return -1;
}
/* Check If media is write-protected */
if(USBD_STORAGE_fops->IsWriteProtected(lun) !=0 )
{
SCSI_SenseCode(lun,
NOT_READY,
WRITE_PROTECTED);
return -1;
}
SCSI_blk_addr = (params[2] << 24) | \
(params[3] << 16) | \
(params[4] << 8) | \
params[5];
SCSI_blk_len = (params[7] << 8) | \
params[8];
/* check if LBA address is in the right range */
if(SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0)
{
return -1; /* error */
}
SCSI_blk_addr *= SCSI_blk_size;
SCSI_blk_len *= SCSI_blk_size;
/* cases 3,11,13 : Hn,Ho <> D0 */
if (MSC_BOT_cbw.dDataLength != SCSI_blk_len)
{
SCSI_SenseCode(MSC_BOT_cbw.bLUN,
ILLEGAL_REQUEST,
INVALID_CDB);
return -1;
}
/* Prepare EP to receive first data packet */
MSC_BOT_State = BOT_DATA_OUT;
DCD_EP_PrepareRx (cdev,
MSC_OUT_EP,
MSC_BOT_Data,
MIN (SCSI_blk_len, MSC_MEDIA_PACKET));
}
else /* Write Process ongoing */
{
return SCSI_ProcessWrite(lun);
}
return 0;
}
/**
* @brief SCSI_Verify10
* Process Verify10 command
* @param lun: Logical unit number
* @param params: Command parameters
* @retval status
*/
static int8_t SCSI_Verify10(uint8_t lun , uint8_t *params){
if ((params[1]& 0x02) == 0x02)
{
SCSI_SenseCode (lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND);
return -1; /* Error, Verify Mode Not supported*/
}
if(SCSI_CheckAddressRange(lun, SCSI_blk_addr, SCSI_blk_len) < 0)
{
return -1; /* error */
}
MSC_BOT_DataLen = 0;
return 0;
}
/**
* @brief SCSI_CheckAddressRange
* Check address range
* @param lun: Logical unit number
* @param blk_offset: first block address
* @param blk_nbr: number of block to be processed
* @retval status
*/
static int8_t SCSI_CheckAddressRange (uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr)
{
if ((blk_offset + blk_nbr) > SCSI_blk_nbr )
{
SCSI_SenseCode(lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE);
return -1;
}
return 0;
}
/**
* @brief SCSI_ProcessRead
* Handle Read Process
* @param lun: Logical unit number
* @retval status
*/
static int8_t SCSI_ProcessRead (uint8_t lun)
{
uint32_t len;
len = MIN(SCSI_blk_len , MSC_MEDIA_PACKET);
if( USBD_STORAGE_fops->Read(lun ,
MSC_BOT_Data,
SCSI_blk_addr / SCSI_blk_size,
len / SCSI_blk_size) < 0)
{
SCSI_SenseCode(lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR);
return -1;
}
DCD_EP_Tx (cdev,
MSC_IN_EP,
MSC_BOT_Data,
len);
SCSI_blk_addr += len;
SCSI_blk_len -= len;
/* case 6 : Hi = Di */
MSC_BOT_csw.dDataResidue -= len;
if (SCSI_blk_len == 0)
{
MSC_BOT_State = BOT_LAST_DATA_IN;
}
return 0;
}
/**
* @brief SCSI_ProcessWrite
* Handle Write Process
* @param lun: Logical unit number
* @retval status
*/
static int8_t SCSI_ProcessWrite (uint8_t lun)
{
uint32_t len;
len = MIN(SCSI_blk_len , MSC_MEDIA_PACKET);
if(USBD_STORAGE_fops->Write(lun ,
MSC_BOT_Data,
SCSI_blk_addr / SCSI_blk_size,
len / SCSI_blk_size) < 0)
{
SCSI_SenseCode(lun, HARDWARE_ERROR, WRITE_FAULT);
return -1;
}
SCSI_blk_addr += len;
SCSI_blk_len -= len;
/* case 12 : Ho = Do */
MSC_BOT_csw.dDataResidue -= len;
if (SCSI_blk_len == 0)
{
MSC_BOT_SendCSW (cdev, CSW_CMD_PASSED);
}
else
{
/* Prapare EP to Receive next packet */
DCD_EP_PrepareRx (cdev,
MSC_OUT_EP,
MSC_BOT_Data,
MIN (SCSI_blk_len, MSC_MEDIA_PACKET));
}
return 0;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,202 +0,0 @@
/**
******************************************************************************
* @file usbd_msc_scsi.h
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief header for the usbd_msc_scsi.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_MSC_SCSI_H
#define __USBD_MSC_SCSI_H
/* Includes ------------------------------------------------------------------*/
#include "usbd_def.h"
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USBD_SCSI
* @brief header file for the storage disk file
* @{
*/
/** @defgroup USBD_SCSI_Exported_Defines
* @{
*/
#define SENSE_LIST_DEEPTH 4
/* SCSI Commands */
enum SCSI_Commands {
SCSI_FORMAT_UNIT = 0x04,
SCSI_INQUIRY = 0x12,
SCSI_MODE_SELECT6 = 0x15,
SCSI_MODE_SELECT10 = 0x55,
SCSI_MODE_SENSE6 = 0x1A,
SCSI_MODE_SENSE10 = 0x5A,
SCSI_ALLOW_MEDIUM_REMOVAL = 0x1E,
SCSI_READ6 = 0x08,
SCSI_READ10 = 0x28,
SCSI_READ12 = 0xA8,
SCSI_READ16 = 0x88,
SCSI_READ_CAPACITY10= 0x25,
SCSI_READ_CAPACITY16= 0x9E,
SCSI_REQUEST_SENSE = 0x03,
SCSI_START_STOP_UNIT= 0x1B,
SCSI_TEST_UNIT_READY= 0x00,
SCSI_WRITE6 = 0x0A,
SCSI_WRITE10 = 0x2A,
SCSI_WRITE12 = 0xAA,
SCSI_WRITE16 = 0x8A,
SCSI_VERIFY10 = 0x2F,
SCSI_VERIFY12 = 0xAF,
SCSI_VERIFY16 = 0x8F,
SCSI_SEND_DIAGNOSTIC= 0x1D,
SCSI_READ_FORMAT_CAPACITIES= 0x23,
};
enum SCSI_Status {
NO_SENSE = 0,
RECOVERED_ERROR = 1,
NOT_READY = 2,
MEDIUM_ERROR = 3,
HARDWARE_ERROR = 4,
ILLEGAL_REQUEST = 5,
UNIT_ATTENTION = 6,
DATA_PROTECT = 7,
BLANK_CHECK = 8,
VENDOR_SPECIFIC = 9,
COPY_ABORTED = 10,
ABORTED_COMMAND = 11,
VOLUME_OVERFLOW = 13,
MISCOMPARE = 14,
};
enum SCSI_ExtStatus {
INVALID_CDB = 0x20,
INVALID_FIELED_IN_COMMAND = 0x24,
PARAMETER_LIST_LENGTH_ERROR = 0x1A,
INVALID_FIELD_IN_PARAMETER_LIST = 0x26,
ADDRESS_OUT_OF_RANGE = 0x21,
MEDIUM_NOT_PRESENT = 0x3A,
MEDIUM_HAVE_CHANGED = 0x28,
WRITE_PROTECTED = 0x27,
UNRECOVERED_READ_ERROR = 0x11,
WRITE_FAULT = 0x03,
READ_FORMAT_CAPACITY_DATA_LEN = 0x0C,
READ_CAPACITY10_DATA_LEN = 0x08,
MODE_SENSE10_DATA_LEN = 0x08,
MODE_SENSE6_DATA_LEN = 0x04,
REQUEST_SENSE_DATA_LEN = 0x12,
STANDARD_INQUIRY_DATA_LEN = 0x24,
BLKVFY = 0x04,
};
extern uint8_t Page00_Inquiry_Data[];
extern uint8_t Standard_Inquiry_Data[];
extern uint8_t Standard_Inquiry_Data2[];
extern uint8_t Mode_Sense6_data[];
extern uint8_t Mode_Sense10_data[];
extern uint8_t Scsi_Sense_Data[];
extern uint8_t ReadCapacity10_Data[];
extern uint8_t ReadFormatCapacity_Data [];
/**
* @}
*/
/** @defgroup USBD_SCSI_Exported_TypesDefinitions
* @{
*/
typedef struct _SENSE_ITEM {
char Skey;
union {
struct _ASCs {
char ASC;
char ASCQ;
}b;
unsigned int ASC;
char *pData;
} w;
} SCSI_Sense_TypeDef;
/**
* @}
*/
/** @defgroup USBD_SCSI_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USBD_SCSI_Exported_Variables
* @{
*/
extern SCSI_Sense_TypeDef SCSI_Sense [SENSE_LIST_DEEPTH];
extern uint8_t SCSI_Sense_Head;
extern uint8_t SCSI_Sense_Tail;
/**
* @}
*/
/** @defgroup USBD_SCSI_Exported_FunctionsPrototype
* @{
*/
int8_t SCSI_ProcessCmd(USB_OTG_CORE_HANDLE *pdev,
uint8_t lun,
uint8_t *cmd);
void SCSI_SenseCode(uint8_t lun,
uint8_t sKey,
uint8_t ASC);
void SCSI_Init(); // needed to start usb IO process
/**
* @}
*/
#endif /* __USBD_MSC_SCSI_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,185 +0,0 @@
/**
******************************************************************************
* @file usbd_storage_template.c
* @author MCD Application Team
* @version V1.1.0
* @date 19-March-2012
* @brief Memory management layer
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usbd_msc_mem.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
#define STORAGE_LUN_NBR 1
int8_t STORAGE_Init (uint8_t lun);
int8_t STORAGE_GetCapacity (uint8_t lun,
uint32_t *block_num,
uint16_t *block_size);
int8_t STORAGE_IsReady (uint8_t lun);
int8_t STORAGE_IsWriteProtected (uint8_t lun);
int8_t STORAGE_Read (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len);
int8_t STORAGE_Write (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len);
int8_t STORAGE_GetMaxLun (void);
/* USB Mass storage Standard Inquiry Data */
const int8_t STORAGE_Inquirydata[] = {//36
/* LUN 0 */
0x00,
0x80,
0x02,
0x02,
(USBD_STD_INQUIRY_LENGTH - 5),
0x00,
0x00,
0x00,
'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', /* Manufacturer : 8 bytes */
'P', 'r', 'o', 'd', 'u', 't', ' ', ' ', /* Product : 16 Bytes */
' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
'0', '.', '0' ,'1', /* Version : 4 Bytes */
};
USBD_STORAGE_cb_TypeDef USBD_MICRO_SDIO_fops =
{
STORAGE_Init,
STORAGE_GetCapacity,
STORAGE_IsReady,
STORAGE_IsWriteProtected,
STORAGE_Read,
STORAGE_Write,
STORAGE_GetMaxLun,
STORAGE_Inquirydata,
};
USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops = &USBD_MICRO_SDIO_fops;
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the microSD card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_Init (uint8_t lun)
{
return (0);
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint16_t *block_size)
{
return (0);
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_IsReady (uint8_t lun)
{
return (0);
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_IsWriteProtected (uint8_t lun)
{
return 0;
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_Read (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len)
{
return 0;
}
/*******************************************************************************
* Function Name : Write_Memory
* Description : Handle the Write operation to the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_Write (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len)
{
return (0);
}
/*******************************************************************************
* Function Name : Write_Memory
* Description : Handle the Write operation to the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
int8_t STORAGE_GetMaxLun (void)
{
return (STORAGE_LUN_NBR - 1);
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,48 +0,0 @@
# Standard things
sp := $(sp).x
dirstack_$(sp) := $(d)
d := $(dir)
BUILDDIRS += $(BUILD_PATH)/$(d)
# Local flags
CFLAGS_$(d) := -Wall -Werror
MS := AP_HAL_F4Light/hardware/massstorage
# Local rules and targets
cppSRCS_$(d) :=
cppSRCS_$(d) += $(MS)/mass_storage.cpp
cSRCS_$(d) :=
cSRCS_$(d) += $(MS)/StorageMode.c
cSRCS_$(d) += $(MS)/device_desc.c
cSRCS_$(d) += $(MS)/msc/usbd_msc_core.c
cSRCS_$(d) += $(MS)/msc/usbd_msc_bot.c
cSRCS_$(d) += $(MS)/msc/usbd_msc_data.c
cSRCS_$(d) += $(MS)/msc/usbd_msc_scsi.c
sSRCS_$(d) :=
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%)
sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
OBJS_$(d) := $(cFILES_$(d):%.c=$(LIBRARIES_PATH)/%.o)
OBJS_$(d) += $(cppFILES_$(d):%.cpp=$(LIBRARIES_PATH)/%.o)
OBJS_$(d) += $(sFILES_$(d):%.S=$(LIBRARIES_PATH)/%.o)
DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
TGT_BIN += $(OBJS_$(d))
# Standard things
-include $(DEPS_$(d))
d := $(dirstack_$(sp))
sp := $(basename $(sp))

View File

@ -1,22 +0,0 @@
#ifndef USBMASSSTORAGE_H
#define USBMASSSTORAGE_H
#include <boards.h>
#include "usb_mass_mal.h"
extern "C" {
#include <usbd_usr.h>
#include <usbd_desc.h>
#include <usb_conf.h>
#include <usbd_core.h>
#include "msc/usbd_msc_core.h"
#define USB_MASS_MAL_FAIL -1
#define USB_MASS_MAL_SUCCESS 0
}
#endif /* USBMASSSTORAGE_H */

View File

@ -1,25 +0,0 @@
#ifndef __USB_MASS_MAL_H
#define __USB_MASS_MAL_H
#include <stdint.h>
#define STORAGE_LUN_NBR 1
#ifdef __cplusplus
extern "C" {
#endif
extern uint32_t MAL_massBlockCount[STORAGE_LUN_NBR];
extern uint32_t MAL_massBlockSize[STORAGE_LUN_NBR];
uint16_t usb_mass_mal_get_status(uint8_t lun);
int8_t usb_mass_mal_read_memory(uint8_t lun, uint8_t *readbuff, uint32_t memoryOffset, uint16_t transferLength);
int8_t usb_mass_mal_write_memory(uint8_t lun, uint8_t *writebuff, uint32_t memoryOffset, uint16_t transferLength);
void usb_mass_mal_USBdisconnect();
#ifdef __cplusplus
}
#endif
#endif