summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-02-28 18:14:55 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-02-28 18:14:55 +0000
commit6875348aa9e7edca7e3404cf25135ded052cde5c (patch)
tree299af02425127a965549141a2b9155d43e99e52a /nuttx
parent933dda93fc98d3cfd445371c9ea29363ce26f085 (diff)
downloadpx4-nuttx-6875348aa9e7edca7e3404cf25135ded052cde5c.tar.gz
px4-nuttx-6875348aa9e7edca7e3404cf25135ded052cde5c.tar.bz2
px4-nuttx-6875348aa9e7edca7e3404cf25135ded052cde5c.zip
Extend CDC/ACM driver so that can be connected/disconnected under software control; Add new NSH commands sercon and serdis that will connect and disconnect the CDC/ACM serial device
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4436 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_allocateheap.c18
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt10
-rw-r--r--nuttx/drivers/usbdev/cdcacm.c71
-rw-r--r--nuttx/drivers/usbdev/cdcacm.h8
-rw-r--r--nuttx/include/nuttx/usb/cdcacm.h25
-rw-r--r--nuttx/include/nuttx/usb/usbdev_trace.h15
7 files changed, 110 insertions, 40 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 08e2bb545..73b594aba 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2516,3 +2516,6 @@
related scripts and programs and could cause some short-term problems.
* configs/stm3240g-eval/, arch/arm/src/stm32/up_allocateheap.c: Add support
for the 16-mbit SRAM on-board the STM3240G-EVAL board.
+ * drivers/usbdev/cdcacm.c and include/nuttx/usbdev/cdcacm.h: The CDC/ACM
+ driver can now be dynamically connected and disconnected from the host
+ under software control.
diff --git a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
index be7862e11..755659549 100644
--- a/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
+++ b/nuttx/arch/arm/src/stm32/stm32_allocateheap.c
@@ -103,12 +103,12 @@
# warning "FSMC SRAM not included in the heap"
# undef CONFIG_STM32_FSMC_SRAM
# elif CONFIG_MM_REGIONS > 2
-# error "CONFIG_MM_REGIONS > 2 but I don't know what any of the region(s) are"
+# error "CONFIG_MM_REGIONS > 2 but I don't know what some of the region(s) are"
# undef CONFIG_MM_REGIONS
# define CONFIG_MM_REGIONS 2
# endif
# elif CONFIG_MM_REGIONS > 1
-# error "CONFIG_MM_REGIONS > 1 but I don't know what any of the region(s) are"
+# error "CONFIG_MM_REGIONS > 1 but I don't know what the other region(s) are"
# endif
/* The STM32 F1 has not TCM SRAM */
@@ -192,7 +192,7 @@
/* Configuration 3: CONFIG_MM_REGIONS should have been 2 */
-# error "CONFIG_MM_REGIONS > 2 but I don't know what any of the region(s) are"
+# error "CONFIG_MM_REGIONS > 2 but I don't know what some of the region(s) are"
# undef CONFIG_MM_REGIONS
# define CONFIG_MM_REGIONS 2
# else
@@ -205,7 +205,7 @@
# warning "TCM SRAM is included in the heap AND DMA is enabled"
# endif
# if CONFIG_MM_REGIONS != 3
-# error "CONFIG_MM_REGIONS > 3 but I don't know what any of the region(s) are"
+# error "CONFIG_MM_REGIONS > 3 but I don't know what some of the region(s) are"
# undef CONFIG_MM_REGIONS
# define CONFIG_MM_REGIONS 3
# endif
@@ -227,7 +227,7 @@
* should be disabled and CONFIG_MM_REGIONS should be 2.
*/
-# ifdef (CONFIG_STM32_DMA)
+# ifdef CONFIG_STM32_DMA
# warning "TCM SRAM is included in the heap AND DMA is enabled"
# endif
# if CONFIG_MM_REGIONS < 2
@@ -235,7 +235,7 @@
# undef CONFIG_STM32_TCMEXCLUDE
# define CONFIG_STM32_TCMEXCLUDE 1
# elif CONFIG_MM_REGIONS > 2
-# error "CONFIG_MM_REGIONS > 2 but I don't know what any of the region(s) are"
+# error "CONFIG_MM_REGIONS > 2 but I don't know what some of the region(s) are"
# undef CONFIG_MM_REGIONS
# define CONFIG_MM_REGIONS 2
# endif
@@ -246,7 +246,7 @@
/* If FSMC SRAM is going to be used as heap, then verify that the starting
* address and size of the external SRAM region has been provided in the
- * configuration.
+ * configuration (as CONFIG_HEAP2_BASE and CONFIG_HEAP2_END).
*/
#ifdef CONFIG_STM32_FSMC_SRAM
@@ -304,10 +304,10 @@ void up_addregion(void)
mm_addregion((FAR void*)SRAM2_START, SRAM2_END-SRAM2_START);
#endif
- /* Add the user specified heap region. */
+ /* Add the external FSMC SRAM heap region. */
#ifdef CONFIG_STM32_FSMC_SRAM
mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
-# endif
+#endif
}
#endif
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index d2d1748ee..4b902802b 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -417,8 +417,8 @@ in order to successfully build NuttX using the Atollic toolchain WITH FPU suppor
-CONFIG_STM32_ATOLLIC_LITE=n : Enable *one* the Atollic toolchains
CONFIG_STM32_ATOLLIC_PRO=n
- -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version
- CONFIG_STM32_ATOLLIC_PRO=n : The "Pro" version
+ -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version, OR
+ CONFIG_STM32_ATOLLIC_PRO=y : The "Pro" version (not both)
-CONFIG_INTELHEX_BINARY=y : Suppress generation FLASH download formats
+CONFIG_INTELHEX_BINARY=n : (Only necessary with the "Lite" version)
@@ -998,8 +998,8 @@ Where <subdir> is one of the following:
-CONFIG_STM32_ATOLLIC_LITE=n : Enable *one* the Atollic toolchains
CONFIG_STM32_ATOLLIC_PRO=n
- -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version
- CONFIG_STM32_ATOLLIC_PRO=n : The "Pro" version
+ -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version, OR
+ CONFIG_STM32_ATOLLIC_PRO=n : The "Pro" version (only one)
-CONFIG_INTELHEX_BINARY=y : Suppress generation FLASH download formats
+CONFIG_INTELHEX_BINARY=n : (Only necessary with the "Lite" version)
@@ -1013,7 +1013,7 @@ Where <subdir> is one of the following:
The FPU test also needs to know the size of the FPU registers save area in
bytes (see arch/arm/include/armv7-m/irq_lazyfpu.h):
- -CONFIG_EXAMPLES_OSTEST_FPUSIZE=(4*33)
+ +CONFIG_EXAMPLES_OSTEST_FPUSIZE=(4*33)
telnetd:
--------
diff --git a/nuttx/drivers/usbdev/cdcacm.c b/nuttx/drivers/usbdev/cdcacm.c
index 52f68c0ab..d0843676a 100644
--- a/nuttx/drivers/usbdev/cdcacm.c
+++ b/nuttx/drivers/usbdev/cdcacm.c
@@ -94,6 +94,7 @@ struct cdcacm_dev_s
uint8_t config; /* Configuration number */
uint8_t nwrq; /* Number of queue write requests (in reqlist)*/
uint8_t nrdq; /* Number of queue read requests (in epbulkout) */
+ uint8_t minor; /* The device minor number */
bool rxenabled; /* true: UART RX "interrupts" enabled */
int16_t rxhead; /* Working head; used when rx int disabled */
@@ -1972,7 +1973,7 @@ static bool cdcuart_txempty(FAR struct uart_dev_s *dev)
*
* Input Parameter:
* minor - Device minor number. E.g., minor 0 would correspond to
- * /dev/ttyUSB0.
+ * /dev/ttyACM0.
* classdev - The location to return the CDC serial class' device
* instance.
*
@@ -1989,7 +1990,7 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev)
FAR struct cdcacm_alloc_s *alloc;
FAR struct cdcacm_dev_s *priv;
FAR struct cdcacm_driver_s *drvr;
- char devname[16];
+ char devname[CDCACM_DEVNAME_SIZE];
int ret;
/* Allocate the structures needed */
@@ -2011,6 +2012,8 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev)
memset(priv, 0, sizeof(struct cdcacm_dev_s));
sq_init(&priv->reqlist);
+ priv->minor = minor;
+
/* Fake line status */
priv->linecoding.baud[0] = (115200) & 0xff; /* Baud=115200 */
@@ -2052,11 +2055,11 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev)
}
#endif
- /* Register the single port supported by this implementation */
+ /* Register the CDC/ACM TTY device */
- sprintf(devname, "/dev/ttyUSB%d", minor);
+ sprintf(devname, CDCACM_DEVNAME_FORMAT, minor);
ret = uart_register(devname, &priv->serdev);
- if (ret)
+ if (ret < 0)
{
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UARTREGISTER), (uint16_t)-ret);
goto errout_with_class;
@@ -2077,7 +2080,10 @@ errout_with_class:
* 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.
+ * minor - Device minor number. E.g., minor 0 would correspond to
+ * /dev/ttyACM0.
+ * handle - An optional opaque reference to the CDC/ACM class object that
+ * may subsequently be used with cdcacm_uninitialize().
*
* Returned Value:
* Zero (OK) means that the driver was successfully registered. On any
@@ -2086,9 +2092,9 @@ errout_with_class:
****************************************************************************/
#ifndef CONFIG_CDCACM_COMPOSITE
-int cdcacm_initialize(int minor)
+int cdcacm_initialize(int minor, FAR void **handle)
{
- FAR struct usbdevclass_driver_s *drvr;
+ FAR struct usbdevclass_driver_s *drvr = NULL;
int ret;
/* Get an instance of the serial driver class object */
@@ -2104,6 +2110,16 @@ int cdcacm_initialize(int minor)
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_DEVREGISTER), (uint16_t)-ret);
}
}
+
+ /* Return the driver instance (if any) if the caller has requested it
+ * by provided a pointer to the location to return it.
+ */
+
+ if (handle)
+ {
+ *handle = (FAR void*)drvr;
+ }
+
return ret;
}
#endif
@@ -2112,10 +2128,20 @@ int cdcacm_initialize(int minor)
* Name: cdcacm_uninitialize
*
* Description:
- * Un-initialize the USB storage class driver
+ * Un-initialize the USB storage class driver. This function is used
+ * internally by the USB composite driver to unitialized the CDC/ACM
+ * driver. This same interface is available (with an untyped input
+ * parameter) when the CDC/ACM driver is used standalone.
*
* Input Parameters:
- * handle - The handle returned by a previous call to cdcacm_configure().
+ * There is one parameter, it differs in typing depending upon whether the
+ * CDC/ACM driver is an internal part of a composite device, or a standalone
+ * USB driver:
+ *
+ * classdev - The class object returned by board_cdcclassobject() or
+ * cdcacm_classobject()
+ * handle - The opaque handle represetning the class object returned by
+ * a previous call to cdcacm_initialize().
*
* Returned Value:
* None
@@ -2124,25 +2150,42 @@ int cdcacm_initialize(int minor)
#ifdef CONFIG_CDCACM_COMPOSITE
void cdcacm_uninitialize(FAR struct usbdevclass_driver_s *classdev)
+#else
+void cdcacm_uninitialize(FAR void *handle)
+#endif
{
+#ifdef CONFIG_CDCACM_COMPOSITE
FAR struct cdcacm_driver_s *drvr = (FAR struct cdcacm_driver_s *)classdev;
+#else
+ FAR struct cdcacm_driver_s *drvr = (FAR struct cdcacm_driver_s *)handle;
+#endif
FAR struct cdcacm_dev_s *priv = drvr->dev;
+ char devname[CDCACM_DEVNAME_SIZE];
+ int ret;
+
+ /* Un-register the CDC/ACM TTY device */
+
+ sprintf(devname, CDCACM_DEVNAME_FORMAT, priv->minor);
+ ret = unregister_driver(devname);
+ if (ret < 0)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_UARTUNREGISTER), (uint16_t)-ret);
+ }
/* Unbind the class (if still bound) */
if (priv->usbdev)
{
- cdcacm_unbind(classdev, priv->usbdev);
+ cdcacm_unbind(&drvr->drvr, priv->usbdev);
}
- /* Unregister the driver (unless we are a part of a composite device */
+ /* Unregister the driver (unless we are a part of a composite device) */
#ifndef CONFIG_CDCACM_COMPOSITE
- usbdev_unregister(&alloc->drvr.drvr);
+ usbdev_unregister(&drvr->drvr);
#endif
/* And free the driver structure */
kfree(priv);
}
-#endif
diff --git a/nuttx/drivers/usbdev/cdcacm.h b/nuttx/drivers/usbdev/cdcacm.h
index ab9cff92a..16f691259 100644
--- a/nuttx/drivers/usbdev/cdcacm.h
+++ b/nuttx/drivers/usbdev/cdcacm.h
@@ -222,6 +222,14 @@
#define CDCACM_EPINBULK_ADDR (USB_DIR_IN|CONFIG_CDCACM_EPBULKIN)
#define CDCACM_EPINBULK_ATTR (USB_EP_ATTR_XFER_BULK)
+/* Device driver definitions ************************************************/
+/* A CDC/ACM device is specific by a minor number in the range of 0-255.
+ * This maps to a character device at /dev/ttyACMx, x=0..255.
+ */
+
+#define CDCACM_DEVNAME_FORMAT "/dev/ttyACM%d"
+#define CDCACM_DEVNAME_SIZE 16
+
/* Misc Macros **************************************************************/
/* MIN/MAX macros */
diff --git a/nuttx/include/nuttx/usb/cdcacm.h b/nuttx/include/nuttx/usb/cdcacm.h
index 012bc55db..1c27f731f 100644
--- a/nuttx/include/nuttx/usb/cdcacm.h
+++ b/nuttx/include/nuttx/usb/cdcacm.h
@@ -344,7 +344,7 @@ EXTERN void board_cdcuninitialize(FAR struct usbdevclass_driver_s *classdev);
*
* Input Parameter:
* minor - Device minor number. E.g., minor 0 would correspond to
- * /dev/ttyUSB0.
+ * /dev/ttyACM0.
* classdev - The location to return the CDC serial class' device
* instance.
*
@@ -364,7 +364,10 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev);
* 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.
+ * minor - Device minor number. E.g., minor 0 would correspond to
+ * /dev/ttyACM0.
+ * handle - An optional opaque reference to the CDC/ACM class object that
+ * may subsequently be used with cdcacm_uninitialize().
*
* Returned Value:
* Zero (OK) means that the driver was successfully registered. On any
@@ -373,17 +376,27 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev);
****************************************************************************/
#if !defined(CONFIG_USBDEV_COMPOSITE) || !defined(CONFIG_CDCACM_COMPOSITE)
-EXTERN int cdcacm_initialize(int minor);
+EXTERN int cdcacm_initialize(int minor, FAR void **handle);
#endif
/****************************************************************************
* Name: cdcacm_uninitialize
*
* Description:
- * Un-initialize the USB storage class driver
+ * Un-initialize the USB storage class driver. This function is used
+ * internally by the USB composite driver to unitialized the CDC/ACM
+ * driver. This same interface is available (with an untyped input
+ * parameter) when the CDC/ACM driver is used standalone.
*
* Input Parameters:
- * handle - The handle returned by a previous call to cdcacm_configure().
+ * There is one parameter, it differs in typing depending upon whether the
+ * CDC/ACM driver is an internal part of a composite device, or a standalone
+ * USB driver:
+ *
+ * classdev - The class object returned by board_cdcclassobject() or
+ * cdcacm_classobject()
+ * handle - The opaque handle represetning the class object returned by
+ * a previous call to cdcacm_initialize().
*
* Returned Value:
* None
@@ -392,6 +405,8 @@ EXTERN int cdcacm_initialize(int minor);
#if defined(CONFIG_USBDEV_COMPOSITE) && defined(CONFIG_CDCACM_COMPOSITE)
EXTERN void cdcacm_uninitialize(FAR struct usbdevclass_driver_s *classdev);
+#else
+EXTERN void cdcacm_uninitialize(FAR void *handle);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
index bde6b227b..051b4ffa6 100644
--- a/nuttx/include/nuttx/usb/usbdev_trace.h
+++ b/nuttx/include/nuttx/usb/usbdev_trace.h
@@ -215,13 +215,14 @@
#define USBSER_TRACEERR_SETUPNOTCONNECTED 0x0019
#define USBSER_TRACEERR_SUBMITFAIL 0x001a
#define USBSER_TRACEERR_UARTREGISTER 0x001b
-#define USBSER_TRACEERR_UNSUPPORTEDCTRLREQ 0x001c
-#define USBSER_TRACEERR_UNSUPPORTEDCLASSREQ 0x001d
-#define USBSER_TRACEERR_UNSUPPORTEDSTDREQ 0x001e
-#define USBSER_TRACEERR_UNSUPPORTEDTYPE 0x001f
-#define USBSER_TRACEERR_WRALLOCREQ 0x0020
-#define USBSER_TRACEERR_WRSHUTDOWN 0x0021
-#define USBSER_TRACEERR_WRUNEXPECTED 0x0022
+#define USBSER_TRACEERR_UARTUNREGISTER 0x001c
+#define USBSER_TRACEERR_UNSUPPORTEDCTRLREQ 0x001d
+#define USBSER_TRACEERR_UNSUPPORTEDCLASSREQ 0x001e
+#define USBSER_TRACEERR_UNSUPPORTEDSTDREQ 0x001f
+#define USBSER_TRACEERR_UNSUPPORTEDTYPE 0x0020
+#define USBSER_TRACEERR_WRALLOCREQ 0x0021
+#define USBSER_TRACEERR_WRSHUTDOWN 0x0022
+#define USBSER_TRACEERR_WRUNEXPECTED 0x0023
/* USB Storage driver class events ******************************************/