summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-12-18 03:24:13 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-12-18 03:24:13 +0000
commit513f435250e6a6e5d0af288358091e9aff47cdba (patch)
treec353c0d4e2ade12f6662461aa8a6f665057b91d7
parent7e3a546c5be3f8c4a5838a73d26a672fb09ea52e (diff)
downloadpx4-nuttx-513f435250e6a6e5d0af288358091e9aff47cdba.tar.gz
px4-nuttx-513f435250e6a6e5d0af288358091e9aff47cdba.tar.bz2
px4-nuttx-513f435250e6a6e5d0af288358091e9aff47cdba.zip
Working through initialization state machine
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3194 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c165
-rw-r--r--nuttx/include/nuttx/usb/usbhost.h128
2 files changed, 222 insertions, 71 deletions
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index 544b8349c..5df0f9c7a 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -87,15 +87,17 @@
* defined here so that it will be used consistently in all places.
*/
-#define DEV_FORMAT "/dev/sd%c"
-#define DEV_NAMELEN 10
+#define DEV_FORMAT "/dev/sd%c"
+#define DEV_NAMELEN 10
/* Used in usbhost_configdesc() */
-#define USBHOST_IFFOUND 0x01
-#define USBHOST_BINFOUND 0x02
-#define USBHOST_BOUTFOUND 0x04
-#define USBHOST_ALLFOUND 0x07
+#define USBHOST_IFFOUND 0x01
+#define USBHOST_BINFOUND 0x02
+#define USBHOST_BOUTFOUND 0x04
+#define USBHOST_ALLFOUND 0x07
+
+#define USBHOST_MAX_RETRIES 100
/****************************************************************************
* Private Types
@@ -105,15 +107,15 @@
enum USBSTRG_STATE_e
{
- USBSTRG_STATE_CREATED = 0, /* State has been created, waiting for config descriptor */
- USBSTRG_STATE_CONFIGURED, /* Received config descriptor */
- USBSTRG_STATE_MAXLUN, /* Requested maximum logical unit number */
- USBSTRG_STATE_UNITREADY, /* Check if the unit is ready */
- USBSTRG_STATE_SENSE, /* Get sense information */
- USBSTRG_STATE_CAPACITY, /* Read the capacity of the volume */
- USBSTRG_STATE_READY, /* Registered the block driver, idle, waiting for operation */
- USBSTRG_STATE_BUSY, /* Transfer in progress */
- USBSTRG_STATE_FAIL /* A fatal error occurred */
+ USBSTRG_STATE_CREATED = 0, /* State has been created, waiting for config descriptor */
+ USBSTRG_STATE_CONFIGURED, /* Received config descriptor */
+ USBSTRG_STATE_MAXLUN, /* Requested maximum logical unit number */
+ USBSTRG_STATE_TESTUNITREADY, /* Waiting for test unit ready to complete */
+ USBSTRG_STATE_SENSE, /* Get sense information */
+ USBSTRG_STATE_CAPACITY, /* Read the capacity of the volume */
+ USBSTRG_STATE_READY, /* Registered the block driver, idle, waiting for operation */
+ USBSTRG_STATE_BUSY, /* Transfer in progress */
+ USBSTRG_STATE_FAIL /* A fatal error occurred */
};
/* This structure contains the internal, private state of the USB host mass
@@ -133,6 +135,7 @@ struct usbhost_state_s
/* The remainder of the fields are provide o the mass storage class */
uint8_t state; /* See enum USBSTRG_STATE_e */
+ uint8_t retries; /* Retry counter */
char sdchar; /* Character identifying the /dev/sd[n] device */
int16_t crefs; /* Reference count on the driver instance */
uint16_t blocksize; /* Block size of USB mass storage device */
@@ -178,6 +181,9 @@ static inline void usbhost_readcbw (size_t startsector, uint16_t blocksize,
static inline void usbhost_writecbw(size_t startsector, uint16_t blocksize,
unsigned int nsectors,
FAR struct usbstrg_cbw_s *cbw);
+/* Command helpers */
+
+static int usbhost_testunitready(FAR struct usbhost_state_s *priv);
/* Worker thread actions */
@@ -572,6 +578,46 @@ usbhost_writecbw(size_t startsector, uint16_t blocksize,
}
/****************************************************************************
+ * Name: Command helpers
+ *
+ * Description:
+ * The following functions are helper functions used to send commands.
+ *
+ * Input Parameters:
+ * priv - A reference to the class instance.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static int usbhost_testunitready(FAR struct usbhost_state_s *priv)
+{
+ FAR struct usbstrg_cbw_s *cbw;
+ int result = -ENOMEM;
+
+ /* Initialize a CBW (allocating it if necessary) */
+
+ cbw = usbhost_cbwalloc(priv);
+ if (cbw)
+ {
+ /* Construc and send the CBW */
+
+ usbhost_testunitreadycbw(cbw);
+ result = DRVR_TRANSFER(priv->drvr, &priv->bulkout,
+ (uint8_t*)cbw, USBSTRG_CBW_SIZEOF);
+ if (result == OK)
+ {
+ /* Receive the CSW */
+
+ result = DRVR_TRANSFER(priv->drvr, &priv->bulkin,
+ priv->tdbuffer, USBSTRG_CSW_SIZEOF);
+ }
+ }
+ return result;
+}
+
+/****************************************************************************
* Name: usbhost_destroy
*
* Description:
@@ -603,6 +649,15 @@ static void usbhost_destroy(FAR void *arg)
usbhost_freedevno(priv);
+ /* Free any transfer buffers */
+
+ usbhost_tdfree(priv);
+
+ /* Destroy the semaphores */
+
+ sem_destroy(&priv->exclsem);
+ sem_destroy(&priv->waitsem);
+
/* And free the class instance. Hmmm.. this may execute on the worker
* thread and the work structure is part of what is getting freed.
*/
@@ -634,7 +689,7 @@ static void usbhost_destroy(FAR void *arg)
static void usbhost_statemachine(FAR void *arg)
{
FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)arg;
- int result;
+ int result = OK;
DEBUGASSERT(priv != NULL);
@@ -643,43 +698,88 @@ static void usbhost_statemachine(FAR void *arg)
{
case USBSTRG_STATE_CONFIGURED: /* Received config descriptor */
{
- /* Request maximum logical unit number */
-#warning "Missing Logic"
- priv->state = USBSTRG_STATE_MAXLUN;
+ struct usb_ctrlreq_s req;
+ uvdbg("USBSTRG_STATE_CONFIGURED\n");
+
+ /* Make sure that we have a buffer allocated */
+
+ result = usbhost_tdalloc(priv);
+ if (result == OK)
+ {
+ /* Request maximum logical unit number */
+
+ memset(&req, 0, sizeof(struct usb_ctrlreq_s));
+ req.type = USB_DIR_IN|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE;
+ req.req = USBSTRG_REQ_GETMAXLUN;
+ usbhost_putle16(req.len, 1);
+
+ result = DRVR_CONTROL(priv->drvr, &req, priv->tdbuffer);
+ priv->state = USBSTRG_STATE_MAXLUN;
+ }
}
break;
case USBSTRG_STATE_MAXLUN: /* Requested maximum logical unit number */
{
- /* Handle maximum LUN info */
+ uvdbg("USBSTRG_STATE_MAXLUN\n");
/* Check if the unit is ready */
+
+ result = usbhost_testunitready(priv);
+ priv->retries = 0;
#warning "Missing Logic"
priv->state = USBSTRG_STATE_MAXLUN;
}
break;
- case USBSTRG_STATE_UNITREADY: /* Check if the unit is ready */
+ case USBSTRG_STATE_SENSE: /* MODESENSE compleed */
{
- /* Request sense information */
-#warning "Missing Logic"
- priv->state = USBSTRG_STATE_SENSE;
+ uvdbg("USBSTRG_STATE_SENSE\n");
+
+ /* Check if the unit is ready again */
+
+ result = usbhost_testunitready(priv);
+ priv->state = USBSTRG_STATE_TESTUNITREADY;
+ priv->retries++;
}
break;
- case USBSTRG_STATE_SENSE: /* Get sense information */
+ case USBSTRG_STATE_TESTUNITREADY: /* TESTUNITREADY completed */
{
- /* Process sense information */
+ uvdbg("USBSTRG_STATE_TESTUNITREADY\n");
- /* Request the capaciy of the volume */
+ /* Check the result */
+
+ if (priv->tdbuffer[12] != 0)
+ {
+ /* Not ready... retry? */
+
+ if (priv->retries < USBHOST_MAX_RETRIES)
+ {
+ /* Request mode sense information */
#warning "Missing Logic"
- priv->state = USBSTRG_STATE_CAPACITY;
+ priv->state = USBSTRG_STATE_SENSE;
+
+ }
+ else
+ {
+ result = -ETIMEDOUT;
+ }
+ }
+ else
+ {
+ /* Request the capaciy of the volume */
+
+#warning "Missing Logic"
+ priv->state = USBSTRG_STATE_CAPACITY;
+ }
}
break;
case USBSTRG_STATE_CAPACITY: /* Read the capacity of the volume */
{
char devname[DEV_NAMELEN];
+ uvdbg("USBSTRG_STATE_CAPACITY\n");
/* Process capacity information */
#warning "Missing Logic"
@@ -713,10 +813,19 @@ static void usbhost_statemachine(FAR void *arg)
default:
{
udbg("ERROR! Completion in unexpected stated: %d\n", priv->state);
+ result = -EINVAL;
}
break;
}
usbhost_givesem(&priv->exclsem);
+
+ /* Abort everything on an error */
+
+ if (result != OK)
+ {
+ udbg("ERROR! Aborting: %d\n", result);
+ usbhost_destroy(priv);
+ }
}
/****************************************************************************
diff --git a/nuttx/include/nuttx/usb/usbhost.h b/nuttx/include/nuttx/usb/usbhost.h
index e72e392ce..f49db871e 100644
--- a/nuttx/include/nuttx/usb/usbhost.h
+++ b/nuttx/include/nuttx/usb/usbhost.h
@@ -197,24 +197,21 @@
#define DRVR_ENUMERATE(drvr) ((drvr)->enumerate(drvr))
/************************************************************************************
- * Name: DRVR_TRANSFER
+ * Name: DRVR_ALLOC
*
* Description:
- * Enqueue a request to handle a transfer descriptor. This method will
- * enqueue the transfer request and return immediately. The transfer will
- * be performed asynchronously. When the transfer completes, the USB host
- * driver will call he complete() method of the struct usbhost_class_s
- * interface. Only one transfer may be queued; this function cannot be
- * again until the class complete() method has been called.
+ * Some hardware supports special memory in which transfer descriptors can
+ * be accessed more efficiently. This method provides a mechanism to allocate
+ * the transfer descriptor memory. If the underlying hardware does not support
+ * such "special" memory, this functions may simply map to malloc.
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
* the class create() method.
- * ed - The IN or OUT endpoint descriptor for the device endpoint on which to
- * perform the transfer.
- * buffer - A buffer containing the data to be sent (OUT endpoint) or received
- * (IN endpoint).
- * buflen - The length of the data to be sent or received.
+ * buffer - The address of a memory location provided by the caller in which to
+ * return the allocated buffer memory address.
+ * maxlen - The address of a memory location provided by the caller in which to
+ * return the maximum size of the allocated buffer memory.
*
* Returned Values:
* On success, zero (OK) is returned. On a failure, a negated errno value is
@@ -225,24 +222,21 @@
*
************************************************************************************/
-#define DRVR_TRANSFER(drvr,ed,buffer,buflen) ((drvr)->transfer(drvr,ed,buffer,buflen))
+#define DRVR_ALLOC(drvr,buffer,maxlen) ((drvr)->alloc(drvr,buffer,maxlen))
/************************************************************************************
- * Name: DRVR_ALLOC
+ * Name: DRVR_FREE
*
* Description:
* Some hardware supports special memory in which transfer descriptors can
- * be accessed more efficiently. This method provides a mechanism to allocate
- * the transfer descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to malloc.
+ * be accessed more efficiently. This method provides a mechanism to free that
+ * transfer descriptor memory. If the underlying hardware does not support
+ * such "special" memory, this functions may simply map to free().
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
* the class create() method.
- * buffer - The address of a memory location provided by the caller in which to
- * return the allocated buffer memory address.
- * maxlen - The address of a memory location provided by the caller in which to
- * return the maximum size of the allocated buffer memory.
+ * buffer - The address of the allocated buffer memory to be freed.
*
* Returned Values:
* On success, zero (OK) is returned. On a failure, a negated errno value is
@@ -253,21 +247,28 @@
*
************************************************************************************/
-#define DRVR_ALLOC(drvr,buffer,maxlen) ((drvr)->alloc(drvr,buffer,maxlen))
+#define DRVR_FREE(drvr,buffer) ((drvr)->free(drvr,buffer))
/************************************************************************************
- * Name: DRVR_FREE
+ * Name: DRVR_CONTROL
*
* Description:
- * Some hardware supports special memory in which transfer descriptors can
- * be accessed more efficiently. This method provides a mechanism to free that
- * transfer descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to free().
+ * Enqueue a request on the control endpoint. This method will enqueue
+ * the request and return immediately. The transfer will be performed
+ * asynchronously. When the transfer completes, the USB host driver will
+ * call the complete() method of the struct usbhost_class_s interface.
+ * Only one transfer may be queued; Neither this method nor the transfer()
+ * method can be called again until the class complete() method has been called.
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
* the class create() method.
- * buffer - The address of the allocated buffer memory to be freed.
+ * req - Describes the request to be sent. This data will be copied from the
+ * user provided memory. Therefore, the req buffer may be declared on the
+ * stack.
+ * buffer - A buffer used for sending the request and for returning any
+ * responses. This buffer must be large enough to hold the length value
+ * in the request description. buffer must have been allocated using DRVR_ALLOC
*
* Returned Values:
* On success, zero (OK) is returned. On a failure, a negated errno value is
@@ -278,7 +279,39 @@
*
************************************************************************************/
-#define DRVR_FREE(drvr,buffer) ((drvr)->free(drvr,buffer))
+#define DRVR_CONTROL(drvr,req,buffer) ((drvr)->control(drvr,req,buffer))
+
+/************************************************************************************
+ * Name: DRVR_TRANSFER
+ *
+ * Description:
+ * Enqueue a request to handle a transfer descriptor. This method will
+ * enqueue the transfer request and return immediately. The transfer will
+ * be performed asynchronously. When the transfer completes, the USB host
+ * driver will call the complete() method of the struct usbhost_class_s
+ * interface. Only one transfer may be queued; Neither this method nor the
+ * control method can be called again until the class complete() method has
+ * been called.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * ed - The IN or OUT endpoint descriptor for the device endpoint on which to
+ * perform the transfer.
+ * buffer - A buffer containing the data to be sent (OUT endpoint) or received
+ * (IN endpoint). buffer must have been allocated using DRVR_ALLOC
+ * buflen - The length of the data to be sent or received.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+#define DRVR_TRANSFER(drvr,ed,buffer,buflen) ((drvr)->transfer(drvr,ed,buffer,buflen))
/************************************************************************************
* Public Types
@@ -376,18 +409,6 @@ struct usbhost_driver_s
int (*enumerate)(FAR struct usbhost_driver_s *drvr);
- /* Enqueue a request to handle a transfer descriptor. This method will
- * enqueue the transfer request and return immediately. The transfer will
- * be performed asynchronously. When the transfer completes, the USB host
- * driver will call he complete() method of the struct usbhost_class_s
- * interface. Only one transfer may be queued; this function cannot be
- * again until the class complete() method has been called.
- */
-
- int (*transfer)(FAR struct usbhost_driver_s *drvr,
- FAR struct usbhost_epdesc_s *ed,
- FAR uint8_t *buffer, size_t buflen);
-
/* Some hardware supports special memory in which transfer descriptors can
* be accessed more efficiently. The following methods provide a mechanism
* to allocate and free the transfer descriptor memory. If the underlying
@@ -399,9 +420,30 @@ struct usbhost_driver_s
FAR uint8_t **buffer, FAR size_t *maxlen);
int (*free)(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer);
- /* Receive control information */
+ /* Enqueue a request on the control endpoint. This method will enqueue
+ * the request and return immediately. The transfer will be performed
+ * asynchronously. When the transfer completes, the USB host driver will
+ * call the complete() method of the struct usbhost_class_s interface.
+ * Only one transfer may be queued; Neither this method nor the transfer()
+ * method can be called again until the class complete() method has been called.
+ */
+
+ int (*control)(FAR struct usbhost_driver_s *drvr,
+ const struct usb_ctrlreq_s *req,
+ FAR uint8_t *buffer);
+
+ /* Enqueue a request to handle a transfer descriptor. This method will
+ * enqueue the transfer request and return immediately. The transfer will
+ * be performed asynchronously. When the transfer completes, the USB host
+ * driver will call the complete() method of the struct usbhost_class_s
+ * interface. Only one transfer may be queued; Neither this method nor the
+ * control method can be called again until the class complete() method has
+ * been called.
+ */
- int (*rcvctrl)(FAR struct usbhost_driver_s *drvr, FAR struct usbhost_epdesc_s *ed);
+ int (*transfer)(FAR struct usbhost_driver_s *drvr,
+ FAR struct usbhost_epdesc_s *ed,
+ FAR uint8_t *buffer, size_t buflen);
};
/* This structure describes one endpoint */