lm4f: Add USB to serial (CDCACM) example

Implements a USB-to-serial adapter, compliant to the CDCACM subclass.
UART1 is used for the TX/RX lines. Although UART1 also has lines for flow
control, they are not used. Instead, the control lines are implemented in
software via GPIOA.

Signed-off-by: Alexandru Gagniuc <mr.nuke.me@gmail.com>
This commit is contained in:
Alexandru Gagniuc
2013-05-15 00:21:33 -05:00
committed by Piotr Esden-Tempski
parent f5b0aa5638
commit 28f92cce2b
6 changed files with 767 additions and 0 deletions

View File

@@ -0,0 +1,27 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usb_to_serial_cdcacm
LDSCRIPT = ../ek-lm4f120xl.ld
OBJS += uart.o usb_cdcacm.o
include ../../Makefile.include

View File

@@ -0,0 +1,42 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example demonstrates the following:
* Using the USB controller
* Setting up a simple usb to serial converter (CDCACM)
File list:
* usb_cdcacm.c - implementation of the CDCACM subclass
* uart.c - implementation of UART peripheral
* usb_to_serial_cdcacm.c - glue logic between UART and CDCACM device
* usb_to_serial_cdcacm.h - common definitions
Implements a USB-to-serial adapter, compliant to the CDCACM subclass. UART1 is
used for the TX/RX lines. Although UART1 also has lines for flow control, they
are not used. Instead, the control lines are implemented in software via GPIOA.
The following pinout is used:
Tx <- PB1
Rx -> PB0
DCD -> PA2
DSR -> PA3
RI -> PA4
CTS -> PA5 (UNUSED)
DTR <- PA6
RTS <- PA7
Note that the CTS pin is unused. The CDCACM specification does not define a way
to control this pin, nor does it define a way to switch between flow control
mechanisms.
The glue logic in usb_to_serial_cdcacm.c receives requests from both the UART
and CDCACM interface, and forward them to their destination, while also
controlling the LEDs
The green LED is lit as long as either DTR or RTS are high.
The red LED is lit while the UART is sending data.
The blue LED is lit while data is read from the UART.
The red and blue LEDs will only be lit for very short periods of time, thus they
may be difficult to notice.

View File

@@ -0,0 +1,99 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012-2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* \addtogroup Examples
*
*/
/*
* Pins handled by hw peripheral:
* Tx <-> PB1
* Rx <-> PB0
* Input pins handled manually via interrupts:
* DCD <-> PA2
* DSR <-> PA3
* RI <-> PA4
* CTS <-> PA5 (UNUSED)
* Output pins handled via commands from the host:
* DTR <-> PA6
* RTS <-> PA7
*/
#include "usb_to_serial_cdcacm.h"
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/uart.h>
#include <libopencm3/lm4f/nvic.h>
static void uart_ctl_line_setup(void)
{
u32 inpins, outpins;
inpins = PIN_DCD | PIN_DSR | PIN_RI | PIN_CTS;
outpins = PIN_DTR | PIN_RTS;
gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, outpins);
gpio_mode_setup(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, inpins);
}
void uart_init(void)
{
/* Enable GPIOA and GPIOB in run mode. */
periph_clock_enable(RCC_GPIOB);
periph_clock_enable(RCC_GPIOA);
uart_ctl_line_setup();
/* Mux PB0 and PB1 to AF1 (UART1 in this case) */
gpio_set_af(GPIOB, 1, GPIO0 | GPIO1);
/* Enable the UART clock */
periph_clock_enable(RCC_UART1);
/* Disable the UART while we mess with its setings */
uart_disable(UART1);
/* Configure the UART clock source */
uart_clock_from_piosc(UART1);
/* We don't make any other settings here. */
uart_enable(UART1);
/* Ping us when something comes in */
uart_enable_rx_interrupt(UART1);
nvic_enable_irq(NVIC_UART1_IRQ);
}
u8 uart_get_ctl_line_state(void)
{
return gpio_read(GPIOA, PIN_RI | PIN_DSR | PIN_DCD);
}
void uart_set_ctl_line_state(u8 dtr, u8 rts)
{
u8 val = 0;
val |= dtr ? PIN_DTR : 0;
val |= rts ? PIN_RTS : 0;
gpio_write(GPIOA, PIN_DTR | PIN_RTS, val);
}
void uart1_isr(void)
{
u8 rx;
rx = uart_recv(UART1);
glue_data_recieved_cb(&rx, 1);
uart_clear_interrupt_flag(UART1, UART_INT_RX);
}

View File

@@ -0,0 +1,303 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
* Copyright (C) 2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include "usb_to_serial_cdcacm.h"
#include <stdlib.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/cdc.h>
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/lm4f/nvic.h>
#include <libopencm3/lm4f/usb.h>
static const struct usb_device_descriptor dev = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x2000,
.bDeviceClass = USB_CLASS_CDC,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0xc03e,
.idProduct = 0xb007,
.bcdDevice = 0x2000,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
/*
* This notification endpoint isn't implemented. According to CDC spec it's
* optional, but its absence causes a NULL pointer dereference in the
* Linux cdc_acm driver.
*/
static const struct usb_endpoint_descriptor comm_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x83,
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
.wMaxPacketSize = 16,
.bInterval = 1,
}};
static const struct usb_endpoint_descriptor data_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x01,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x82,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}};
static const struct {
struct usb_cdc_header_descriptor header;
struct usb_cdc_call_management_descriptor call_mgmt;
struct usb_cdc_acm_descriptor acm;
struct usb_cdc_union_descriptor cdc_union;
} __attribute__ ((packed)) cdcacm_functional_descriptors = {
.header = {
.bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_HEADER,
.bcdCDC = 0x0110,
},
.call_mgmt = {
.bFunctionLength =
sizeof(struct usb_cdc_call_management_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
.bmCapabilities = 0,
.bDataInterface = 1,
},
.acm = {
.bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_ACM,
.bmCapabilities = (1 << 1),
},
.cdc_union = {
.bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_UNION,
.bControlInterface = 0,
.bSubordinateInterface0 = 1,
}
};
static const struct usb_interface_descriptor comm_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_CDC,
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
.bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
.iInterface = 0,
.endpoint = comm_endp,
.extra = &cdcacm_functional_descriptors,
.extralen = sizeof(cdcacm_functional_descriptors)
}};
static const struct usb_interface_descriptor data_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
.endpoint = data_endp,
}};
static const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = comm_iface,
}, {
.num_altsetting = 1,
.altsetting = data_iface,
}};
static const struct usb_config_descriptor config = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 0x32,
.interface = ifaces,
};
static const char *usb_strings[] = {
"libopencm3",
"usb_to_serial_cdcacm",
"none",
"DEMO",
};
usbd_device *acm_dev;
u8 usbd_control_buffer[128];
extern usbd_driver lm4f_usb_driver;
static int cdcacm_control_request(usbd_device * usbd_dev,
struct usb_setup_data *req, u8 ** buf,
u16 * len,
void (**complete) (usbd_device * usbd_dev,
struct usb_setup_data *
req))
{
u8 dtr, rts;
(void)complete;
(void)buf;
(void)usbd_dev;
switch (req->bRequest) {
case USB_CDC_REQ_SET_CONTROL_LINE_STATE:{
/*
* This Linux cdc_acm driver requires this to be implemented
* even though it's optional in the CDC spec, and we don't
* advertise it in the ACM functional descriptor.
*/
dtr = (req->wValue & (1 << 0)) ? 1 : 0;
rts = (req->wValue & (1 << 1)) ? 1 : 0;
glue_set_line_state_cb(dtr, rts);
return 1;
}
case USB_CDC_REQ_SET_LINE_CODING:{
struct usb_cdc_line_coding *coding;
if (*len < sizeof(struct usb_cdc_line_coding))
return 0;
coding = (struct usb_cdc_line_coding *)*buf;
return glue_set_line_coding_cb(coding->dwDTERate,
coding->bDataBits,
coding->bParityType,
coding->bCharFormat);
}
}
return 0;
}
static void cdcacm_data_rx_cb(usbd_device * usbd_dev, u8 ep)
{
u8 buf[64];
(void)ep;
int len = usbd_ep_read_packet(usbd_dev, 0x01, buf, 64);
glue_send_data_cb(buf, len);
}
void cdcacm_send_data(u8 * buf, u16 len)
{
usbd_ep_write_packet(acm_dev, 0x82, buf, len);
}
static void cdcacm_set_config(usbd_device * usbd_dev, u16 wValue)
{
(void)wValue;
usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64,
cdcacm_data_rx_cb);
usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
usbd_register_control_callback(usbd_dev,
USB_REQ_TYPE_CLASS |
USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE |
USB_REQ_TYPE_RECIPIENT,
cdcacm_control_request);
}
void cdcacm_line_state_changed_cb(u8 linemask)
{
const int size = sizeof(struct usb_cdc_notification) + 2;
u8 buf[size];
struct usb_cdc_notification *notify = (void *)buf;
notify->bmRequestType = 0xa1;
notify->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
notify->wValue = 0;
notify->wIndex = 1;
notify->wLength = 2;
u16 *data = (void *)&buf[sizeof(struct usb_cdc_notification)];
*data = linemask;
while (usbd_ep_write_packet(acm_dev, 0x83, buf, size) == size) ;
}
static void usb_pins_setup(void)
{
/* USB pins are connected to port D */
periph_clock_enable(RCC_GPIOD);
/* Mux USB pins to their analog function */
gpio_mode_setup(GPIOD, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO4 | GPIO5);
}
static void usb_ints_setup(void)
{
u8 usbints;
/* Gimme some interrupts */
usbints = USB_INT_RESET | USB_INT_DISCON | USB_INT_RESUME | USB_INT_SUSPEND; //| USB_IM_SOF;
usb_enable_interrupts(usbints, 0xff, 0xff);
nvic_enable_irq(NVIC_USB0_IRQ);
}
void cdcacm_init(void)
{
usbd_device *usbd_dev;
usb_pins_setup();
usbd_dev = usbd_init(&lm4f_usb_driver, &dev, &config, usb_strings, 4,
usbd_control_buffer, sizeof(usbd_control_buffer));
acm_dev = usbd_dev;
usbd_register_set_config_callback(usbd_dev, cdcacm_set_config);
usb_ints_setup();
}
void usb0_isr(void)
{
usbd_poll(acm_dev);
}

View File

@@ -0,0 +1,206 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
* Copyright (C) 2012-2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* \addtogroup Examples
*
* Flashes the Red, Green and Blue diodes on the board, in order.
*
* RED controlled by PF1
* Green controlled by PF3
* Blue controlled by PF2
*/
#include "usb_to_serial_cdcacm.h"
#include <libopencm3/lm4f/systemcontrol.h>
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/lm4f/uart.h>
#include <libopencm3/lm4f/nvic.h>
#include <libopencm3/cm3/scb.h>
#define PLL_DIV_80MHZ 5
/* This is how the RGB LED is connected on the stellaris launchpad */
#define RGB_PORT GPIOF
enum {
LED_R = GPIO1,
LED_G = GPIO3,
LED_B = GPIO2,
};
/*
* Clock setup:
* Take the main crystal oscillator at 16MHz, run it through the PLL, and divide
* the 400MHz PLL clock to get a system clock of 80MHz.
*/
static void clock_setup(void)
{
rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLL_DIV_80MHZ);
}
/*
* GPIO setup:
* Enable the pins driving the RGB LED as outputs.
*/
static void gpio_setup(void)
{
/*
* Configure GPIOF
* This port is used to control the RGB LED
*/
periph_clock_enable(RCC_GPIOF);
const u32 opins = (LED_R | LED_G | LED_B);
gpio_mode_setup(RGB_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, opins);
gpio_set_output_config(RGB_PORT, GPIO_OTYPE_PP, GPIO_DRIVE_2MA, opins);
}
static void cm4f_enable_fpu(void)
{
/* Enable FPU */
SCB_CPACR |= SCB_CPACR_FULL * (SCB_CPACR_CP10 | SCB_CPACR_CP11);
/* Wait for store to complete */
__asm__("DSB");
/* Reset pipeline. Now the FPU is enabled */
__asm__("ISB");
}
void glue_data_recieved_cb(u8 * buf, u16 len)
{
/* Blue LED indicates data coming in */
gpio_set(RGB_PORT, LED_B);
cdcacm_send_data(buf, len);
gpio_clear(RGB_PORT, LED_B);
}
void glue_set_line_state_cb(u8 dtr, u8 rts)
{
/* Green LED indicated one of the control lines are active */
if (dtr || rts)
gpio_set(RGB_PORT, LED_G);
else
gpio_clear(RGB_PORT, LED_G);
uart_set_ctl_line_state(dtr, rts);
}
int glue_set_line_coding_cb(u32 baud, u8 databits,
enum usb_cdc_line_coding_bParityType cdc_parity,
enum usb_cdc_line_coding_bCharFormat cdc_stopbits)
{
enum uart_parity parity;
u8 uart_stopbits;
if (databits < 5 || databits > 8)
return 0;
switch (cdc_parity) {
case USB_CDC_NO_PARITY:
parity = UART_PARITY_NONE;
break;
case USB_CDC_ODD_PARITY:
parity = UART_PARITY_ODD;
break;
case USB_CDC_EVEN_PARITY:
parity = UART_PARITY_EVEN;
break;
default:
return 0;
}
switch (cdc_stopbits) {
case USB_CDC_1_STOP_BITS:
uart_stopbits = 1;
break;
case USB_CDC_2_STOP_BITS:
uart_stopbits = 2;
break;
default:
return 0;
}
/* Disable the UART while we mess with its settings */
uart_disable(UART1);
/* Set communication parameters */
uart_set_baudrate(UART1, baud);
uart_set_databits(UART1, databits);
uart_set_parity(UART1, parity);
uart_set_stopbits(UART1, uart_stopbits);
/* Back to work. */
uart_enable(UART1);
return 1;
}
void glue_send_data_cb(u8 * buf, u16 len)
{
int i;
/* Red LED indicates data going out */
gpio_set(RGB_PORT, LED_R);
for (i = 0; i < len; i++) {
uart_send_blocking(UART1, buf[i]);
}
gpio_clear(RGB_PORT, LED_R);
}
static void mainloop(void)
{
u8 linestate, cdcacmstate;
static u8 oldlinestate = 0;
/* See if the state of control lines has changed */
linestate = uart_get_ctl_line_state();
if (oldlinestate != linestate) {
/* Inform host of state change */
cdcacmstate = 0;
if (linestate & PIN_RI)
cdcacmstate |= CDCACM_RI;
if (linestate & PIN_DSR)
cdcacmstate |= CDCACM_DSR;
if (linestate & PIN_DCD)
cdcacmstate |= CDCACM_DCD;
cdcacm_line_state_changed_cb(cdcacmstate);
}
oldlinestate = linestate;
}
int main(void)
{
gpio_enable_ahb_aperture();
clock_setup();
gpio_setup();
cdcacm_init();
uart_init();
cm4f_enable_fpu();
while (1)
mainloop();
return 0;
}

View File

@@ -0,0 +1,90 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/**@{*/
#ifndef __STELLARIS_EK_LM4F120XL_USB_TO_SERIAL_CDCACM_H
#define __STELLARIS_EK_LM4F120XL_USB_TO_SERIAL_CDCACM_H
#include <libopencm3/cm3/common.h>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/usb/cdc.h>
/* =============================================================================
* Definitions missing from cdc.h
*
* TODO: Integrate those definitions into cdc.h
* ---------------------------------------------------------------------------*/
/* Table 17: Line Coding Structure */
enum usb_cdc_line_coding_bCharFormat {
USB_CDC_1_STOP_BITS = 0,
USB_CDC_1_5_STOP_BITS = 1,
USB_CDC_2_STOP_BITS = 2,
};
enum usb_cdc_line_coding_bParityType {
USB_CDC_NO_PARITY = 0,
USB_CDC_ODD_PARITY = 1,
USB_CDC_EVEN_PARITY = 2,
USB_CDC_MARK_PARITY = 3,
USB_CDC_SPACE_PARITY = 4,
};
/* =============================================================================
* UART control
* ---------------------------------------------------------------------------*/
enum rs232pin {
PIN_DCD = GPIO2,
PIN_DSR = GPIO3,
PIN_RI = GPIO4,
PIN_CTS = GPIO5,
PIN_DTR = GPIO6,
PIN_RTS = GPIO7,
};
void uart_init(void);
u8 uart_get_ctl_line_state(void);
void uart_set_ctl_line_state(u8 dtr, u8 rts);
/* =============================================================================
* CDCACM control
* ---------------------------------------------------------------------------*/
enum cdc_serial_state_line {
CDCACM_DCD = (1 << 0),
CDCACM_DSR = (1 << 1),
CDCACM_RI = (1 << 3),
};
void cdcacm_init(void);
void cdcacm_line_state_changed_cb(u8 linemask);
void cdcacm_send_data(u8 *buf, u16 len);
/* =============================================================================
* CDCACM <-> UART glue
* ---------------------------------------------------------------------------*/
void glue_data_recieved_cb(u8 *buf, u16 len);
void glue_set_line_state_cb(u8 dtr, u8 rts);
int glue_set_line_coding_cb(u32 baud, u8 databits,
enum usb_cdc_line_coding_bParityType cdc_parity,
enum usb_cdc_line_coding_bCharFormat cdc_stopbits);
void glue_send_data_cb(u8 *buf, u16 len);
#endif /* __STELLARIS_EK_LM4F120XL_USB_TO_SERIAL_CDCACM_H */
/**@}*/