summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-25 23:04:17 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-25 23:04:17 +0000
commit8f0c521b7b0bc4722d46ba380a7592171eae4420 (patch)
treefd550ef0b0378b85df1a1296000848184fc3b1de /nuttx/include
parent4bd61ddb8690c76e3e1424cf16a43c678b0666da (diff)
downloadpx4-nuttx-8f0c521b7b0bc4722d46ba380a7592171eae4420.tar.gz
px4-nuttx-8f0c521b7b0bc4722d46ba380a7592171eae4420.tar.bz2
px4-nuttx-8f0c521b7b0bc4722d46ba380a7592171eae4420.zip
More name changes: USBSER->PL2303 CDCSER->CDCACM
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4337 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/ioctl.h6
-rw-r--r--nuttx/include/nuttx/usb/cdcacm.h (renamed from nuttx/include/nuttx/usb/cdc_serial.h)170
-rw-r--r--nuttx/include/nuttx/usb/usbdev.h2
-rw-r--r--nuttx/include/nuttx/usb/usbdev_trace.h4
4 files changed, 91 insertions, 91 deletions
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
index 4c17f74d9..dd76c879f 100644
--- a/nuttx/include/nuttx/ioctl.h
+++ b/nuttx/include/nuttx/ioctl.h
@@ -1,8 +1,8 @@
/****************************************************************************
* include/nuttx/ioctl.h
*
- * Copyright (C) 2008, 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008, 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -182,7 +182,7 @@
#define _PWMIOC(nr) _IOC(_PWMIOCBASE,nr)
/* NuttX USB CDC/ACM serial driver ioctl definitions ************************/
-/* (see nuttx/usb/cdc_serial.h) */
+/* (see nuttx/usb/cdcacm.h) */
#define _CAIOCVALID(c) (_IOC_TYPE(c)==_CAIOCBASE)
#define _CAIOC(nr) _IOC(_CAIOCBASE,nr)
diff --git a/nuttx/include/nuttx/usb/cdc_serial.h b/nuttx/include/nuttx/usb/cdcacm.h
index ad2c0e64f..3ca6f52f1 100644
--- a/nuttx/include/nuttx/usb/cdc_serial.h
+++ b/nuttx/include/nuttx/usb/cdcacm.h
@@ -1,8 +1,8 @@
/****************************************************************************
- * include/nuttx/usb/cdc_serial.h
+ * include/nuttx/usb/cdcacm.h
*
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __INCLUDE_NUTTX_USB_CDC_SERIAL_H
-#define __INCLUDE_NUTTX_USB_CDC_SERIAL_H
+#ifndef __INCLUDE_NUTTX_USB_CDCACM_H
+#define __INCLUDE_NUTTX_USB_CDCACM_H
/****************************************************************************
* Included Files
@@ -48,74 +48,74 @@
* Preprocessor definitions
****************************************************************************/
/* Configuration ************************************************************/
-/* CONFIG_CDCSER
+/* CONFIG_CDCACM
* Enable compilation of the USB serial driver
- * CONFIG_CDCSER_EP0MAXPACKET
+ * CONFIG_CDCACM_EP0MAXPACKET
* Endpoint 0 max packet size. Default 64.
- * CONFIG_CDCSER_EPINTIN
+ * CONFIG_CDCACM_EPINTIN
* The logical 7-bit address of a hardware endpoint that supports
* interrupt IN operation. Default 2.
- * CONFIG_CDCSER_EPINTIN_FSSIZE
+ * CONFIG_CDCACM_EPINTIN_FSSIZE
* Max package size for the interrupt IN endpoint if full speed mode.
* Default 64.
- * CONFIG_CDCSER_EPINTIN_HSSIZE
+ * CONFIG_CDCACM_EPINTIN_HSSIZE
* Max package size for the interrupt IN endpoint if high speed mode.
* Default 64.
- * CONFIG_CDCSER_EPBULKOUT
+ * CONFIG_CDCACM_EPBULKOUT
* The logical 7-bit address of a hardware endpoint that supports
* bulk OUT operation
- * CONFIG_CDCSER_EPBULKOUT_FSSIZE
+ * CONFIG_CDCACM_EPBULKOUT_FSSIZE
* Max package size for the bulk OUT endpoint if full speed mode.
* Default 64.
- * CONFIG_CDCSER_EPBULKOUT_HSSIZE
+ * CONFIG_CDCACM_EPBULKOUT_HSSIZE
* Max package size for the bulk OUT endpoint if high speed mode.
* Default 512.
- * CONFIG_CDCSER_EPBULKIN
+ * CONFIG_CDCACM_EPBULKIN
* The logical 7-bit address of a hardware endpoint that supports
* bulk IN operation
- * CONFIG_CDCSER_EPBULKIN_FSSIZE
+ * CONFIG_CDCACM_EPBULKIN_FSSIZE
* Max package size for the bulk IN endpoint if full speed mode.
* Default 64.
- * CONFIG_CDCSER_EPBULKIN_HSSIZE
+ * CONFIG_CDCACM_EPBULKIN_HSSIZE
* Max package size for the bulk IN endpoint if high speed mode.
* Default 512.
- * CONFIG_CDCSER_NWRREQS and CONFIG_CDCSER_NRDREQS
+ * CONFIG_CDCACM_NWRREQS and CONFIG_CDCACM_NRDREQS
* The number of write/read requests that can be in flight.
- * CONFIG_CDCSER_NWRREQS includes write requests used for both the
+ * CONFIG_CDCACM_NWRREQS includes write requests used for both the
* interrupt and bulk IN endpoints. Default 4.
- * CONFIG_CDCSER_VENDORID and CONFIG_CDCSER_VENDORSTR
+ * CONFIG_CDCACM_VENDORID and CONFIG_CDCACM_VENDORSTR
* The vendor ID code/string. Default 0x0525 and "NuttX"
* 0x0525 is the Netchip vendor and should not be used in any
* products. This default VID was selected for compatibility with
* the Linux CDC ACM default VID.
- * CONFIG_CDCSER_PRODUCTID and CONFIG_CDCSER_PRODUCTSTR
+ * CONFIG_CDCACM_PRODUCTID and CONFIG_CDCACM_PRODUCTSTR
* The product ID code/string. Default 0xa4a7 and "CDC/ACM Serial"
* 0xa4a7 was selected for compatibility with the Linux CDC ACM
* default PID.
- * CONFIG_CDCSER_RXBUFSIZE and CONFIG_CDCSER_TXBUFSIZE
+ * CONFIG_CDCACM_RXBUFSIZE and CONFIG_CDCACM_TXBUFSIZE
* Size of the serial receive/transmit buffers. Default 256.
*/
/* EP0 max packet size */
-#ifndef CONFIG_CDCSER_EP0MAXPACKET
-# define CONFIG_CDCSER_EP0MAXPACKET 64
+#ifndef CONFIG_CDCACM_EP0MAXPACKET
+# define CONFIG_CDCACM_EP0MAXPACKET 64
#endif
/* Endpoint number and size (in bytes) of the CDC serial device-to-host (IN)
* notification interrupt endpoint.
*/
-#ifndef CONFIG_CDCSER_EPINTIN
-# define CONFIG_CDCSER_EPINTIN 2
+#ifndef CONFIG_CDCACM_EPINTIN
+# define CONFIG_CDCACM_EPINTIN 2
#endif
-#ifndef CONFIG_CDCSER_EPINTIN_FSSIZE
-# define CONFIG_CDCSER_EPINTIN_FSSIZE 64
+#ifndef CONFIG_CDCACM_EPINTIN_FSSIZE
+# define CONFIG_CDCACM_EPINTIN_FSSIZE 64
#endif
-#ifndef CONFIG_CDCSER_EPINTIN_HSSIZE
-# define CONFIG_CDCSER_EPINTIN_HSSIZE 64
+#ifndef CONFIG_CDCACM_EPINTIN_HSSIZE
+# define CONFIG_CDCACM_EPINTIN_HSSIZE 64
#endif
/* Endpoint number and size (in bytes) of the CDC device-to-host (IN) data
@@ -123,16 +123,16 @@
* or high speed (HS) modes.
*/
-#ifndef CONFIG_CDCSER_EPBULKIN
-# define CONFIG_CDCSER_EPBULKIN 3
+#ifndef CONFIG_CDCACM_EPBULKIN
+# define CONFIG_CDCACM_EPBULKIN 3
#endif
-#ifndef CONFIG_CDCSER_EPBULKIN_FSSIZE
-# define CONFIG_CDCSER_EPBULKIN_FSSIZE 64
+#ifndef CONFIG_CDCACM_EPBULKIN_FSSIZE
+# define CONFIG_CDCACM_EPBULKIN_FSSIZE 64
#endif
-#ifndef CONFIG_CDCSER_EPBULKIN_HSSIZE
-# define CONFIG_CDCSER_EPBULKIN_HSSIZE 512
+#ifndef CONFIG_CDCACM_EPBULKIN_HSSIZE
+# define CONFIG_CDCACM_EPBULKIN_HSSIZE 512
#endif
/* Endpoint number and size (in bytes) of the CDC host-to-device (OUT) data
@@ -140,67 +140,67 @@
* or high speed (HS) modes.
*/
-#ifndef CONFIG_CDCSER_EPBULKOUT
-# define CONFIG_CDCSER_EPBULKOUT 4
+#ifndef CONFIG_CDCACM_EPBULKOUT
+# define CONFIG_CDCACM_EPBULKOUT 4
#endif
-#ifndef CONFIG_CDCSER_EPBULKOUT_FSSIZE
-# define CONFIG_CDCSER_EPBULKOUT_FSSIZE 64
+#ifndef CONFIG_CDCACM_EPBULKOUT_FSSIZE
+# define CONFIG_CDCACM_EPBULKOUT_FSSIZE 64
#endif
-#ifndef CONFIG_CDCSER_EPBULKOUT_HSSIZE
-# define CONFIG_CDCSER_EPBULKOUT_HSSIZE 512
+#ifndef CONFIG_CDCACM_EPBULKOUT_HSSIZE
+# define CONFIG_CDCACM_EPBULKOUT_HSSIZE 512
#endif
/* 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
+#ifndef CONFIG_CDCACM_NWRREQS
+# define CONFIG_CDCACM_NWRREQS 4
#endif
/* Number of requests in the read queue */
-#ifndef CONFIG_CDCSER_NRDREQS
-# define CONFIG_CDCSER_NRDREQS 4
+#ifndef CONFIG_CDCACM_NRDREQS
+# define CONFIG_CDCACM_NRDREQS 4
#endif
/* TX/RX buffer sizes */
-#ifndef CONFIG_CDCSER_RXBUFSIZE
-# define CONFIG_CDCSER_RXBUFSIZE 256
+#ifndef CONFIG_CDCACM_RXBUFSIZE
+# define CONFIG_CDCACM_RXBUFSIZE 256
#endif
-#ifndef CONFIG_CDCSER_TXBUFSIZE
-# define CONFIG_CDCSER_TXBUFSIZE 256
+#ifndef CONFIG_CDCACM_TXBUFSIZE
+# define CONFIG_CDCACM_TXBUFSIZE 256
#endif
/* Vendor and product IDs and strings. The default is the Linux Netchip
* CDC ACM VID and PID.
*/
-#ifndef CONFIG_CDCSER_VENDORID
-# define CONFIG_CDCSER_VENDORID 0x0525
+#ifndef CONFIG_CDCACM_VENDORID
+# define CONFIG_CDCACM_VENDORID 0x0525
#endif
-#ifndef CONFIG_CDCSER_PRODUCTID
-# define CONFIG_CDCSER_PRODUCTID 0xa4a7
+#ifndef CONFIG_CDCACM_PRODUCTID
+# define CONFIG_CDCACM_PRODUCTID 0xa4a7
#endif
-#ifndef CONFIG_CDCSER_VENDORSTR
-# define CONFIG_CDCSER_VENDORSTR "NuttX"
+#ifndef CONFIG_CDCACM_VENDORSTR
+# define CONFIG_CDCACM_VENDORSTR "NuttX"
#endif
-#ifndef CONFIG_CDCSER_PRODUCTSTR
-# define CONFIG_CDCSER_PRODUCTSTR "CDC ACM Serial"
+#ifndef CONFIG_CDCACM_PRODUCTSTR
+# define CONFIG_CDCACM_PRODUCTSTR "CDC ACM Serial"
#endif
-#undef CONFIG_CDCSER_SERIALSTR
-#define CONFIG_CDCSER_SERIALSTR "0"
+#undef CONFIG_CDCACM_SERIALSTR
+#define CONFIG_CDCACM_SERIALSTR "0"
-#undef CONFIG_CDCSER_CONFIGSTR
-#define CONFIG_CDCSER_CONFIGSTR "Bulk"
+#undef CONFIG_CDCACM_CONFIGSTR
+#define CONFIG_CDCACM_CONFIGSTR "Bulk"
/* USB Controller */
@@ -226,7 +226,7 @@
*
* CAICO_REGISTERCB
* Register a callback for serial event notification. Argument:
- * cdcser_callback_t. See cdcser_callback_t type definition below.
+ * cdcacm_callback_t. See cdcacm_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
@@ -235,11 +235,11 @@
* 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).
+ * CDCACM_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
+ * called to get the data associated CDCACM_EVENT_CTRLLINE event (see event
* definition below).
* CAIOC_NOTIFY
* Send a serial state to the host via the Interrupt IN endpoint.
@@ -265,26 +265,26 @@ 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
+/* Reported serial events. Data is associated with CDCACM_EVENT_LINECODING
+ * and CDCACM_EVENT_CTRLLINE. The data may be obtained using CDCACM IOCTL
* commands described above.
*
- * CDCSER_EVENT_LINECODING - See "Table 50: Line Coding Structure" and struct
+ * CDCACM_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
+ * CDCACM_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
+ * CDCACM_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
+enum cdcacm_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 */
+ CDCACM_EVENT_LINECODING = 0, /* New line coding received from host */
+ CDCACM_EVENT_CTRLLINE, /* New control line status received from host */
+ CDCACM_EVENT_SENDBREAK /* Send break request received */
};
-typedef FAR void (*cdcser_callback_t)(enum cdcser_event_e event);
+typedef FAR void (*cdcacm_callback_t)(enum cdcacm_event_e event);
/****************************************************************************
* Public Function Prototypes
@@ -296,7 +296,7 @@ typedef FAR void (*cdcser_callback_t)(enum cdcser_event_e event);
* Description:
* If the CDC serial class driver is part of composite device, then
* board-specific logic must provide board_cdcclassobject(). In the simplest
- * case, board_cdcclassobject() is simply a wrapper around cdcser_classobject()
+ * case, board_cdcclassobject() is simply a wrapper around cdcacm_classobject()
* that provides the correct device minor number.
*
* Input Parameters:
@@ -308,12 +308,12 @@ typedef FAR void (*cdcser_callback_t)(enum cdcser_event_e event);
*
****************************************************************************/
-#if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCSER_COMPOSITE)
+#if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCACM_COMPOSITE)
EXTERN int board_cdcclassobject(FAR struct usbdevclass_driver_s **classdev);
#endif
/****************************************************************************
- * Name: cdcser_classobject
+ * Name: cdcacm_classobject
*
* Description:
* Register USB serial port (and USB serial console if so configured) and
@@ -330,12 +330,12 @@ EXTERN int board_cdcclassobject(FAR struct usbdevclass_driver_s **classdev);
*
****************************************************************************/
-#if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCSER_COMPOSITE)
-int cdcser_classobject(int minor, FAR struct usbdevclass_driver_s **classdev);
+#if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCACM_COMPOSITE)
+int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev);
#endif
/****************************************************************************
- * Name: cdcser_initialize
+ * Name: cdcacm_initialize
*
* Description:
* Register USB serial port (and USB serial console if so configured).
@@ -349,24 +349,24 @@ int cdcser_classobject(int minor, FAR struct usbdevclass_driver_s **classdev);
*
****************************************************************************/
-EXTERN int cdcser_initialize(int minor);
+EXTERN int cdcacm_initialize(int minor);
/****************************************************************************
- * Name: cdcser_uninitialize
+ * Name: cdcacm_uninitialize
*
* Description:
* Un-initialize the USB storage class driver
*
* Input Parameters:
- * handle - The handle returned by a previous call to cdcser_configure().
+ * handle - The handle returned by a previous call to cdcacm_configure().
*
* Returned Value:
* None
*
****************************************************************************/
-#ifndef CONFIG_CDCSER_COMPOSITE
-EXTERN void cdcser_uninitialize(FAR struct usbdevclass_driver_s *classdev);
+#ifndef CONFIG_CDCACM_COMPOSITE
+EXTERN void cdcacm_uninitialize(FAR struct usbdevclass_driver_s *classdev);
#endif
#undef EXTERN
@@ -374,4 +374,4 @@ EXTERN void cdcser_uninitialize(FAR struct usbdevclass_driver_s *classdev);
}
#endif
-#endif /* __INCLUDE_NUTTX_USB_CDC_SERIAL_H */
+#endif /* __INCLUDE_NUTTX_USB_CDCACM_H */
diff --git a/nuttx/include/nuttx/usb/usbdev.h b/nuttx/include/nuttx/usb/usbdev.h
index 00ded5770..8e89eddab 100644
--- a/nuttx/include/nuttx/usb/usbdev.h
+++ b/nuttx/include/nuttx/usb/usbdev.h
@@ -464,7 +464,7 @@ EXTERN int usbmsc_unbindlun(FAR void *handle, unsigned int lunno);
EXTERN int usbmsc_exportluns(FAR void *handle);
/****************************************************************************
- * Name: cdcser_classobject
+ * Name: usbmsc_classobject
*
* Description:
* .
diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
index ce9b4bebd..bc60da211 100644
--- a/nuttx/include/nuttx/usb/usbdev_trace.h
+++ b/nuttx/include/nuttx/usb/usbdev_trace.h
@@ -170,7 +170,7 @@
#define TRACE_CLSERROR(id) TRACE_EVENT(TRACE_CLSERROR_ID, id)
/* USB Serial driver class events *******************************************/
-
+/* Used by both the CDC/ACM and the PL2303 serial class drivers */
/* UART interface API calls */
#define USBSER_TRACECLASSAPI_SETUP 0x0001
@@ -184,7 +184,7 @@
#define USBSER_TRACECLASSAPI_SEND 0x0009
#define USBSER_TRACECLASSAPI_TXINT 0x000a
#define USBSER_TRACECLASSAPI_TXREADY 0x000b
-#define USBSER_TRACECLASSAPI_TXEMPTY 0x000c
+#define RTXEMPTY 0x000c
/* Values of the class error ID used by the USB serial driver */