Skip to content

Commit

Permalink
Move CDC descriptors to composite device, using structures
Browse files Browse the repository at this point in the history
This replaces the descriptor byte arrays from usbd_cdc_core.c

The following changes were made to the descriptor content:
* The device is self-powered
* Don't set flag indicating that it accepts AT commands
* Remove Call Management Functional Descriptor
  • Loading branch information
kevinmehall committed Aug 19, 2015
1 parent 6493c8f commit 430c01d
Show file tree
Hide file tree
Showing 5 changed files with 205 additions and 3 deletions.
45 changes: 45 additions & 0 deletions src/include/cdc_standard.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
#pragma once

#define CDC_INTERFACE_CLASS 0x02
#define CDC_INTERFACE_SUBCLASS_ACM 0x02
#define CDC_INTERFACE_CLASS_DATA 0x0A

#define CDC_SUBTYPE_HEADER 0x00
#define CDC_SUBTYPE_ACM 0x02
#define CDC_SUBTYPE_UNION 0x06

#define CDC_SEND_ENCAPSULATED_COMMAND 0x0
#define CDC_GET_ENCAPSULATED_RESPONSE 0x1
#define CDC_SET_LINE_ENCODING 0x20
#define CDC_GET_LINE_ENCODING 0x21
#define CDC_SET_CONTROL_LINE_STATE 0x22
#define CDC_SEND_BREAK 0x23

typedef struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint16_t bcdCDC;
} __attribute__((packed)) CDC_FunctionalHeaderDescriptor;

typedef struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bmCapabilities;
} __attribute__((packed)) CDC_FunctionalACMDescriptor;

typedef struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bMasterInterface;
uint8_t bSlaveInterface;
} __attribute__((packed)) CDC_FunctionalUnionDescriptor;

typedef struct {
uint32_t baud_rate;
uint8_t char_format;
uint8_t parity_type;
uint8_t data_bits;
} __attribute__((packed)) CDC_LineEncoding;
2 changes: 1 addition & 1 deletion inc/usb_standard.h → src/include/usb_standard.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ enum {
USB_DTYPE_InterfaceAssociation = 0x0B,
USB_DTYPE_CSInterface = 0x24,
USB_DTYPE_CSEndpoint = 0x25,
} USB_dtype;
};

typedef enum {
USB_CSCP_NoDeviceClass = 0x00,
Expand Down
3 changes: 2 additions & 1 deletion src/modules/flow/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@


__ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END;
extern USBD_Class_cb_TypeDef custom_composite_cb;

/* timer constants */
#define SONAR_POLL_MS 100 /* steps in milliseconds ticks */
Expand Down Expand Up @@ -240,7 +241,7 @@ int main(void)
USBD_Init( &USB_OTG_dev,
USB_OTG_FS_CORE_ID,
&USR_desc,
&USBD_CDC_cb,
&custom_composite_cb,
&USR_cb);

/* init mavlink */
Expand Down
3 changes: 2 additions & 1 deletion src/modules/flow/module.mk
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,8 @@ SRCS += main.c \
camera.c \
filter.c \
result_accumulator.c \
timer.c
timer.c \
usb_composite.c \


SRCS += $(ST_LIB)STM32F4xx_StdPeriph_Driver/src/misc.c \
Expand Down
155 changes: 155 additions & 0 deletions src/modules/flow/usb_composite.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
#include "usb_standard.h"
#include "cdc_standard.h"
#include "usbd_conf.h"
#include "usbd_cdc_core.h"

#define INTERFACE_CDC_CONTROL 0
#define INTERFACE_CDC_DATA 1

typedef struct ConfigDesc {
USB_ConfigurationDescriptor Config;

USB_InterfaceDescriptor CDC_control_interface;
CDC_FunctionalHeaderDescriptor CDC_functional_header;
CDC_FunctionalACMDescriptor CDC_functional_ACM;
CDC_FunctionalUnionDescriptor CDC_functional_union;
USB_EndpointDescriptor CDC_notification_endpoint;

USB_InterfaceDescriptor CDC_data_interface;
USB_EndpointDescriptor CDC_out_endpoint;
USB_EndpointDescriptor CDC_in_endpoint;
} __attribute__((packed)) ConfigDesc;

const ConfigDesc configuration_descriptor = {
.Config = {
.bLength = sizeof(USB_ConfigurationDescriptor),
.bDescriptorType = USB_DTYPE_Configuration,
.wTotalLength = sizeof(ConfigDesc),
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = USB_CONFIG_ATTR_BUSPOWERED,
.bMaxPower = USB_CONFIG_POWER_MA(500)
},
.CDC_control_interface = {
.bLength = sizeof(USB_InterfaceDescriptor),
.bDescriptorType = USB_DTYPE_Interface,
.bInterfaceNumber = INTERFACE_CDC_CONTROL,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = CDC_INTERFACE_CLASS,
.bInterfaceSubClass = CDC_INTERFACE_SUBCLASS_ACM,
.bInterfaceProtocol = 0,
.iInterface = 0,
},
.CDC_functional_header = {
.bLength = sizeof(CDC_FunctionalHeaderDescriptor),
.bDescriptorType = USB_DTYPE_CSInterface,
.bDescriptorSubtype = CDC_SUBTYPE_HEADER,
.bcdCDC = 0x0110,
},
.CDC_functional_ACM = {
.bLength = sizeof(CDC_FunctionalACMDescriptor),
.bDescriptorType = USB_DTYPE_CSInterface,
.bDescriptorSubtype = CDC_SUBTYPE_ACM,
.bmCapabilities = 0x00,
},
.CDC_functional_union = {
.bLength = sizeof(CDC_FunctionalUnionDescriptor),
.bDescriptorType = USB_DTYPE_CSInterface,
.bDescriptorSubtype = CDC_SUBTYPE_UNION,
.bMasterInterface = INTERFACE_CDC_CONTROL,
.bSlaveInterface = INTERFACE_CDC_DATA,
},
.CDC_notification_endpoint = {
.bLength = sizeof(USB_EndpointDescriptor),
.bDescriptorType = USB_DTYPE_Endpoint,
.bEndpointAddress = CDC_CMD_EP,
.bmAttributes = (USB_EP_TYPE_INTERRUPT | ENDPOINT_ATTR_NO_SYNC | ENDPOINT_USAGE_DATA),
.wMaxPacketSize = CDC_CMD_PACKET_SZE,
.bInterval = 0xFF
},
.CDC_data_interface = {
.bLength = sizeof(USB_InterfaceDescriptor),
.bDescriptorType = USB_DTYPE_Interface,
.bInterfaceNumber = INTERFACE_CDC_DATA,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = CDC_INTERFACE_CLASS_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
},
.CDC_out_endpoint = {
.bLength = sizeof(USB_EndpointDescriptor),
.bDescriptorType = USB_DTYPE_Endpoint,
.bEndpointAddress = CDC_OUT_EP,
.bmAttributes = (USB_EP_TYPE_BULK | ENDPOINT_ATTR_NO_SYNC | ENDPOINT_USAGE_DATA),
.wMaxPacketSize = CDC_DATA_MAX_PACKET_SIZE,
.bInterval = 0x0
},
.CDC_in_endpoint = {
.bLength = sizeof(USB_EndpointDescriptor),
.bDescriptorType = USB_DTYPE_Endpoint,
.bEndpointAddress = CDC_IN_EP,
.bmAttributes = (USB_EP_TYPE_BULK | ENDPOINT_ATTR_NO_SYNC | ENDPOINT_USAGE_DATA),
.wMaxPacketSize = CDC_DATA_MAX_PACKET_SIZE,
.bInterval = 0x0
},
};

static uint8_t usb_Init (void *pdev, uint8_t cfgidx);
static uint8_t usb_DeInit (void *pdev, uint8_t cfgidx);
static uint8_t usb_Setup (void *pdev, USB_SETUP_REQ *req);
static uint8_t usb_EP0_RxReady (void *pdev);
static uint8_t usb_DataIn (void *pdev, uint8_t epnum);
static uint8_t usb_DataOut (void *pdev, uint8_t epnum);
static uint8_t usb_SOF (void *pdev);
static uint8_t* usb_GetCfgDesc (uint8_t speed, uint16_t *length);

USBD_Class_cb_TypeDef custom_composite_cb = {
.Init = usb_Init,
.DeInit = usb_DeInit,
.Setup = usb_Setup,
.EP0_TxSent = NULL,
.EP0_RxReady = usb_EP0_RxReady,
.DataIn = usb_DataIn,
.DataOut = usb_DataOut,
.SOF = usb_SOF,
.IsoINIncomplete = NULL,
.IsoOUTIncomplete = NULL,
.GetConfigDescriptor = usb_GetCfgDesc,
};

static uint8_t usb_Init (void *pdev, uint8_t cfgidx) {
return USBD_CDC_cb.Init(pdev, cfgidx);
}

static uint8_t usb_DeInit (void *pdev, uint8_t cfgidx) {
return USBD_CDC_cb.DeInit(pdev, cfgidx);
}

static uint8_t usb_Setup (void *pdev, USB_SETUP_REQ *req) {
return USBD_CDC_cb.Setup(pdev, req);
}

static uint8_t usb_EP0_RxReady (void *pdev) {
return USBD_CDC_cb.EP0_RxReady(pdev);
}

static uint8_t usb_DataIn (void *pdev, uint8_t epnum) {
return USBD_CDC_cb.DataIn(pdev, epnum);
}

static uint8_t usb_DataOut (void *pdev, uint8_t epnum) {
return USBD_CDC_cb.DataOut(pdev, epnum);
}

static uint8_t usb_SOF (void *pdev) {
return USBD_CDC_cb.SOF(pdev);
}

static uint8_t* usb_GetCfgDesc (uint8_t speed, uint16_t *length) {
*length = sizeof (configuration_descriptor);
return (uint8_t*) &configuration_descriptor;
}

0 comments on commit 430c01d

Please sign in to comment.