summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/drivers/usbdev/cdcacm.c414
-rw-r--r--nuttx/drivers/usbdev/composite.c8
-rw-r--r--nuttx/drivers/usbdev/usbmsc.c8
-rw-r--r--nuttx/include/nuttx/usb/usbdev_trace.h1
4 files changed, 221 insertions, 210 deletions
diff --git a/nuttx/drivers/usbdev/cdcacm.c b/nuttx/drivers/usbdev/cdcacm.c
index d34728a4b..52f68c0ab 100644
--- a/nuttx/drivers/usbdev/cdcacm.c
+++ b/nuttx/drivers/usbdev/cdcacm.c
@@ -1207,277 +1207,283 @@ static int cdcacm_setup(FAR struct usbdevclass_driver_s *driver,
uvdbg("type=%02x req=%02x value=%04x index=%04x len=%04x\n",
ctrl->type, ctrl->req, value, index, len);
- switch (ctrl->type & USB_REQ_TYPE_MASK)
+ if ((ctrl->type & USB_REQ_TYPE_MASK) == USB_REQ_TYPE_STANDARD)
{
- /***********************************************************************
- * Standard Requests
- ***********************************************************************/
+ /***********************************************************************
+ * Standard Requests
+ ***********************************************************************/
- case USB_REQ_TYPE_STANDARD:
- {
- switch (ctrl->req)
+ switch (ctrl->req)
+ {
+ case USB_REQ_GETDESCRIPTOR:
{
- 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)
- */
+ /* 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])
- {
- /* If the serial device is used in as part of a composite device,
- * then the device descriptor is provided by logic in the composite
- * device implementation.
- */
+ switch (ctrl->value[1])
+ {
+ /* If the serial device is used in as part of a composite device,
+ * then the device descriptor is provided by logic in the composite
+ * device implementation.
+ */
#ifndef CONFIG_CDCACM_COMPOSITE
- case USB_DESC_TYPE_DEVICE:
- {
- ret = USB_SIZEOF_DEVDESC;
- memcpy(ctrlreq->buf, cdcacm_getdevdesc(), ret);
- }
- break;
+ case USB_DESC_TYPE_DEVICE:
+ {
+ ret = USB_SIZEOF_DEVDESC;
+ memcpy(ctrlreq->buf, cdcacm_getdevdesc(), ret);
+ }
+ break;
#endif
- /* If the serial device is used in as part of a composite device,
- * then the device qualifier descriptor is provided by logic in the
- * composite device implementation.
- */
+ /* If the serial device is used in as part of a composite device,
+ * then the device qualifier descriptor is provided by logic in the
+ * composite device implementation.
+ */
#if !defined(CONFIG_CDCACM_COMPOSITE) && defined(CONFIG_USBDEV_DUALSPEED)
- case USB_DESC_TYPE_DEVICEQUALIFIER:
- {
- ret = USB_SIZEOF_QUALDESC;
- memcpy(ctrlreq->buf, cdcacm_getqualdesc(), ret);
- }
- break;
+ case USB_DESC_TYPE_DEVICEQUALIFIER:
+ {
+ ret = USB_SIZEOF_QUALDESC;
+ memcpy(ctrlreq->buf, cdcacm_getqualdesc(), ret);
+ }
+ break;
- case USB_DESC_TYPE_OTHERSPEEDCONFIG:
+ case USB_DESC_TYPE_OTHERSPEEDCONFIG:
#endif
- /* If the serial device is used in as part of a composite device,
- * then the configuration descriptor is provided by logic in the
- * composite device implementation.
- */
+ /* If the serial device is used in as part of a composite device,
+ * then the configuration descriptor is provided by logic in the
+ * composite device implementation.
+ */
#ifndef CONFIG_CDCACM_COMPOSITE
- case USB_DESC_TYPE_CONFIG:
- {
+ case USB_DESC_TYPE_CONFIG:
+ {
#ifdef CONFIG_USBDEV_DUALSPEED
- ret = cdcacm_mkcfgdesc(ctrlreq->buf, dev->speed, ctrl->req);
+ ret = cdcacm_mkcfgdesc(ctrlreq->buf, dev->speed, ctrl->req);
#else
- ret = cdcacm_mkcfgdesc(ctrlreq->buf);
+ ret = cdcacm_mkcfgdesc(ctrlreq->buf);
#endif
- }
- break;
+ }
+ break;
#endif
- /* If the serial device is used in as part of a composite device,
- * then the language string descriptor is provided by logic in the
- * composite device implementation.
- */
+ /* If the serial device is used in as part of a composite device,
+ * then the language string descriptor is provided by logic in the
+ * composite device implementation.
+ */
#ifndef CONFIG_CDCACM_COMPOSITE
- case USB_DESC_TYPE_STRING:
- {
- /* index == language code. */
-
- ret = cdcacm_mkstrdesc(ctrl->value[0], (struct usb_strdesc_s *)ctrlreq->buf);
- }
- break;
-#endif
+ case USB_DESC_TYPE_STRING:
+ {
+ /* index == language code. */
- default:
- {
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_GETUNKNOWNDESC), value);
- }
- break;
+ ret = cdcacm_mkstrdesc(ctrl->value[0], (struct usb_strdesc_s *)ctrlreq->buf);
}
- }
- break;
+ break;
+#endif
- case USB_REQ_SETCONFIGURATION:
- {
- if (ctrl->type == 0)
+ default:
{
- ret = cdcacm_setconfig(priv, value);
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_GETUNKNOWNDESC), value);
}
- }
- break;
+ break;
+ }
+ }
+ break;
+
+ case USB_REQ_SETCONFIGURATION:
+ {
+ if (ctrl->type == 0)
+ {
+ ret = cdcacm_setconfig(priv, value);
+ }
+ }
+ break;
- /* If the serial device is used in as part of a composite device,
- * then the overall composite class configuration is managed by logic
- * in the composite device implementation.
- */
+ /* If the serial device is used in as part of a composite device,
+ * then the overall composite class configuration is managed by logic
+ * in the composite device implementation.
+ */
#ifndef CONFIG_CDCACM_COMPOSITE
- case USB_REQ_GETCONFIGURATION:
- {
- if (ctrl->type == USB_DIR_IN)
- {
- *(uint8_t*)ctrlreq->buf = priv->config;
- ret = 1;
- }
- }
- break;
+ case USB_REQ_GETCONFIGURATION:
+ {
+ if (ctrl->type == USB_DIR_IN)
+ {
+ *(uint8_t*)ctrlreq->buf = priv->config;
+ ret = 1;
+ }
+ }
+ break;
#endif
- case USB_REQ_SETINTERFACE:
- {
- if (ctrl->type == USB_REQ_RECIPIENT_INTERFACE &&
- priv->config == CDCACM_CONFIGID)
- {
- if ((index == CDCACM_NOTIFID && value == CDCACM_NOTALTIFID) ||
- (index == CDCACM_DATAIFID && value == CDCACM_DATAALTIFID))
- {
- cdcacm_resetconfig(priv);
- cdcacm_setconfig(priv, priv->config);
- ret = 0;
- }
- }
- }
- break;
+ case USB_REQ_SETINTERFACE:
+ {
+ if (ctrl->type == USB_REQ_RECIPIENT_INTERFACE &&
+ priv->config == CDCACM_CONFIGID)
+ {
+ if ((index == CDCACM_NOTIFID && value == CDCACM_NOTALTIFID) ||
+ (index == CDCACM_DATAIFID && value == CDCACM_DATAALTIFID))
+ {
+ cdcacm_resetconfig(priv);
+ cdcacm_setconfig(priv, priv->config);
+ ret = 0;
+ }
+ }
+ }
+ break;
- case USB_REQ_GETINTERFACE:
- {
- if (ctrl->type == (USB_DIR_IN|USB_REQ_RECIPIENT_INTERFACE) &&
- priv->config == CDCACM_CONFIGIDNONE)
- {
- if ((index == CDCACM_NOTIFID && value == CDCACM_NOTALTIFID) ||
- (index == CDCACM_DATAIFID && value == CDCACM_DATAALTIFID))
- {
- *(uint8_t*) ctrlreq->buf = value;
- ret = 1;
- }
- else
- {
- ret = -EDOM;
- }
- }
- }
- break;
+ case USB_REQ_GETINTERFACE:
+ {
+ if (ctrl->type == (USB_DIR_IN|USB_REQ_RECIPIENT_INTERFACE) &&
+ priv->config == CDCACM_CONFIGIDNONE)
+ {
+ if ((index == CDCACM_NOTIFID && value == CDCACM_NOTALTIFID) ||
+ (index == CDCACM_DATAIFID && value == CDCACM_DATAALTIFID))
+ {
+ *(uint8_t*) ctrlreq->buf = value;
+ ret = 1;
+ }
+ else
+ {
+ ret = -EDOM;
+ }
+ }
+ }
+ break;
- default:
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
- break;
- }
- }
- break;
+ default:
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDSTDREQ), ctrl->req);
+ break;
+ }
+ }
- /************************************************************************
- * CDC ACM-Specific Requests
- ************************************************************************/
+ else if ((ctrl->type & USB_REQ_TYPE_MASK) == USB_REQ_TYPE_CLASS)
+ {
+ /***********************************************************************
+ * CDC ACM-Specific Requests
+ ***********************************************************************/
- /* ACM_GET_LINE_CODING requests current DTE rate, stop-bits, parity, and
- * number-of-character bits. (Optional)
- */
+ switch (ctrl->req)
+ {
+ /* ACM_GET_LINE_CODING requests current DTE rate, stop-bits, parity, and
+ * number-of-character bits. (Optional)
+ */
- case ACM_GET_LINE_CODING:
- {
- if (ctrl->type == (USB_DIR_IN|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
- index == CDCACM_NOTIFID)
+ case ACM_GET_LINE_CODING:
{
- /* Return the current line status from the private data structure */
+ if (ctrl->type == (USB_DIR_IN|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
+ index == CDCACM_NOTIFID)
+ {
+ /* Return the current line status from the private data structure */
- memcpy(ctrlreq->buf, &priv->linecoding, SIZEOF_CDC_LINECODING);
- ret = SIZEOF_CDC_LINECODING;
- }
- else
- {
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
+ memcpy(ctrlreq->buf, &priv->linecoding, SIZEOF_CDC_LINECODING);
+ ret = SIZEOF_CDC_LINECODING;
+ }
+ else
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
+ }
}
- }
- break;
+ break;
- /* ACM_SET_LINE_CODING configures DTE rate, stop-bits, parity, and
- * number-of-character bits. (Optional)
- */
+ /* ACM_SET_LINE_CODING configures DTE rate, stop-bits, parity, and
+ * number-of-character bits. (Optional)
+ */
- case ACM_SET_LINE_CODING:
- {
- if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
- len == SIZEOF_CDC_LINECODING && index == CDCACM_NOTIFID)
+ case ACM_SET_LINE_CODING:
{
- /* Save the new line coding in the private data structure */
+ if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
+ len == SIZEOF_CDC_LINECODING && index == CDCACM_NOTIFID)
+ {
+ /* Save the new line coding in the private data structure */
- memcpy(&priv->linecoding, ctrlreq->buf, MIN(len, 7));
- ret = 0;
+ memcpy(&priv->linecoding, ctrlreq->buf, MIN(len, 7));
+ ret = 0;
- /* If there is a registered callback to receive line status info, then
- * callout now.
- */
+ /* If there is a registered callback to receive line status info, then
+ * callout now.
+ */
- if (priv->callback)
+ if (priv->callback)
+ {
+ priv->callback(CDCACM_EVENT_LINECODING);
+ }
+ }
+ else
{
- priv->callback(CDCACM_EVENT_LINECODING);
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
}
}
- else
- {
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
- }
- }
- break;
+ break;
- /* ACM_SET_CTRL_LINE_STATE: RS-232 signal used to tell the DCE device the
- * DTE device is now present. (Optional)
- */
+ /* ACM_SET_CTRL_LINE_STATE: RS-232 signal used to tell the DCE device the
+ * DTE device is now present. (Optional)
+ */
- case ACM_SET_CTRL_LINE_STATE:
- {
- if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
- index == CDCACM_NOTIFID)
+ case ACM_SET_CTRL_LINE_STATE:
{
- /* Save the control line state in the private data structure. Only bits
- * 0 and 1 have meaning.
- */
+ if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
+ index == CDCACM_NOTIFID)
+ {
+ /* Save the control line state in the private data structure. Only bits
+ * 0 and 1 have meaning.
+ */
- priv->ctrlline = value & 3;
- ret = 0;
+ priv->ctrlline = value & 3;
+ ret = 0;
- /* If there is a registered callback to receive control line status info,
- * then callout now.
- */
+ /* If there is a registered callback to receive control line status info,
+ * then callout now.
+ */
- if (priv->callback)
+ if (priv->callback)
+ {
+ priv->callback(CDCACM_EVENT_CTRLLINE);
+ }
+ }
+ else
{
- priv->callback(CDCACM_EVENT_CTRLLINE);
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
}
}
- else
- {
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
- }
- }
- break;
+ break;
- /* Sends special carrier*/
+ /* Sends special carrier*/
- case ACM_SEND_BREAK:
- {
- if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
- index == CDCACM_NOTIFID)
+ case ACM_SEND_BREAK:
{
- /* If there is a registered callback to handle the SendBreak request,
- * then callout now.
- */
+ if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE) &&
+ index == CDCACM_NOTIFID)
+ {
+ /* If there is a registered callback to handle the SendBreak request,
+ * then callout now.
+ */
- ret = 0;
- if (priv->callback)
+ ret = 0;
+ if (priv->callback)
+ {
+ priv->callback(CDCACM_EVENT_SENDBREAK);
+ }
+ }
+ else
{
- priv->callback(CDCACM_EVENT_SENDBREAK);
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
}
}
- else
- {
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->type);
- }
- }
- break;
+ break;
- default:
+ default:
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDCLASSREQ), ctrl->req);
+ break;
+ }
+ }
+ else
+ {
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UNSUPPORTEDTYPE), ctrl->type);
- break;
}
/* Respond to the setup command if data was returned. On an error return
diff --git a/nuttx/drivers/usbdev/composite.c b/nuttx/drivers/usbdev/composite.c
index 2ca583a0b..1c56f79a8 100644
--- a/nuttx/drivers/usbdev/composite.c
+++ b/nuttx/drivers/usbdev/composite.c
@@ -189,13 +189,13 @@ static int composite_classsetup(FAR struct composite_dev_s *priv,
index = GETUINT16(ctrl->index);
interface = (uint8_t)(index & 0xff);
- if (interface >= DEV1_FIRSTINTERFACE && interface <= (DEV1_FIRSTINTERFACE + DEV1_NINTERFACES))
+ if (interface >= DEV1_FIRSTINTERFACE && interface < (DEV1_FIRSTINTERFACE + DEV1_NINTERFACES))
{
ret = CLASS_SETUP(priv->dev1, dev, ctrl);
}
- else if (interface >= DEV2_FIRSTINTERFACE && interface <= (DEV2_FIRSTINTERFACE + DEV2_NINTERFACES))
+ else if (interface >= DEV2_FIRSTINTERFACE && interface < (DEV2_FIRSTINTERFACE + DEV2_NINTERFACES))
{
- ret = CLASS_SETUP(priv->dev1, dev, ctrl);
+ ret = CLASS_SETUP(priv->dev2, dev, ctrl);
}
return ret;
@@ -505,7 +505,7 @@ static int composite_setup(FAR struct usbdevclass_driver_s *driver,
if (ret >= 0)
{
- ret = CLASS_SETUP(priv->dev1, dev, ctrl);
+ ret = CLASS_SETUP(priv->dev2, dev, ctrl);
if (ret >= 0)
{
priv->config = value;
diff --git a/nuttx/drivers/usbdev/usbmsc.c b/nuttx/drivers/usbdev/usbmsc.c
index f521c0a2d..948b72fe6 100644
--- a/nuttx/drivers/usbdev/usbmsc.c
+++ b/nuttx/drivers/usbdev/usbmsc.c
@@ -710,7 +710,7 @@ static int usbmsc_setup(FAR struct usbdevclass_driver_s *driver,
break;
}
}
- else
+ else if ((ctrl->type & USB_REQ_TYPE_MASK) == USB_REQ_TYPE_CLASS)
{
/**********************************************************************
* Bulk-Only Mass Storage Class Requests
@@ -775,10 +775,14 @@ static int usbmsc_setup(FAR struct usbdevclass_driver_s *driver,
break;
default:
- usbtrace(TRACE_CLSERROR(USBMSC_TRACEERR_BADREQUEST), index);
+ usbtrace(TRACE_CLSERROR(USBMSC_TRACEERR_BADREQUEST), ctrl->req);
break;
}
}
+ else
+ {
+ usbtrace(TRACE_CLSERROR(USBMSC_TRACEERR_UNSUPPORTEDTYPE), ctrl->type);
+ }
/* Respond to the setup command if data was returned. On an error return
* value (ret < 0), the USB driver will stall EP0.
diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
index 814478686..bde6b227b 100644
--- a/nuttx/include/nuttx/usb/usbdev_trace.h
+++ b/nuttx/include/nuttx/usb/usbdev_trace.h
@@ -382,6 +382,7 @@
#define USBMSC_TRACEERR_WRITE6READONLY 0x0075
#define USBMSC_TRACEERR_WRSHUTDOWN 0x0076
#define USBMSC_TRACEERR_WRUNEXPECTED 0x0077
+#define USBMSC_TRACEERR_UNSUPPORTEDTYPE 0x0078
/****************************************************************************
* Public Types