summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-09-15 13:26:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-09-15 13:26:00 +0000
commit893721387a67b3e472506c21bfdb70cd6fe62776 (patch)
treea6e6955ac693b3e9f60acfd6e97955fb01e7154c /nuttx/include
parent18d4d71fbd502bffaaadacb4ab9087426cce7047 (diff)
downloadpx4-nuttx-893721387a67b3e472506c21bfdb70cd6fe62776.tar.gz
px4-nuttx-893721387a67b3e472506c21bfdb70cd6fe62776.tar.bz2
px4-nuttx-893721387a67b3e472506c21bfdb70cd6fe62776.zip
More CDC serial updates
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3954 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/ioctl.h43
-rwxr-xr-xnuttx/include/nuttx/usb/cdc.h26
-rw-r--r--nuttx/include/nuttx/usb/cdc_serial.h127
3 files changed, 165 insertions, 31 deletions
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
index 194b83715..61fccef88 100644
--- a/nuttx/include/nuttx/ioctl.h
+++ b/nuttx/include/nuttx/ioctl.h
@@ -51,16 +51,17 @@
* defined below:
*/
-#define _TIOCBASE (0x5400) /* Terminal I/O ioctl commands */
-#define _WDIOCBASE (0x5500) /* Watchdog driver ioctl commands */
-#define _FIOCBASE (0x8700) /* File system ioctl commands */
-#define _DIOCBASE (0x8800) /* Character driver ioctl commands */
-#define _BIOCBASE (0x8900) /* Block driver ioctl commands */
-#define _MTDIOCBASE (0x8a00) /* MTD ioctl commands */
-#define _SIOCBASE (0x8b00) /* Socket ioctl commands */
-#define _ARPBASE (0x8c00) /* ARP ioctl commands */
-#define _TSBASE (0x8d00) /* Touchscreen ioctl commands */
-#define _SNBASE (0x8e00) /* Sensor ioctl commands */
+#define _TIOCBASE (0x0100) /* Terminal I/O ioctl commands */
+#define _WDIOCBASE (0x0200) /* Watchdog driver ioctl commands */
+#define _FIOCBASE (0x0300) /* File system ioctl commands */
+#define _DIOCBASE (0x0400) /* Character driver ioctl commands */
+#define _BIOCBASE (0x0500) /* Block driver ioctl commands */
+#define _MTDIOCBASE (0x0600) /* MTD ioctl commands */
+#define _SIOCBASE (0x0700) /* Socket ioctl commands */
+#define _ARPIOCBASE (0x0800) /* ARP ioctl commands */
+#define _TSIOCBASE (0x0900) /* Touchscreen ioctl commands */
+#define _SNIOCBASE (0x0a00) /* Sensor ioctl commands */
+#define _CAIOCBASE (0x0b00) /* CDC/ACM ioctl commands */
/* Macros used to manage ioctl commands */
@@ -159,18 +160,24 @@
/* NuttX ARP driver ioctl definitions (see netinet/arp.h) *******************/
-#define _ARPIOCVALID(c) (_IOC_TYPE(c)==_ARPBASE)
-#define _ARPIOC(nr) _IOC(_ARPBASE,nr)
+#define _ARPIOCVALID(c) (_IOC_TYPE(c)==_ARPIOCBASE)
+#define _ARPIOC(nr) _IOC(_ARPIOCBASE,nr)
-/* NuttX ARP touchscreen ioctl definitions (see nuttx/input/touchscreen.h) **/
+/* NuttX touchscreen ioctl definitions (see nuttx/input/touchscreen.h) ******/
-#define _TSIOCVALID(c) (_IOC_TYPE(c)==_TSBASE)
-#define _TSIOC(nr) _IOC(_TSBASE,nr)
+#define _TSIOCVALID(c) (_IOC_TYPE(c)==_TSIOCBASE)
+#define _TSIOC(nr) _IOC(_TSIOCBASE,nr)
-/* NuttX ARP sensor ioctl definitions (see nuttx/sensor/*.h) ****************/
+/* NuttX sensor ioctl definitions (see nuttx/sensor/*.h) ********************/
-#define _SNIOCVALID(c) (_IOC_TYPE(c)==_SNBASE)
-#define _SNIOC(nr) _IOC(_SNBASE,nr)
+#define _SNIOCVALID(c) (_IOC_TYPE(c)==_SNIOCBASE)
+#define _SNIOC(nr) _IOC(_SNIOCBASE,nr)
+
+/* NuttX USB CDC/ACM serial driver ioctl definitions ************************/
+/* (see nuttx/usb/cdc_serial.h) */
+
+#define _CAIOCVALID(c) (_IOC_TYPE(c)==_CAIOCBASE)
+#define _CAIOC(nr) _IOC(_CAIOCBASE,nr)
/****************************************************************************
* Public Type Definitions
diff --git a/nuttx/include/nuttx/usb/cdc.h b/nuttx/include/nuttx/usb/cdc.h
index 4d75356db..53b19b5a2 100755
--- a/nuttx/include/nuttx/usb/cdc.h
+++ b/nuttx/include/nuttx/usb/cdc.h
@@ -408,15 +408,26 @@
#define CDC_PARITY_MARK 3 /* Mark parity */
#define CDC_PARITY_SPACE 4 /* Space parity */
+/* Table 51: Control Signal Bitmap Values for SetControlLineState */
+
+#define CDC_DTE_PRESENT (1 << 0) /* Indicates to DCE if DTE is present or not.
+ * This signal corresponds to V.24 signal
+ * 108/2 and RS-232 signal DTR.
+ */
+#define CDC_ACTIVATE_CARRIER (1 << 1) /* Carrier control for half duplex modems.
+ * This signal corresponds to V.24 signal
+ * 105 and RS-232 signal RTS.
+ */
+
/* Table 58: Call State Value Definitions */
-#define CDC_CALLST_IDLE 0x00 /* Call is idle */
-#define CDC_CALLST_DIAL 0x01 /* Typical dial tone */
-#define CDC_CALLST_INTDIAL 0x02 /* Interrupted dial tone */
-#define CDC_CALLST_DIALING 0x03 /* Dialing is in progress */
-#define CDC_CALLST_RINGBACK 0x04 /* Ringback */
-#define CDC_CALLST_CONNECTED 0x05 /* Connected */
-#define CDC_CALLSTINCOMING 0x06 /* Incoming call */
+#define CDC_CALLST_IDLE 0x00 /* Call is idle */
+#define CDC_CALLST_DIAL 0x01 /* Typical dial tone */
+#define CDC_CALLST_INTDIAL 0x02 /* Interrupted dial tone */
+#define CDC_CALLST_DIALING 0x03 /* Dialing is in progress */
+#define CDC_CALLST_RINGBACK 0x04 /* Ringback */
+#define CDC_CALLST_CONNECTED 0x05 /* Connected */
+#define CDC_CALLSTINCOMING 0x06 /* Incoming call */
/* Table 62: Ethernet Packet Filter Bitmap */
@@ -513,7 +524,6 @@
/* Notifications ****************************************************************************/
/* Table 69: UART State Bitmap Values */
-
#define CDC_UART_RXCARRIER (1 << 0) /* bRxCarrier State of receiver carrier detection
* mechanism of device. This signal corresponds to
* V.24 signal 109 and RS-232 signal DCD.
diff --git a/nuttx/include/nuttx/usb/cdc_serial.h b/nuttx/include/nuttx/usb/cdc_serial.h
index 7d5a706b4..72410a22d 100644
--- a/nuttx/include/nuttx/usb/cdc_serial.h
+++ b/nuttx/include/nuttx/usb/cdc_serial.h
@@ -41,12 +41,56 @@
****************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/ioctl.h>
#include <nuttx/usb/usb.h>
/****************************************************************************
* Preprocessor definitions
****************************************************************************/
/* Configuration ************************************************************/
+/* CONFIG_CDCSER
+ * Enable compilation of the USB serial driver
+ * CONFIG_CDCSER_EP0MAXPACKET
+ * Endpoint 0 max packet size. Default 8.
+ * CONFIG_CDCSER_EPINTIN
+ * The logical 7-bit address of a hardware endpoint that supports
+ * interrupt IN operation. Default 2.
+ * CONFIG_CDCSER_EPINTIN_FSSIZE
+ * Max package size for the interrupt IN endpoint if full speed mode.
+ * Default 64.
+ * CONFIG_CDCSER_EPINTIN_HSSIZE
+ * Max package size for the interrupt IN endpoint if high speed mode.
+ * Default 512.
+ * CONFIG_CDCSER_EPBULKOUT
+ * The logical 7-bit address of a hardware endpoint that supports
+ * bulk OUT operation
+ * CONFIG_CDCSER_EPBULKOUT_FSSIZE
+ * Max package size for the bulk OUT endpoint if full speed mode.
+ * Default 64.
+ * CONFIG_CDCSER_EPBULKOUT_HSSIZE
+ * Max package size for the bulk OUT endpoint if high speed mode.
+ * Default 512.
+ * CONFIG_CDCSER_EPBULKIN
+ * The logical 7-bit address of a hardware endpoint that supports
+ * bulk IN operation
+ * CONFIG_CDCSER_EPBULKIN_FSSIZE
+ * Max package size for the bulk IN endpoint if full speed mode.
+ * Default 64.
+ * CONFIG_CDCSER_EPBULKIN_HSSIZE
+ * Max package size for the bulk IN endpoint if high speed mode.
+ * Default 512.
+ * CONFIG_CDCSER_NWRREQS and CONFIG_CDCSER_NRDREQS
+ * The number of write/read requests that can be in flight.
+ * CONFIG_CDCSER_NWRREQS includes write requests used for both the
+ * interrupt and bulk IN endpoints. Default 4.
+ * CONFIG_CDCSER_VENDORID and CONFIG_CDCSER_VENDORSTR
+ * The vendor ID code/string. Default 0x03eb and "NuttX"
+ * CONFIG_CDCSER_PRODUCTID and CONFIG_CDCSER_PRODUCTSTR
+ * The product ID code/string. Default 0x204b and "CDC/ACM Serial"
+ * CONFIG_CDCSER_RXBUFSIZE and CONFIG_CDCSER_TXBUFSIZE
+ * Size of the serial receive/transmit buffers. Default 256.
+ */
+
/* EP0 max packet size */
#ifndef CONFIG_CDCSER_EP0MAXPACKET
@@ -103,7 +147,9 @@
# define CONFIG_CDCSER_EPBULKOUT_HSSIZE 512
#endif
-/* Number of requests in the write queue */
+/* Number of requests in the write queue. This includes write requests used
+ * for both the interrupt and bulk IN endpoints.
+ */
#ifndef CONFIG_CDCSER_NWRREQS
# define CONFIG_CDCSER_NWRREQS 4
@@ -167,12 +213,41 @@
# define CONFIG_USBDEV_MAXPOWER 100
#endif
-/****************************************************************************
- * Public Types
- ****************************************************************************/
+/* IOCTL Commands ***********************************************************/
+/* The USB serial driver will support a subset of the TIOC IOCTL commands
+ * defined in include/nuttx/tioctl.h. This subset includes:
+ *
+ * CAICO_REGISTERCB
+ * Register a callback for serial event notification. Argument:
+ * cdcser_callback_t. See cdcser_callback_t type definition below.
+ * NOTE: The callback will most likely invoked at the interrupt level.
+ * The called back function should, therefore, limit its operations to
+ * invoking some kind of IPC to handle the serial event in some normal
+ * task environment.
+ * CAIOC_GETLINECODING
+ * Get current line coding. Argument: struct cdc_linecoding_s*.
+ * See include/nuttx/usb/cdc.h for structure definition. This IOCTL
+ * should be called to get the data associated with the
+ * CDCSER_EVENT_LINECODING event (see devent definition below).
+ * CAIOC_GETCTRLLINE
+ * Get control line status bits. Argument FAR int*. See
+ * include/nuttx/usb/cdc.h for bit definitions. This IOCTL should be
+ * called to get the data associated CDCSER_EVENT_CTRLLINE event (see event
+ * definition below).
+ * CAIOC_NOTIFY
+ * Send a serial state to the host via the Interrupt IN endpoint.
+ * Argument: int. This includes the current state of the carrier detect,
+ * DSR, break, and ring signal. See "Table 69: UART State Bitmap Values"
+ * and CDC_UART_definitions in include/nuttx/usb/cdc.h.
+ */
+
+#define CAIOC_REGISTERCB _CAIOC(0x0001)
+#define CAIOC_GETLINECODING _CAIOC(0x0002)
+#define CAIOC_GETCTRLLINE _CAIOC(0x0003)
+#define CAIOC_NOTIFY _CAIOC(0x0004)
/****************************************************************************
- * Public Function Prototypes
+ * Public Types
****************************************************************************/
#undef EXTERN
@@ -183,6 +258,48 @@ extern "C" {
# define EXTERN extern
#endif
+/* Reported serial events. Data is associated with CDCSER_EVENT_LINECODING
+ * and CDCSER_EVENT_CTRLLINE. The data may be obtained using CDCSER IOCTL
+ * commands described above.
+ *
+ * CDCSER_EVENT_LINECODING - See "Table 50: Line Coding Structure" and struct
+ * cdc_linecoding_s in include/nuttx/usb/cdc.h.
+ * CDCSER_EVENT_CTRLLINE - See "Table 51: Control Signal Bitmap Values for
+ * SetControlLineState" and definitions in include/nutt/usb/cdc.h
+ * CDCSER_EVENT_SENDBREAK - See Paragraph "6.2.15 SendBreak." This request
+ * sends special carrier modulation that generates an RS-232 style break.
+ */
+
+enum cdcser_event_e
+{
+ CDCSER_EVENT_LINECODING = 0, /* New line coding received from host */
+ CDCSER_EVENT_CTRLLINE, /* New control line status received from host */
+ CDCSER_EVENT_SENDBREAK /* Send break request received */
+};
+
+typedef FAR void (*cdcser_callback_t)(enum cdcser_event_e event);
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: cdcser_initialize
+ *
+ * Description:
+ * Register USB serial port (and USB serial console if so configured).
+ *
+ * Input Parameter:
+ * Device minor number. E.g., minor 0 would correspond to /dev/ttyUSB0.
+ *
+ * Returned Value:
+ * Zero (OK) means that the driver was successfully registered. On any
+ * failure, a negated errno value is retured.
+ *
+ ****************************************************************************/
+
+EXTERN int cdcser_initialize(int minor);
+
#undef EXTERN
#if defined(__cplusplus)
}