From 55a34548ccc4fc7aa55ad585b007c7d77d8cf937 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 25 Sep 2013 16:54:39 -0600 Subject: Move apps/examples/usbmsc to apps/system/usbmsc --- apps/system/Kconfig | 4 + apps/system/Make.defs | 4 + apps/system/Makefile | 2 +- apps/system/usbmsc/.gitignore | 11 + apps/system/usbmsc/Kconfig | 171 ++++++++++ apps/system/usbmsc/Makefile | 120 +++++++ apps/system/usbmsc/usbmsc.h | 180 +++++++++++ apps/system/usbmsc/usbmsc_main.c | 660 +++++++++++++++++++++++++++++++++++++++ 8 files changed, 1151 insertions(+), 1 deletion(-) create mode 100644 apps/system/usbmsc/.gitignore create mode 100644 apps/system/usbmsc/Kconfig create mode 100644 apps/system/usbmsc/Makefile create mode 100644 apps/system/usbmsc/usbmsc.h create mode 100644 apps/system/usbmsc/usbmsc_main.c (limited to 'apps/system') diff --git a/apps/system/Kconfig b/apps/system/Kconfig index b2e1f3c62..22d212b12 100644 --- a/apps/system/Kconfig +++ b/apps/system/Kconfig @@ -51,6 +51,10 @@ menu "Stack Monitor" source "$APPSDIR/system/stackmonitor/Kconfig" endmenu +menu "USB Mass Storage Class" +source "$APPSDIR/system/usbmsc/Kconfig" +endmenu + menu "Zmodem Commands" source "$APPSDIR/system/zmodem/Kconfig" endmenu diff --git a/apps/system/Make.defs b/apps/system/Make.defs index 58e4c306d..c12a77af0 100644 --- a/apps/system/Make.defs +++ b/apps/system/Make.defs @@ -82,6 +82,10 @@ ifeq ($(CONFIG_SYSTEM_STACKMONITOR),y) CONFIGURED_APPS += system/stackmonitor endif +ifeq ($(CONFIG_SYSTEM_USBMSC),y) +CONFIGURED_APPS += system/usbmsc +endif + ifeq ($(CONFIG_SYSTEM_ZMODEM),y) CONFIGURED_APPS += system/zmodem endif diff --git a/apps/system/Makefile b/apps/system/Makefile index 8cf858267..01008dbdc 100644 --- a/apps/system/Makefile +++ b/apps/system/Makefile @@ -38,7 +38,7 @@ # Sub-directories containing system task SUBDIRS = flash_eraseall free i2c install poweroff ramtest ramtron readline -SUBDIRS += sdcard stackmonitor sysinfo usbmonitor zmodem +SUBDIRS += sdcard stackmonitor sysinfo usbmonitor usbmsc zmodem # Create the list of installed runtime modules (INSTALLED_DIRS) diff --git a/apps/system/usbmsc/.gitignore b/apps/system/usbmsc/.gitignore new file mode 100644 index 000000000..fa1ec7579 --- /dev/null +++ b/apps/system/usbmsc/.gitignore @@ -0,0 +1,11 @@ +/Make.dep +/.depend +/.built +/*.asm +/*.obj +/*.rel +/*.lst +/*.sym +/*.adb +/*.lib +/*.src diff --git a/apps/system/usbmsc/Kconfig b/apps/system/usbmsc/Kconfig new file mode 100644 index 000000000..d78f8a8ac --- /dev/null +++ b/apps/system/usbmsc/Kconfig @@ -0,0 +1,171 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config SYSTEM_USBMSC + bool "USB mass storage class controls" + default n + depends on USBMSC + ---help--- + Enable the USB mass storage class controls. These controls include: + + msconn: Connect the mass storage device to the host + msdis : Disconnect the mass storage device to the host + +if SYSTEM_USBMSC + +config SYSTEM_USBMSC_NLUNS + int "Number of LUNs" + default 1 + ---help--- + 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 + int "LUN1 Minor Device Number" + default 0 + ---help--- + 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 + string "LUN1 Device Path" + default "/dev/mmcsd0" + ---help--- + The full path to the registered block driver. Default is + "/dev/mmcsd0" + +config SYSTEM_USBMSC_DEVMINOR2 + int "LUN2 Minor Device Number" + default 1 + ---help--- + The minor device number of the block driver for the second LUN. For + example, N in /dev/mmcsdN. Used for registering the block driver. + Ignored if SYSTEM_USBMSC_NLUNS < 2. Default is one. + +config SYSTEM_USBMSC_DEVPATH2 + string "LUN2 Device Path" + default "/dev/mmcsd1" + ---help--- + The full path to the registered block driver. Ignored if + SYSTEM_USBMSC_NLUNS < 2. Default is "/dev/mmcsd1" + +config SYSTEM_USBMSC_DEVMINOR3 + int "LUN3 Minor Device Number" + default 2 + ---help--- + The minor device number of the block driver for the third LUN. For + example, N in /dev/mmcsdN. Used for registering the block driver. + Ignored if SYSTEM_USBMSC_NLUNS < 2. Default is two. + +config SYSTEM_USBMSC_DEVPATH3 + string "LUN3 Device Path" + default "/dev/mmcsd2" + ---help--- + The full path to the registered block driver. Ignored if + SYSTEM_USBMSC_NLUNS < 2. Default is "/dev/mmcsd2" + +config SYSTEM_USBMSC_DEBUGMM + bool "USB MSC MM Debug" + default n + ---help--- + Enables some debug tests to check for memory usage and memory leaks. + +config SYSTEM_USBMSC_TRACE + bool "Trace USB activity" + default n + depends on (USBDEV_TRACE || DEBUG_USB) && !NSH_BUILTIN_APPS + ---help--- + If this add-on is built as a standalone task and if USB device tracing is + enabled, then this add-on can be configured to unobtrusively monitor + USB activity by selecting this option. + +if SYSTEM_USBMSC_TRACE + +config SYSTEM_USBMSC_TRACEINIT + bool "USB Trace Initialization" + default n + ---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_USBMSC_TRACECLASS + bool "USB Trace Class" + default n + ---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_USBMSC_TRACETRANSFERS + bool "USB Trace Transfers" + default n + ---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_USBMSC_TRACECONTROLLER + bool "USB Trace Device Controller Events" + default n + ---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_USBMSC_TRACEINTERRUPTS + bool "USB Trace Device Controller Interrupt Events" + default n + ---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 # SYSTEM_USBMSC_TRACE + +if NSH_BUILTIN_APPS + +config SYSTEM_USBMSC_CMD_STACKSIZE + int "Stacksize of msconn and msdis commands" + default 768 + ---help--- + Size of the stack used by the small 'msconn' and 'msdis' command + applications. Warning, just because the applications are small, + the stack usage could still be deep! + +config SYSTEM_USBMSC_CMD_PRIORITY + int "Priority of the msconn and msdis commands" + default 100 + ---help--- + Priority of the small 'msconn' and 'msdis' command applications. + +config SYSTEM_USBMSC_DAEMON_STACKSIZE + int "Stacksize of msconn daemon" + default 2048 + ---help--- + To avoid threading entanglements, the USB MSC class is initialized + on a daemon thread. This permits the msconn application to return + to the NSH command line immediately. This is the stack used for + that short-lived USB MSC initialization daemon. + +config SYSTEM_USBMSC_DAEMON_PRIORITY + int "Priority of the msconn daemon" + default 100 + ---help--- + To avoid threading entanglements, the USB MSC class is initialized + on a daemon thread. This permits the msconn application to return + to the NSH command line immediately. This is the priority used for + that short-lived USB MSC initialization daemon. + +endif # NSH_BUILTIN_APPS +endif # SYSTEM_USBMSC + diff --git a/apps/system/usbmsc/Makefile b/apps/system/usbmsc/Makefile new file mode 100644 index 000000000..842733ef7 --- /dev/null +++ b/apps/system/usbmsc/Makefile @@ -0,0 +1,120 @@ +############################################################################ +# apps/system/usbmsc/Makefile +# +# Copyright (C) 2008, 2010-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 device mass storage add-on + +ASRCS = +CSRCS = usbmsc_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 storage built-in application info + +CONFIG_SYSTEM_USBMSC_CMD_STACKSIZE ?= 768 +CONFIG_SYSTEM_USBMSC_CMD_PRIORITY ?= SCHED_PRIORITY_DEFAULT + +APPNAME1 = msconn +PRIORITY1 = $(CONFIG_SYSTEM_USBMSC_CMD_PRIORITY) +STACKSIZE1 = $(CONFIG_SYSTEM_USBMSC_CMD_STACKSIZE) + +APPNAME2 = msdis +PRIORITY2 = $(CONFIG_SYSTEM_USBMSC_CMD_PRIORITY) +STACKSIZE2 = $(CONFIG_SYSTEM_USBMSC_CMD_STACKSIZE) + +# 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/usbmsc/usbmsc.h b/apps/system/usbmsc/usbmsc.h new file mode 100644 index 000000000..c829473e4 --- /dev/null +++ b/apps/system/usbmsc/usbmsc.h @@ -0,0 +1,180 @@ +/**************************************************************************** + * system/usbmsc/usbmsc.h + * + * Copyright (C) 2008-2009, 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 __EXAMPLES_USBSTORAGE_USBMSC_H +#define __EXAMPLES_USBSTORAGE_USBMSC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_SYSTEM_USBMSC_NLUNS +# define CONFIG_SYSTEM_USBMSC_NLUNS 1 +#endif + +#ifndef CONFIG_SYSTEM_USBMSC_DEVMINOR1 +# define CONFIG_SYSTEM_USBMSC_DEVMINOR1 0 +#endif + +#ifndef CONFIG_SYSTEM_USBMSC_DEVPATH1 +# define CONFIG_SYSTEM_USBMSC_DEVPATH1 "/dev/mmcsd0" +#endif + +#if CONFIG_SYSTEM_USBMSC_NLUNS > 1 +# ifndef CONFIG_SYSTEM_USBMSC_DEVMINOR2 +# error "CONFIG_SYSTEM_USBMSC_DEVMINOR2 for LUN=2" +# endif +# ifndef CONFIG_SYSTEM_USBMSC_DEVPATH2 +# error "CONFIG_SYSTEM_USBMSC_DEVPATH2 for LUN=2" +# endif +# if CONFIG_SYSTEM_USBMSC_NLUNS > 2 +# ifndef CONFIG_SYSTEM_USBMSC_DEVMINOR3 +# error "CONFIG_SYSTEM_USBMSC_DEVMINOR2 for LUN=3" +# endif +# ifndef CONFIG_SYSTEM_USBMSC_DEVPATH3 +# error "CONFIG_SYSTEM_USBMSC_DEVPATH3 for LUN=3" +# endif +# if CONFIG_SYSTEM_USBMSC_NLUNS > 3 +# error "CONFIG_SYSTEM_USBMSC_NLUNS must be {1,2,3}" +# endif +# else +# undef CONFIG_SYSTEM_USBMSC_DEVMINOR3 +# undef CONFIG_SYSTEM_USBMSC_DEVPATH3 +# endif +#else +# undef CONFIG_SYSTEM_USBMSC_DEVMINOR2 +# undef CONFIG_SYSTEM_USBMSC_DEVPATH2 +# undef CONFIG_SYSTEM_USBMSC_DEVMINOR3 +# undef CONFIG_SYSTEM_USBMSC_DEVPATH3 +#endif + +#if defined(CONFIG_NSH_BUILTIN_APPS) && defined(CONFIG_SCHED_WAITPID) +# ifndef CONFIG_SYSTEM_USBMSC_DAEMON_STACKSIZE +# define CONFIG_SYSTEM_USBMSC_DAEMON_STACKSIZE 2048 +# endif +#endif + +/* 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. + */ + +#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_SYSTEM_USBMSC_DEBUGMM) +struct usbmsc_state_s +{ + /* This is the handle that references to this particular USB storage driver + * instance. It is only needed if the USB mass storage device add-on is + * built using CONFIG_NSH_BUILTIN_APPS. In this case, the value + * of the driver handle must be remembered between the 'msconn' and 'msdis' + * commands. + */ + +#ifdef CONFIG_NSH_BUILTIN_APPS + FAR void *mshandle; +#endif + + /* Heap usage samples. These are useful for checking USB storage memory + * usage and for tracking down memoryh leaks. + */ + +#ifdef CONFIG_SYSTEM_USBMSC_DEBUGMM + struct mallinfo mmstart; /* Memory usage before the connection */ + struct mallinfo mmprevious; /* The last memory usage sample */ + struct mallinfo mmcurrent; /* The current memory usage sample */ +#endif +}; +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* All global variables used by this add-on are packed into a structure in + * order to avoid name collisions. + */ + +#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_SYSTEM_USBMSC_DEBUGMM) +extern struct usbmsc_state_s g_usbmsc; +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbmsc_archinitialize + * + * Description: + * Perform architecture specific initialization. This function must + * configure the block device to export via USB. This function must be + * provided by architecture-specific logic in order to use this add-on. + * + ****************************************************************************/ + +extern int usbmsc_archinitialize(void); + +#endif /* __EXAMPLES_USBSTORAGE_USBMSC_H */ diff --git a/apps/system/usbmsc/usbmsc_main.c b/apps/system/usbmsc/usbmsc_main.c new file mode 100644 index 000000000..3b3dc96cc --- /dev/null +++ b/apps/system/usbmsc/usbmsc_main.c @@ -0,0 +1,660 @@ +/**************************************************************************** + * system/usbmsc/usbmsc_main.c + * + * Copyright (C) 2008-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 +#include + +#include "usbmsc.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#ifdef CONFIG_SYSTEM_USBMSC_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_USBMSC_TRACECLASS +# define TRACE_CLASS_BITS (TRACE_CLASS_BIT|TRACE_CLASSAPI_BIT|TRACE_CLASSSTATE_BIT) +#else +# define TRACE_CLASS_BITS (0) +#endif + +#ifdef CONFIG_SYSTEM_USBMSC_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_USBMSC_TRACECONTROLLER +# define TRACE_CONTROLLER_BITS (TRACE_EP_BIT|TRACE_DEV_BIT) +#else +# define TRACE_CONTROLLER_BITS (0) +#endif + +#ifdef CONFIG_SYSTEM_USBMSC_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) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* All global variables used by this add-on are packed into a structure in + * order to avoid name collisions. + */ + +#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_SYSTEM_USBMSC_DEBUGMM) +struct usbmsc_state_s g_usbmsc; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: show_memory_usage + ****************************************************************************/ + +#ifdef CONFIG_SYSTEM_USBMSC_DEBUGMM +static void show_memory_usage(struct mallinfo *mmbefore, + struct mallinfo *mmafter) +{ + int diff; + + message(" total used free largest\n"); + message("Before:%11d%11d%11d%11d\n", + mmbefore->arena, mmbefore->uordblks, mmbefore->fordblks, mmbefore->mxordblk); + message("After: %11d%11d%11d%11d\n", + mmafter->arena, mmafter->uordblks, mmafter->fordblks, mmafter->mxordblk); + + diff = mmbefore->uordblks - mmafter->uordblks; + if (diff < 0) + { + message("Change:%11d allocated\n", -diff); + } + else if (diff > 0) + { + message("Change:%11d freed\n", diff); + } +} +#else +# define show_memory_usage(mm1, mm2) +#endif + +/**************************************************************************** + * Name: check_test_memory_usage + ****************************************************************************/ + +#ifdef CONFIG_SYSTEM_USBMSC_DEBUGMM +static void check_test_memory_usage(FAR const char *msg) +{ + /* Get the current memory usage */ + +#ifdef CONFIG_CAN_PASS_STRUCTS + g_usbmsc.mmcurrent = mallinfo(); +#else + (void)mallinfo(&g_usbmsc.mmcurrent); +#endif + + /* Show the change from the previous time */ + + message("\%s:\n", msg); + show_memory_usage(&g_usbmsc.mmprevious, &g_usbmsc.mmcurrent); + + /* Set up for the next test */ + +#ifdef CONFIG_CAN_PASS_STRUCTS + g_usbmsc.mmprevious = g_usbmsc.mmcurrent; +#else + memcpy(&g_usbmsc.mmprevious, &g_usbmsc.mmcurrent, sizeof(struct mallinfo)); +#endif +} +#else +# define check_test_memory_usage(msg) +#endif + +/**************************************************************************** + * Name: check_test_memory_usage + ****************************************************************************/ + +#ifdef CONFIG_SYSTEM_USBMSC_DEBUGMM +static void final_memory_usage(FAR const char *msg) +{ + /* Get the current memory usage */ + +#ifdef CONFIG_CAN_PASS_STRUCTS + g_usbmsc.mmcurrent = mallinfo(); +#else + (void)mallinfo(&g_usbmsc.mmcurrent); +#endif + + /* Show the change from the previous time */ + + message("\n%s:\n", msg); + show_memory_usage(&g_usbmsc.mmstart, &g_usbmsc.mmcurrent); +} +#else +# define final_memory_usage(msg) +#endif + +/**************************************************************************** + * Name: usbmsc_enumerate + ****************************************************************************/ + +#ifdef CONFIG_SYSTEM_USBMSC_TRACE +static int usbmsc_enumerate(struct usbtrace_s *trace, void *arg) +{ + switch (trace->event) + { + case TRACE_DEVINIT: + message("USB controller initialization: %04x\n", trace->value); + break; + + case TRACE_DEVUNINIT: + message("USB controller un-initialization: %04x\n", trace->value); + break; + + case TRACE_DEVREGISTER: + message("usbdev_register(): %04x\n", trace->value); + break; + + case TRACE_DEVUNREGISTER: + message("usbdev_unregister(): %04x\n", trace->value); + break; + + case TRACE_EPCONFIGURE: + message("Endpoint configure(): %04x\n", trace->value); + break; + + case TRACE_EPDISABLE: + message("Endpoint disable(): %04x\n", trace->value); + break; + + case TRACE_EPALLOCREQ: + message("Endpoint allocreq(): %04x\n", trace->value); + break; + + case TRACE_EPFREEREQ: + message("Endpoint freereq(): %04x\n", trace->value); + break; + + case TRACE_EPALLOCBUFFER: + message("Endpoint allocbuffer(): %04x\n", trace->value); + break; + + case TRACE_EPFREEBUFFER: + message("Endpoint freebuffer(): %04x\n", trace->value); + break; + + case TRACE_EPSUBMIT: + message("Endpoint submit(): %04x\n", trace->value); + break; + + case TRACE_EPCANCEL: + message("Endpoint cancel(): %04x\n", trace->value); + break; + + case TRACE_EPSTALL: + message("Endpoint stall(true): %04x\n", trace->value); + break; + + case TRACE_EPRESUME: + message("Endpoint stall(false): %04x\n", trace->value); + break; + + case TRACE_DEVALLOCEP: + message("Device allocep(): %04x\n", trace->value); + break; + + case TRACE_DEVFREEEP: + message("Device freeep(): %04x\n", trace->value); + break; + + case TRACE_DEVGETFRAME: + message("Device getframe(): %04x\n", trace->value); + break; + + case TRACE_DEVWAKEUP: + message("Device wakeup(): %04x\n", trace->value); + break; + + case TRACE_DEVSELFPOWERED: + message("Device selfpowered(): %04x\n", trace->value); + break; + + case TRACE_DEVPULLUP: + message("Device pullup(): %04x\n", trace->value); + break; + + case TRACE_CLASSBIND: + message("Class bind(): %04x\n", trace->value); + break; + + case TRACE_CLASSUNBIND: + message("Class unbind(): %04x\n", trace->value); + break; + + case TRACE_CLASSDISCONNECT: + message("Class disconnect(): %04x\n", trace->value); + break; + + case TRACE_CLASSSETUP: + message("Class setup(): %04x\n", trace->value); + break; + + case TRACE_CLASSSUSPEND: + message("Class suspend(): %04x\n", trace->value); + break; + + case TRACE_CLASSRESUME: + message("Class resume(): %04x\n", trace->value); + break; + + case TRACE_CLASSRDCOMPLETE: + message("Class RD request complete: %04x\n", trace->value); + break; + + case TRACE_CLASSWRCOMPLETE: + message("Class WR request complete: %04x\n", trace->value); + break; + + default: + switch (TRACE_ID(trace->event)) + { + case TRACE_CLASSAPI_ID: /* Other class driver system API calls */ + message("Class API call %d: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_CLASSSTATE_ID: /* Track class driver state changes */ + message("Class state %d: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_INTENTRY_ID: /* Interrupt handler entry */ + message("Interrrupt %d entry: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_INTDECODE_ID: /* Decoded interrupt trace->event */ + message("Interrrupt decode %d: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_INTEXIT_ID: /* Interrupt handler exit */ + message("Interrrupt %d exit: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_OUTREQQUEUED_ID: /* Request queued for OUT endpoint */ + message("EP%d OUT request queued: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_INREQQUEUED_ID: /* Request queued for IN endpoint */ + message("EP%d IN request queued: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_READ_ID: /* Read (OUT) action */ + message("EP%d OUT read: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_WRITE_ID: /* Write (IN) action */ + message("EP%d IN write: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_COMPLETE_ID: /* Request completed */ + message("EP%d request complete: %04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_DEVERROR_ID: /* USB controller driver error event */ + message("Controller error: %02x:%04x\n", TRACE_DATA(trace->event), trace->value); + break; + + case TRACE_CLSERROR_ID: /* USB class driver error event */ + message("Class error: %02x:%04x\n", TRACE_DATA(trace->event), trace->value); + break; + + default: + message("Unrecognized event: %02x:%02x:%04x\n", + TRACE_ID(trace->event) >> 8, TRACE_DATA(trace->event), trace->value); + break; + } + } + return OK; +} +#endif + +/**************************************************************************** + * msconn_main + * + * Description: + * This is the main program that configures the USB mass storage device + * and exports the LUN(s). If CONFIG_NSH_BUILTIN_APPS is defined + * in the NuttX configuration, then this program can be executed by + * entering the "msconn" command at the NSH console. + * + ****************************************************************************/ + +static int msconn_daemon(int argc, char *argv[]) +{ + FAR void *handle; + int ret; + + /* If this program is implemented as the NSH 'msconn' command, then we need to + * do a little error checking to assure that we are not being called re-entrantly. + */ + +#ifdef CONFIG_NSH_BUILTIN_APPS + /* Check if there is a non-NULL USB mass storage device handle (meaning that the + * USB mass storage device is already configured). + */ + + if (g_usbmsc.mshandle) + { + message("msconn_main: ERROR: Already connected\n"); + return EXIT_FAILURE; + } +#endif + +#ifdef CONFIG_SYSTEM_USBMSC_DEBUGMM +# ifdef CONFIG_CAN_PASS_STRUCTS + g_usbmsc.mmstart = mallinfo(); + g_usbmsc.mmprevious = g_usbmsc.mmstart; +# else + (void)mallinfo(&g_usbmsc.mmstart); + memcpy(&g_usbmsc.mmprevious, &g_usbmsc.mmstart, sizeof(struct mallinfo)); +# endif +#endif + + /* Initialize USB trace output IDs */ + +#ifdef CONFIG_SYSTEM_USBMSC_TRACE + usbtrace_enable(TRACE_BITSET); + check_test_memory_usage("After usbtrace_enable()"); +#endif + + /* Register block drivers (architecture-specific) */ + + message("msconn_main: Creating block drivers\n"); + ret = usbmsc_archinitialize(); + if (ret < 0) + { + message("msconn_main: usbmsc_archinitialize failed: %d\n", -ret); + return EXIT_FAILURE; + } + check_test_memory_usage("After usbmsc_archinitialize()"); + + /* Then exports the LUN(s) */ + + message("msconn_main: Configuring with NLUNS=%d\n", CONFIG_SYSTEM_USBMSC_NLUNS); + ret = usbmsc_configure(CONFIG_SYSTEM_USBMSC_NLUNS, &handle); + if (ret < 0) + { + message("msconn_main: usbmsc_configure failed: %d\n", -ret); + usbmsc_uninitialize(handle); + return EXIT_FAILURE; + } + message("msconn_main: handle=%p\n", handle); + check_test_memory_usage("After usbmsc_configure()"); + + message("msconn_main: Bind LUN=0 to %s\n", CONFIG_SYSTEM_USBMSC_DEVPATH1); + ret = usbmsc_bindlun(handle, CONFIG_SYSTEM_USBMSC_DEVPATH1, 0, 0, 0, false); + if (ret < 0) + { + message("msconn_main: usbmsc_bindlun failed for LUN 1 using %s: %d\n", + CONFIG_SYSTEM_USBMSC_DEVPATH1, -ret); + usbmsc_uninitialize(handle); + return EXIT_FAILURE; + } + check_test_memory_usage("After usbmsc_bindlun()"); + +#if CONFIG_SYSTEM_USBMSC_NLUNS > 1 + + message("msconn_main: Bind LUN=1 to %s\n", CONFIG_SYSTEM_USBMSC_DEVPATH2); + ret = usbmsc_bindlun(handle, CONFIG_SYSTEM_USBMSC_DEVPATH2, 1, 0, 0, false); + if (ret < 0) + { + message("msconn_main: usbmsc_bindlun failed for LUN 2 using %s: %d\n", + CONFIG_SYSTEM_USBMSC_DEVPATH2, -ret); + usbmsc_uninitialize(handle); + return EXIT_FAILURE; + } + check_test_memory_usage("After usbmsc_bindlun() #2"); + +#if CONFIG_SYSTEM_USBMSC_NLUNS > 2 + + message("msconn_main: Bind LUN=2 to %s\n", CONFIG_SYSTEM_USBMSC_DEVPATH3); + ret = usbmsc_bindlun(handle, CONFIG_SYSTEM_USBMSC_DEVPATH3, 2, 0, 0, false); + if (ret < 0) + { + message("msconn_main: usbmsc_bindlun failed for LUN 3 using %s: %d\n", + CONFIG_SYSTEM_USBMSC_DEVPATH3, -ret); + usbmsc_uninitialize(handle); + return EXIT_FAILURE; + } + check_test_memory_usage("After usbmsc_bindlun() #3"); + +#endif +#endif + + ret = usbmsc_exportluns(handle); + if (ret < 0) + { + message("msconn_main: usbmsc_exportluns failed: %d\n", -ret); + usbmsc_uninitialize(handle); + return EXIT_FAILURE; + } + check_test_memory_usage("After usbmsc_exportluns()"); + + /* It this program was configued as an NSH command, then just exit now. + * Also, if signals are not enabled (and, hence, sleep() is not supported. + * then we have not real option but to exit now. + */ + +#if !defined(CONFIG_NSH_BUILTIN_APPS) && !defined(CONFIG_DISABLE_SIGNALS) + + /* Otherwise, this thread will hang around and monitor the USB storage activity */ + + for (;;) + { + msgflush(); + sleep(5); + +# ifdef CONFIG_SYSTEM_USBMSC_TRACE + message("\nmsconn_main: USB TRACE DATA:\n"); + ret = usbtrace_enumerate(usbmsc_enumerate, NULL); + if (ret < 0) + { + message("msconn_main: usbtrace_enumerate failed: %d\n", -ret); + usbmsc_uninitialize(handle); + return EXIT_FAILURE; + } + check_test_memory_usage("After usbtrace_enumerate()"); +# else + message("msconn_main: Still alive\n"); +# endif + } +#elif defined(CONFIG_NSH_BUILTIN_APPS) + + /* Return the USB mass storage device handle so it can be used by the 'misconn' + * command. + */ + + message("msconn_main: Connected\n"); + g_usbmsc.mshandle = handle; + check_test_memory_usage("After MS connection"); + +#else /* defined(CONFIG_DISABLE_SIGNALS) */ + + /* Just exit */ + + message("msconn_main: Exiting\n"); + + /* Dump debug memory usage */ + + final_memory_usage("Final memory usage"); +#endif + return EXIT_SUCCESS; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * msconn_main + * + * Description: + * This is the main program that configures the USB mass storage device + * and exports the LUN(s). If CONFIG_NSH_BUILTIN_APPS is defined + * in the NuttX configuration, then this program can be executed by + * entering the "msconn" command at the NSH console. + * + ****************************************************************************/ + +int msconn_main(int argc, char *argv[]) +{ + /* If this function is started as a built-in application from the NSH + * command line, then daemonize. Why? Because NSH is probably waiting + * on waitpid() for msconn to complete. But the USB MSC initialization + * logic creates a dedicated worker thread using pthread_create(). As + * consequences, there will be two members of the task group and waitpid() + * will not wake up when msconn returns. It will not wake-up until both + * msconn and the USB MSC work thread terminate. + */ + +#if defined(CONFIG_NSH_BUILTIN_APPS) && defined(CONFIG_SCHED_WAITPID) + char *newargv[1] = { NULL }; + struct sched_param param; + int ret; + + /* Check if there is a non-NULL USB mass storage device handle (meaning + * that the USB mass storage device is already configured). There is + * no handshaking so there is a race condition: We will check again + * when the daemon is started. + * + * REVISIT: This might a good application for vfork(); + */ + + if (g_usbmsc.mshandle) + { + message("msconn_main: ERROR: Already connected\n"); + return 1; + } + +#ifndef CONFIG_SYSTEM_USBMSC_DAEMON_PRIORITY + /* Set the daemon to the same priority as this task */ + + ret = sched_getparam(0, ¶m); + if (ret < 0) + { + message("msconn_main: ERROR: Already connected\n"); + return EXIT_FAILURE; + } +#else + param.sched_priority = CONFIG_SYSTEM_USBMSC_DAEMON_PRIORITY; +#endif + + ret = TASK_CREATE("msconn daemon", param.sched_priority, + CONFIG_SYSTEM_USBMSC_DAEMON_STACKSIZE, + msconn_daemon, newargv); + if (ret < 0) + { + message("msconn_main: ERROR: TASK_CREATE failed: %d\n", ret); + return EXIT_FAILURE; + } + + return EXIT_SUCCESS; +#else + /* Otherwise, there is no need to daemonize */ + + return msconn_daemon(argc, argv); +#endif +} + +/**************************************************************************** + * msdis_main + * + * Description: + * This is a program entry point that will disconnet the USB mass storage + * device. This program is only available if CONFIG_NSH_BUILTIN_APPS + * is defined in the NuttX configuration. In that case, this program can + * be executed by entering the "msdis" command at the NSH console. + * + ****************************************************************************/ + +#ifdef CONFIG_NSH_BUILTIN_APPS +int msdis_main(int argc, char *argv[]) +{ + /* First check if the USB mass storage device is already connected */ + + if (!g_usbmsc.mshandle) + { + message("msdis: ERROR: Not connected\n"); + return EXIT_FAILURE; + } + check_test_memory_usage("Since MS connection"); + + /* Then disconnect the device and uninitialize the USB mass storage driver */ + + usbmsc_uninitialize(g_usbmsc.mshandle); + g_usbmsc.mshandle = NULL; + message("msdis: Disconnected\n"); + check_test_memory_usage("After usbmsc_uninitialize()"); + + /* Dump debug memory usage */ + + final_memory_usage("Final memory usage"); + return EXIT_SUCCESS; +} +#endif -- cgit v1.2.3