From 54cd9689cccad1949c067f40d500491851799221 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 25 Sep 2013 17:23:03 -0600 Subject: Move apps/examples/cdcacm to apps/system/cdcacm --- apps/system/Kconfig | 6 +- apps/system/Make.defs | 4 + apps/system/Makefile | 4 +- apps/system/cdcacm/.gitignore | 11 +++ apps/system/cdcacm/Kconfig | 77 ++++++++++++++++++ apps/system/cdcacm/Makefile | 117 +++++++++++++++++++++++++++ apps/system/cdcacm/README.txt | 43 ++++++++++ apps/system/cdcacm/cdcacm.h | 165 +++++++++++++++++++++++++++++++++++++++ apps/system/cdcacm/cdcacm_main.c | 147 ++++++++++++++++++++++++++++++++++ apps/system/usbmsc/Kconfig | 2 +- apps/system/usbmsc/README.txt | 76 ++++++++++++++++++ apps/system/usbmsc/usbmsc.h | 8 +- 12 files changed, 652 insertions(+), 8 deletions(-) create mode 100644 apps/system/cdcacm/.gitignore create mode 100644 apps/system/cdcacm/Kconfig create mode 100644 apps/system/cdcacm/Makefile create mode 100755 apps/system/cdcacm/README.txt create mode 100644 apps/system/cdcacm/cdcacm.h create mode 100644 apps/system/cdcacm/cdcacm_main.c create mode 100755 apps/system/usbmsc/README.txt (limited to 'apps/system') diff --git a/apps/system/Kconfig b/apps/system/Kconfig index 22d212b12..c2eec877b 100644 --- a/apps/system/Kconfig +++ b/apps/system/Kconfig @@ -3,6 +3,10 @@ # see misc/tools/kconfig-language.txt. # +menu "USB CDC/ACM Class Commands" +source "$APPSDIR/system/cdcacm/Kconfig" +endmenu + menu "Custom Free Memory Command" source "$APPSDIR/system/free/Kconfig" endmenu @@ -51,7 +55,7 @@ menu "Stack Monitor" source "$APPSDIR/system/stackmonitor/Kconfig" endmenu -menu "USB Mass Storage Class" +menu "USB Mass Storage Class Commands" source "$APPSDIR/system/usbmsc/Kconfig" endmenu diff --git a/apps/system/Make.defs b/apps/system/Make.defs index c12a77af0..a314220aa 100644 --- a/apps/system/Make.defs +++ b/apps/system/Make.defs @@ -34,6 +34,10 @@ # ############################################################################ +ifeq ($(CONFIG_SYSTEM_CDCACM),y) +CONFIGURED_APPS += system/cdcacm +endif + ifeq ($(CONFIG_SYSTEM_FREE),y) CONFIGURED_APPS += system/free endif diff --git a/apps/system/Makefile b/apps/system/Makefile index 01008dbdc..46ceccdda 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -37,8 +37,8 @@ # Sub-directories containing system task -SUBDIRS = flash_eraseall free i2c install poweroff ramtest ramtron readline -SUBDIRS += sdcard stackmonitor sysinfo usbmonitor usbmsc zmodem +SUBDIRS = cdcacm flash_eraseall free i2c install poweroff ramtest ramtron +SUBDIRS += readline sdcard stackmonitor sysinfo usbmonitor usbmsc zmodem # Create the list of installed runtime modules (INSTALLED_DIRS) diff --git a/apps/system/cdcacm/.gitignore b/apps/system/cdcacm/.gitignore new file mode 100644 index 000000000..fa1ec7579 --- /dev/null +++ b/apps/system/cdcacm/.gitignore @@ -0,0 +1,11 @@ +/Make.dep +/.depend +/.built +/*.asm +/*.obj +/*.rel +/*.lst +/*.sym +/*.adb +/*.lib +/*.src diff --git a/apps/system/cdcacm/Kconfig b/apps/system/cdcacm/Kconfig new file mode 100644 index 000000000..b85b15a9e --- /dev/null +++ b/apps/system/cdcacm/Kconfig @@ -0,0 +1,77 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config SYSTEM_CDCACM + bool "CDC/ACM class controls" + default n + depends on CDCACM && !KERNEL_BUILD + ---help--- + Enable the USB CDC/ACM class controls. These controls include: + + sercon: Connect the mass storage device to the host + serdis: Disconnect the mass storage device to the host + +if SYSTEM_CDCACM + +config SYSTEM_CDCACM_DEVMINOR + int "CDC/ACM Minor Device Number" + default 0 + ---help--- + The minor device number of the serial driver for the CDC/ACM device. + For example, N in /dev/ttyACMN. Used for registering the serial + driver. Default is zero. + +config SYSTEM_CDCACM_TRACEINIT + bool "USB Trace Initialization" + default n + depends on USBDEV_TRACE || DEBUG_USB + ---help--- + If USBDEV_TRACE is enabled (or DEBUG and DEBUG_USB), + then the add-on code will also manage the USB trace output. The + amount of trace output can be controlled this configuration value: + This setting will show USB initialization events + +config SYSTEM_CDCACM_TRACECLASS + bool "USB Trace Class" + default n + depends on USBDEV_TRACE || DEBUG_USB + ---help--- + If USBDEV_TRACE is enabled (or DEBUG and DEBUG_USB), + then the add-on code will also manage the USB trace output. The + amount of trace output can be controlled this configuration value: + This setting will show USB class driver events + +config SYSTEM_CDCACM_TRACETRANSFERS + bool "USB Trace Transfers" + default n + depends on USBDEV_TRACE || DEBUG_USB + ---help--- + If USBDEV_TRACE is enabled (or DEBUG and DEBUG_USB), + then the add-on code will also manage the USB trace output. The + amount of trace output can be controlled this configuration value: + This setting will show USB data transfer events + +config SYSTEM_CDCACM_TRACECONTROLLER + bool "USB Trace Device Controller Events" + default n + depends on USBDEV_TRACE || DEBUG_USB + ---help--- + If USBDEV_TRACE is enabled (or DEBUG and DEBUG_USB), + then the add-on code will also manage the USB trace output. The + amount of trace output can be controlled this configuration value: + This setting will show USB device controller events + +config SYSTEM_CDCACM_TRACEINTERRUPTS + bool "USB Trace Device Controller Interrupt Events" + default n + depends on USBDEV_TRACE || DEBUG_USB + ---help--- + If USBDEV_TRACE is enabled (or DEBUG and DEBUG_USB), + then the add-on code will also manage the USB trace output. The + amount of trace output can be controlled this configuration value: + This setting will show USB device controller interrupt-related events. + +endif + diff --git a/apps/system/cdcacm/Makefile b/apps/system/cdcacm/Makefile new file mode 100644 index 000000000..b72bb9fae --- /dev/null +++ b/apps/system/cdcacm/Makefile @@ -0,0 +1,117 @@ +############################################################################ +# apps/system/cdcacm/Makefile +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# USB CDC/ACM serial mass storage add-on + +ASRCS = +CSRCS = cdcacm_main.c + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + BIN = ..\..\libapps$(LIBEXT) +else +ifeq ($(WINTOOL),y) + BIN = ..\\..\\libapps$(LIBEXT) +else + BIN = ../../libapps$(LIBEXT) +endif +endif + +ROOTDEPPATH = --dep-path . + +# USB CDC/ACM built-in application info + +APPNAME1 = sercon +PRIORITY1 = SCHED_PRIORITY_DEFAULT +STACKSIZE1 = 2048 + +APPNAME2 = serdis +PRIORITY2 = SCHED_PRIORITY_DEFAULT +STACKSIZE2 = 2048 + +# Common build + +VPATH = + +all: .built +.PHONY: context clean depend distclean + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +.built: $(OBJS) + $(call ARCHIVE, $(BIN), $(OBJS)) + @touch .built + +ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) +$(BUILTIN_REGISTRY)$(DELIM)$(APPNAME1)_main.bdat: $(DEPCONFIG) Makefile + $(call REGISTER,$(APPNAME1),$(PRIORITY1),$(STACKSIZE1),$(APPNAME1)_main) + +$(BUILTIN_REGISTRY)$(DELIM)$(APPNAME2)_main.bdat: $(DEPCONFIG) Makefile + $(call REGISTER,$(APPNAME2),$(PRIORITY2),$(STACKSIZE2),$(APPNAME2)_main) + +context: $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME1)_main.bdat $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME2)_main.bdat +else +context: +endif + +.depend: Makefile $(SRCS) + @$(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + $(call DELFILE, .built) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep + diff --git a/apps/system/cdcacm/README.txt b/apps/system/cdcacm/README.txt new file mode 100755 index 000000000..a428cb318 --- /dev/null +++ b/apps/system/cdcacm/README.txt @@ -0,0 +1,43 @@ +system/cdcacm +^^^^^^^^^^^^^^^ + + This very simple add-on allows the USB CDC/ACM serial device can be dynamically + connected and disconnected from a host. This add-on can only be used as + an NSH built-in command. If built-in, then two new NSH commands will be + supported: + + 1. sercon - Connect the CDC/ACM serial device + 2. serdis - Disconnect the CDC/ACM serial device + + Configuration prequisites (not complete): + + CONFIG_USBDEV=y : USB device support must be enabled + CONFIG_CDCACM=y : The CDC/ACM driver must be built + CONFIG_NSH_BUILTIN_APPS : NSH built-in application support must be enabled + + Configuration options specific to this add-on: + + CONFIG_SYSTEM_CDCACM_DEVMINOR : The minor number of the CDC/ACM device. + : i.e., the 'x' in /dev/ttyACMx + + If CONFIG_USBDEV_TRACE is enabled (or CONFIG_DEBUG and CONFIG_DEBUG_USB, or + CONFIG_USBDEV_TRACE), then the add-on code will also initialize the USB trace + output. The amount of trace output can be controlled using: + + CONFIG_SYSTEM_CDCACM_TRACEINIT + Show initialization events + CONFIG_SYSTEM_CDCACM_TRACECLASS + Show class driver events + CONFIG_SYSTEM_CDCACM_TRACETRANSFERS + Show data transfer events + CONFIG_SYSTEM_CDCACM_TRACECONTROLLER + Show controller events + CONFIG_SYSTEM_CDCACM_TRACEINTERRUPTS + Show interrupt-related events. + + Note: This add-on is only enables or disable USB CDC/ACM via the NSH + 'sercon' and 'serdis' command. It will enable and disable tracing per + the settings before enabling and after disabling the CDC/ACM device. It + will not, however, monitor buffered trace data in the interim. If + CONFIG_USBDEV_TRACE is defined (and the debug options are not), other + application logic will need to monitor the buffered trace data. diff --git a/apps/system/cdcacm/cdcacm.h b/apps/system/cdcacm/cdcacm.h new file mode 100644 index 000000000..bc9cf2f9e --- /dev/null +++ b/apps/system/cdcacm/cdcacm.h @@ -0,0 +1,165 @@ +/**************************************************************************** + * system/cdcacm/cdcacm.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __SYSTEM_CDCACM_CDCACM_H +#define __SYSTEM_CDCACM_CDCACM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ +/* Prerequisites */ + +#ifndef CONFIG_USBDEV +# error "CONFIG_USBDEV is not defined" +#endif + +#ifndef CONFIG_CDCACM +# error "CONFIG_CDCACM is not defined" +#endif + +#ifndef CONFIG_NSH_BUILTIN_APPS +# error "This add-on can only be built as an NSH built-in application" +#endif + +/* Default configuration values */ + +#ifndef CONFIG_SYSTEM_CDCACM_DEVMINOR +# define CONFIG_SYSTEM_CDCACM_DEVMINOR 0 +#endif + +/* Trace Configuration ******************************************************/ + +#ifdef CONFIG_SYSTEM_CDCACM_TRACEINIT +# define TRACE_INIT_BITS (TRACE_INIT_BIT) +#else +# define TRACE_INIT_BITS (0) +#endif + +#define TRACE_ERROR_BITS (TRACE_DEVERROR_BIT|TRACE_CLSERROR_BIT) + +#ifdef CONFIG_SYSTEM_CDCACM_TRACECLASS +# define TRACE_CLASS_BITS (TRACE_CLASS_BIT|TRACE_CLASSAPI_BIT|TRACE_CLASSSTATE_BIT) +#else +# define TRACE_CLASS_BITS (0) +#endif + +#ifdef CONFIG_SYSTEM_CDCACM_TRACETRANSFERS +# define TRACE_TRANSFER_BITS (TRACE_OUTREQQUEUED_BIT|TRACE_INREQQUEUED_BIT|TRACE_READ_BIT|\ + TRACE_WRITE_BIT|TRACE_COMPLETE_BIT) +#else +# define TRACE_TRANSFER_BITS (0) +#endif + +#ifdef CONFIG_SYSTEM_CDCACM_TRACECONTROLLER +# define TRACE_CONTROLLER_BITS (TRACE_EP_BIT|TRACE_DEV_BIT) +#else +# define TRACE_CONTROLLER_BITS (0) +#endif + +#ifdef CONFIG_SYSTEM_CDCACM_TRACEINTERRUPTS +# define TRACE_INTERRUPT_BITS (TRACE_INTENTRY_BIT|TRACE_INTDECODE_BIT|TRACE_INTEXIT_BIT) +#else +# define TRACE_INTERRUPT_BITS (0) +#endif + +#define TRACE_BITSET (TRACE_INIT_BITS|TRACE_ERROR_BITS|TRACE_CLASS_BITS|\ + TRACE_TRANSFER_BITS|TRACE_CONTROLLER_BITS|TRACE_INTERRUPT_BITS) + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lowsyslog(__VA_ARGS__) +# define msgflush() +# else +# define message(...) printf(__VA_ARGS__) +# define msgflush() fflush(stdout) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lowsyslog +# define msgflush() +# else +# define message printf +# define msgflush() fflush(stdout) +# endif +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* All global variables used by this add-on are packed into a structure in + * order to avoid name collisions. + */ + +struct cdcacm_state_s +{ + /* This is the handle that references to this particular USB CDC/ACM driver + * instance. It is only needed if the USB CDC/ACM device add-on is + * built using CONFIG_NSH_BUILTIN_APPS. In this case, the value + * of the driver handle must be remembered between the 'sercon' and 'msdis' + * commands. + */ + + FAR void *handle; +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* All global variables used by this add-on are packed into a structure in + * order to avoid name collisions. + */ + +extern struct cdcacm_state_s g_cdcacm; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#endif /* __SYSTEM_CDCACM_CDCACM_H */ diff --git a/apps/system/cdcacm/cdcacm_main.c b/apps/system/cdcacm/cdcacm_main.c new file mode 100644 index 000000000..724e8fd14 --- /dev/null +++ b/apps/system/cdcacm/cdcacm_main.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * system/cdcacm/cdcacm_main.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#include +#include + +#include "cdcacm.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* All global variables used by this add-on are packed into a structure in + * order to avoid name collisions. + */ + +struct cdcacm_state_s g_cdcacm; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * sercon_main + * + * Description: + * This is the main program that configures the CDC/ACM serial device. + * + ****************************************************************************/ + +int sercon_main(int argc, char *argv[]) +{ + int ret; + + /* Check if there is a non-NULL USB mass storage device handle (meaning that the + * USB mass storage device is already configured). + */ + + if (g_cdcacm.handle) + { + message("sercon:: ERROR: Already connected\n"); + return EXIT_FAILURE; + } + + /* Then, in any event, enable trace data collection as configured BEFORE + * enabling the CDC/ACM device. + */ + + usbtrace_enable(TRACE_BITSET); + + /* Initialize the USB CDC/ACM serial driver */ + + message("sercon: Registering CDC/ACM serial driver\n"); + ret = cdcacm_initialize(CONFIG_SYSTEM_CDCACM_DEVMINOR, &g_cdcacm.handle); + if (ret < 0) + { + message("sercon: ERROR: Failed to create the CDC/ACM serial device: %d\n", -ret); + return EXIT_FAILURE; + } + + message("sercon: Successfully registered the CDC/ACM serial driver\n"); + return EXIT_SUCCESS; +} + +/**************************************************************************** + * serdis_main + * + * Description: + * This is a program entry point that will disconnect the CDC/ACM serial + * device. + * + ****************************************************************************/ + +int serdis_main(int argc, char *argv[]) +{ + /* First check if the USB mass storage device is already connected */ + + if (!g_cdcacm.handle) + { + message("serdis: ERROR: Not connected\n"); + return EXIT_FAILURE; + } + + /* Then, in any event, disable trace data collection as configured BEFORE + * enabling the CDC/ACM device. + */ + + usbtrace_enable(0); + + /* Then disconnect the device and uninitialize the USB mass storage driver */ + + cdcacm_uninitialize(g_cdcacm.handle); + g_cdcacm.handle = NULL; + message("serdis: Disconnected\n"); + return EXIT_SUCCESS; +} diff --git a/apps/system/usbmsc/Kconfig b/apps/system/usbmsc/Kconfig index d78f8a8ac..7be540e33 100644 --- a/apps/system/usbmsc/Kconfig +++ b/apps/system/usbmsc/Kconfig @@ -6,7 +6,7 @@ config SYSTEM_USBMSC bool "USB mass storage class controls" default n - depends on USBMSC + depends on USBMSC && !KERNEL_BUILD ---help--- Enable the USB mass storage class controls. These controls include: diff --git a/apps/system/usbmsc/README.txt b/apps/system/usbmsc/README.txt new file mode 100755 index 000000000..6734a4ed8 --- /dev/null +++ b/apps/system/usbmsc/README.txt @@ -0,0 +1,76 @@ +system/usbmsc +^^^^^^^^^^^^^^^ + + This add-on registers a block device driver, then exports the block + the device using the USB storage class driver. In order to use this + add-on, your board-specific logic must provide the function: + + void usbmsc_archinitialize(void); + + This function will be called by the system/usbmsc in order to + do the actual registration of the block device drivers. For examples + of the implementation of usbmsc_archinitialize() see + configs/mcu123-lpc124x/src/up_usbmsc.c or + configs/stm3210e-eval/src/usbmsc.c + + Configuration options: + + CONFIG_NSH_BUILTIN_APPS + This add-on can be built as two NSH "built-in" commands if this option + is selected: 'msconn' will connect the USB mass storage device; 'msdis' + will disconnect the USB storage device. + CONFIG_SYSTEM_USBMSC_NLUNS + Defines the number of logical units (LUNs) exported by the USB storage + driver. Each LUN corresponds to one exported block driver (or partition + of a block driver). May be 1, 2, or 3. Default is 1. + CONFIG_SYSTEM_USBMSC_DEVMINOR1 + The minor device number of the block driver for the first LUN. For + example, N in /dev/mmcsdN. Used for registering the block driver. Default + is zero. + CONFIG_SYSTEM_USBMSC_DEVPATH1 + The full path to the registered block driver. Default is "/dev/mmcsd0" + CONFIG_SYSTEM_USBMSC_DEVMINOR2 and CONFIG_SYSTEM_USBMSC_DEVPATH2 + Similar parameters that would have to be provided if CONFIG_SYSTEM_USBMSC_NLUNS + is 2 or 3. No defaults. + CONFIG_SYSTEM_USBMSC_DEVMINOR3 and CONFIG_SYSTEM_USBMSC_DEVPATH3 + Similar parameters that would have to be provided if CONFIG_SYSTEM_USBMSC_NLUNS + is 3. No defaults. + CONFIG_SYSTEM_USBMSC_DEBUGMM + Enables some debug tests to check for memory usage and memory leaks. + + If CONFIG_USBDEV_TRACE is enabled (or CONFIG_DEBUG and CONFIG_DEBUG_USB), then + the code will also manage the USB trace output. The amount of trace output + can be controlled using: + + CONFIG_SYSTEM_USBMSC_TRACEINIT + Show initialization events + CONFIG_SYSTEM_USBMSC_TRACECLASS + Show class driver events + CONFIG_SYSTEM_USBMSC_TRACETRANSFERS + Show data transfer events + CONFIG_SYSTEM_USBMSC_TRACECONTROLLER + Show controller events + CONFIG_SYSTEM_USBMSC_TRACEINTERRUPTS + Show interrupt-related events. + + Error results are always shown in the trace output + + NOTE 1: When built as an NSH add-on command (CONFIG_NSH_BUILTIN_APPS=y), + Caution should be used to assure that the SD drive (or other storage device) is + not in use when the USB storage device is configured. Specifically, the SD + driver should be unmounted like: + + nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Card is mounted in NSH + ... + nsh> umount /mnd/sdcard # Unmount before connecting USB!!! + nsh> msconn # Connect the USB storage device + ... + nsh> msdis # Disconnect USB storate device + nsh> mount -t vfat /dev/mmcsd0 /mnt/sdcard # Restore the mount + + Failure to do this could result in corruption of the SD card format. + + NOTE 2: This add-on used internal USB device driver interfaces. As such, + it relies on internal OS interfaces that are not normally available to a + user-space program. As a result, this add-on cannot be used if a + NuttX is built as a protected, supervisor kernel (CONFIG_NUTTX_KERNEL). diff --git a/apps/system/usbmsc/usbmsc.h b/apps/system/usbmsc/usbmsc.h index c829473e4..1a0afb9a2 100644 --- a/apps/system/usbmsc/usbmsc.h +++ b/apps/system/usbmsc/usbmsc.h @@ -1,7 +1,7 @@ /**************************************************************************** * system/usbmsc/usbmsc.h * - * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __EXAMPLES_USBSTORAGE_USBMSC_H -#define __EXAMPLES_USBSTORAGE_USBMSC_H +#ifndef __SYSTEM_USBMSC_USBMSC_H +#define __SYSTEM_USBMSC_USBMSC_H /**************************************************************************** * Included Files @@ -177,4 +177,4 @@ extern struct usbmsc_state_s g_usbmsc; extern int usbmsc_archinitialize(void); -#endif /* __EXAMPLES_USBSTORAGE_USBMSC_H */ +#endif /* __SYSTEM_USBMSC_USBMSC_H */ -- cgit v1.2.3