From 5f737db4e495ebc1da1ac40b02836b529db77abe Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 24 Oct 2008 22:42:28 +0000 Subject: Add USB storage class driver git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1075 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 + nuttx/Documentation/NuttX.html | 25 +- nuttx/drivers/usbdev/Make.defs | 3 + nuttx/drivers/usbdev/usbdev_scsi.c | 2571 +++++++++++++++++++++++++++++++++ nuttx/drivers/usbdev/usbdev_storage.c | 1891 ++++++++++++++++++++++++ nuttx/drivers/usbdev/usbdev_storage.h | 538 +++++++ nuttx/include/nuttx/scsi.h | 53 +- nuttx/include/nuttx/usbdev_trace.h | 108 +- 8 files changed, 5100 insertions(+), 93 deletions(-) create mode 100644 nuttx/drivers/usbdev/usbdev_scsi.c create mode 100644 nuttx/drivers/usbdev/usbdev_storage.c create mode 100644 nuttx/drivers/usbdev/usbdev_storage.h diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 0d7af43ca..fb52d571a 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -509,4 +509,8 @@ * Fixed a problem with a un-initialized variable in the USB serial driver. * Added USB storage NXP LPC214x configuration * Added a test for USB storage under examples/usbstorage + * Fixed a bug in the LPC214x USB driver: It was not properly clearing a HALTed + endpoints (other than EP) on receipt of CLEAR FEATURES request. + * Added USB storage class device side driver (BBB) + diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index d9f51c030..b3a25507a 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

NuttX RTOS

-

Last Updated: October 23, 2008

+

Last Updated: October 24, 2008

@@ -356,7 +356,7 @@

-

  • Network, serial, CAN, driver architecture.
  • +
  • Network, USB (device), serial, CAN, driver architecture.
  • @@ -374,7 +374,6 @@
  • Mount-able volumes. Bind mountpoint, filesystem, and block device driver.
  • -
    @@ -382,7 +381,6 @@
  • FAT12/16/32 filesystem support.
  • -
    @@ -390,13 +388,13 @@
  • ROMFS filesystem support.
  • + C Library -
    @@ -411,7 +409,6 @@ Networking -
    @@ -419,7 +416,6 @@
  • TCP/IP, UDP, ICMP stacks.
  • -
    @@ -427,7 +423,6 @@
  • Small footprint (based on uIP).
  • -
    @@ -435,7 +430,6 @@
  • BSD compatible socket layer.
  • -
    @@ -450,7 +444,6 @@ USB Device Support -
    @@ -458,7 +451,6 @@
  • Gadget-like architecture for USB device controller drivers and device-dependent USB class drivers.
  • -
    @@ -466,7 +458,6 @@
  • USB device controller drivers available for the NXP LPC214x and TI DM320.
  • -
    @@ -474,6 +465,13 @@
  • Device-dependent USB class drivers available for USB serial.
  • + +
    + +

    +

  • Bult-in USB trace functionality for USB debug.
  • +

    + @@ -1141,6 +1139,9 @@ nuttx-0.3.17 2008-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr> * Fixed a problem with a un-initialized variable in the USB serial driver. * Added USB storage NXP LPC214x configuration * Added a test for USB storage under examples/usbstorage + * Fixed a bug in the LPC214x USB driver: It was not properly clearing a HALTed + endpoints (other than EP) on receipt of CLEAR FEATURES request. + * Added USB storage class device side driver (BBB) pascal-0.1.3 2008-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr> diff --git a/nuttx/drivers/usbdev/Make.defs b/nuttx/drivers/usbdev/Make.defs index 1bd391fa9..e83372856 100644 --- a/nuttx/drivers/usbdev/Make.defs +++ b/nuttx/drivers/usbdev/Make.defs @@ -40,6 +40,9 @@ ifeq ($(CONFIG_USBDEV),y) ifeq ($(CONFIG_USBSER),y) USBDEV_CSRCS += usbdev_serial.c endif +ifeq ($(CONFIG_USBSTRG),y) +USBDEV_CSRCS += usbdev_storage.c usbdev_scsi.c +endif USBDEV_CSRCS += usbdev_trace.c endif diff --git a/nuttx/drivers/usbdev/usbdev_scsi.c b/nuttx/drivers/usbdev/usbdev_scsi.c new file mode 100644 index 000000000..08e7cc1b4 --- /dev/null +++ b/nuttx/drivers/usbdev/usbdev_scsi.c @@ -0,0 +1,2571 @@ +/**************************************************************************** + * drivers/usbdev/usbdev_storage.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Mass storage class device. Bulk-only with SCSI subclass. + * + * References: + * "Universal Serial Bus Mass Storage Class, Specification Overview," + * Revision 1.2, USB Implementer's Forum, June 23, 2003. + * + * "Universal Serial Bus Mass Storage Class, Bulk-Only Transport," + * Revision 1.0, USB Implementer's Forum, September 31, 1999. + * + * "SCSI Primary Commands - 3 (SPC-3)," American National Standard + * for Information Technology, May 4, 2005 + * + * "SCSI Primary Commands - 4 (SPC-4)," American National Standard + * for Information Technology, July 19, 2008 + * + * "SCSI Block Commands -2 (SBC-2)," American National Standard + * for Information Technology, November 13, 2004 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "usbdev_storage.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Debug ********************************************************************/ + +#if defined(CONFIG_DEBUG_VERBOSE) && defined (CONFIG_DEBUG_USB) +static void usbstrg_dumpdata(const char *msg, const ubyte *buf, int buflen); +#else +# define usbstrg_dumpdata(msg, buf, len) +#endif + +/* Utility Support Functions ************************************************/ + +static uint16 usbstrg_getbe16(ubyte *buf); +static uint32 usbstrg_getbe32(ubyte *buf); +static void usbstrg_putbe16(ubyte * buf, uint16 val); +static void usbstrg_putbe32(ubyte *buf, uint32 val); +#if 0 /* not used */ +static uint16 usbstrg_getle16(ubyte *buf); +#endif +static uint32 usbstrg_getle32(ubyte *buf); +#if 0 /* not used */ +static void usbstrg_putle16(ubyte * buf, uint16 val); +#endif +static void usbstrg_putle32(ubyte *buf, uint32 val); + +/* SCSI Command Processing **************************************************/ + +static inline int usbstrg_cmdtestunitready(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdrequestsense(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf); +static inline int usbstrg_cmdread6(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdwrite6(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdinquiry(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf); +static inline int usbstrg_cmdmodeselect6(FAR struct usbstrg_dev_s *priv); +static int usbstrg_modepage(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf, ubyte pcpgcode, int *mdlen); +static inline int usbstrg_cmdmodesense6(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf); +static inline int usbstrg_cmdstartstopunit(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdpreventmediumremoval(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdreadcapacity10(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf); +static inline int usbstrg_cmdread10(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdwrite10(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdverify10(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdsynchronizecache10(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdmodeselect10(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdmodesense10(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf); +static inline int usbstrg_cmdread12(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_cmdwrite12(FAR struct usbstrg_dev_s *priv); +static inline int usbstrg_setupcmd(FAR struct usbstrg_dev_s *priv, ubyte cdblen, + ubyte flags); + +/* SCSI Worker Thread *******************************************************/ + +static int usbstrg_idlestate(FAR struct usbstrg_dev_s *priv); +static int usbstrg_cmdparsestate(FAR struct usbstrg_dev_s *priv); +static int usbstrg_cmdreadstate(FAR struct usbstrg_dev_s *priv); +static int usbstrg_cmdwritestate(FAR struct usbstrg_dev_s *priv); +static int usbstrg_cmdfinishstate(FAR struct usbstrg_dev_s *priv); +static int usbstrg_cmdstatusstate(FAR struct usbstrg_dev_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Debug + ****************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_dumpdata + ****************************************************************************/ + +#if defined(CONFIG_DEBUG_VERBOSE) && defined (CONFIG_DEBUG_USB) +static void usbstrg_dumpdata(const char *msg, const ubyte *buf, int buflen) +{ + int i; + + dbgprintf("%s:", msg); + for (i = 0; i < buflen; i++) + { + dbgprintf(" %02x", buf[i]); + } + dbgprintf("\n"); +} +#endif + +/**************************************************************************** + * Utility Support Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_getbe16 + * + * Description: + * Get a 16-bit big-endian value reference by the byte pointer + * + ****************************************************************************/ + +static uint16 usbstrg_getbe16(ubyte *buf) +{ + return ((uint16)buf[0] << 8) | ((uint16)buf[1]); +} + +/**************************************************************************** + * Name: usbstrg_getbe32 + * + * Description: + * Get a 32-bit big-endian value reference by the byte pointer + * + ****************************************************************************/ + +static uint32 usbstrg_getbe32(ubyte *buf) +{ + return ((uint32)buf[0] << 24) | ((uint32)buf[1] << 16) | + ((uint32)buf[2] << 8) | ((uint32)buf[3]); +} + +/**************************************************************************** + * Name: usbstrg_putbe16 + * + * Description: + * Store a 16-bit value in big-endian order to the location specified by + * a byte pointer + * + ****************************************************************************/ + +static void usbstrg_putbe16(ubyte * buf, uint16 val) +{ + buf[0] = val >> 8; + buf[1] = val; +} + +/**************************************************************************** + * Name: usbstrg_putbe32 + * + * Description: + * Store a 32-bit value in big-endian order to the location specified by + * a byte pointer + * + ****************************************************************************/ + +static void usbstrg_putbe32(ubyte *buf, uint32 val) +{ + buf[0] = val >> 24; + buf[1] = val >> 16; + buf[2] = val >> 8; + buf[3] = val; +} + +/**************************************************************************** + * Name: usbstrg_getle16 + * + * Description: + * Get a 16-bit little-endian value reference by the byte pointer + * + ****************************************************************************/ + +#if 0 /* not used */ +static uint16 usbstrg_getle16(ubyte *buf) +{ + return ((uint16)buf[1] << 8) | ((uint16)buf[0]); +} +#endif + +/**************************************************************************** + * Name: usbstrg_getle32 + * + * Description: + * Get a 32-bit little-endian value reference by the byte pointer + * + ****************************************************************************/ + +static uint32 usbstrg_getle32(ubyte *buf) +{ + return ((uint32)buf[3] << 24) | ((uint32)buf[2] << 16) | + ((uint32)buf[1] << 8) | ((uint32)buf[0]); +} + +/**************************************************************************** + * Name: usbstrg_putle16 + * + * Description: + * Store a 16-bit value in little-endian order to the location specified by + * a byte pointer + * + ****************************************************************************/ + +#if 0 /* not used */ +static void usbstrg_putle16(ubyte * buf, uint16 val) +{ + buf[0] = val; + buf[1] = val >> 8; +} +#endif + +/**************************************************************************** + * Name: usbstrg_putle32 + * + * Description: + * Store a 32-bit value in little-endian order to the location specified by + * a byte pointer + * + ****************************************************************************/ + +static void usbstrg_putle32(ubyte *buf, uint32 val) +{ + buf[0] = val; + buf[1] = val >> 8; + buf[2] = val >> 16; + buf[3] = val >> 24; +} + +/**************************************************************************** + * SCSI Worker Thread + ****************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_cmdtestunitready + * + * Description: + * Handle the SCSI_CMD_TESTUNITREADY command + * + ****************************************************************************/ + +static inline int usbstrg_cmdtestunitready(FAR struct usbstrg_dev_s *priv) +{ + int ret; + + priv->u.alloclen = 0; + ret = usbstrg_setupcmd(priv, 6, USBSTRG_FLAGS_DIRNONE); + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdrequestsense + * + * Description: + * Handle the SCSI_CMD_REQUESTSENSE command + * + ****************************************************************************/ + +static inline int usbstrg_cmdrequestsense(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf) +{ + FAR struct scsicmd_requestsense_s *request = (FAR struct scsicmd_requestsense_s *)priv->cdb; + FAR struct scsiresp_fixedsensedata_s *response = (FAR struct scsiresp_fixedsensedata_s *)buf; + FAR struct usbstrg_lun_s *lun; + uint32 sd; + uint32 sdinfo; + ubyte cdblen; + int ret; + + /* Extract the host allocation length */ + + priv->u.alloclen = request->alloclen; + + /* Get the expected length of the command (with hack for MS-Windows 12-byte + * REQUEST SENSE command. + */ + + cdblen = SCSICMD_REQUESTSENSE_SIZEOF; + if (cdblen != priv->cdblen) + { + /* Try MS-Windows REQUEST SENSE with cbw->cdblen == 12 */ + + cdblen = SCSICMD_REQUESTSENSE_MSSIZEOF; + } + + ret = usbstrg_setupcmd(priv, cdblen, + USBSTRG_FLAGS_DIRDEVICE2HOST|USBSTRG_FLAGS_LUNNOTNEEDED| + USBSTRG_FLAGS_UACOKAY|USBSTRG_FLAGS_RETAINSENSEDATA); + if (ret == OK) + { + lun = priv->lun; + if (!lun) + { + sd = SCSI_KCQIR_INVALIDLUN; + sdinfo = 0; + } + else + { + /* Get the saved sense data from the LUN structure */ + + sd = lun->sd; + sdinfo = lun->sdinfo; + + /* Discard the sense data */ + + lun->sd = SCSI_KCQ_NOSENSE; + lun->sdinfo = 0; + } + + /* Create the fixed sense data response */ + + memset(response, 0, SCSIRESP_FIXEDSENSEDATA_SIZEOF); + + response->code = SCSIRESP_SENSEDATA_RESPVALID|SCSIRESP_SENSEDATA_CURRENTFIXED; + response->flags = (ubyte)(sd >> 16); + usbstrg_putbe32(response->info, sdinfo); + response->len = SCSIRESP_FIXEDSENSEDATA_SIZEOF - 7; + response->code2 = (ubyte)(sd >> 8); + response->qual2 = (ubyte)sd; + + priv->nreqbytes = SCSIRESP_FIXEDSENSEDATA_SIZEOF; + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdread6 + * + * Description: + * Handle the SCSI_CMD_READ6 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdread6(FAR struct usbstrg_dev_s *priv) +{ + FAR struct scsicmd_read6_s *read6 = (FAR struct scsicmd_read6_s*)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + int ret; + + priv->u.xfrlen = (uint16)read6->xfrlen; + if (priv->u.xfrlen == 0) + { + priv->u.xfrlen = 256; + } + + ret = usbstrg_setupcmd(priv, SCSICMD_READ6_SIZEOF, USBSTRG_FLAGS_DIRDEVICE2HOST|USBSTRG_FLAGS_BLOCKXFR); + if (ret == OK) + { + /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */ + + priv->sector = (read6->mslba & SCSICMD_READ6_MSLBAMASK) << 16 | usbstrg_getbe16(read6->lslba); + + /* Verify that a block driver has been bound to the LUN */ + + if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ6MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Verify that sector lies in the range supported by the block driver */ + + else if (priv->sector >= lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ6LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + ret = -EINVAL; + } + + /* Looks like we are good to go */ + + else + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDREAD6), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDREAD; + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdwrite6 + * + * Description: + * Handle the SCSI_CMD_WRITE6 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdwrite6(FAR struct usbstrg_dev_s *priv) +{ + FAR struct scsicmd_write6_s *write6 = (FAR struct scsicmd_write6_s *)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + int ret; + + priv->u.xfrlen = (uint16)write6->xfrlen; + if (priv->u.xfrlen == 0) + { + priv->u.xfrlen = 256; + } + + ret = usbstrg_setupcmd(priv, SCSICMD_WRITE6_SIZEOF, USBSTRG_FLAGS_DIRHOST2DEVICE|USBSTRG_FLAGS_BLOCKXFR); + if (ret == OK) + { + /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */ + + priv->sector = (write6->mslba & SCSICMD_WRITE6_MSLBAMASK) << 16 | usbstrg_getbe16(write6->lslba); + + /* Verify that a block driver has been bound to the LUN */ + + if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE6MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Check for attempts to write to a read-only device */ + + else if (lun->readonly) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE6READONLY), 0); + lun->sd = SCSI_KCQWP_COMMANDNOTALLOWED; + ret = -EINVAL; + } + + /* Verify that sector lies in the range supported by the block driver */ + + else if (priv->sector >= lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE6LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + ret = -EINVAL; + } + + /* Looks like we are good to go */ + + else + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDWRITE6), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDWRITE; + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdinquiry + * + * Description: + * Handle SCSI_CMD_INQUIRY command + * + ****************************************************************************/ + +static inline int usbstrg_cmdinquiry(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf) +{ + FAR struct scscicmd_inquiry_s *inquiry = (FAR struct scscicmd_inquiry_s *)priv->cdb; + FAR struct scsiresp_inquiry_s *response = (FAR struct scsiresp_inquiry_s *)buf; + int len; + int ret; + + priv->u.alloclen = usbstrg_getbe16(inquiry->alloclen); + ret = usbstrg_setupcmd(priv, SCSICMD_INQUIRY_SIZEOF, + USBSTRG_FLAGS_DIRDEVICE2HOST|USBSTRG_FLAGS_LUNNOTNEEDED|USBSTRG_FLAGS_UACOKAY); + if (ret == OK) + { + if (!priv->lun) + { + response->qualtype = SCSIRESP_INQUIRYPQ_NOTCAPABLE|SCSIRESP_INQUIRYPD_UNKNOWN; + } + else if ((inquiry->flags != 0) || (inquiry->pagecode != 0)) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_INQUIRYFLAGS), 0); + priv->lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + else + { + memset(response, 0, SCSIRESP_INQUIRY_SIZEOF); + priv->nreqbytes = SCSIRESP_INQUIRY_SIZEOF; + +#ifdef CONFIG_USBSTRG_REMOVABLE + response->flags1 = SCSIRESP_INQUIRYFLAGS1_RMB; +#endif + response->version = 2; /* SCSI-2 */ + response->flags2 = 2; /* SCSI-2 INQUIRY response data format */ + response->len = SCSIRESP_INQUIRY_SIZEOF - 5; + + /* Strings */ + + memset(response->vendorid, ' ', 8+16+4); + + len = strlen(g_vendorstr); + DEBUGASSERT(len <= 8); + memcpy(response->vendorid, g_vendorstr, len); + + len = strlen(g_productstr); + DEBUGASSERT(len <= 16); + memcpy(response->productid, g_productstr, len); + + len = strlen(g_serialstr); + DEBUGASSERT(len <= 4); + memcpy(response->productid, g_serialstr, len); + } + } + + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdmodeselect6 + * + * Description: + * Handle SCSI_CMD_MODESELECT6 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdmodeselect6(FAR struct usbstrg_dev_s *priv) +{ + FAR struct scsicmd_modeselect6_s *modeselect = (FAR struct scsicmd_modeselect6_s *)priv->cdb; + + priv->u.alloclen = modeselect->plen; + (void)usbstrg_setupcmd(priv, SCSICMD_MODESELECT6_SIZEOF, USBSTRG_FLAGS_DIRHOST2DEVICE); + + /* Not supported */ + + priv->lun->sd = SCSI_KCQIR_INVALIDCOMMAND; + return -EINVAL; +} + +/**************************************************************************** + * Name: usbstrg_modepage + * + * Description: + * Common logic for usbstrg_cmdmodesense6() and usbstrg_cmdmodesense10() + * + ****************************************************************************/ + +static int usbstrg_modepage(FAR struct usbstrg_dev_s *priv, FAR ubyte *buf, + ubyte pcpgcode, int *mdlen) +{ + FAR struct scsiresp_cachingmodepage_s *cmp = (FAR struct scsiresp_cachingmodepage_s *)buf; + + /* Saving parms not supported */ + + if ((pcpgcode & SCSICMD_MODESENSE_PCMASK) == SCSICMD_MODESENSE_PCSAVED) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_PCSAVED), 0); + priv->lun->sd = SCSI_KCQIR_SAVINGPARMSNOTSUPPORTED; + return -EINVAL; + } + + /* Only the caching mode page is supported: */ + + if ((pcpgcode & SCSICMD_MODESENSE_PGCODEMASK) == SCSIRESP_MODESENSE_PGCCODE_CACHING || + (pcpgcode & SCSICMD_MODESENSE_PGCODEMASK) == SCSIRESP_MODESENSE_PGCCODE_RETURNALL) + { + memset(cmp, 0, 12); + cmp->pgcode = SCSIRESP_MODESENSE_PGCCODE_CACHING; + cmp->len = 10; /* n-2 */ + + /* None of the fields are changeable */ + + if (((pcpgcode & SCSICMD_MODESENSE_PCMASK) != SCSICMD_MODESENSE_PCCHANGEABLE)) + { + cmp->flags1 = SCSIRESP_CACHINGMODEPG_WCE; /* Write cache enable */ + cmp->dpflen[0] = 0xff; /* Disable prefetch transfer length = 0xffffffff */ + cmp->dpflen[1] = 0xff; + cmp->maxpf[0] = 0xff; /* Maximum pre-fetch = 0xffffffff */ + cmp->maxpf[1] = 0xff; + cmp->maxpfc[0] = 0xff; /* Maximum pref-fetch ceiling = 0xffffffff */ + cmp->maxpfc[1] = 0xff; + } + + /* Return the mode data length */ + + *mdlen = 12; /* Only the first 12-bytes of caching mode page sent */ + return OK; + } + else + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_MODEPAGEFLAGS), pcpgcode); + priv->lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + return -EINVAL; + } +} + +/**************************************************************************** + * Name: usbstrg_cmdmodesense6 + * + * Description: + * Handle SCSI_CMD_MODESENSE6 command + * + ****************************************************************************/ + +static int inline usbstrg_cmdmodesense6(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf) +{ + FAR struct scsicmd_modesense6_s *modesense = (FAR struct scsicmd_modesense6_s *)priv->cdb; + FAR struct scsiresp_modeparameterhdr6_s *mph = (FAR struct scsiresp_modeparameterhdr6_s *)buf; + int mdlen; + int ret; + + priv->u.alloclen = modesense->alloclen; + ret = usbstrg_setupcmd(priv, SCSICMD_MODESENSE6_SIZEOF, USBSTRG_FLAGS_DIRDEVICE2HOST); + if (ret == OK) + { + if ((modesense->flags & ~SCSICMD_MODESENSE6_DBD) != 0 || modesense->subpgcode != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_MODESENSE6FLAGS), 0); + priv->lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + else + { + /* The response consists of: + * + * (1) A MODESENSE6-specific mode parameter header, + * (2) A variable length list of block descriptors, and + * (3) A variable lengtth list of mode page formats + */ + + mph->type = 0; /* Medium type */ + mph->param = (priv->lun->readonly ? SCSIRESP_MODEPARMHDR_DAPARM_WP : 0x00); + mph->bdlen = 0; /* Block descriptor length */ + + /* There are no block descriptors, only the following mode page: */ + + ret = usbstrg_modepage(priv, &buf[SCSIREP_MODEPARAMETERHDR6_SIZEOF], modesense->pcpgcode, &mdlen); + if (ret == OK) + { + /* Store the mode data length and return the total message size */ + + mph->mdlen = mdlen - 1; + priv->nreqbytes = mdlen + SCSIREP_MODEPARAMETERHDR6_SIZEOF; + } + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdstartstopunit + * + * Description: + * Handle SCSI_CMD_STARTSTOPUNIT command + * + ****************************************************************************/ + +static inline int usbstrg_cmdstartstopunit(FAR struct usbstrg_dev_s *priv) +{ + int ret; + + priv->u.alloclen = 0; + ret = usbstrg_setupcmd(priv, SCSICMD_STARTSTOPUNIT_SIZEOF, USBSTRG_FLAGS_DIRNONE); + if (ret == OK) + { +#ifndef CONFIG_USBSTRG_REMOVABLE + /* This command is not valid if the media is not removable */ + + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_NOTREMOVABLE), 0); + lun->sd = SCSI_KCQIR_INVALIDCOMMAND; + ret = -EINVAL; +#endif + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdpreventmediumremoval + * + * Description: + * Handle SCSI_CMD_PREVENTMEDIAREMOVAL command + * + ****************************************************************************/ + +static inline int usbstrg_cmdpreventmediumremoval(FAR struct usbstrg_dev_s *priv) +{ +#ifdef CONFIG_USBSTRG_REMOVABLE + FAR struct scsicmd_preventmediumremoval_s *pmr = (FAR struct scsicmd_preventmediumremoval_s *)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; +#endif + int ret; + + priv->u.alloclen = 0; + ret = usbstrg_setupcmd(priv, SCSICMD_PREVENTMEDIUMREMOVAL_SIZEOF, USBSTRG_FLAGS_DIRNONE); + if (ret == OK) + { +#ifndef CONFIG_USBSTRG_REMOVABLE + lun->sd = SCSI_KCQIR_INVALIDCOMMAND; + ret = -EINVAL; +#else + if ((pmr->prevent & ~SCSICMD_PREVENTMEDIUMREMOVAL_TRANSPORT) != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_PREVENTMEDIUMREMOVALPREVENT), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + + lun->locked = pmr->prevent & SCSICMD_PREVENTMEDIUMREMOVAL_TRANSPORT; +#endif + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdreadcapacity10 + * + * Description: + * Handle SCSI_CMD_READCAPACITY10 command + * + ****************************************************************************/ + +static int inline usbstrg_cmdreadcapacity10(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf) +{ + FAR struct scsicmd_readcapacity10_s *rcc = (FAR struct scsicmd_readcapacity10_s *)priv->cdb; + FAR struct scsiresp_readcapacity10_s *rcr = (FAR struct scsiresp_readcapacity10_s *)buf; + FAR struct usbstrg_lun_s *lun = priv->lun; + uint32 lba; + int ret; + + priv->u.alloclen = SCSIRESP_READCAPACITY10_SIZEOF; /* Fake the allocation length */ + ret = usbstrg_setupcmd(priv, SCSICMD_READCAPACITY10_SIZEOF, USBSTRG_FLAGS_DIRDEVICE2HOST); + if (ret == OK) + { + /* Check the PMI and LBA fields */ + + lba = usbstrg_getbe32(rcc->lba); + + if (rcc->pmi > 1 || (rcc->pmi == 0 && lba != 0)) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READCAPACITYFLAGS), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + else + { + usbstrg_putbe32(rcr->lba, lun->nsectors - 1); + usbstrg_putbe32(&buf[4], lun->sectorsize); + priv->nreqbytes = SCSIRESP_READCAPACITY10_SIZEOF; + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdread10 + * + * Description: + * Handle SCSI_CMD_READ10 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdread10(FAR struct usbstrg_dev_s *priv) +{ + struct scsicmd_read10_s *read10 = (struct scsicmd_read10_s*)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + int ret; + + priv->u.xfrlen = usbstrg_getbe16(read10->xfrlen); + ret = usbstrg_setupcmd(priv, SCSICMD_READ10_SIZEOF, USBSTRG_FLAGS_DIRDEVICE2HOST|USBSTRG_FLAGS_BLOCKXFR); + if (ret == OK) + { + /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */ + + priv->sector = usbstrg_getbe32(read10->lba); + + /* Verify that we can support this read command */ + + if ((read10->flags & ~(SCSICMD_READ10FLAGS_DPO|SCSICMD_READ10FLAGS_FUA)) != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ10FLAGS), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + + /* Verify that a block driver has been bound to the LUN */ + + else if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ10MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Verify that LBA lies in the range supported by the block driver */ + + else if (priv->sector >= lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ10LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + ret = -EINVAL; + } + + /* Looks like we are good to go */ + + else + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDREAD10), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDREAD; + } + } + + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdwrite10 + * + * Description: + * Handle SCSI_CMD_WRITE10 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdwrite10(FAR struct usbstrg_dev_s *priv) +{ + struct scsicmd_write10_s *write10 = (struct scsicmd_write10_s *)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + int ret; + + priv->u.xfrlen = usbstrg_getbe16(write10->xfrlen); + ret = usbstrg_setupcmd(priv, SCSICMD_WRITE10_SIZEOF, USBSTRG_FLAGS_DIRHOST2DEVICE|USBSTRG_FLAGS_BLOCKXFR); + if (ret == OK) + { + /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */ + + priv->sector = usbstrg_getbe32(write10->lba); + + /* Verify that we can support this write command */ + + if ((write10->flags & ~(SCSICMD_WRITE10FLAGS_DPO|SCSICMD_WRITE10FLAGS_FUA)) != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE10FLAGS), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + + /* Verify that a block driver has been bound to the LUN */ + + else if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE10MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Check for attempts to write to a read-only device */ + + else if (lun->readonly) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE10READONLY), 0); + lun->sd = SCSI_KCQWP_COMMANDNOTALLOWED; + ret = -EINVAL; + } + + /* Verify that LBA lies in the range supported by the block driver */ + + else if (priv->sector >= lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE10LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + ret = -EINVAL; + } + + /* Looks like we are good to go */ + + else + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDWRITE10), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDWRITE; + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdverify10 + * + * Description: + * Handle SCSI_CMD_VERIFY10 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdverify10(FAR struct usbstrg_dev_s *priv) +{ + FAR struct scsicmd_verify10_s *verf = (FAR struct scsicmd_verify10_s *)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + uint32 lba; + uint16 blocks; + size_t sector; + ssize_t nread; + int ret; + int i; + + priv->u.alloclen = 0; + ret = usbstrg_setupcmd(priv, SCSICMD_VERIFY10_SIZEOF, USBSTRG_FLAGS_DIRNONE); + if (ret == OK) + { + /* Verify the starting and ending LBA */ + + lba = usbstrg_getbe32(verf->lba); + blocks = usbstrg_getbe16(verf->len); + + if ((verf->flags & ~SCSICMD_VERIFY10_DPO) != 0 || verf->groupno != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_VERIFY10FLAGS), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + else if (blocks == 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_VERIFY10NOBLOCKS), 0); + ret = -EIO; /* No reply */ + } + + /* Verify that a block driver has been bound to the LUN */ + + else if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_VERIFY10MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Verify that LBA lies in the range supported by the block driver */ + + else if (lba >= lun->nsectors || lba + blocks > lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_VERIFY10LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + ret = -EINVAL; + } + else + { + /* Try to read the requested blocks */ + + for (i = 0, sector = lba + lun->startsector; i < blocks; i++, sector++) + { + nread = USBSTRG_DRVR_READ(lun, priv->iobuffer, sector, 1); + if (nread < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_VERIFY10READFAIL), i); + lun->sd = SCSI_KCQME_UNRRE1; + lun->sdinfo = sector; + ret = -EIO; + break; + } + } + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdsynchronizecache10 + * + * Description: + * Handle SCSI_CMD_SYNCHCACHE10 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdsynchronizecache10(FAR struct usbstrg_dev_s *priv) +{ + int ret; + + priv->u.alloclen = 0; + + /* Verify that we have the LUN structure and the block driver has been bound */ + + if (!priv->lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SYNCCACHEMEDIANOTPRESENT), 0); + priv->lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + else + { + ret = usbstrg_setupcmd(priv, SCSICMD_SYNCHRONIZECACHE10_SIZEOF, USBSTRG_FLAGS_DIRNONE); + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdmodeselect10 + * + * Description: + * Handle SCSI_CMD_MODESELECT10 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdmodeselect10(FAR struct usbstrg_dev_s *priv) +{ + FAR struct scsicmd_modeselect10_s *modeselect = (FAR struct scsicmd_modeselect10_s *)priv->cdb; + + priv->u.alloclen = usbstrg_getbe16(modeselect->parmlen); + (void)usbstrg_setupcmd(priv, SCSICMD_MODESELECT10_SIZEOF, USBSTRG_FLAGS_DIRHOST2DEVICE); + + /* Not supported */ + + priv->lun->sd = SCSI_KCQIR_INVALIDCOMMAND; + return -EINVAL; +} + +/**************************************************************************** + * Name: usbstrg_cmdmodesense10 + * + * Description: + * Handle SCSI_CMD_MODESENSE10 command + * + ****************************************************************************/ + +static int inline usbstrg_cmdmodesense10(FAR struct usbstrg_dev_s *priv, + FAR ubyte *buf) +{ + FAR struct scsicmd_modesense10_s *modesense = (FAR struct scsicmd_modesense10_s *)priv->cdb; + FAR struct scsiresp_modeparameterhdr10_s *mph = (FAR struct scsiresp_modeparameterhdr10_s *)buf; + int mdlen; + int ret; + + priv->u.alloclen = usbstrg_getbe16(modesense->alloclen); + ret = usbstrg_setupcmd(priv, SCSICMD_MODESENSE10_SIZEOF, USBSTRG_FLAGS_DIRDEVICE2HOST); + if (ret == OK) + { + if ((modesense->flags & ~SCSICMD_MODESENSE10_DBD) != 0 || modesense->subpgcode != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_MODESENSE10FLAGS), 0); + priv->lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + else + { + /* The response consists of: + * + * (1) A MODESENSE6-specific mode parameter header, + * (2) A variable length list of block descriptors, and + * (3) A variable lengtth list of mode page formats + */ + + memset(mph, 0, SCSIREP_MODEPARAMETERHDR10_SIZEOF); + mph->param = (priv->lun->readonly ? SCSIRESP_MODEPARMHDR_DAPARM_WP : 0x00); + + /* There are no block descriptors, only the following mode page: */ + + ret = usbstrg_modepage(priv, &buf[SCSIREP_MODEPARAMETERHDR10_SIZEOF], modesense->pcpgcode, &mdlen); + if (ret == OK) + { + /* Store the mode data length and return the total message size */ + + usbstrg_putbe16(mph->mdlen, mdlen - 2); + priv->nreqbytes = mdlen + SCSIREP_MODEPARAMETERHDR10_SIZEOF; + } + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdread12 + * + * Description: + * Handle SCSI_CMD_READ12 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdread12(FAR struct usbstrg_dev_s *priv) +{ + struct scsicmd_read12_s *read12 = (struct scsicmd_read12_s*)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + int ret; + + priv->u.xfrlen = usbstrg_getbe32(read12->xfrlen); + ret = usbstrg_setupcmd(priv, SCSICMD_READ12_SIZEOF, USBSTRG_FLAGS_DIRDEVICE2HOST|USBSTRG_FLAGS_BLOCKXFR); + if (ret == OK) + { + /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */ + + priv->sector = usbstrg_getbe32(read12->lba); + + /* Verify that we can support this read command */ + + if ((read12->flags & ~(SCSICMD_READ12FLAGS_DPO|SCSICMD_READ12FLAGS_FUA)) != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ12FLAGS), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + ret = -EINVAL; + } + + /* Verify that a block driver has been bound to the LUN */ + + else if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ12MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Verify that LBA lies in the range supported by the block driver */ + + else if (priv->sector >= lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_READ12LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + ret = -EINVAL; + } + + /* Looks like we are good to go */ + + else + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDREAD12), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDREAD; + } + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdwrite12 + * + * Description: + * Handle SCSI_CMD_WRITE12 command + * + ****************************************************************************/ + +static inline int usbstrg_cmdwrite12(FAR struct usbstrg_dev_s *priv) +{ + struct scsicmd_write12_s *write12 = (struct scsicmd_write12_s *)priv->cdb; + FAR struct usbstrg_lun_s *lun = priv->lun; + int ret; + + priv->u.xfrlen = usbstrg_getbe32(write12->xfrlen); + ret = usbstrg_setupcmd(priv, SCSICMD_WRITE12_SIZEOF, USBSTRG_FLAGS_DIRHOST2DEVICE|USBSTRG_FLAGS_BLOCKXFR); + if (ret == OK) + { + /* Get the Logical Block Address (LBA) from cdb[] as the starting sector */ + + priv->sector = usbstrg_getbe32(write12->lba); + + /* Verify that we can support this write command */ + + if ((write12->flags & ~(SCSICMD_WRITE12FLAGS_DPO|SCSICMD_WRITE12FLAGS_FUA)) != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE12FLAGS), 0); + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + } + + /* Verify that a block driver has been bound to the LUN */ + + else if (!lun->inode) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE12MEDIANOTPRESENT), 0); + lun->sd = SCSI_KCQNR_MEDIANOTPRESENT; + ret = -EINVAL; + } + + /* Check for attempts to write to a read-only device */ + + else if (lun->readonly) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE12READONLY), 0); + lun->sd = SCSI_KCQWP_COMMANDNOTALLOWED; + } + + /* Verify that LBA lies in the range supported by the block driver */ + + else if (priv->sector >= lun->nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRITE12LBARANGE), 0); + lun->sd = SCSI_KCQIR_LBAOUTOFRANGE; + } + + /* Looks like we are good to go */ + + else + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDWRITE12), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDWRITE; + return OK; + } + } + + return ret; +} + +/**************************************************************************** + * Name: usbstrg_setupcmd + * + * Description: + * Called after each SCSI command is identified in order to perform setup + * and verification operations that are common to all SCSI commands. This + * function performs the following common setup operations: + * + * 1. Determine the direction of the response + * 2. Verify lengths + * 3. Setup and verify the LUN + * + * Includes special logic for INQUIRY and REQUESTSENSE commands + * + ****************************************************************************/ + +static int inline usbstrg_setupcmd(FAR struct usbstrg_dev_s *priv, ubyte cdblen, ubyte flags) +{ + FAR struct usbstrg_lun_s *lun; + uint32 datlen; + ubyte dir = flags & USBSTRG_FLAGS_DIRMASK; + int ret = OK; + + /* Verify the LUN and set up the current LUN reference in the + * device structure + */ + + if (priv->cbwlun < priv->nluns) + { + /* LUN number is valid in a valid range, but the LUN is not necessarily + * bound to a block driver. That will be checked as necessary in each + * individual command. + */ + + lun = &priv->luntab[priv->cbwlun]; + priv->lun = lun; + } + else + { + priv->lun = NULL; + + /* Only a few commands may specify unsupported LUNs */ + + if ((flags & USBSTRG_FLAGS_LUNNOTNEEDED) == 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDBADLUN), priv->cbwlun); + ret = -EINVAL; + } + } + + /* Extract the direction and data transfer length */ + + dir = flags & USBSTRG_FLAGS_DIRMASK; /* Expected data direction */ + datlen = 0; + if ((flags & USBSTRG_FLAGS_BLOCKXFR) == 0) + { + /* Non-block transfer. Data length: Host allocation to receive data + * (only for device-to-host transfers. At present, alloclen is set + * to zero for all host-to-device, non-block transfers. + */ + + datlen = priv->u.alloclen; + } + else if (lun) + { + /* Block transfer: Calculate the total size of all sectors to be transferred */ + + datlen = priv->u.alloclen * lun->sectorsize; + } + + /* Check the data direction. This was set up at the end of the + * IDLE state when the CBW was parsed, but if there is no data, + * then the direction is none. + */ + + if (datlen == 0) + { + /* No data.. then direction is none */ + + dir = USBSTRG_FLAGS_DIRNONE; + } + + /* Compare the expected data length in the command to the data length + * in the CBW. + */ + + else if (priv->cbwlen < datlen) + { + /* Clip to the length in the CBW and declare a phase error */ + + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_PHASEERROR1), priv->cdb[0]); + if ((flags & USBSTRG_FLAGS_BLOCKXFR) != 0) + { + priv->u.alloclen = priv->cbwlen; + } + else + { + priv->u.xfrlen = priv->cbwlen / lun->sectorsize; + } + + priv->phaseerror = 1; + } + + /* Initialize the residue */ + + priv->residue = priv->cbwlen; + + /* Conflicting data directions is a phase error */ + + if (priv->cbwdir != dir && datlen > 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_PHASEERROR2), priv->cdb[0]); + priv->phaseerror = 1; + ret = -EINVAL; + } + + /* Compare the length of data in the cdb[] with the expected length + * of the command. + */ + + if (cdblen != priv->cdblen) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_PHASEERROR3), priv->cdb[0]); + priv->phaseerror = 1; + ret = -EINVAL; + } + + if (lun) + { + /* Retain the sense data for the REQUEST SENSE command */ + + if ((flags & USBSTRG_FLAGS_RETAINSENSEDATA) == 0) + { + /* Discard the sense data */ + + lun->sd = SCSI_KCQ_NOSENSE; + lun->sdinfo = 0; + } + + /* If a unit attention condition exists, then only a restricted set of + * commands is permitted. + */ + + if (lun->uad != SCSI_KCQ_NOSENSE && (flags & USBSTRG_FLAGS_UACOKAY) != 0) + { + /* Command not permitted */ + + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDUNEVIOLATION), priv->cbwlun); + lun->sd = lun->uad; + lun->uad = SCSI_KCQ_NOSENSE; + ret = -EINVAL; + } + } + + /* The final, 1-byte field of every SCSI command is the Control field which + * must be zero + */ + + if (priv->cdb[cdblen-1] != 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SCSICMDCONTROL), 0); + if (lun) + { + lun->sd = SCSI_KCQIR_INVALIDFIELDINCBA; + } + ret = -EINVAL; + } + return ret; +} + +/**************************************************************************** + * Name: usbstrg_idlestate + * + * Description: + * Called from the worker thread in the USBSTRG_STATE_IDLE state. Checks + * for the receipt of a bulk CBW. + * + * Returned value: + * If no new, valid CBW is available, this function returns a negated errno. + * Otherwise, when a new CBW is successfully parsed, this function sets + * priv->thstate to USBSTRG_STATE_CMDPARSE and returns OK. + * + ****************************************************************************/ + +static int usbstrg_idlestate(FAR struct usbstrg_dev_s *priv) +{ + FAR struct usbstrg_req_s *privreq; + FAR struct usbdev_req_s *req; + FAR struct usbstrg_cbw_s *cbw; + irqstate_t flags; + int ret = -EINVAL; + + /* Take a request from the rdreqlist */ + + flags = irqsave(); + privreq = (FAR struct usbstrg_req_s *)sq_remfirst(&priv->rdreqlist); + irqrestore(flags); + + /* Has anything been received? If not, just return an error. + * This will cause us to remain in the IDLE state. When a USB request is + * received, the worker thread will be awakened in the USBSTRG_STATE_IDLE + * and we will be called again. + */ + + if (!privreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_IDLERDREQLISTEMPTY), 0); + return -ENOMEM; + } + + req = privreq->req; + cbw = (FAR struct usbstrg_cbw_s *)req->buf; + + /* Handle the CBW */ + + usbstrg_dumpdata("SCSCI CBW", (ubyte*)cbw, USBSTRG_CBW_SIZEOF - USBSTRG_MAXCDBLEN); + usbstrg_dumpdata(" CDB", cbw->cdb, min(cbw->cdblen, USBSTRG_MAXCDBLEN)); + + /* Check for properly formatted CBW? */ + + if (req->xfrd != USBSTRG_CBW_SIZEOF || + cbw->signature[0] != 'U' || + cbw->signature[1] != 'S' || + cbw->signature[2] != 'B' || + cbw->signature[3] != 'C') + { + /* CBS BAD: Stall the bulk endpoints. If the CBW is bad we must stall the + * bulk IN endpoint and either (1) stall the bulk OUT endpoint, or + * (2) discard data from the endpoint. + */ + + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_INVALIDCBWSIGNATURE), 0); + EP_STALL(priv->epbulkout); + EP_STALL(priv->epbulkin); + } + + /* Is the CBW meaningful? */ + + else if (cbw->lun >= priv->nluns || (cbw->flags & ~USBSTRG_CBWFLAG_IN) != 0 || + cbw->cdblen < 6 || cbw->cdblen > USBSTRG_MAXCDBLEN) + { + /* CBS BAD: Stall the bulk endpoints. If the CBW is bad we must stall the + * bulk IN endpoint and either (1) stall the bulk OUT endpoint, or + * (2) discard data from the endpoint. + */ + + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_INVALIDCBWCONTENT), 0); + EP_STALL(priv->epbulkout); + EP_STALL(priv->epbulkin); + } + + /* Save the information from the CBW */ + + else + { + /* Extract the CDB and copy the whole CBD[] for later use */ + + priv->cdblen = cbw->cdblen; + memcpy(priv->cdb, cbw->cdb, priv->cdblen); + + /* Extract the data direction */ + + if ((cbw->flags & USBSTRG_CBWFLAG_IN) != 0) + { + /* IN: Device-to-host */ + + priv->cbwdir = USBSTRG_FLAGS_DIRDEVICE2HOST; + } + else + { + /* OUT: Host-to-device */ + + priv->cbwdir = USBSTRG_FLAGS_DIRHOST2DEVICE; + } + + /* Get the max size of the data response */ + + priv->cbwlen = usbstrg_getle32(cbw->datlen); + if (priv->cbwlen == 0) + { + /* No length? Then no direction either */ + + priv->cbwdir = USBSTRG_FLAGS_DIRNONE; + } + + /* Extract and save the LUN index and TAG value */ + + priv->cbwlun = cbw->lun; + priv->cbwtag = usbstrg_getle32(cbw->tag); + + /* Return the read request to the bulk out endpoint for re-filling */ + + req = privreq->req; + req->len = CONFIG_USBSTRG_BULKOUTREQLEN; + req->private = privreq; + req->callback = usbstrg_rdcomplete; + + if (EP_SUBMIT(priv->epbulkout, req) != OK) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_IDLERDSUBMIT), (uint16)-ret); + } + + /* Change to the CMDPARSE state and return success */ + + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_IDLECMDPARSE), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDPARSE; + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: usbstrg_cmdparsestate + * + * Description: + * Called from the worker thread in the USBSTRG_STATE_CMDPARSE state. + * This state is entered when usbstrg_idlestate obtains a valid CBW + * containing SCSI commands. This function processes those SCSI commands. + * + * Returned value: + * If no write request is available or certain other errors occur, this + * function returns a negated errno and stays in the USBSTRG_STATE_CMDPARSE + * state. Otherwise, when the new CBW is successfully process, this + * function sets priv->thstate to one of USBSTRG_STATE_CMDREAD, + * USBSTRG_STATE_CMDWRITE, or USBSTRG_STATE_CMDFINISH and returns OK. + * + ****************************************************************************/ + +static int usbstrg_cmdparsestate(FAR struct usbstrg_dev_s *priv) +{ + FAR struct usbstrg_req_s *privreq; + FAR ubyte *buf; + int ret = -EINVAL; + + usbstrg_dumpdata("SCSCI CDB", priv->cdb, priv->cdblen); + + /* Check if there is a request in the wrreqlist that we will be able to + * use for data or status. + */ + + privreq = (FAR struct usbstrg_req_s *)sq_peek(&priv->wrreqlist); + + /* If there no request structures available, then just return an error. + * This will cause us to remain in the CMDPARSE state. When a request is + * returned, the worker thread will be awakened in the USBSTRG_STATE_CMDPARSE + * and we will be called again. + */ + + if (!privreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDPARSEWRREQLISTEMPTY), 0); + return -ENOMEM; + } + DEBUGASSERT(privreq->req && privreq->req->buf); + buf = privreq->req->buf; + + /* Assume that no errors will be encountered */ + + priv->phaseerror = 0; + priv->shortpacket = 0; + + /* No data is buffered */ + + priv->nsectbytes = 0; + priv->nreqbytes = 0; + + /* Get exclusive access to the block driver */ + + pthread_mutex_lock(&priv->mutex); + switch (priv->cdb[0]) + { + case SCSI_CMD_TESTUNITREADY: /* 0x00 Mandatory */ + ret = usbstrg_cmdtestunitready(priv); + break; + + /* case SCSI_CMD_REZEROUNIT: * 0x01 Obsolete + * * 0x02 Vendor-specific */ + + case SCSI_CMD_REQUESTSENSE: /* 0x03 Mandatory */ + ret = usbstrg_cmdrequestsense(priv, buf); + break; + + /* case SCSI_CMD_FORMAT_UNIT: * 0x04 Mandatory, but not implemented + * * 0x05 Vendor specific + * * 0x06 Vendor specific + * case SCSI_CMD_REASSIGNBLOCKS: * 0x07 Optional */ + + case SCSI_CMD_READ6: /* 0x08 Mandatory */ + return usbstrg_cmdread6(priv); + break; + + /* * 0x09 Vendor specific */ + + case SCSI_CMD_WRITE6: /* 0x0a Optional */ + return usbstrg_cmdwrite6(priv); + break; + + /* case SCSI_CMD_SEEK6: * 0x0b Obsolete + * * 0x0c-0x10 Vendor specific + * case SCSI_CMD_SPACE6: * 0x11 Vendor specific */ + + case SCSI_CMD_INQUIRY: /* 0x12 Mandatory */ + ret = usbstrg_cmdinquiry(priv, buf); + break; + + /* * 0x13-0x14 Vendor specific */ + + case SCSI_CMD_MODESELECT6: /* 0x15 Optional */ + ret = usbstrg_cmdmodeselect6(priv); + break; + + /* case SCSI_CMD_RESERVE6: * 0x16 Obsolete + * case SCSI_CMD_RELEASE6: * 0x17 Obsolete + * case SCSI_CMD_COPY: * 0x18 Obsolete + * * 0x19 Vendor specific */ + + case SCSI_CMD_MODESENSE6: /* 0x1a Optional */ + ret = usbstrg_cmdmodesense6(priv, buf); + break; + + case SCSI_CMD_STARTSTOPUNIT: /* 0x1b Optional */ + ret = usbstrg_cmdstartstopunit(priv); + break; + + /* case SCSI_CMD_RECEIVEDIAGNOSTICRESULTS: * 0x1c Optional + * case SCSI_CMD_SENDDIAGNOSTIC: * 0x1d Mandatory, but not implemented */ + + case SCSI_CMD_PREVENTMEDIAREMOVAL: /* 0x1e Optional */ + ret = usbstrg_cmdpreventmediumremoval(priv); + break; + + /* * 0x20-22 Vendor specific + * case SCSI_CMD_READFORMATCAPACITIES: * 0x23 Vendor-specific + * * 0x24 Vendor specific */ + + case SCSI_CMD_READCAPACITY10: /* 0x25 Mandatory */ + ret = usbstrg_cmdreadcapacity10(priv, buf); + break; + + /* * 0x26-27 Vendor specific */ + + case SCSI_CMD_READ10: /* 0x28 Mandatory */ + return usbstrg_cmdread10(priv); + break; + + /* * 0x29 Vendor specific */ + + case SCSI_CMD_WRITE10: /* 0x2a Optional */ + return usbstrg_cmdwrite10(priv); + break; + + /* case SCSI_CMD_SEEK10: * 0x2b Obsolete + * * 0x2c-2d Vendor specific + * case SCSI_CMD_WRITEANDVERIFY: * 0x2e Optional */ + + case SCSI_CMD_VERIFY10: /* 0x2f Optional, but needed my MS Windows */ + ret = usbstrg_cmdverify10(priv); + break; + + /* case SCSI_CMD_SEARCHDATAHIGH: * 0x30 Obsolete + * case SCSI_CMD_SEARCHDATAEQUAL: * 0x31 Obsolete + * case SCSI_CMD_SEARCHDATALOW: * 0x32 Obsolete + * case SCSI_CMD_SETLIMITS10: * 0x33 Obsolete + * case SCSI_CMD_PREFETCH10: * 0x34 Optional */ + + case SCSI_CMD_SYNCHCACHE10: /* 0x35 Optional */ + ret = usbstrg_cmdsynchronizecache10(priv); + break; + + /* case SCSI_CMD_LOCKCACHE: * 0x36 Obsolete + * case SCSI_CMD_READDEFECTDATA10: * 0x37 Optional + * case SCSI_CMD_COMPARE: * 0x39 Obsolete + * case SCSI_CMD_COPYANDVERIFY: * 0x3a Obsolete + * case SCSI_CMD_WRITEBUFFER: * 0x3b Optional + * case SCSI_CMD_READBUFFER: * 0x3c Optional + * case SCSI_CMD_READLONG10: * 0x3e Optional + * case SCSI_CMD_WRITELONG10: * 0x3f Optional + * case SCSI_CMD_CHANGEDEFINITION: * 0x40 Obsolete + * case SCSI_CMD_WRITESAME10: * 0x41 Optional + * case SCSI_CMD_LOGSELECT: * 0x4c Optional + * case SCSI_CMD_LOGSENSE: * 0x4d Optional + * case SCSI_CMD_XDWRITE10: * 0x50 Optional + * case SCSI_CMD_XPWRITE10: * 0x51 Optional + * case SCSI_CMD_XDREAD10: * 0x52 Optional */ + + case SCSI_CMD_MODESELECT10: /* 0x55 Optional */ + ret = usbstrg_cmdmodeselect10(priv); + break; + + /* case SCSI_CMD_RESERVE10: * 0x56 Obsolete + * case SCSI_CMD_RELEASE10: * 0x57 Obsolete */ + + case SCSI_CMD_MODESENSE10: /* 0x5a Optional */ + ret = usbstrg_cmdmodesense10(priv, buf); + break; + + /* case SCSI_CMD_PERSISTENTRESERVEIN: * 0x5e Optional + * case SCSI_CMD_PERSISTENTRESERVEOUT: * 0x5f Optional + * case SCSI_CMD_32: * 0x7f Optional + * case SCSI_CMD_XDWRITEEXTENDED: * 0x80 Obsolete + * case SCSI_CMD_REBUILD: * 0x81 Obsolete + * case SCSI_CMD_REGENERATE: * 0x82 Obsolete + * case SCSI_CMD_EXTENDEDCOPY: * 0x83 Optional + * case SCSI_CMD_COPYRESULTS: * 0x84 Optional + * case SCSI_CMD_ACCESSCONTROLIN: * 0x86 Optional + * case SCSI_CMD_ACCESSCONTROLOUT: * 0x87 Optional + * case SCSI_CMD_READ16: * 0x88 Optional + * case SCSI_CMD_WRITE16: * 0x8a Optional + * case SCSI_CMD_READATTRIBUTE: * 0x8c Optional + * case SCSI_CMD_WRITEATTRIBUTE: * 0x8d Optional + * case SCSI_CMD_WRITEANDVERIFY16: * 0x8e Optional + * case SCSI_CMD_SYNCHCACHE16: * 0x91 Optional + * case SCSI_CMD_LOCKUNLOCKACACHE: * 0x92 Optional + * case SCSI_CMD_WRITESAME16: * 0x93 Optional + * case SCSI_CMD_READCAPACITY16: * 0x9e Optional + * case SCSI_CMD_READLONG16: * 0x9e Optional + * case SCSI_CMD_WRITELONG16 * 0x9f Optional + * case SCSI_CMD_REPORTLUNS: * 0xa0 Mandatory, but not implemented + * case SCSI_CMD_MAINTENANCEIN: * 0xa3 Optional (SCCS==0) + * case SCSI_CMD_MAINTENANCEOUT: * 0xa4 Optional (SCCS==0) + * case SCSI_CMD_MOVEMEDIUM: * 0xa5 ? + * case SCSI_CMD_MOVEMEDIUMATTACHED: * 0xa7 Optional (MCHNGR==0) */ + + case SCSI_CMD_READ12: /* 0xa8 Optional */ + return usbstrg_cmdread12(priv); + break; + + case SCSI_CMD_WRITE12: /* 0xaa Optional */ + return usbstrg_cmdwrite12(priv); + break; + + /* case SCSI_CMD_READMEDIASERIALNUMBER: * 0xab Optional + * case SCSI_CMD_WRITEANDVERIFY12: * 0xae Optional + * case SCSI_CMD_VERIFY12: * 0xaf Optional + * case SCSI_CMD_SETLIMITS12 * 0xb3 Obsolete + * case SCSI_CMD_READELEMENTSTATUS: * 0xb4 Optional (MCHNGR==0) + * case SCSI_CMD_READDEFECTDATA12: * 0xb7 Optional + * case SCSI_CMD_REDUNDANCYGROUPIN: * 0xba Optional + * case SCSI_CMD_REDUNDANCYGROUPOUT: * 0xbb Optional + * case SCSI_CMD_SPAREIN: * 0xbc Optional (SCCS==0) + * case SCSI_CMD_SPAREOUT: * 0xbd Optional (SCCS==0) + * case SCSI_CMD_VOLUMESETIN: * 0xbe Optional (SCCS==0) + * case SCSI_CMD_VOLUMESETOUT: * 0xbe Optional (SCCS==0) + * * 0xc0-0xff Vendor specific */ + + default: + priv->u.alloclen = 0; + if (ret == OK) + { + priv->lun->sd = SCSI_KCQIR_INVALIDCOMMAND; + ret = -EINVAL; + } + break; + } + pthread_mutex_unlock(&priv->mutex); + + /* All commands come through this path (EXCEPT read6/10/12 and write6/10/12). + * For all other commands, the following setup is expected for the response + * based on data direction: + * + * For direction NONE: + * 1. priv->u.alloclen == 0 + * 2. priv->nreqbytes == 0 + * + * For direction = device-to-host: + * 1. priv->u.alloclen == allocation length; space set aside by the + * host to receive the device data. The size of the response + * cannot exceed this value. + * 2. response data is in the request currently at the head of + * the priv->wrreqlist queue. priv->nreqbytes is set to the length + * of data in the response. + * + * For direction host-to-device + * At present, there are no supported commands that should have host-to-device + * transfers (except write6/10/12 and that command logic does not take this + * path. The 'residue' is left at the full host-to-device data size. + * + * For all: + * ret set to <0 if an error occurred in parsing the commands. + */ + + /* For from device-to-hose operations, the residue is the expected size + * (the initial value of 'residue') minus the amount actually returned + * in the response: + */ + + if (priv->cbwdir == USBSTRG_FLAGS_DIRDEVICE2HOST) + { + /* The number of bytes in the response cannot exceed the the host + * 'allocation length' in the command. + */ + + if (priv->nreqbytes > priv->u.alloclen) + { + priv->nreqbytes = priv->u.alloclen; + } + + /* The residue is then the number of bytes that were not sent */ + + priv->residue -= priv->nreqbytes; + } + + /* On return, we need the following: + * + * 1. Setup for CMDFINISH state if appropriate + * 2. priv->thstate set to either CMDPARSE if no buffer was available or + * CMDFINISH to send the response + * 3. Return OK to continue; <0 to wait for the next event + */ + + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDPARSECMDFINISH), priv->cdb[0]); + priv->thstate = USBSTRG_STATE_CMDFINISH; + return OK; +} + +/**************************************************************************** + * Name: usbstrg_cmdreadstate + * + * Description: + * Called from the worker thread in the USBSTRG_STATE_CMDREAD state. + * The USBSTRG_STATE_CMDREAD state is entered when usbstrg_cmdparsestate + * obtains a valid SCSI read command. This state is really a continuation + * of the USBSTRG_STATE_CMDPARSE state that handles extended SCSI read + * command handling. + * + * Returned value: + * If no USBDEV write request is available or certain other errors occur, this + * function returns a negated errno and stays in the USBSTRG_STATE_CMDREAD + * state. Otherwise, when the new SCSI read command is fully processed, + * this function sets priv->thstate to USBSTRG_STATE_CMDFINISH and returns OK. + * + * State variables: + * xfrlen - holds the number of sectors read to be read. + * sector - holds the sector number of the next sector to be read + * nsectbytes - holds the number of bytes buffered for the current sector + * nreqbytes - holds the number of bytes currently buffered in the request + * at the head of the wrreqlist. + * + ****************************************************************************/ + +static int usbstrg_cmdreadstate(FAR struct usbstrg_dev_s *priv) +{ + FAR struct usbstrg_lun_s *lun = priv->lun; + FAR struct usbstrg_req_s *privreq; + FAR struct usbdev_req_s *req; + irqstate_t flags; + ssize_t nread; + ubyte *src; + ubyte *dest; + int nbytes; + int ret; + + /* Loop transferring data until either (1) all of the data has been + * transferred, or (2) we have used up all of the write requests that we have + * available. + */ + + while (priv->u.xfrlen > 0 || priv->nsectbytes > 0) + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDREAD), priv->u.xfrlen); + + /* Is the I/O buffer empty? */ + + if (priv->nsectbytes <= 0) + { + /* Yes.. read the next sector */ + + nread = USBSTRG_DRVR_READ(lun, priv->iobuffer, priv->sector, 1); + if (nread < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDREADREADFAIL), -nread); + lun->sd = SCSI_KCQME_UNRRE1; + lun->sdinfo = priv->sector; + break; + } + + priv->nsectbytes = lun->sectorsize; + priv->u.xfrlen--; + priv->sector++; + } + + /* Check if there is a request in the wrreqlist that we will be able to + * use for data transfer. + */ + + privreq = (FAR struct usbstrg_req_s *)sq_peek(&priv->wrreqlist); + + /* If there no request structures available, then just return an error. + * This will cause us to remain in the CMDREAD state. When a request is + * returned, the worker thread will be awakened in the USBSTRG_STATE_CMDREAD + * and we will be called again. + */ + + if (!privreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDREADWRRQEMPTY), 0); + priv->nreqbytes = 0; + return -ENOMEM; + } + req = privreq->req; + + /* Transfer all of the data that will (1) fit into the request buffer, OR (2) + * all of the data available in the sector buffer. + */ + + src = &priv->iobuffer[lun->sectorsize - priv->nsectbytes]; + dest = &req->buf[priv->nreqbytes]; + + nbytes = min(CONFIG_USBSTRG_BULKINREQLEN - priv->nreqbytes, priv->nsectbytes); + + /* Copy the data from the sector buffer to the USB request and update counts */ + + memcpy(dest, src, nbytes); + priv->nreqbytes += nbytes; + priv->nsectbytes -= nbytes; + + /* If (1) the request buffer is full OR (2) this is the final request full of data, + * then submit the request + */ + + if (priv->nreqbytes >= CONFIG_USBSTRG_BULKINREQLEN || + (priv->u.xfrlen <= 0 && priv->nsectbytes <= 0)) + { + /* Remove the request that we just filled from wrreqlist (we've already checked + * that is it not NULL + */ + + flags = irqsave(); + privreq = (FAR struct usbstrg_req_s *)sq_remfirst(&priv->wrreqlist); + irqrestore(flags); + + /* And submit the request to the bulk IN endpoint */ + + req->len = priv->nreqbytes; + req->private = privreq; + req->callback = usbstrg_wrcomplete; + + ret = EP_SUBMIT(priv->epbulkin, req); + if (ret != OK) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDREADSUBMIT), (uint16)-ret); + lun->sd = SCSI_KCQME_UNRRE1; + lun->sdinfo = priv->sector; + break; + } + + /* Assume success... residue should probably really be decremented in + * wrcomplete when we know that the transfer completed successfully. + */ + + priv->residue -= priv->nreqbytes; + priv->nreqbytes = 0; + } + } + + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDREADCMDFINISH), priv->u.xfrlen); + priv->thstate = USBSTRG_STATE_CMDFINISH; + return OK; +} + +/**************************************************************************** + * Name: usbstrg_cmdwritestate + * + * Description: + * Called from the worker thread in the USBSTRG_STATE_CMDWRITE state. + * The USBSTRG_STATE_CMDWRITE state is entered when usbstrg_cmdparsestate + * obtains a valid SCSI write command. This state is really a continuation + * of the USBSTRG_STATE_CMDPARSE state that handles extended SCSI write + * command handling. + * + * Returned value: + * If no USBDEV write request is available or certain other errors occur, this + * function returns a negated errno and stays in the USBSTRG_STATE_CMDWRITE + * state. Otherwise, when the new SCSI write command is fully processed, + * this function sets priv->thstate to USBSTRG_STATE_CMDFINISH and returns OK. + * + * State variables: + * xfrlen - holds the number of sectors read to be written. + * sector - holds the sector number of the next sector to write + * nsectbytes - holds the number of bytes buffered for the current sector + * nreqbytes - holds the number of untransferred bytes currently in the + * request at the head of the rdreqlist. + * + ****************************************************************************/ + +static int usbstrg_cmdwritestate(FAR struct usbstrg_dev_s *priv) +{ + FAR struct usbstrg_lun_s *lun = priv->lun; + FAR struct usbstrg_req_s *privreq; + FAR struct usbdev_req_s *req; + ssize_t nwritten; + uint16 xfrd; + ubyte *src; + ubyte *dest; + int nbytes; + int ret; + + /* Loop transferring data until either (1) all of the data has been + * transferred, or (2) we have written all of the data in the available + * read requests. + */ + + while (priv->u.xfrlen > 0) + { + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDWRITE), priv->u.xfrlen); + + /* Check if there is a request in the rdreqlist containing additional + * data to be written. + */ + + privreq = (FAR struct usbstrg_req_s *)sq_peek(&priv->rdreqlist); + + /* If there no request data available, then just return an error. + * This will cause us to remain in the CMDWRITE state. When a filled request is + * received, the worker thread will be awakened in the USBSTRG_STATE_CMDWRITE + * and we will be called again. + */ + + if (!privreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDWRITERDRQEMPTY), 0); + priv->nreqbytes = 0; + return -ENOMEM; + } + + req = privreq->req; + xfrd = req->xfrd; + priv->nreqbytes = xfrd; + + /* Now loop until all of the data in the read request has been tranferred + * to the block driver OR all of the request data has been transferred. + */ + + while (priv->nreqbytes > 0 && priv->u.xfrlen > 0) + { + /* Copy the data received in the read request into the sector I/O buffer */ + + src = &req->buf[xfrd - priv->nreqbytes]; + dest = &priv->iobuffer[priv->nsectbytes]; + + nbytes = min(lun->sectorsize - priv->nsectbytes, priv->nreqbytes); + + /* Copy the data from the sector buffer to the USB request and update counts */ + + memcpy(dest, src, nbytes); + priv->nsectbytes += nbytes; + priv->nreqbytes -= nbytes; + + /* Is the I/O buffer full? */ + + if (priv->nsectbytes >= lun->sectorsize) + { + /* Yes.. Write the next sector */ + + nwritten = USBSTRG_DRVR_WRITE(lun, priv->iobuffer, priv->sector, 1); + if (nwritten < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDWRITEWRITEFAIL), -nwritten); + lun->sd = SCSI_KCQME_WRITEFAULTAUTOREALLOCFAILED; + lun->sdinfo = priv->sector; + goto errout; + } + + priv->nsectbytes = 0; + priv->residue -= lun->sectorsize; + priv->u.xfrlen--; + priv->sector++; + } + } + + /* In either case, we are finished with this read request and can return it + * to the endpoint. Then we will go back to the top of the top and attempt + * to get the next read request. + */ + + req->len = priv->epbulkout->maxpacket; + req->private = privreq; + req->callback = usbstrg_rdcomplete; + + ret = EP_SUBMIT(priv->epbulkout, req); + if (ret != OK) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDWRITERDSUBMIT), (uint16)-ret); + } + + /* Did the host decide to stop early? */ + + if (xfrd != priv->epbulkout->maxpacket) + { + priv->shortpacket = 1; + goto errout; + } + } + +errout: + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDWRITECMDFINISH), priv->u.xfrlen); + priv->thstate = USBSTRG_STATE_CMDFINISH; + return OK; +} + +/**************************************************************************** + * Name: usbstrg_cmdfinishstate + * + * Description: + * Called from the worker thread in the USBSTRG_STATE_CMDFINISH state. + * The USBSTRG_STATE_CMDFINISH state is entered when processing of a + * command has finished but before status has been returned. + * + * Returned value: + * If no USBDEV write request is available or certain other errors occur, this + * function returns a negated errno and stays in the USBSTRG_STATE_CMDFINISH + * state. Otherwise, when the command is fully processed, this function + * sets priv->thstate to USBSTRG_STATE_CMDSTATUS and returns OK. + * + ****************************************************************************/ + +static int usbstrg_cmdfinishstate(FAR struct usbstrg_dev_s *priv) +{ + FAR struct usbstrg_req_s *privreq; + irqstate_t flags; + int ret = OK; + + /* Check if there is a request in the wrreqlist that we will be able to + * use for data transfer. + */ + + privreq = (FAR struct usbstrg_req_s *)sq_peek(&priv->wrreqlist); + + /* If there no request structures available, then just return an error. + * This will cause us to remain in the CMDREAD state. When a request is + * returned, the worker thread will be awakened in the USBSTRG_STATE_CMDREAD + * and we will be called again. + */ + + if (!privreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDFINISHRQEMPTY), 0); + return -ENOMEM; + } + + /* Finish the final stages of the reply */ + + switch (priv->cbwdir) + { + /* Device-to-host: All but the last data buffer has been sent */ + + case USBSTRG_FLAGS_DIRDEVICE2HOST: + if (priv->cbwlen > 0) + { + struct usbdev_req_s *req; + + /* Take a request from the wrreqlist (we've already checked + * that is it not NULL) + */ + + flags = irqsave(); + privreq = (FAR struct usbstrg_req_s *)sq_remfirst(&priv->wrreqlist); + irqrestore(flags); + + /* Send the write request */ + + req = privreq->req; + req->len = priv->nreqbytes; + req->callback = usbstrg_wrcomplete; + req->private = privreq; + ret = EP_SUBMIT(priv->epbulkin, privreq->req); + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDFINISHSUBMIT), (uint16)-ret); + } + + /* Stall the BULK In endpoint if there is a residue */ + + if (priv->residue > 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDFINISHRESIDUE), (uint16)priv->residue); + (void)EP_STALL(priv->epbulkin); + } + } + break; + + /* Host-to-device: We have processed all we want of the host data. */ + + case USBSTRG_FLAGS_DIRHOST2DEVICE: + if (priv->residue > 0) + { + /* Did the host stop sending unexpectedly early? */ + + flags = irqsave(); + if (priv->shortpacket) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDFINISHSHORTPKT), (uint16)priv->residue); + } + + /* Unprocessed incoming data: STALL and cancel requests. */ + + else + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDFINSHSUBMIT), (uint16)priv->residue); + EP_STALL(priv->epbulkout); + } + + priv->theventset |= USBSTRG_EVENT_ABORTBULKOUT; + irqrestore(flags); + } + break; + + default: + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDFINSHDIR), priv->cbwdir); + case USBSTRG_FLAGS_DIRNONE: /* Nothing to send */ + break; + } + + /* Return to the IDLE state */ + + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDFINISHCMDSTATUS), 0); + priv->thstate = USBSTRG_STATE_CMDSTATUS; + return OK; +} + +/**************************************************************************** + * Name: usbstrg_cmdstatusstate + * + * Description: + * Called from the worker thread in the USBSTRG_STATE_CMDSTATUS state. + * That state is after a CBW has been fully processed. This function sends + * the concluding CSW. + * + * Returned value: + * If no write request is available or certain other errors occur, this + * function returns a negated errno and stays in the USBSTRG_STATE_CMDSTATUS + * state. Otherwise, when the SCSI statis is successfully returned, this + * function sets priv->thstate to USBSTRG_STATE_IDLE and returns OK. + * + ****************************************************************************/ + +static int usbstrg_cmdstatusstate(FAR struct usbstrg_dev_s *priv) +{ + FAR struct usbstrg_lun_s *lun = priv->lun; + FAR struct usbstrg_req_s *privreq; + FAR struct usbdev_req_s *req; + FAR struct usbstrg_csw_s *csw; + irqstate_t flags; + uint32 sd; + ubyte status = USBSTRG_CSWSTATUS_PASS; + int ret; + + /* Take a request from the wrreqlist */ + + flags = irqsave(); + privreq = (FAR struct usbstrg_req_s *)sq_remfirst(&priv->wrreqlist); + irqrestore(flags); + + /* If there no request structures available, then just return an error. + * This will cause us to remain in the CMDSTATUS status. When a request is + * returned, the worker thread will be awakened in the USBSTRG_STATE_CMDSTATUS + * and we will be called again. + */ + + if (!privreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CMDSTATUSRDREQLISTEMPTY), 0); + return -ENOMEM; + } + + req = privreq->req; + csw = (struct usbstrg_csw_s*)req->buf; + + /* Extract the sense data from the LUN structure */ + + if (lun) + { + sd = lun->sd; + } + else + { + sd = SCSI_KCQIR_INVALIDLUN; + } + + /* Determine the CSW status: PASS, PHASEERROR, or FAIL */ + + if (priv->phaseerror) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SNDPHERROR), 0); + status = USBSTRG_CSWSTATUS_PHASEERROR; + sd = SCSI_KCQIR_INVALIDCOMMAND; + } + else if (sd != SCSI_KCQ_NOSENSE) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SNDCSWFAIL), 0); + status = USBSTRG_CSWSTATUS_FAIL; + } + + /* Format and submit the CSW */ + + csw->signature[0] = 'U'; + csw->signature[1] = 'S'; + csw->signature[2] = 'B'; + csw->signature[3] = 'S'; + usbstrg_putle32(csw->tag, priv->cbwtag); + usbstrg_putle32(csw->residue, priv->residue); + csw->status = status; + + usbstrg_dumpdata("SCSCI CSW", (ubyte*)csw, USBSTRG_CSW_SIZEOF); + + req->len = USBSTRG_CSW_SIZEOF; + req->callback = usbstrg_wrcomplete; + req->private = privreq; + ret = EP_SUBMIT(priv->epbulkin, req); + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SNDSTATUSSUBMIT), (uint16)-ret); + flags = irqsave(); + (void)sq_addlast((sq_entry_t*)privreq, &priv->wrreqlist); + irqrestore(flags); + } + + /* Return to the IDLE state */ + + usbtrace(TRACE_CLASSSTATE(USBSTRG_CLASSSTATE_CMDSTATUSIDLE), 0); + priv->thstate = USBSTRG_STATE_IDLE; + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_workerthread + * + * Description: + * This is the main function of the USB storage worker thread. It loops + * until USB-related events occur, then processes those events accordingly + * + ****************************************************************************/ + +void *usbstrg_workerthread(void *arg) +{ + struct usbstrg_dev_s *priv = (struct usbstrg_dev_s *)arg; + irqstate_t flags; + uint16 eventset; + int ret; + + /* This thread is started before the USB storage class is fully initialized. + * wait here until we are told to begin. Start in the NOTINITIALIZED state + */ + + pthread_mutex_lock(&priv->mutex); + priv->thstate = USBSTRG_STATE_STARTED; + while ((priv->theventset & USBSTRG_EVENT_READY) != 0 && + (priv->theventset & USBSTRG_EVENT_TERMINATEREQUEST) != 0) + { + pthread_cond_wait(&priv->cond, &priv->mutex); + } + + /* Transition to the INITIALIZED/IDLE state */ + + priv->thstate = USBSTRG_STATE_IDLE; + eventset = priv->theventset; + priv->theventset = USBSTRG_EVENT_NOEVENTS; + pthread_mutex_unlock(&priv->mutex); + + /* Then loop until we are asked to terminate */ + + while (eventset != USBSTRG_EVENT_TERMINATEREQUEST) + { + /* Wait for some interesting event. Note that we must both take the + * lock (to eliminate race conditions with other threads) and disable + * interrupts (to eliminate race conditions with USB interrupt handling. + */ + + pthread_mutex_lock(&priv->mutex); + flags = irqsave(); + if (priv->theventset == USBSTRG_EVENT_NOEVENTS) + { + pthread_cond_wait(&priv->cond, &priv->mutex); + } + + /* Sample any events before re-enabling interrupts. Any events that + * occur after re-enabling interrupts will have to be handled in the + * next time through the loop. + */ + + eventset = priv->theventset; + priv->theventset = USBSTRG_EVENT_NOEVENTS; + irqrestore(flags); + + /* Were we awakened by some event that requires immediate action? */ + + /* The USBSTRG_EVENT_DISCONNECT is signalled from the disconnect method + * after all transfers have been stopped, when the host is disconnected. + */ + + if ((eventset & USBSTRG_EVENT_DISCONNECT) != 0) + { +#warning LOGIC needed + } + + /* Called with the bulk-storage-specific USBSTRG_REQ_MSRESET EP0 setup + * received. We must stop the current operation and reinialize state. + */ + + if ((eventset & USBSTRG_EVENT_RESET) != 0) + { +#warning LOGIC needed + priv->thstate = USBSTRG_STATE_IDLE; + usbstrg_deferredresponse(priv, FALSE); + } + + /* The USBSTRG_EVENT_CFGCHANGE is signaled when the EP0 setup + * logic receives a USB_REQ_SETCONFIGURATION request + */ + + if ((eventset & USBSTRG_EVENT_CFGCHANGE) != 0) + { +#warning LOGIC needed + usbstrg_setconfig(priv, priv->thvalue); + priv->thstate = USBSTRG_STATE_IDLE; + usbstrg_deferredresponse(priv, FALSE); + } + + /* The USBSTRG_EVENT_IFCHANGE is signaled when the EP0 setup + * logic receives a USB_REQ_SETINTERFACE request + */ + if ((eventset & USBSTRG_EVENT_IFCHANGE) != 0) + { +#warning LOGIC needed + usbstrg_resetconfig(priv); + usbstrg_setconfig(priv, priv->thvalue); + priv->thstate = USBSTRG_STATE_IDLE; + usbstrg_deferredresponse(priv, FALSE); + } + + /* Set by the CMDFINISH logic when there is a residue after processing + * a host-to-device transfer. We need to discard all incoming request. + */ + + if ((eventset & USBSTRG_EVENT_ABORTBULKOUT) != 0) + { +#warning LOGIC needed + priv->thstate = USBSTRG_STATE_IDLE; + } + + /* All other events are just wakeup calls and are intended only + * drive the state maching. Remember only the terminate request event... + * we'll process that at the end of the loop. + */ + + eventset &= USBSTRG_EVENT_TERMINATEREQUEST; + + /* Loop processing each SCSI command state. Each state handling + * function will do the following: + * + * - If it must block for an event, it will return a negated errno value + * - If it completes the processing for that state, it will (1) set + * the next appropriate state value and (2) return OK. + * + * So the following will loop until we must block for an event in + * a particular state. When we are awakened by an event (above) we + * will resume processing in the same state. + */ + + for (ret = OK; ret == OK; ) + { + switch (priv->thstate) + { + case USBSTRG_STATE_IDLE: /* Started and waiting for commands */ + ret = usbstrg_idlestate(priv); + break; + + case USBSTRG_STATE_CMDPARSE: /* Parsing the received a command */ + ret = usbstrg_cmdparsestate(priv); + break; + + case USBSTRG_STATE_CMDREAD: /* Continuing to process a SCSI read command */ + ret = usbstrg_cmdreadstate(priv); + break; + + case USBSTRG_STATE_CMDWRITE: /* Continuing to process a SCSI write command */ + ret = usbstrg_cmdwritestate(priv); + break; + + case USBSTRG_STATE_CMDFINISH: /* Finish command processing */ + ret = usbstrg_cmdfinishstate(priv); + break; + + case USBSTRG_STATE_CMDSTATUS: /* Processing the status phase of a command */ + ret = usbstrg_cmdstatusstate(priv); + break; + + case USBSTRG_STATE_NOTSTARTED: /* Thread has not yet been started */ + case USBSTRG_STATE_STARTED: /* Started, but is not yet initialized */ + case USBSTRG_STATE_TERMINATED: /* Thread has exitted */ + default: + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_INVALIDSTATE), priv->thstate); + priv->thstate = USBSTRG_STATE_IDLE; + break; + } + } + } + + /* Transition to the TERMINATED state and exit */ + + priv->thstate = USBSTRG_STATE_TERMINATED; + return NULL; +} diff --git a/nuttx/drivers/usbdev/usbdev_storage.c b/nuttx/drivers/usbdev/usbdev_storage.c new file mode 100644 index 000000000..128249a88 --- /dev/null +++ b/nuttx/drivers/usbdev/usbdev_storage.c @@ -0,0 +1,1891 @@ +/**************************************************************************** + * drivers/usbdev/usbdev_storage.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Mass storage class device. Bulk-only with SCSI subclass. + * + * References: + * "Universal Serial Bus Mass Storage Class, Specification Overview," + * Revision 1.2, USB Implementer's Forum, June 23, 2003. + * + * "Universal Serial Bus Mass Storage Class, Bulk-Only Transport," + * Revision 1.0, USB Implementer's Forum, September 31, 1999. + * + * "SCSI Primary Commands - 3 (SPC-3)," American National Standard + * for Information Technology, May 4, 2005 + * + * "SCSI Primary Commands - 4 (SPC-4)," American National Standard + * for Information Technology, July 19, 2008 + * + * "SCSI Block Commands -2 (SBC-2)," American National Standard + * for Information Technology, November 13, 2004 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "usbdev_storage.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* The internal version of the class driver */ + +struct usbstrg_driver_s +{ + struct usbdevclass_driver_s drvr; + FAR struct usbstrg_dev_s *dev; +}; + +/* This is what is allocated */ + +struct usbstrg_alloc_s +{ + struct usbstrg_dev_s dev; + struct usbstrg_driver_s drvr; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Class Driver Support *****************************************************/ + +static void usbstrg_ep0incomplete(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req); +static struct usbdev_req_s *usbstrg_allocreq(FAR struct usbdev_ep_s *ep, + uint16 len); +static void usbstrg_freereq(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req); +static int usbstrg_mkstrdesc(ubyte id, struct usb_strdesc_s *strdesc); +#ifdef CONFIG_USBDEV_DUALSPEED +static sint16 usbstrg_mkcfgdesc(ubyte *buf, ubyte speed); +#else +static sint16 usbstrg_mkcfgdesc(ubyte *buf); +#endif + +/* Class Driver Operations (most at interrupt level) ************************/ + +static int usbstrg_bind(FAR struct usbdev_s *dev, + FAR struct usbdevclass_driver_s *driver); +static void usbstrg_unbind(FAR struct usbdev_s *dev); +static int usbstrg_setup(FAR struct usbdev_s *dev, + FAR const struct usb_ctrlreq_s *ctrl); +static void usbstrg_disconnect(FAR struct usbdev_s *dev); + +/* Initialization/Uninitialization ******************************************/ + +static void usbstrg_lununinitialize(struct usbstrg_lun_s *lun); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Driver operations ********************************************************/ + +static struct usbdevclass_driverops_s g_driverops = +{ + usbstrg_bind, /* bind */ + usbstrg_unbind, /* unbind */ + usbstrg_setup, /* setup */ + usbstrg_disconnect, /* disconnect */ + NULL, /* suspend */ + NULL /* resume */ +}; + +/* Descriptors **************************************************************/ + +/* Device descriptor */ + +static const struct usb_devdesc_s g_devdesc = +{ + USB_SIZEOF_DEVDESC, /* len */ + USB_DESC_TYPE_DEVICE, /* type */ + {LSBYTE(0x0200), MSBYTE(0x0200)}, /* usb */ + USB_CLASS_PER_INTERFACE, /* class */ + 0, /* subclass */ + 0, /* protocol */ + CONFIG_USBSTRG_EP0MAXPACKET, /* maxpacketsize */ + { LSBYTE(CONFIG_USBSTRG_VENDORID), /* vendor */ + MSBYTE(CONFIG_USBSTRG_VENDORID) }, + { LSBYTE(CONFIG_USBSTRG_PRODUCTID), /* product */ + MSBYTE(CONFIG_USBSTRG_PRODUCTID) }, + { LSBYTE(CONFIG_USBSTRG_VERSIONNO), /* device */ + MSBYTE(CONFIG_USBSTRG_VERSIONNO) }, + USBSTRG_MANUFACTURERSTRID, /* imfgr */ + USBSTRG_PRODUCTSTRID, /* iproduct */ + USBSTRG_SERIALSTRID, /* serno */ + USBSTRG_NCONFIGS /* nconfigs */ +}; + +/* Configuration descriptor */ + +static const struct usb_cfgdesc_s g_cfgdesc = +{ + USB_SIZEOF_CFGDESC, /* len */ + USB_DESC_TYPE_CONFIG, /* type */ + {0, 0}, /* totallen -- to be provided */ + USBSTRG_NINTERFACES, /* ninterfaces */ + USBSTRG_CONFIGID, /* cfgvalue */ + USBSTRG_CONFIGSTRID, /* icfg */ + USB_CONFIG_ATTR_ONE|SELFPOWERED|REMOTEWAKEUP, /* attr */ + (CONFIG_USBDEV_MAXPOWER + 1) / 2 /* mxpower */ +}; + +/* Single interface descriptor */ + +static const struct usb_ifdesc_s g_ifdesc = +{ + USB_SIZEOF_IFDESC, /* len */ + USB_DESC_TYPE_INTERFACE, /* type */ + 0, /* ifno */ + 0, /* alt */ + USBSTRG_NENDPOINTS, /* neps */ + USB_CLASS_MASS_STORAGE, /* class */ + SUBSTRG_SUBCLASS_SCSI, /* subclass */ + USBSTRG_PROTO_BULKONLY, /* protocol */ + USBSTRG_CONFIGSTRID /* iif */ +}; + +/* Endpoint descriptors */ + +static const struct usb_epdesc_s g_fsepbulkoutdesc = +{ + USB_SIZEOF_EPDESC, /* len */ + USB_DESC_TYPE_ENDPOINT, /* type */ + USBSTRG_EPOUTBULK_ADDR, /* addr */ + USBSTRG_EPOUTBULK_ATTR, /* attr */ + { LSBYTE(USBSTRG_FSBULKMAXPACKET), /* maxpacket */ + MSBYTE(USBSTRG_FSBULKMAXPACKET) }, + 0 /* interval */ +}; + +static const struct usb_epdesc_s g_fsepbulkindesc = +{ + USB_SIZEOF_EPDESC, /* len */ + USB_DESC_TYPE_ENDPOINT, /* type */ + USBSTRG_EPINBULK_ADDR, /* addr */ + USBSTRG_EPINBULK_ATTR, /* attr */ + { LSBYTE(USBSTRG_FSBULKMAXPACKET), /* maxpacket */ + MSBYTE(USBSTRG_FSBULKMAXPACKET) }, + 0 /* interval */ +}; + +#ifdef CONFIG_USBDEV_DUALSPEED +static const struct usb_qualdesc_s g_qualdesc = +{ + USB_SIZEOF_QUALDESC, /* len */ + USB_DESC_TYPE_DEVICEQUALIFIER, /* type */ + {LSBYTE(0x0200), MSBYTE(0x0200) }, /* USB */ + USB_CLASS_PER_INTERFACE, /* class */ + 0, /* subclass */ + 0, /* protocol */ + CONFIG_USBSTRG_EP0MAXPACKET, /* mxpacketsize */ + USBSTRG_NCONFIGS, /* nconfigs */ + 0, /* reserved */ +}; + +static const struct usb_epdesc_s g_hsepbulkoutdesc = +{ + USB_SIZEOF_EPDESC, /* len */ + USB_DESC_TYPE_ENDPOINT, /* type */ + USBSTRG_EPOUTBULK_ADDR, /* addr */ + USBSTRG_EPOUTBULK_ATTR, /* attr */ + { LSBYTE(USBSTRG_HSBULKMAXPACKET), /* maxpacket */ + MSBYTE(USBSTRG_HSBULKMAXPACKET) }, + 0 /* interval */ +}; + +static const struct usb_epdesc_s g_hsepbulkindesc = +{ + USB_SIZEOF_EPDESC, /* len */ + USB_DESC_TYPE_ENDPOINT, /* type */ + USBSTRG_EPINBULK_ADDR, /* addr */ + USBSTRG_EPINBULK_ATTR, /* attr */ + { LSBYTE(USBSTRG_HSBULKMAXPACKET), /* maxpacket */ + MSBYTE(USBSTRG_HSBULKMAXPACKET) }, + 0 /* interval */ +}; +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* String *******************************************************************/ + +const char g_vendorstr[] = CONFIG_USBSTRG_VENDORSTR; +const char g_productstr[] = CONFIG_USBSTRG_PRODUCTSTR; +const char g_serialstr[] = CONFIG_USBSTRG_SERIALSTR; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Class Driver Support + ****************************************************************************/ +/**************************************************************************** + * Name: usbstrg_ep0incomplete + * + * Description: + * Handle completion of EP0 control operations + * + ****************************************************************************/ + +static void usbstrg_ep0incomplete(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req) +{ + if (req->result || req->xfrd != req->len) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_REQRESULT), (uint16)-req->result); + } +} + +/**************************************************************************** + * Name: usbstrg_allocreq + * + * Description: + * Allocate a request instance along with its buffer + * + ****************************************************************************/ + +static struct usbdev_req_s *usbstrg_allocreq(FAR struct usbdev_ep_s *ep, uint16 len) +{ + FAR struct usbdev_req_s *req; + + req = EP_ALLOCREQ(ep); + if (req != NULL) + { + req->len = len; + req->buf = EP_ALLOCBUFFER(ep, len); + if (!req->buf) + { + EP_FREEREQ(ep, req); + req = NULL; + } + } + return req; +} + +/**************************************************************************** + * Name: usbstrg_freereq + * + * Description: + * Free a request instance along with its buffer + * + ****************************************************************************/ + +static void usbstrg_freereq(FAR struct usbdev_ep_s *ep, struct usbdev_req_s *req) +{ + if (ep != NULL && req != NULL) + { + if (req->buf != NULL) + { + EP_FREEBUFFER(ep, req->buf); + } + EP_FREEREQ(ep, req); + } +} + +/**************************************************************************** + * Name: usbstrg_mkstrdesc + * + * Description: + * Construct a string descriptor + * + ****************************************************************************/ + +static int usbstrg_mkstrdesc(ubyte id, struct usb_strdesc_s *strdesc) +{ + const char *str; + int len; + int ndata; + int i; + + switch (id) + { + case 0: + { + /* Descriptor 0 is the language id */ + + strdesc->len = 4; + strdesc->type = USB_DESC_TYPE_STRING; + strdesc->data[0] = LSBYTE(USBSTRG_STR_LANGUAGE); + strdesc->data[1] = MSBYTE(USBSTRG_STR_LANGUAGE); + return 4; + } + + case USBSTRG_MANUFACTURERSTRID: + str = g_vendorstr; + break; + + case USBSTRG_PRODUCTSTRID: + str = g_productstr; + break; + + case USBSTRG_SERIALSTRID: + str = g_serialstr; + break; + + case USBSTRG_CONFIGSTRID: + str = CONFIG_USBSTRG_CONFIGSTR; + break; + + default: + return -EINVAL; + } + + /* The string is utf16-le. The poor man's utf-8 to utf16-le + * conversion below will only handle 7-bit en-us ascii + */ + + len = strlen(str); + for (i = 0, ndata = 0; i < len; i++, ndata += 2) + { + strdesc->data[ndata] = str[i]; + strdesc->data[ndata+1] = 0; + } + + strdesc->len = ndata+2; + strdesc->type = USB_DESC_TYPE_STRING; + return strdesc->len; +} + +/**************************************************************************** + * Name: usbstrg_mkcfgdesc + * + * Description: + * Construct the configuration descriptor + * + ****************************************************************************/ + +#ifdef CONFIG_USBDEV_DUALSPEED +static sint16 usbstrg_mkcfgdesc(ubyte *buf, ubyte speed) +#else +static sint16 usbstrg_mkcfgdesc(ubyte *buf) +#endif +{ + FAR struct usb_cfgdesc_s *cfgdesc = (struct usb_cfgdesc_s*)buf; +#ifdef CONFIG_USBDEV_DUALSPEED + FAR struct usb_epdesc_s *epdesc; + boolean hispeed = (speed == USB_SPEED_HIGH); + uint16 bulkmxpacket; +#endif + uint16 totallen; + + /* This is the total length of the configuration (not necessarily the + * size that we will be sending now. + */ + + totallen = USB_SIZEOF_CFGDESC + USB_SIZEOF_IFDESC + USBSTRG_NENDPOINTS * USB_SIZEOF_EPDESC; + + /* Configuration descriptor -- Copy the canned descriptor and fill in the + * type (we'll also need to update the size below + */ + + memcpy(cfgdesc, &g_cfgdesc, USB_SIZEOF_CFGDESC); + buf += USB_SIZEOF_CFGDESC; + + /* Copy the canned interface descriptor */ + + memcpy(buf, &g_ifdesc, USB_SIZEOF_IFDESC); + buf += USB_SIZEOF_IFDESC; + + /* Make the two endpoint configurations */ + +#ifdef CONFIG_USBDEV_DUALSPEED + /* Check for switches between high and full speed */ + + hispeed = (speed == USB_SPEED_HIGH); + if (type == USB_DESC_TYPE_OTHERSPEEDCONFIG) + { + hispeed = !hispeed; + } + + bulkmxpacket = USBSTRG_BULKMAXPACKET(hispeed); + epdesc = USBSTRG_EPBULKINDESC(hispeed); + memcpy(buf, epdesc, USB_SIZEOF_EPDESC); + buf += USB_SIZEOF_EPDESC; + + epdesc = USBSTRG_EPBULKOUTDESC(hispeed); + memcpy(buf, epdesc, USB_SIZEOF_EPDESC); +#else + memcpy(buf, &g_fsepbulkoutdesc, USB_SIZEOF_EPDESC); + buf += USB_SIZEOF_EPDESC; + memcpy(buf, &g_fsepbulkindesc, USB_SIZEOF_EPDESC); +#endif + + /* Finally, fill in the total size of the configuration descriptor */ + + cfgdesc->totallen[0] = LSBYTE(totallen); + cfgdesc->totallen[1] = MSBYTE(totallen); + return totallen; +} + +/**************************************************************************** + * Class Driver Interfaces + ****************************************************************************/ +/**************************************************************************** + * Name: usbstrg_bind + * + * Description: + * Invoked when the driver is bound to a USB device driver + * + ****************************************************************************/ + +static int usbstrg_bind(FAR struct usbdev_s *dev, FAR struct usbdevclass_driver_s *driver) +{ + FAR struct usbstrg_dev_s *priv = ((struct usbstrg_driver_s*)driver)->dev; + FAR struct usbstrg_req_s *reqcontainer; + irqstate_t flags; + int ret; + int i; + + usbtrace(TRACE_CLASSBIND, 0); + + /* Bind the structures */ + + priv->usbdev = dev; + dev->ep0->private = priv; + + /* The configured EP0 size should match the reported EP0 size. We could + * easily adapt to the reported EP0 size, but then we could not use the + * const, canned descriptors. + */ + + DEBUGASSERT(CONFIG_USBSTRG_EP0MAXPACKET == dev->ep0->maxpacket); + + /* Preallocate control request */ + + priv->ctrlreq = usbstrg_allocreq(dev->ep0, USBSTRG_MXDESCLEN); + if (priv->ctrlreq == NULL) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_ALLOCCTRLREQ), 0); + ret = -ENOMEM; + goto errout; + } + priv->ctrlreq->callback = usbstrg_ep0incomplete; + + /* Pre-allocate all endpoints... the endpoints will not be functional + * until the SET CONFIGURATION request is processed in usbstrg_setconfig. + * This is done here because there may be calls to malloc and the SET + * CONFIGURATION processing probably occurrs within interrupt handling + * logic where malloc calls will fail. + */ + + /* Pre-allocate the IN bulk endpoint */ + + priv->epbulkin = DEV_ALLOCEP(dev, USBSTRG_EPINBULK_ADDR, TRUE, USB_EP_ATTR_XFER_BULK); + if (!priv->epbulkin) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EPBULKINALLOCFAIL), 0); + ret = -ENODEV; + goto errout; + } + priv->epbulkin->private = priv; + + /* Pre-allocate the OUT bulk endpoint */ + + priv->epbulkout = DEV_ALLOCEP(dev, USBSTRG_EPOUTBULK_ADDR, FALSE, USB_EP_ATTR_XFER_BULK); + if (!priv->epbulkout) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EPBULKOUTALLOCFAIL), 0); + ret = -ENODEV; + goto errout; + } + priv->epbulkout->private = priv; + + /* Pre-allocate read requests */ + + for (i = 0; i < CONFIG_USBSTRG_NRDREQS; i++) + { + reqcontainer = &priv->rdreqs[i]; + reqcontainer->req = usbstrg_allocreq(priv->epbulkout, CONFIG_USBSTRG_BULKOUTREQLEN); + if (reqcontainer->req == NULL) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_RDALLOCREQ), (uint16)-ret); + ret = -ENOMEM; + goto errout; + } + reqcontainer->req->private = reqcontainer; + reqcontainer->req->callback = usbstrg_rdcomplete; + } + + /* Pre-allocate write request containers and put in a free list */ + + for (i = 0; i < CONFIG_USBSTRG_NWRREQS; i++) + { + reqcontainer = &priv->wrreqs[i]; + reqcontainer->req = usbstrg_allocreq(priv->epbulkin, CONFIG_USBSTRG_BULKINREQLEN); + if (reqcontainer->req == NULL) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRALLOCREQ), (uint16)-ret); + ret = -ENOMEM; + goto errout; + } + reqcontainer->req->private = reqcontainer; + reqcontainer->req->callback = usbstrg_wrcomplete; + + flags = irqsave(); + sq_addlast((sq_entry_t*)reqcontainer, &priv->wrreqlist); + priv->nwrq++; /* Count of write requests available */ + irqrestore(flags); + } + + /* Report if we are selfpowered */ + +#ifdef CONFIG_USBDEV_SELFPOWERED + DEV_SETSELFPOWERED(dev); +#endif + return OK; + +errout: + usbstrg_unbind(dev); + return ret; +} + +/**************************************************************************** + * Name: usbstrg_unbind + * + * Description: + * Invoked when the driver is unbound from a USB device driver + * + ****************************************************************************/ + +static void usbstrg_unbind(FAR struct usbdev_s *dev) +{ + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_req_s *reqcontainer; + irqstate_t flags; + int i; + + usbtrace(TRACE_CLASSUNBIND, 0); + +#ifdef CONFIG_DEBUG + if (!dev || !dev->ep0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNBINDINVALIDARGS), 0); + return; + } +#endif + + /* Extract reference to private data */ + + priv = (FAR struct usbstrg_dev_s *)dev->ep0->private; + +#ifdef CONFIG_DEBUG + if (!priv) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EP0NOTBOUND1), 0); + return; + } +#endif + + /* The worker thread should have already been stopped by the + * driver un-initialize logic. + */ + + DEBUGASSERT(priv->thstate == USBSTRG_STATE_TERMINATED); + + /* Make sure that we are not already unbound */ + + if (priv != NULL) + { + /* Make sure that the endpoints have been unconfigured. If + * we were terminated gracefully, then the configuration should + * already have been reset. If not, then calling usbstrg_resetconfig + * should cause the endpoints to immediately terminate all + * transfers and return the requests to us (with result == -ESHUTDOWN) + */ + + usbstrg_resetconfig(priv); + up_mdelay(50); + + /* Free the bulk IN endpoint */ + + if (priv->epbulkin) + { + DEV_FREEEP(dev, priv->epbulkin); + priv->epbulkin = NULL; + } + + /* Free the pre-allocated control request */ + + if (priv->ctrlreq != NULL) + { + usbstrg_freereq(dev->ep0, priv->ctrlreq); + priv->ctrlreq = NULL; + } + + /* Free pre-allocated read requests (which should all have + * been returned to the free list at this time -- we don't check) + */ + + DEBUGASSERT(priv->nrdq == 0); + for (i = 0; i < CONFIG_USBSTRG_NRDREQS; i++) + { + reqcontainer = &priv->rdreqs[i]; + if (reqcontainer->req) + { + usbstrg_freereq(priv->epbulkout, reqcontainer->req); + reqcontainer->req = NULL; + } + } + + /* Free the bulk OUT endpoint */ + + if (priv->epbulkout) + { + DEV_FREEEP(dev, priv->epbulkout); + priv->epbulkout = NULL; + } + + /* Free write requests that are not in use (which should be all + * of them + */ + + flags = irqsave(); + DEBUGASSERT(priv->nwrq == CONFIG_USBSTRG_NWRREQS); + while (!sq_empty(&priv->wrreqlist)) + { + reqcontainer = (struct usbstrg_req_s *)sq_remfirst(&priv->wrreqlist); + if (reqcontainer->req != NULL) + { + usbstrg_freereq(priv->epbulkin, reqcontainer->req); + priv->nwrq--; /* Number of write requests queued */ + } + } + DEBUGASSERT(priv->nwrq == 0); + irqrestore(flags); + } +} + +/**************************************************************************** + * Name: usbstrg_setup + * + * Description: + * Invoked for ep0 control requests. This function probably executes + * in the context of an interrupt handler. + * + ****************************************************************************/ + +static int usbstrg_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s *ctrl) +{ + FAR struct usbstrg_dev_s *priv; + FAR struct usbdev_req_s *ctrlreq; + uint16 value; + uint16 index; + uint16 len; + int ret = -EOPNOTSUPP; + +#ifdef CONFIG_DEBUG + if (!dev || !dev->ep0 || !ctrl) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SETUPINVALIDARGS), 0); + return -EIO; + } +#endif + + /* Extract reference to private data */ + + usbtrace(TRACE_CLASSSETUP, ctrl->req); + priv = (FAR struct usbstrg_dev_s *)dev->ep0->private; + +#ifdef CONFIG_DEBUG + if (!priv || !priv->ctrlreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EP0NOTBOUND2), 0); + return -ENODEV; + } +#endif + ctrlreq = priv->ctrlreq; + + /* Extract the little-endian 16-bit values to host order */ + + value = GETUINT16(ctrl->value); + index = GETUINT16(ctrl->index); + len = GETUINT16(ctrl->len); + + uvdbg("type=%02x req=%02x value=%04x index=%04x len=%04x\n", + ctrl->type, ctrl->req, value, index, len); + + if ((ctrl->type & USB_REQ_TYPE_MASK) == USB_REQ_TYPE_STANDARD) + { + /********************************************************************** + * Standard Requests + **********************************************************************/ + + switch (ctrl->req) + { + case USB_REQ_GETDESCRIPTOR: + { + /* The value field specifies the descriptor type in the MS byte and the + * descriptor index in the LS byte (order is little endian) + */ + + switch (ctrl->value[1]) + { + case USB_DESC_TYPE_DEVICE: + { + ret = USB_SIZEOF_DEVDESC; + memcpy(ctrlreq->buf, &g_devdesc, ret); + } + break; + +#ifdef CONFIG_USBDEV_DUALSPEED + case USB_DESC_TYPE_DEVICEQUALIFIER: + { + ret = USB_SIZEOF_QUALDESC; + memcpy(ctrlreq->buf, &g_qualdesc, ret); + } + break; + + case USB_DESC_TYPE_OTHERSPEEDCONFIG: +#endif /* CONFIG_USBDEV_DUALSPEED */ + + case USB_DESC_TYPE_CONFIG: + { +#ifdef CONFIG_USBDEV_DUALSPEED + ret = usbstrg_mkcfgdesc(ctrlreq->buf, dev->speed, len); +#else + ret = usbstrg_mkcfgdesc(ctrlreq->buf); +#endif + } + break; + + case USB_DESC_TYPE_STRING: + { + /* index == language code. */ + + ret = usbstrg_mkstrdesc(ctrl->value[0], (struct usb_strdesc_s *)ctrlreq->buf); + } + break; + + default: + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_GETUNKNOWNDESC), value); + } + break; + } + } + break; + + case USB_REQ_SETCONFIGURATION: + { + if (ctrl->type == 0) + { + /* Signal the worker thread to instantiate the new configuration */ + + priv->theventset |= USBSTRG_EVENT_CFGCHANGE; + priv->thvalue = value; + pthread_cond_signal(&priv->cond); + + /* Return here... the response will be provided later by the + * worker thread. + */ + + return OK; + } + } + break; + + case USB_REQ_GETCONFIGURATION: + { + if (ctrl->type == USB_DIR_IN) + { + ctrlreq->buf[0] = priv->config; + ret = 1; + } + } + break; + + case USB_REQ_SETINTERFACE: + { + if (ctrl->type == USB_REQ_RECIPIENT_INTERFACE) + { + if (priv->config == USBSTRG_CONFIGID && + index == USBSTRG_INTERFACEID && + value == USBSTRG_ALTINTERFACEID) + { + /* Signal to instantiate the interface change */ + + priv->theventset |= USBSTRG_EVENT_IFCHANGE; + pthread_cond_signal(&priv->cond); + + /* Return here... the response will be provided later by the + * worker thread. + */ + + return OK; + } + } + } + break; + + case USB_REQ_GETINTERFACE: + { + if (ctrl->type == (USB_DIR_IN|USB_REQ_RECIPIENT_INTERFACE) && + priv->config == USBSTRG_CONFIGIDNONE) + { + if (index != USBSTRG_INTERFACEID) + { + ret = -EDOM; + } + else + { + ctrlreq->buf[0] = USBSTRG_ALTINTERFACEID; + ret = 1; + } + } + } + break; + + default: + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req); + break; + } + } + else + { + /********************************************************************** + * Bulk-Only Mass Storage Class Requests + **********************************************************************/ + + /* Verify that we are configured */ + + if (!priv->config) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_NOTCONFIGURED), 0); + return ret; + } + + switch (ctrl->req) + { + case USBSTRG_REQ_MSRESET: /* Reset mass storage device and interface */ + { + if (ctrl->type == USBSTRG_TYPE_SETUPOUT && value == 0 && len == 0) + { + /* Only one interface is supported */ + + if (index != USBSTRG_CONFIGID) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_MSRESETNDX), index); + ret = -EDOM; + } + else + { + /* Signal to stop the current operation and reinitialize state */ + + priv->theventset |= USBSTRG_EVENT_RESET; + pthread_cond_signal(&priv->cond); + + /* Return here... the response will be provided later by the + * worker thread. + */ + + return OK; + } + } + } + break; + + case USBSTRG_REQ_GETMAXLUN: /* Return number LUNs supported */ + { + if (ctrl->type != USBSTRG_TYPE_SETUPIN && value == 0) + { + /* Only one interface is supported */ + + if (index != USBSTRG_CONFIGID) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_GETMAXLUNNDX), index); + ret = -EDOM; + } + else + { + ctrlreq->buf[0] = priv->nluns - 1; + ret = 1; + } + } + } + break; + + default: + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_BADREQUEST), index); + break; + } + } + + /* Respond to the setup command if data was returned. On an error return + * value (ret < 0), the USB driver will stall EP0. + */ + + if (ret >= 0) + { + ctrlreq->len = min(len, ret); + ret = EP_SUBMIT(dev->ep0, ctrlreq); + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EPRESPQ), (uint16)-ret); +#if 0 /* Not necessary */ + ctrlreq->result = OK; + usbstrg_ep0incomplete(dev->ep0, ctrlreq); +#endif + } + } + + return ret; +} + +/**************************************************************************** + * Name: usbstrg_disconnect + * + * Description: + * Invoked after all transfers have been stopped, when the host is + * disconnected. This function is probably called from the context of an + * interrupt handler. + * + ****************************************************************************/ + +static void usbstrg_disconnect(FAR struct usbdev_s *dev) +{ + struct usbstrg_dev_s *priv; + irqstate_t flags; + + usbtrace(TRACE_CLASSDISCONNECT, 0); + +#ifdef CONFIG_DEBUG + if (!dev || !dev->ep0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_DISCONNECTINVALIDARGS), 0); + return; + } +#endif + + /* Extract reference to private data */ + + priv = (FAR struct usbstrg_dev_s *)dev->ep0->private; + +#ifdef CONFIG_DEBUG + if (!priv) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EP0NOTBOUND3), 0); + return; + } +#endif + + /* Reset the configuration */ + + flags = irqsave(); + usbstrg_resetconfig(priv); + + /* Signal the worker thread */ + + priv->theventset |= USBSTRG_EVENT_DISCONNECT; + pthread_cond_signal(&priv->cond); + irqrestore(flags); +} + +/**************************************************************************** + * Initialization/Un-Initialization + ****************************************************************************/ +/**************************************************************************** + * Name: usbstrg_lununinitialize + ****************************************************************************/ + +static void usbstrg_lununinitialize(struct usbstrg_lun_s *lun) +{ + /* Has a block driver has been bound to the LUN? */ + + if (lun->inode) + { + /* Close the block driver */ + + (void)close_blockdriver(lun->inode); + } + + memset(lun, 0, sizeof(struct usbstrg_lun_s *)); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Internal Interfaces + ****************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_setconfig + * + * Description: + * Set the device configuration by allocating and configuring endpoints and + * by allocating and queue read and write requests. + * + ****************************************************************************/ + +int usbstrg_setconfig(FAR struct usbstrg_dev_s *priv, ubyte config) +{ + FAR struct usbstrg_req_s *privreq; + FAR struct usbdev_req_s *req; +#ifdef CONFIG_USBDEV_DUALSPEED + struct usb_epdesc_s *epdesc; + uint16 bulkmxpacket; +#endif + int i; + int ret = 0; + +#if CONFIG_DEBUG + if (priv == NULL) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_SETCONFIGINVALIDARGS), 0); + return -EIO; + } +#endif + + if (config == priv->config) + { + /* Already configured -- Do nothing */ + + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_ALREADYCONFIGURED), 0); + return 0; + } + + /* Discard the previous configuration data */ + + usbstrg_resetconfig(priv); + + /* Was this a request to simply discard the current configuration? */ + + if (config == USBSTRG_CONFIGIDNONE) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CONFIGNONE), 0); + return 0; + } + + /* We only accept one configuration */ + + if (config != USBSTRG_CONFIGID) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_CONFIGIDBAD), 0); + return -EINVAL; + } + + /* Configure the IN bulk endpoint */ + +#ifdef CONFIG_USBDEV_DUALSPEED + bulkmxpacket = USBSTRG_BULKMAXPACKET(hispeed); + epdesc = USBSTRG_EPBULKINDESC(hispeed); + ret = EP_CONFIGURE(priv->epbulkin, epdesc, FALSE); +#else + ret = EP_CONFIGURE(priv->epbulkin, &g_fsepbulkindesc, FALSE); +#endif + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EPBULKINCONFIGFAIL), 0); + goto errout; + } + + priv->epbulkin->private = priv; + + /* Configure the OUT bulk endpoint */ + +#ifdef CONFIG_USBDEV_DUALSPEED + epdesc = USBSTRG_EPBULKINDESC(hispeed); + ret = EP_CONFIGURE(priv->epbulkout, epdesc, TRUE); +#else + ret = EP_CONFIGURE(priv->epbulkout, &g_fsepbulkoutdesc, TRUE); +#endif + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EPBULKOUTCONFIGFAIL), 0); + goto errout; + } + + priv->epbulkout->private = priv; + + /* Queue read requests in the bulk OUT endpoint */ + + DEBUGASSERT(priv->nrdq == 0); + for (i = 0; i < CONFIG_USBSTRG_NRDREQS; i++) + { + privreq = &priv->rdreqs[i]; + req = privreq->req; + req->len = CONFIG_USBSTRG_BULKOUTREQLEN; + req->private = privreq; + req->callback = usbstrg_rdcomplete; + ret = EP_SUBMIT(priv->epbulkout, req); + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_RDSUBMIT), (uint16)-ret); + goto errout; + } + priv->nrdq++; + } + + priv->config = config; + return OK; + +errout: + usbstrg_resetconfig(priv); + return ret; +} + +/**************************************************************************** + * Name: usbstrg_resetconfig + * + * Description: + * Mark the device as not configured and disable all endpoints. + * + ****************************************************************************/ + +void usbstrg_resetconfig(FAR struct usbstrg_dev_s *priv) +{ + /* Are we configured? */ + + if (priv->config != USBSTRG_CONFIGIDNONE) + { + /* Yes.. but not anymore */ + + priv->config = USBSTRG_CONFIGIDNONE; + + /* Disable endpoints. This should force completion of all pending + * transfers. + */ + + EP_DISABLE(priv->epbulkin); + EP_DISABLE(priv->epbulkout); + } +} + +/**************************************************************************** + * Name: usbstrg_wrcomplete + * + * Description: + * Handle completion of write request. This function probably executes + * in the context of an interrupt handler. + * + ****************************************************************************/ + +void usbstrg_wrcomplete(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) +{ + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_req_s *privreq; + irqstate_t flags; + + /* Sanity check */ + +#ifdef CONFIG_DEBUG + if (!ep || !ep->private || !req || !req->private) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRCOMPLETEINVALIDARGS), 0); + return; + } +#endif + + /* Extract references to private data */ + + priv = (FAR struct usbstrg_dev_s*)ep->private; + privreq = (FAR struct usbstrg_req_s *)req->private; + + /* Return the write request to the free list */ + + flags = irqsave(); + sq_addlast((sq_entry_t*)privreq, &priv->wrreqlist); + priv->nwrq++; + irqrestore(flags); + + /* Process the received data unless this is some unusual condition */ + + switch (req->result) + { + case OK: /* Normal completion */ + usbtrace(TRACE_CLASSWRCOMPLETE, priv->nwrq); + break; + + case -ESHUTDOWN: /* Disconnection */ + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRSHUTDOWN), 0); + break; + + default: /* Some other error occurred */ + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_WRUNEXPECTED), (uint16)-req->result); + break; + }; + + /* Inform the worker thread that a write request has been returned */ + + priv->theventset |= USBSTRG_EVENT_WRCOMPLETE; + pthread_cond_signal(&priv->cond); +} + +/**************************************************************************** + * Name: usbstrg_rdcomplete + * + * Description: + * Handle completion of read request on the bulk OUT endpoint. This + * is handled like the receipt of serial data on the "UART" + * + ****************************************************************************/ + +void usbstrg_rdcomplete(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) +{ + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_req_s *privreq; + irqstate_t flags; + int ret; + + /* Sanity check */ + +#ifdef CONFIG_DEBUG + if (!ep || !ep->private || !req || !req->private) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_RDCOMPLETEINVALIDARGS), 0); + return; + } +#endif + + /* Extract references to private data */ + + priv = (FAR struct usbstrg_dev_s*)ep->private; + privreq = (FAR struct usbstrg_req_s *)req->private; + + /* Process the received data unless this is some unusual condition */ + + switch (req->result) + { + case 0: /* Normal completion */ + { + usbtrace(TRACE_CLASSRDCOMPLETE, priv->nrdq); + + /* Add the filled read request from the rdreqlist */ + + flags = irqsave(); + sq_addlast((sq_entry_t*)privreq, &priv->rdreqlist); + irqrestore(flags); + + /* Signal the worker thread that there is received data to be processed */ + + priv->theventset |= USBSTRG_EVENT_RDCOMPLETE; + pthread_cond_signal(&priv->cond); + } + break; + + case -ESHUTDOWN: /* Disconnection */ + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_RDSHUTDOWN), 0); + + /* Drop the read request... it will be cleaned up later */ + } + break; + + default: /* Some other error occurred */ + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_RDUNEXPECTED), (uint16)-req->result); + + /* Return the read request to the bulk out endpoint for re-filling */ + + req = privreq->req; + req->private = privreq; + req->callback = usbstrg_rdcomplete; + + ret = EP_SUBMIT(priv->epbulkout, req); + if (ret != OK) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_RDCOMPLETERDSUBMIT), (uint16)-ret); + } + } + break; + } +} + +/**************************************************************************** + * Name: usbstrg_deferredresponse + * + * Description: + * Some EP0 setup request cannot be responded to immediately becuase they + * require some asynchronous action from the SCSI worker thread. This + * function is provided for the SCSI thread to make that deferred response. + * The specific requests that require this deferred response are: + * + * 1. USB_REQ_SETCONFIGURATION, + * 2. USB_REQ_SETINTERFACE, or + * 3. USBSTRG_REQ_MSRESET + * + * In all cases, the success reponse is a zero-length packet; the failure + * response is an EP0 stall. + * + * Input parameters: + * priv - Private state structure for this USB storage instance + * stall - TRUE is the action failed and a stall is required + * + ****************************************************************************/ + +void usbstrg_deferredresponse(FAR struct usbstrg_dev_s *priv, boolean failed) +{ + FAR struct usbdev_s *dev; + FAR struct usbdev_req_s *ctrlreq; + int ret; + +#ifdef CONFIG_DEBUG + if (!priv || !priv->usbdev || !priv->ctrlreq) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_DEFERREDRESPINVALIDARGS), 0); + return; + } +#endif + + dev = priv->usbdev; + ctrlreq = priv->ctrlreq; + + /* If no error occurs, response to the deferred setup command with a null + * packet. + */ + + if (!failed) + { + ctrlreq->len = 0; + ret = EP_SUBMIT(dev->ep0, ctrlreq); + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_DEFERREDRESPSUBMIT), (uint16)-ret); +#if 0 /* Not necessary */ + ctrlreq->result = OK; + usbstrg_ep0incomplete(dev->ep0, ctrlreq); +#endif + } + } + else + { + /* On a failure, the USB driver will stall. */ + + usbtrace(TRACE_DEVERROR(USBSTRG_TRACEERR_DEFERREDRESPSTALLED), 0); + EP_STALL(dev->ep0); + } +} + +/**************************************************************************** + * User Interfaces + ****************************************************************************/ +/**************************************************************************** + * Name: usbstrg_configure + * + * Description: + * One-time initialization of the USB storage driver. The initialization + * sequence is as follows: + * + * 1. Call usbstrg_configure to perform one-time initialization specifying + * the number of luns. + * 2. Call usbstrg_bindlun to configure each supported LUN + * 3. Call usbstrg_exportluns when all LUNs are configured + * + * Input Parameters: + * nluns - the number of LUNs that will be registered + * handle - Location to return a handle that is used in other API calls. + * + * Returned Value: + * 0 on success; a negated errno on failure + * + ****************************************************************************/ + +int usbstrg_configure(unsigned int nluns, void **handle) +{ + FAR struct usbstrg_alloc_s *alloc; + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_driver_s *drvr; + int ret; + +#ifdef CONFIG_DEBUG + if (nluns > 15) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_TOOMANYLUNS), 0); + return -EDOM; + } +#endif + + /* Allocate the structures needed */ + + alloc = (FAR struct usbstrg_alloc_s*)malloc(sizeof(struct usbstrg_alloc_s)); + if (!alloc) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_ALLOCDEVSTRUCT), 0); + return -ENOMEM; + } + + /* Initialize the USB storage driver structure */ + + priv = &alloc->dev; + memset(priv, 0, sizeof(struct usbstrg_dev_s)); + + pthread_mutex_init(&priv->mutex, NULL); + pthread_cond_init(&priv->cond, NULL); + sq_init(&priv->wrreqlist); + + priv->nluns = nluns; + + /* Allocate the LUN table */ + + priv->luntab = (struct usbstrg_lun_s*)malloc(priv->nluns*sizeof(struct usbstrg_lun_s)); + if (!priv->luntab) + { + ret = -ENOMEM; + goto errout; + } + memset(priv->luntab, 0, priv->nluns * sizeof(struct usbstrg_lun_s)); + + /* Initialize the USB class driver structure */ + + drvr = &alloc->drvr; +#ifdef CONFIG_USBDEV_DUALSPEED + drvr->drvr.speed = USB_SPEED_HIGH; +#else + drvr->drvr.speed = USB_SPEED_FULL; +#endif + drvr->drvr.ops = &g_driverops; + drvr->dev = priv; + + /* Return the handle and success */ + + *handle = (FAR void*)alloc; + return OK; + +errout: + usbstrg_uninitialize(alloc); + return ret; +} + +/**************************************************************************** + * Name: usbstrg_bindlun + * + * Description: + * Bind the block driver specified by drvrpath to a USB storage LUN. + * + * Input Parameters: + * handle - The handle returned by a previous call to usbstrg_configure(). + * drvrpath - the full path to the block driver + * startsector - A sector offset into the block driver to the start of the + * partition on drvrpath (0 if no partitions) + * nsectors - The number of sectors in the partition (if 0, all sectors + * to the end of the media will be exported). + * lunno - the LUN to bind to + * + * Returned Value: + * 0 on success; a negated errno on failure. + * + ****************************************************************************/ + +int usbstrg_bindlun(FAR void *handle, FAR const char *drvrpath, + unsigned int lunno, off_t startsector, size_t nsectors, + boolean readonly) +{ + FAR struct usbstrg_alloc_s *alloc = (FAR struct usbstrg_alloc_s *)handle; + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_lun_s *lun; + FAR struct inode *inode; + struct geometry geo; + int ret; + +#ifdef CONFIG_DEBUG + if (!alloc || !drvrpath || startsector < 0 || nsectors < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_BINLUNINVALIDARGS1), 0); + return -EINVAL; + } +#endif + + priv = &alloc->dev; + +#ifdef CONFIG_DEBUG + if (!priv->luntab) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_INTERNALCONFUSION1), 0); + return -EIO; + } + + if (lunno > priv->nluns) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_BINDLUNINVALIDARGS2), 0); + return -EINVAL; + } +#endif + + lun = &priv->luntab[lunno]; + +#ifdef CONFIG_DEBUG + if (lun->inode != NULL) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_LUNALREADYBOUND), 0); + return -EBUSY; + } +#endif + + /* Open the block driver */ + + ret = open_blockdriver(drvrpath, 0, &inode); + if (ret < 0) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_BLKDRVEOPEN), 0); + return ret; + } + + /* Get the drive geometry */ + + if (!inode || !inode->u.i_bops || !inode->u.i_bops->geometry || + inode->u.i_bops->geometry(inode, &geo) != OK || !geo.geo_available) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_NOGEOMETRY), 0); + return -ENODEV; + } + + /* Verify that the partition parameters are valid */ + + if (startsector >= geo.geo_nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_BINDLUNINVALIDARGS3), 0); + return -EDOM; + } + else if (nsectors == 0) + { + nsectors = geo.geo_nsectors - startsector; + } + else if (startsector + nsectors >= geo.geo_nsectors) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_BINDLUNINVALIDARGS4), 0); + return -EDOM; + } + + /* Initialize the LUN structure */ + + memset(lun, 0, sizeof(struct usbstrg_lun_s *)); + + /* Allocate an I/O buffer big enough to hold one hardware sector. SCSI commands + * are processed one at a time so all LUNs may share a single I/O buffer. The + * I/O buffer will be allocated so that is it as large as the largest block + * device sector size + */ + + if (!priv->iobuffer) + { + priv->iobuffer = (ubyte*)malloc(geo.geo_sectorsize); + if (!priv->iobuffer) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_ALLOCIOBUFFER), geo.geo_sectorsize); + return -ENOMEM; + } + priv->iosize = geo.geo_sectorsize; + } + else if (priv->iosize < geo.geo_sectorsize) + { + void *tmp; + tmp = (ubyte*)realloc(priv->iobuffer, geo.geo_sectorsize); + if (!tmp) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_REALLOCIOBUFFER), geo.geo_sectorsize); + return -ENOMEM; + } + + priv->iobuffer = (ubyte*)tmp; + priv->iosize = geo.geo_sectorsize; + } + + lun->inode = inode; + lun->startsector = startsector; + lun->nsectors = nsectors; + lun->sectorsize = geo.geo_sectorsize; + + /* If the driver does not support the write method, then this is read-only */ + + if (!inode->u.i_bops->write) + { + lun->readonly = TRUE; + } + return OK; +} + +/**************************************************************************** + * Name: usbstrg_unbindlun + * + * Description: + * Un-bind the block driver for the specified LUN + * + * Input Parameters: + * handle - The handle returned by a previous call to usbstrg_configure(). + * lun - the LUN to unbind from + * + * Returned Value: + * 0 on success; a negated errno on failure. + * + ****************************************************************************/ + +int usbstrg_unbindlun(FAR void *handle, unsigned int lunno) +{ + FAR struct usbstrg_alloc_s *alloc = (FAR struct usbstrg_alloc_s *)handle; + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_lun_s *lun; + int ret; + +#ifdef CONFIG_DEBUG + if (!alloc) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNBINDLUNINVALIDARGS1), 0); + return -EINVAL; + } +#endif + + priv = &alloc->dev; + +#ifdef CONFIG_DEBUG + if (!priv->luntab) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_INTERNALCONFUSION2), 0); + return -EIO; + } + + if (lunno > priv->nluns) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNBINDLUNINVALIDARGS2), 0); + return -EINVAL; + } +#endif + + lun = &priv->luntab[lunno]; + pthread_mutex_lock(&priv->mutex); + +#ifdef CONFIG_DEBUG + if (lun->inode == NULL) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_LUNNOTBOUND), 0); + pthread_mutex_lock(&priv->mutex); + ret = -EBUSY; + } + else +#endif + { + /* Close the block driver */ + + usbstrg_lununinitialize(lun); + ret = OK; + } + + pthread_mutex_unlock(&priv->mutex); + return ret; +} + +/**************************************************************************** + * Name: usbstrg_exportluns + * + * Description: + * After all of the LUNs have been bound, this function may be called + * in order to export those LUNs in the USB storage device. + * + * Input Parameters: + * handle - The handle returned by a previous call to usbstrg_configure(). + * + * Returned Value: + * 0 on success; a negated errno on failure + * + ****************************************************************************/ + +int usbstrg_exportluns(FAR void *handle) +{ + FAR struct usbstrg_alloc_s *alloc = (FAR struct usbstrg_alloc_s *)handle; + FAR struct usbstrg_dev_s *priv; + FAR struct usbstrg_driver_s *drvr; + irqstate_t flags; +#ifdef SDCC + pthread_attr_t attr; +#endif + int ret; + +#ifdef CONFIG_DEBUG + if (!alloc) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_EXPORTLUNSINVALIDARGS), 0); + return -ENXIO; + } +#endif + + priv = &alloc->dev; + drvr = &alloc->drvr; + + /* Start the worker thread */ + + pthread_mutex_lock(&priv->mutex); + priv->thstate = USBSTRG_STATE_NOTSTARTED; + priv->theventset = USBSTRG_EVENT_NOEVENTS; + +#ifdef SDCC + (void)pthread_attr_init(&attr); + ret = pthread_create(&priv->thread, &attr, usbstrg_workerthread, (pthread_addr_t)priv); +#else + ret = pthread_create(&priv->thread, NULL, usbstrg_workerthread, (pthread_addr_t)priv); +#endif + if (ret != OK) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_THREADCREATE), (uint16)-ret); + goto errout_with_mutex; + } + + /* Register the USB storage class driver */ + + ret = usbdev_register(&drvr->drvr); + if (ret != OK) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_DEVREGISTER), (uint16)-ret); + goto errout_with_mutex; + } + + /* Signal to start the thread */ + + flags = irqsave(); + priv->theventset |= USBSTRG_EVENT_READY; + pthread_cond_signal(&priv->cond); + irqrestore(flags); + +errout_with_mutex: + pthread_mutex_unlock(&priv->mutex); + return ret; +} + +/**************************************************************************** + * Name: usbstrg_uninitialize + * + * Description: + * Un-initialize the USB storage class driver + * + * Input Parameters: + * handle - The handle returned by a previous call to usbstrg_configure(). + * + * Returned Value: + * None + * + ****************************************************************************/ + +void usbstrg_uninitialize(FAR void *handle) +{ + FAR struct usbstrg_alloc_s *alloc = (FAR struct usbstrg_alloc_s *)handle; + FAR struct usbstrg_dev_s *priv; + irqstate_t flags; +#ifdef SDCC + pthread_addr_t result1, result2; + pthread_attr_t attr; +#endif + void *value; + int ret; + int i; + +#ifdef CONFIG_DEBUG + if (!handle) + { + usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_UNINITIALIZEINVALIDARGS), 0); + return; + } +#endif + priv = &alloc->dev; + + /* If the thread hasn't already exitted, tell it to exit now */ + + if (priv->thstate != USBSTRG_STATE_NOTSTARTED) + { + /* The thread was started.. Is it still running? */ + + pthread_mutex_lock(&priv->mutex); + if (priv->thstate != USBSTRG_STATE_TERMINATED) + { + /* Yes.. Ask the thread to stop */ + + flags = irqsave(); + priv->theventset |= USBSTRG_EVENT_TERMINATEREQUEST; + pthread_cond_signal(&priv->cond); + irqrestore(flags); + } + pthread_mutex_unlock(&priv->mutex); + + /* Wait for the thread to exit. This is necessary even if the + * thread has already exitted in order to collect the join + * garbage + */ + + ret = pthread_join(priv->thread, &value); + } + priv->thread = 0; + + /* Unregister the driver */ + + usbdev_unregister(&alloc->drvr.drvr); + + /* Uninitialize and release the LUNs */ + + for (i = 0; i < priv->nluns; ++i) + { + usbstrg_lununinitialize(&priv->luntab[i]); + } + free(priv->luntab); + + /* Release the I/O buffer */ + + if (priv->iobuffer) + { + free(priv->iobuffer); + } + + /* Uninitialize and release the driver structure */ + + pthread_mutex_destroy(&priv->mutex); + pthread_cond_destroy(&priv->cond); + + free(priv); +} diff --git a/nuttx/drivers/usbdev/usbdev_storage.h b/nuttx/drivers/usbdev/usbdev_storage.h new file mode 100644 index 000000000..9f42d1567 --- /dev/null +++ b/nuttx/drivers/usbdev/usbdev_storage.h @@ -0,0 +1,538 @@ +/**************************************************************************** + * drivers/usbdev/usbdev_storage.h + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Mass storage class device. Bulk-only with SCSI subclass. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __DRIVERS_USBDEV_USBDEV_STORAGE_H +#define __DRIVERS_USBDEV_USBDEV_STORAGE_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Number of requests in the write queue */ + +#ifndef CONFIG_USBSTRG_NWRREQS +# define CONFIG_USBSTRG_NWRREQS 4 +#endif + +/* Number of requests in the read queue */ + +#ifndef CONFIG_USBSTRG_NRDREQS +# define CONFIG_USBSTRG_NRDREQS 4 +#endif + +/* Logical endpoint numbers / max packet sizes */ + +#ifndef CONFIG_USBSTRG_EPBULKOUT +# warning "EPBULKOUT not defined in the configuration" +# define CONFIG_USBSTRG_EPBULKOUT 2 +#endif + +#ifndef CONFIG_USBSTRG_EPBULKIN +# warning "EPBULKIN not defined in the configuration" +# define CONFIG_USBSTRG_EPBULKIN 3 +#endif + +/* Packet and request buffer sizes */ + +#ifndef CONFIG_USBSTRG_EP0MAXPACKET +# define CONFIG_USBSTRG_EP0MAXPACKET 64 +#endif + +#ifndef CONFIG_USBSTRG_BULKINREQLEN +# ifdef CONFIG_USBDEV_DUALSPEED +# define CONFIG_USBSTRG_BULKINREQLEN 512 +# else +# define CONFIG_USBSTRG_BULKINREQLEN 64 +# endif +#else +# ifdef CONFIG_USBDEV_DUALSPEED +# if CONFIG_USBSTRG_BULKINREQLEN < 512 +# warning "Bulk in buffer size smaller than max packet" +# undef CONFIG_USBSTRG_BULKINREQLEN +# define CONFIG_USBSTRG_BULKINREQLEN 512 +# endif +# else +# if CONFIG_USBSTRG_BULKINREQLEN < 64 +# warning "Bulk in buffer size smaller than max packet" +# undef CONFIG_USBSTRG_BULKINREQLEN +# define CONFIG_USBSTRG_BULKINREQLEN 64 +# endif +# endif +#endif + +#ifndef CONFIG_USBSTRG_BULKOUTREQLEN +# ifdef CONFIG_USBDEV_DUALSPEED +# define CONFIG_USBSTRG_BULKOUTREQLEN 512 +# else +# define CONFIG_USBSTRG_BULKOUTREQLEN 64 +# endif +#else +# ifdef CONFIG_USBDEV_DUALSPEED +# if CONFIG_USBSTRG_BULKOUTREQLEN < 512 +# warning "Bulk in buffer size smaller than max packet" +# undef CONFIG_USBSTRG_BULKOUTREQLEN +# define CONFIG_USBSTRG_BULKOUTREQLEN 512 +# endif +# else +# if CONFIG_USBSTRG_BULKOUTREQLEN < 64 +# warning "Bulk in buffer size smaller than max packet" +# undef CONFIG_USBSTRG_BULKOUTREQLEN +# define CONFIG_USBSTRG_BULKOUTREQLEN 64 +# endif +# endif +#endif + +/* Vendor and product IDs and strings */ + +#ifndef CONFIG_USBSTRG_VENDORID +# warning "CONFIG_USBSTRG_VENDORID not defined" +# define CONFIG_USBSTRG_VENDORID 0x584e +#endif + +#ifndef CONFIG_USBSTRG_PRODUCTID +# warning "CONFIG_USBSTRG_PRODUCTID not defined" +# define CONFIG_USBSTRG_PRODUCTID 0x5342 +#endif + +#ifndef CONFIG_USBSTRG_VERSIONNO +# define CONFIG_USBSTRG_VERSIONNO (0x0399) +#endif + +#ifndef CONFIG_USBSTRG_VENDORSTR +# warning "No Vendor string specified" +# define CONFIG_USBSTRG_VENDORSTR "NuttX" +#endif + +#ifndef CONFIG_USBSTRG_PRODUCTSTR +# warning "No Product string specified" +# define CONFIG_USBSTRG_PRODUCTSTR "USBdev Storage" +#endif + +#undef CONFIG_USBSTRG_SERIALSTR +#define CONFIG_USBSTRG_SERIALSTR "0101" + +#undef CONFIG_USBSTRG_CONFIGSTR +#define CONFIG_USBSTRG_CONFIGSTR "Bulk" + +/* Debug -- must be consistent with include/debug.h */ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# ifdef CONFIG_ARCH_LOWPUTC +# define dbgprintf(format, arg...) lib_lowprintf(format, ##arg) +# else +# define dbgprintf(format, arg...) lib_rawprintf(format, ##arg) +# endif +# else +# define dbgprintf(x...) +# endif +#else +# ifdef CONFIG_DEBUG +# ifdef CONFIG_ARCH_LOWPUTC +# define dbgprintf lib_lowprintf +# else +# define dbgprintf lib_rawprintf +# endif +# else +# define dbgprintf (void) +# endif +#endif + +/* Packet and request buffer sizes */ + +#ifndef CONFIG_USBSTRG_EP0MAXPACKET +# define CONFIG_USBSTRG_EP0MAXPACKET 64 +#endif + +/* USB Controller */ + +#ifndef CONFIG_USBDEV_SELFPOWERED +# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER +#else +# define SELFPOWERED (0) +#endif + +#ifndef CONFIG_USBDEV_REMOTEWAKEUP +# define REMOTEWAKEUP USB_CONFIG_ATTR_WAKEUP +#else +# define REMOTEWAKEUP (0) +#endif + +#ifndef CONFIG_USBDEV_MAXPOWER +# define CONFIG_USBDEV_MAXPOWER 100 +#endif + +/* Current state of the worker thread */ + +#define USBSTRG_STATE_NOTSTARTED (0) /* Thread has not yet been started */ +#define USBSTRG_STATE_STARTED (1) /* Started, but is not yet initialized */ +#define USBSTRG_STATE_IDLE (2) /* Started and waiting for commands */ +#define USBSTRG_STATE_CMDPARSE (3) /* Processing a received command */ +#define USBSTRG_STATE_CMDREAD (4) /* Processing a SCSI read command */ +#define USBSTRG_STATE_CMDWRITE (5) /* Processing a SCSI write command */ +#define USBSTRG_STATE_CMDFINISH (6) /* Finish command processing */ +#define USBSTRG_STATE_CMDSTATUS (7) /* Processing the final status of the command */ +#define USBSTRG_STATE_TERMINATED (8) /* Thread has exitted */ + +/* Event communicated to worker thread */ + +#define USBSTRG_EVENT_NOEVENTS (0) /* There are no outstanding events */ +#define USBSTRG_EVENT_READY (1 << 0) /* Initialization is complete */ +#define USBSTRG_EVENT_RDCOMPLETE (1 << 1) /* A read has completed there is data to be processed */ +#define USBSTRG_EVENT_WRCOMPLETE (1 << 2) /* A write has completed and a request is available */ +#define USBSTRG_EVENT_TERMINATEREQUEST (1 << 3) /* Shutdown requested */ +#define USBSTRG_EVENT_DISCONNECT (1 << 4) /* USB disconnect received */ +#define USBSTRG_EVENT_RESET (1 << 5) /* USB storage setup reset received */ +#define USBSTRG_EVENT_CFGCHANGE (1 << 6) /* USB setup configuration change received */ +#define USBSTRG_EVENT_IFCHANGE (1 << 7) /* USB setup interface change received */ +#define USBSTRG_EVENT_ABORTBULKOUT (1 << 8) /* SCSI receive failure */ + +/* SCSI command flags (passed to usbstrg_setupcmd()) */ + +#define USBSTRG_FLAGS_DIRMASK (0x03) /* Bits 0-1: Data direction */ +#define USBSTRG_FLAGS_DIRNONE (0x00) /* No data to send */ +#define USBSTRG_FLAGS_DIRHOST2DEVICE (0x01) /* Host-to-device */ +#define USBSTRG_FLAGS_DIRDEVICE2HOST (0x02) /* Device-to-host */ +#define USBSTRG_FLAGS_BLOCKXFR (0x04) /* Bit 2: Command is a block transfer request */ +#define USBSTRG_FLAGS_LUNNOTNEEDED (0x08) /* Bit 3: Command does not require a valid LUN */ +#define USBSTRG_FLAGS_UACOKAY (0x10) /* Bit 4: Command OK if unit attention condition */ +#define USBSTRG_FLAGS_RETAINSENSEDATA (0x20) /* Bit 5: Do not clear sense data */ + +/* Descriptors **************************************************************/ + +/* Big enough to hold our biggest descriptor */ + +#define USBSTRG_MXDESCLEN (64) + +/* String language */ + +#define USBSTRG_STR_LANGUAGE (0x0409) /* en-us */ + +/* Descriptor strings */ + +#define USBSTRG_MANUFACTURERSTRID (1) +#define USBSTRG_PRODUCTSTRID (2) +#define USBSTRG_SERIALSTRID (3) +#define USBSTRG_CONFIGSTRID (4) +#define USBSTRG_NCONFIGS (1) /* Number of configurations supported */ + +/* Configuration Descriptor */ + +#define USBSTRG_NINTERFACES (1) /* Number of interfaces in the configuration */ +#define USBSTRG_INTERFACEID (0) +#define USBSTRG_ALTINTERFACEID (0) +#define USBSTRG_CONFIGIDNONE (0) /* Config ID means to return to address mode */ +#define USBSTRG_CONFIGID (1) /* The only supported configuration ID */ + +#define STRING_MANUFACTURER (1) +#define STRING_PRODUCT (2) +#define STRING_SERIAL (3) + +#define USBSTRG_CONFIGID (1) /* There is only one configuration. */ + +/* Interface description */ + +#define USBSTRG_NENDPOINTS (2) /* Number of endpoints in the interface */ + +/* Endpoint configuration */ + +#define USBSTRG_EPOUTBULK_ADDR (CONFIG_USBSTRG_EPBULKOUT) +#define USBSTRG_EPOUTBULK_ATTR (USB_EP_ATTR_XFER_BULK) + +#define USBSTRG_EPINBULK_ADDR (USB_DIR_IN|CONFIG_USBSTRG_EPBULKIN) +#define USBSTRG_EPINBULK_ATTR (USB_EP_ATTR_XFER_BULK) + +#define USBSTRG_HSBULKMAXPACKET (512) +#define USBSTRG_HSBULKMXPKTSHIFT (9) +#define USBSTRG_HSBULKMXPKTMASK (0x000001ff) +#define USBSTRG_FSBULKMAXPACKET (64) +#define USBSTRG_FSBULKMXPKTSHIFT (6) +#define USBSTRG_FSBULKMXPKTMASK (0x0000003f) + +/* Macros for dual speed vs. full speed only operation */ + +#ifdef CONFIG_USBDEV_DUALSPEED +# define USBSTRG_EPBULKINDESC(hs) ((hs) ? (g_hsepbulkindesc) : (g_fsepbulkindesc)) +# define USBSTRG_EPBULKOUTDESC(hs) ((hs) ? (g_hsepbulkoutdesc) : (g_fsepbulkoutdesc)) +# define USBSTRG_BULKMAXPACKET(hs) \ + ((hs) ? USBSTRG_HSBULKMAXPACKET : USBSTRG_FSBULKMAXPACKET) +# define USBSTRG_BULKMXPKTSHIFT(d) \ + (((d)->speed==USB_SPEED_HIGH) ? USBSTRG_HSBULKMXPKTSHIFT : USBSTRG_FSBULKMXPKTSHIFT) +# define USBSTRG_BULKMXPKTMASK(d) \ + (((d)->speed==USB_SPEED_HIGH) ? USBSTRG_HSBULKMXPKTMASK : USBSTRG_FSBULKMXPKTMASK) +#else +# define USBSTRG_EPBULKINDESC(d) (g_fsepbulkindesc)) +# define USBSTRG_EPBULKOUTDESC(d) (g_fsepbulkoutdesc)) +# define USBSTRG_BULKMAXPACKET(hs) USBSTRG_FSBULKMAXPACKET +# define USBSTRG_BULKMXPKTSHIFT(d) USBSTRG_FSBULKMXPKTSHIFT +# define USBSTRG_BULKMXPKTMASK(d) USBSTRG_FSBULKMXPKTMASK +#endif + +/* Block driver helpers *****************************************************/ + +#define USBSTRG_DRVR_READ(l,b,s,n) ((l)->inode->u.i_bops->read((l)->inode,b,s,n)) +#define USBSTRG_DRVR_WRITE(l,b,s,n) ((l)->inode->u.i_bops->write((l)->inode,b,s,n)) +#define USBSTRG_DRVR_GEOMETRY(l,g) ((l)->inode->u.i_bops->geometry((l)->inode,g)) + +/* Everpresent min/max macros ***********************************************/ + +#ifndef min +# define min(a,b) ((a) < (b) ? (a) : (b)) +#endif + +#ifndef max +# define max(a,b) ((a) > (b) ? (a) : (b)) +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Container to support a list of requests */ + +struct usbstrg_req_s +{ + FAR struct usbstrg_req_s *flink; /* Implements a singly linked list */ + FAR struct usbdev_req_s *req; /* The contained request */ +}; + +/* This structure describes one LUN: */ + +struct usbstrg_lun_s +{ + struct inode *inode; /* Inode structure of open'ed block driver */ + ubyte readonly:1; /* Media is read-only */ + ubyte locked:1; /* Media removal is prevented */ + uint16 sectorsize; /* The size of one sector */ + uint32 sd; /* Sense data */ + uint32 sdinfo; /* Sense data information */ + uint32 uad; /* Unit needs attention data */ + off_t startsector; /* Sector offset to start of partition */ + size_t nsectors; /* Number of sectors in the partition */ +}; + +/* Describes the overall state of the driver */ + +struct usbstrg_dev_s +{ + FAR struct usbdev_s *usbdev; /* usbdev driver pointer (Non-null if registered) */ + + /* Worker thread interface */ + + pthread_t thread; /* The worker thread */ + pthread_mutex_t mutex; /* Mutually exclusive access to resources*/ + pthread_cond_t cond; /* Used to signal worker thread */ + volatile ubyte thstate; /* State of the worker thread */ + volatile uint16 theventset; /* Set of pending events signaled to worker thread */ + volatile ubyte thvalue; /* Value passed with the event (must persist) */ + + /* Storage class configuration and state */ + + ubyte nluns:4; /* Number of LUNs */ + ubyte config; /* Configuration number */ + ubyte nwrq; /* Number of queue write requests (in wrreqlist)*/ + ubyte nrdq; /* Number of queue read requests (in epbulkout) */ + + /* Endpoints */ + + FAR struct usbdev_ep_s *epbulkin; /* Bulk IN endpoint structure */ + FAR struct usbdev_ep_s *epbulkout; /* Bulk OUT endpoint structure */ + FAR struct usbdev_req_s *ctrlreq; /* Control request (for ep0 setup responses) */ + + /* SCSI commands */ + + struct usbstrg_lun_s *lun; /* Currently selected LUN */ + struct usbstrg_lun_s *luntab; /* Allocated table of all LUNs */ + ubyte cdb[USBSTRG_MAXCDBLEN]; /* Command data (cdb[]) from CBW */ + ubyte phaseerror:1; /* Need to send phase sensing status */ + ubyte shortpacket:1; /* Host transmission stopped unexpectedly */ + ubyte cbwdir:2; /* Direction from CBW. See USBSTRG_FLAGS_DIR* definitions */ + ubyte cdblen; /* Length of cdb[] from CBW */ + ubyte cbwlun; /* LUN from the CBW */ + uint16 nsectbytes; /* Bytes buffered in iobuffer[] */ + uint16 nreqbytes; /* Bytes buffered in head write requests */ + uint16 iosize; /* Size of iobuffer[] */ + uint32 cbwlen; /* Length of data from CBW */ + uint32 cbwtag; /* Tag from the CBW */ + union + { + uint32 xfrlen; /* Read/Write: Sectors remaining to be transferred */ + uint32 alloclen; /* Other device-to-host: Host allocation length */ + } u; + uint32 sector; /* Current sector (relative to lun->startsector) */ + uint32 residue; /* Untransferred amount reported in the CSW */ + ubyte *iobuffer; /* Buffer for data transfers */ + + /* Write request list */ + + struct sq_queue_s wrreqlist; /* List of empty write request containers */ + struct sq_queue_s rdreqlist; /* List of filled read request containers */ + + /* Pre-allocated write request containers. The write requests will + * be linked in a free list (wrreqlist), and used to send requests to + * EPBULKIN; Read requests will be queued in the EBULKOUT. + */ + + struct usbstrg_req_s wrreqs[CONFIG_USBSTRG_NWRREQS]; + struct usbstrg_req_s rdreqs[CONFIG_USBSTRG_NRDREQS]; +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +# define EXTERN extern "C" +extern "C" +{ +#else +# define EXTERN extern +#endif + +/* String *******************************************************************/ + +EXTERN const char g_vendorstr[]; +EXTERN const char g_productstr[]; +EXTERN const char g_serialstr[]; + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_workerthread + * + * Description: + * This is the main function of the USB storage worker thread. It loops + * until USB-related events occur, then processes those events accordingly + * + ****************************************************************************/ + +EXTERN void *usbstrg_workerthread(void *arg); + +/**************************************************************************** + * Name: usbstrg_setconfig + * + * Description: + * Set the device configuration by allocating and configuring endpoints and + * by allocating and queue read and write requests. + * + ****************************************************************************/ + +EXTERN int usbstrg_setconfig(FAR struct usbstrg_dev_s *priv, ubyte config); + +/**************************************************************************** + * Name: usbstrg_resetconfig + * + * Description: + * Mark the device as not configured and disable all endpoints. + * + ****************************************************************************/ + +EXTERN void usbstrg_resetconfig(FAR struct usbstrg_dev_s *priv); + +/**************************************************************************** + * Name: usbstrg_wrcomplete + * + * Description: + * Handle completion of write request. This function probably executes + * in the context of an interrupt handler. + * + ****************************************************************************/ + +EXTERN void usbstrg_wrcomplete(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req); + +/**************************************************************************** + * Name: usbstrg_rdcomplete + * + * Description: + * Handle completion of read request on the bulk OUT endpoint. This + * is handled like the receipt of serial data on the "UART" + * + ****************************************************************************/ + +EXTERN void usbstrg_rdcomplete(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req); + +/**************************************************************************** + * Name: usbstrg_deferredresponse + * + * Description: + * Some EP0 setup request cannot be responded to immediately becuase they + * require some asynchronous action from the SCSI worker thread. This + * function is provided for the SCSI thread to make that deferred response. + * The specific requests that require this deferred response are: + * + * 1. USB_REQ_SETCONFIGURATION, + * 2. USB_REQ_SETINTERFACE, or + * 3. USBSTRG_REQ_MSRESET + * + * In all cases, the success reponse is a zero-length packet; the failure + * response is an EP0 stall. + * + * Input parameters: + * priv - Private state structure for this USB storage instance + * stall - TRUE is the action failed and a stall is required + * + ****************************************************************************/ + +EXTERN void usbstrg_deferredresponse(FAR struct usbstrg_dev_s *priv, boolean failed); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* #define __DRIVERS_USBDEV_USBDEV_STORAGE_H */ diff --git a/nuttx/include/nuttx/scsi.h b/nuttx/include/nuttx/scsi.h index a7a568ed8..e21b7a90d 100644 --- a/nuttx/include/nuttx/scsi.h +++ b/nuttx/include/nuttx/scsi.h @@ -632,10 +632,11 @@ struct scsicmd_requestsense_s ubyte opcode; /* 0: 0x03 */ ubyte flags; /* 1: See SCSICMD_REQUESTSENSE_FLAGS_* */ ubyte reserved[2]; /* 2-3: Reserved */ - ubyte len; /* 4: Allocation length */ + ubyte alloclen; /* 4: Allocation length */ ubyte control; /* 5: Control */ }; #define SCSICMD_REQUESTSENSE_SIZEOF 6 +#define SCSICMD_REQUESTSENSE_MSSIZEOF 12 /* MS-Windows REQUEST SENSE with cbw->cdblen == 12 */ struct scsiresp_fixedsensedata_s { @@ -658,7 +659,7 @@ struct scscicmd_inquiry_s ubyte opcode; /* 0: 0x12 */ ubyte flags; /* 1: See SCSICMD_INQUIRY_FLAGS_* */ ubyte pagecode; /* 2: Page code */ - ubyte len[2]; /* 3-4: Allocation length */ + ubyte alloclen[2]; /* 3-4: Allocation length */ ubyte control; /* 5: Control */ }; #define SCSICMD_INQUIRY_SIZEOF 6 @@ -713,7 +714,7 @@ struct scsicmd_modesense6_s ubyte flags; /* 1: See SCSICMD_MODESENSE6_FLAGS_* */ ubyte pcpgcode; /* 2: Bits 6-7: PC, bits 0-5: page code */ ubyte subpgcode; /* 3: subpage code */ - ubyte len; /* 4: Allocation length */ + ubyte alloclen; /* 4: Allocation length */ ubyte control; /* 5: Control */ }; #define SCSICMD_MODESENSE6_SIZEOF 6 @@ -775,7 +776,7 @@ struct scsicmd_read6_s ubyte opcode; /* 0: 0x08 */ ubyte mslba; /* 1: Bits 5-7: reserved; Bits 0-6: MS Logical Block Address (LBA) */ ubyte lslba[2]; /* 2-3: LS Logical Block Address (LBA) */ - ubyte xfrlen; /* 4: Transfer length */ + ubyte xfrlen; /* 4: Transfer length (in contiguous logical blocks)*/ ubyte control; /* 5: Control */ }; #define SCSICMD_READ6_SIZEOF 6 @@ -785,7 +786,7 @@ struct scsicmd_write6_s ubyte opcode; /* 0: 0x0a */ ubyte mslba; /* 1: Bits 5-7: reserved; Bits 0-6: MS Logical Block Address (LBA) */ ubyte lslba[2]; /* 2-3: LS Logical Block Address (LBA) */ - ubyte xfrlen; /* 4: Transfer length */ + ubyte xfrlen; /* 4: Transfer length (in contiguous logical blocks) */ ubyte control; /* 5: Control */ }; #define SCSICMD_WRITE6_SIZEOF 6 @@ -830,12 +831,12 @@ struct scsiresp_readcapacity10_s struct scsicmd_read10_s { - ubyte opcode; /* 0x28 */ - ubyte flags; /* See SCSICMD_READ10FLAGS_* */ - ubyte lba[4]; /* Logical Block Address (LBA) */ - ubyte groupno; /* Bits 5-7: reserved; Bits 0-6: group number */ - ubyte xfrlen[2]; /* Transfer length */ - ubyte control; /* Control */ + ubyte opcode; /* 0: 0x28 */ + ubyte flags; /* 1: See SCSICMD_READ10FLAGS_* */ + ubyte lba[4]; /* 2-5: Logical Block Address (LBA) */ + ubyte groupno; /* 6: Bits 5-7: reserved; Bits 0-6: group number */ + ubyte xfrlen[2]; /* 7-8: Transfer length (in contiguous logical blocks) */ + ubyte control; /* 9: Control */ }; #define SCSICMD_READ10_SIZEOF 10 @@ -845,7 +846,7 @@ struct scsicmd_write10_s ubyte flags; /* 1: See SCSICMD_WRITE10FLAGS_* */ ubyte lba[4]; /* 2-5: Logical Block Address (LBA) */ ubyte groupno; /* 6: Bits 5-7: reserved; Bits 0-6: group number */ - ubyte xfrlen[2]; /* 7-8: Transfer length */ + ubyte xfrlen[2]; /* 7-8: Transfer length (in contiguous logical blocks) */ ubyte control; /* 9: Control */ }; #define SCSICMD_WRITE10_SIZEOF 10 @@ -877,7 +878,7 @@ struct scsicmd_modeselect10_s ubyte opcode; /* 0: 0x55 */ ubyte flags; /* 1: See SCSICMD_MODESELECT10_FLAGS_* */ ubyte reserved[5]; /* 2-6: Reserved */ - ubyte plen[2]; /* 7-8: Parameter list length */ + ubyte parmlen[2]; /* 7-8: Parameter list length */ ubyte control; /* 9: Control */ }; #define SCSICMD_MODESELECT10_SIZEOF 10 @@ -899,7 +900,7 @@ struct scsicmd_modesense10_s ubyte pcpgcode; /* 2: Bits 6-7: PC, bits 0-5: page code */ ubyte subpgcode; /* 3: subpage code */ ubyte reserved[3]; /* 4-6: reserved */ - ubyte len[2]; /* 7-8: Allocation length */ + ubyte alloclen[2]; /* 7-8: Allocation length */ ubyte control; /* 9: Control */ }; #define SCSICMD_MODESENSE10_SIZEOF 10 @@ -917,23 +918,23 @@ struct scsicmd_readcapacity16_s struct scsicmd_read12_s { - ubyte opcode; /* 0xa8 */ - ubyte flags; /* See SCSICMD_READ12FLAGS_* */ - ubyte lba[4]; /* Logical Block Address (LBA) */ - ubyte xfrlen[4]; /* Transfer length */ - ubyte groupno; /* Bit 7: restricted; Bits 5-6: reserved; Bits 0-6: group number */ - ubyte control; /* Control */ + ubyte opcode; /* 0: 0xa8 */ + ubyte flags; /* 1: See SCSICMD_READ12FLAGS_* */ + ubyte lba[4]; /* 2-5: Logical Block Address (LBA) */ + ubyte xfrlen[4]; /* 6-9: Transfer length (in contiguous logical blocks) */ + ubyte groupno; /* 10: Bit 7: restricted; Bits 5-6: reserved; Bits 0-6: group number */ + ubyte control; /* 11: Control */ }; #define SCSICMD_READ12_SIZEOF 12 struct scsicmd_write12_s { - ubyte opcode; /* 0xaa */ - ubyte flags; /* See SCSICMD_WRITE12FLAGS_* */ - ubyte lba[4]; /* Logical Block Address (LBA) */ - ubyte xfrlen[4]; /* Transfer length */ - ubyte groupno; /* Bit 7: restricted; Bits 5-6: reserved; Bits 0-6: group number */ - ubyte control; /* Control */ + ubyte opcode; /* 0: 0xaa */ + ubyte flags; /* 1: See SCSICMD_WRITE12FLAGS_* */ + ubyte lba[4]; /* 2-5: Logical Block Address (LBA) */ + ubyte xfrlen[4]; /* 6-9: Transfer length (in contiguous logical blocks) */ + ubyte groupno; /* 10: Bit 7: restricted; Bits 5-6: reserved; Bits 0-6: group number */ + ubyte control; /* 11: Control */ }; #define SCSICMD_WRITE12_SIZEOF 12 diff --git a/nuttx/include/nuttx/usbdev_trace.h b/nuttx/include/nuttx/usbdev_trace.h index 13a949f70..b2a2d0f25 100644 --- a/nuttx/include/nuttx/usbdev_trace.h +++ b/nuttx/include/nuttx/usbdev_trace.h @@ -288,61 +288,59 @@ #define USBSTRG_TRACEERR_PHASEERROR1 0x0040 #define USBSTRG_TRACEERR_PHASEERROR2 0x0041 #define USBSTRG_TRACEERR_PHASEERROR3 0x0042 -#define USBSTRG_TRACEERR_PREVENTMEDIUMREMOVALFLAGS 0x0043 -#define USBSTRG_TRACEERR_PREVENTMEDIUMREMOVALPREVENT 0x0044 -#define USBSTRG_TRACEERR_RDALLOCREQ 0x0045 -#define USBSTRG_TRACEERR_RDCOMPLETEINVALIDARGS 0x0046 -#define USBSTRG_TRACEERR_RDCOMPLETERDSUBMIT 0x0047 -#define USBSTRG_TRACEERR_RDSHUTDOWN 0x0048 -#define USBSTRG_TRACEERR_RDSUBMIT 0x0049 -#define USBSTRG_TRACEERR_RDUNEXPECTED 0x004a -#define USBSTRG_TRACEERR_READ10FLAGS 0x004b -#define USBSTRG_TRACEERR_READ10LBARANGE 0x004c -#define USBSTRG_TRACEERR_READ10MEDIANOTPRESENT 0x004d -#define USBSTRG_TRACEERR_READ12FLAGS 0x004e -#define USBSTRG_TRACEERR_READ12LBARANGE 0x004f -#define USBSTRG_TRACEERR_READ12MEDIANOTPRESENT 0x0050 -#define USBSTRG_TRACEERR_READ6FLAGS 0x0051 -#define USBSTRG_TRACEERR_READ6LBARANGE 0x0052 -#define USBSTRG_TRACEERR_READ6MEDIANOTPRESENT 0x0053 -#define USBSTRG_TRACEERR_READCAPACITYFLAGS 0x0054 -#define USBSTRG_TRACEERR_REALLOCIOBUFFER 0x0055 -#define USBSTRG_TRACEERR_REQRESULT 0x0056 -#define USBSTRG_TRACEERR_SETCONFIGINVALIDARGS 0x0057 -#define USBSTRG_TRACEERR_SETUPINVALIDARGS 0x0058 -#define USBSTRG_TRACEERR_SNDCSWFAIL 0x0059 -#define USBSTRG_TRACEERR_SNDPHERROR 0x005a -#define USBSTRG_TRACEERR_SNDSTATUSSUBMIT 0x005b -#define USBSTRG_TRACEERR_SYNCCACHEMEDIANOTPRESENT 0x005c -#define USBSTRG_TRACEERR_THREADCREATE 0x005d -#define USBSTRG_TRACEERR_TOOMANYLUNS 0x005e -#define USBSTRG_TRACEERR_UNBINDINVALIDARGS 0x005f -#define USBSTRG_TRACEERR_UNBINDLUNINVALIDARGS1 0x0060 -#define USBSTRG_TRACEERR_UNBINDLUNINVALIDARGS2 0x0061 -#define USBSTRG_TRACEERR_UNINITIALIZEINVALIDARGS 0x0062 -#define USBSTRG_TRACEERR_UNSUPPORTEDSTDREQ 0x0063 -#define USBSTRG_TRACEERR_VERIFY10FLAGS 0x0064 -#define USBSTRG_TRACEERR_VERIFY10LBARANGE 0x0065 -#define USBSTRG_TRACEERR_VERIFY10MEDIANOTPRESENT 0x0066 -#define USBSTRG_TRACEERR_VERIFY10NOBLOCKS 0x0067 -#define USBSTRG_TRACEERR_VERIFY10READFAIL 0x0068 -#define USBSTRG_TRACEERR_WRALLOCREQ 0x0069 -#define USBSTRG_TRACEERR_SNDPHERROR 0x006a -#define USBSTRG_TRACEERR_WRCOMPLETEINVALIDARGS 0x006b -#define USBSTRG_TRACEERR_WRITE10FLAGS 0x006c -#define USBSTRG_TRACEERR_WRITE10LBARANGE 0x006d -#define USBSTRG_TRACEERR_WRITE10MEDIANOTPRESENT 0x006e -#define USBSTRG_TRACEERR_WRITE10READONLY 0x006f -#define USBSTRG_TRACEERR_WRITE12FLAGS 0x0070 -#define USBSTRG_TRACEERR_WRITE12LBARANGE 0x0071 -#define USBSTRG_TRACEERR_WRITE12MEDIANOTPRESENT 0x0072 -#define USBSTRG_TRACEERR_WRITE12READONLY 0x0073 -#define USBSTRG_TRACEERR_WRITE6FLAGS 0x0074 -#define USBSTRG_TRACEERR_WRITE6LBARANGE 0x0075 -#define USBSTRG_TRACEERR_WRITE6MEDIANOTPRESENT 0x0076 -#define USBSTRG_TRACEERR_WRITE6READONLY 0x0077 -#define USBSTRG_TRACEERR_WRSHUTDOWN 0x0078 -#define USBSTRG_TRACEERR_WRUNEXPECTED 0x0079 +#define USBSTRG_TRACEERR_PREVENTMEDIUMREMOVALPREVENT 0x0043 +#define USBSTRG_TRACEERR_RDALLOCREQ 0x0044 +#define USBSTRG_TRACEERR_RDCOMPLETEINVALIDARGS 0x0045 +#define USBSTRG_TRACEERR_RDCOMPLETERDSUBMIT 0x0046 +#define USBSTRG_TRACEERR_RDSHUTDOWN 0x0047 +#define USBSTRG_TRACEERR_RDSUBMIT 0x0048 +#define USBSTRG_TRACEERR_RDUNEXPECTED 0x0049 +#define USBSTRG_TRACEERR_READ10FLAGS 0x004a +#define USBSTRG_TRACEERR_READ10LBARANGE 0x004b +#define USBSTRG_TRACEERR_READ10MEDIANOTPRESENT 0x004c +#define USBSTRG_TRACEERR_READ12FLAGS 0x004d +#define USBSTRG_TRACEERR_READ12LBARANGE 0x004e +#define USBSTRG_TRACEERR_READ12MEDIANOTPRESENT 0x004f +#define USBSTRG_TRACEERR_READ6LBARANGE 0x0050 +#define USBSTRG_TRACEERR_READ6MEDIANOTPRESENT 0x0051 +#define USBSTRG_TRACEERR_READCAPACITYFLAGS 0x0052 +#define USBSTRG_TRACEERR_REALLOCIOBUFFER 0x0053 +#define USBSTRG_TRACEERR_REQRESULT 0x0054 +#define USBSTRG_TRACEERR_SCSICMDCONTROL 0x0055 +#define USBSTRG_TRACEERR_SETCONFIGINVALIDARGS 0x0056 +#define USBSTRG_TRACEERR_SETUPINVALIDARGS 0x0057 +#define USBSTRG_TRACEERR_SNDCSWFAIL 0x0058 +#define USBSTRG_TRACEERR_SNDPHERROR 0x0059 +#define USBSTRG_TRACEERR_SNDSTATUSSUBMIT 0x005a +#define USBSTRG_TRACEERR_SYNCCACHEMEDIANOTPRESENT 0x005b +#define USBSTRG_TRACEERR_THREADCREATE 0x005c +#define USBSTRG_TRACEERR_TOOMANYLUNS 0x005d +#define USBSTRG_TRACEERR_UNBINDINVALIDARGS 0x005e +#define USBSTRG_TRACEERR_UNBINDLUNINVALIDARGS1 0x005f +#define USBSTRG_TRACEERR_UNBINDLUNINVALIDARGS2 0x0060 +#define USBSTRG_TRACEERR_UNINITIALIZEINVALIDARGS 0x0061 +#define USBSTRG_TRACEERR_UNSUPPORTEDSTDREQ 0x0062 +#define USBSTRG_TRACEERR_VERIFY10FLAGS 0x0063 +#define USBSTRG_TRACEERR_VERIFY10LBARANGE 0x0064 +#define USBSTRG_TRACEERR_VERIFY10MEDIANOTPRESENT 0x0065 +#define USBSTRG_TRACEERR_VERIFY10NOBLOCKS 0x0066 +#define USBSTRG_TRACEERR_VERIFY10READFAIL 0x0067 +#define USBSTRG_TRACEERR_WRALLOCREQ 0x0068 +#define USBSTRG_TRACEERR_SNDPHERROR 0x0069 +#define USBSTRG_TRACEERR_WRCOMPLETEINVALIDARGS 0x006a +#define USBSTRG_TRACEERR_WRITE10FLAGS 0x006b +#define USBSTRG_TRACEERR_WRITE10LBARANGE 0x006c +#define USBSTRG_TRACEERR_WRITE10MEDIANOTPRESENT 0x006d +#define USBSTRG_TRACEERR_WRITE10READONLY 0x006e +#define USBSTRG_TRACEERR_WRITE12FLAGS 0x006f +#define USBSTRG_TRACEERR_WRITE12LBARANGE 0x0070 +#define USBSTRG_TRACEERR_WRITE12MEDIANOTPRESENT 0x0071 +#define USBSTRG_TRACEERR_WRITE12READONLY 0x0072 +#define USBSTRG_TRACEERR_WRITE6LBARANGE 0x0073 +#define USBSTRG_TRACEERR_WRITE6MEDIANOTPRESENT 0x0074 +#define USBSTRG_TRACEERR_WRITE6READONLY 0x0075 +#define USBSTRG_TRACEERR_WRSHUTDOWN 0x0076 +#define USBSTRG_TRACEERR_WRUNEXPECTED 0x0077 /**************************************************************************** * Public Types -- cgit v1.2.3