From 893721387a67b3e472506c21bfdb70cd6fe62776 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 15 Sep 2011 13:26:00 +0000 Subject: More CDC serial updates git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3954 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/usbserial/main.c | 8 ++ nuttx/Documentation/NuttxPortingGuide.html | 4 +- nuttx/arch/arm/src/stm32/Make.defs | 4 + nuttx/configs/README.txt | 7 +- nuttx/drivers/usbdev/cdc_serial.c | 134 +++++++++++++++++++++++++++-- nuttx/include/nuttx/ioctl.h | 43 +++++---- nuttx/include/nuttx/usb/cdc.h | 26 ++++-- nuttx/include/nuttx/usb/cdc_serial.h | 127 +++++++++++++++++++++++++-- 8 files changed, 311 insertions(+), 42 deletions(-) diff --git a/apps/examples/usbserial/main.c b/apps/examples/usbserial/main.c index d84c063e1..d7bc4c56a 100644 --- a/apps/examples/usbserial/main.c +++ b/apps/examples/usbserial/main.c @@ -51,6 +51,10 @@ #include #include +#ifdef CONFIG_CDCSER +# include +#endif + /**************************************************************************** * Definitions ****************************************************************************/ @@ -211,7 +215,11 @@ int user_start(int argc, char *argv[]) /* Initialize the USB serial driver */ message("user_start: Registering USB serial driver\n"); +#ifdef CONFIG_CDCSER + ret = cdcser_initialize(0); +#else ret = usbdev_serialinitialize(0); +#endif if (ret < 0) { message("user_start: ERROR: Failed to create the USB serial device: %d\n", -ret); diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index de02f2519..6aa11bc78 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -4811,7 +4811,9 @@ build 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. Default 4. + 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" diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index 47820afcc..bd5f43b7f 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -44,6 +44,10 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \ up_usestack.c up_doirq.c up_hardfault.c up_svcall.c +ifeq ($(CONFIG_DEBUG_STACK),y) +CMN_CSRCS += up_checkstack.c +endif + CHIP_ASRCS = CHIP_CSRCS = stm32_start.c stm32_rcc.c stm32_gpio.c stm32_flash.c \ stm32_irq.c stm32_timerisr.c stm32_dma.c stm32_lowputc.c \ diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 32767c1c2..b50592b81 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -966,7 +966,7 @@ defconfig -- This is a configuration file similar to the Linux 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. + 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 @@ -975,11 +975,12 @@ defconfig -- This is a configuration file similar to the Linux 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. + 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. - Default 256. + 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 diff --git a/nuttx/drivers/usbdev/cdc_serial.c b/nuttx/drivers/usbdev/cdc_serial.c index 6e14ca6e8..693cdc4bf 100644 --- a/nuttx/drivers/usbdev/cdc_serial.c +++ b/nuttx/drivers/usbdev/cdc_serial.c @@ -174,6 +174,7 @@ struct usbser_dev_s uint8_t ctrlline; /* Buffered control line state */ struct cdc_linecoding_s linecoding; /* Buffered line status */ + cdcser_callback_t callback; /* Serial event callback function */ FAR struct usbdev_ep_s *epintin; /* Interrupt IN endpoint structure */ FAR struct usbdev_ep_s *epbulkin; /* Bulk IN endpoint structure */ @@ -284,6 +285,7 @@ static int usbser_setup(FAR struct uart_dev_s *dev); static void usbser_shutdown(FAR struct uart_dev_s *dev); static int usbser_attach(FAR struct uart_dev_s *dev); static void usbser_detach(FAR struct uart_dev_s *dev); +static int usbser_ioctl(FAR struct file *filep,int cmd,unsigned long arg); static void usbser_rxint(FAR struct uart_dev_s *dev, bool enable); static void usbser_txint(FAR struct uart_dev_s *dev, bool enable); static bool usbser_txempty(FAR struct uart_dev_s *dev); @@ -312,7 +314,7 @@ static const struct uart_ops_s g_uartops = usbser_shutdown, /* shutdown */ usbser_attach, /* attach */ usbser_detach, /* detach */ - NULL, /* ioctl */ + usbser_ioctl, /* ioctl */ NULL, /* receive */ usbser_rxint, /* rxinit */ NULL, /* rxavailable */ @@ -1828,7 +1830,7 @@ static int usbclass_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s * { if (ctrl->type == (USB_DIR_OUT|USB_REQ_TYPE_CLASS|USB_REQ_RECIPIENT_INTERFACE)) { - /* Save the new line status in the private data structure */ + /* Save the new line coding in the private data structure */ memcpy(&priv->linecoding, ctrlreq->buf, min(len, 7)); ret = 0; @@ -1836,7 +1838,11 @@ static int usbclass_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s * /* If there is a registered callback to receive line status info, then * callout now. */ -#warning "Missing logic" + + if (priv->callback) + { + priv->callback(CDCSER_EVENT_LINECODING); + } } else { @@ -1863,7 +1869,11 @@ static int usbclass_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s * /* If there is a registered callback to receive control line status info, * then callout now. */ -#warning "Missing logic" + + if (priv->callback) + { + priv->callback(CDCSER_EVENT_CTRLLINE); + } } else { @@ -1881,8 +1891,12 @@ static int usbclass_setup(FAR struct usbdev_s *dev, const struct usb_ctrlreq_s * /* If there is a registered callback to handle the SendBreak request, * then callout now. */ -#warning "Missing logic" + ret = 0; + if (priv->callback) + { + priv->callback(CDCSER_EVENT_SENDBREAK); + } } else { @@ -2067,6 +2081,105 @@ static void usbser_detach(FAR struct uart_dev_s *dev) usbtrace(CDCSER_CLASSAPI_DETACH, 0); } +/**************************************************************************** + * Name: usbser_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int usbser_ioctl(FAR struct file *filep,int cmd,unsigned long arg) +{ + struct inode *inode = filep->f_inode; + struct usbser_dev_s *priv = inode->i_private; + int ret = OK; + + switch (cmd) + { + /* 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. + */ + + case CAIOC_REGISTERCB: + { + /* Save the new callback function */ + + priv->callback = (cdcser_callback_t)((uintptr_t)arg); + } + break; + + /* 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). + */ + + case CAIOC_GETLINECODING: + { + FAR struct cdc_linecoding_s *ptr = (FAR struct cdc_linecoding_s *)((uintptr_t)arg); + if (ptr) + { + memcpy(ptr, &priv->linecoding, sizeof(struct cdc_linecoding_s)); + } + else + { + ret = -EINVAL; + } + } + break; + + /* 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. + */ + + case CAIOC_GETCTRLLINE: + { + FAR int *ptr = (FAR int *)((uintptr_t)arg); + if (ptr) + { + *ptr = priv->ctrlline; + } + else + { + ret = -EINVAL; + } + } + break; + + /* 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. + */ + + case CAIOC_NOTIFY: + { + /* Not yet implemented. I probably won't bother to implement until + * I com up with a usage model that needs it. + */ + + ret = -ENOSYS; + } + break; + + default: + ret = -ENOTTY; + break; + } + + return ret; +} + /**************************************************************************** * Name: usbser_rxint * @@ -2248,14 +2361,21 @@ static bool usbser_txempty(FAR struct uart_dev_s *dev) ****************************************************************************/ /**************************************************************************** - * Name: usbdev_serialinitialize + * 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. + * ****************************************************************************/ -int usbdev_serialinitialize(int minor) +int cdcser_initialize(int minor) { FAR struct usbser_alloc_s *alloc; FAR struct usbser_dev_s *priv; 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 +#include #include /**************************************************************************** * 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) } -- cgit v1.2.3