From 1924debc29cbc64094cf41bbdf878c6c53dd4d7b Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 11 Mar 2011 17:37:41 +0000 Subject: More apps/ updates git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3366 42af7a65-404d-4744-a932-0658087f49c3 --- apps/exec_nuttapp.c | 15 ++++-- nuttx/Makefile | 10 ++-- nuttx/examples/nsh/Makefile | 6 ++- nuttx/examples/nsh/nsh.h | 6 +++ nuttx/examples/nsh/nsh_apps.c | 118 ++++++++++++++++++++++++++++++++++++++++++ nuttx/examples/nsh/nsh_main.c | 25 ++------- 6 files changed, 149 insertions(+), 31 deletions(-) create mode 100644 nuttx/examples/nsh/nsh_apps.c diff --git a/apps/exec_nuttapp.c b/apps/exec_nuttapp.c index 4550de27e..3cc4b5139 100644 --- a/apps/exec_nuttapp.c +++ b/apps/exec_nuttapp.c @@ -120,10 +120,6 @@ int exec_nuttapp(FAR const char *appname, FAR const char *argv[]) { int i; - // Not sure what to do with exports and nexports ... as found in exec - // FAR const struct symtab_s *exports, int nexports - // so they are ommited in the args list. - if ( (i = nuttapp_isavail(appname)) >= 0 ) { #ifndef CONFIG_CUSTOM_STACK @@ -132,6 +128,17 @@ int exec_nuttapp(FAR const char *appname, FAR const char *argv[]) #else i = task_create(nuttapps[i].name, nuttapps[i].priority, nuttapps[i].main, &argv[1]); #endif + +#if CONFIG_RR_INTERVAL > 0 + if (i > 0) + { + struct sched_param param; + + sched_getparam(0, ¶m); + sched_setscheduler(i, SCHED_RR, ¶m); + } +#endif + return i; } diff --git a/nuttx/Makefile b/nuttx/Makefile index 4c44492b6..c7e2406ef 100644 --- a/nuttx/Makefile +++ b/nuttx/Makefile @@ -59,14 +59,16 @@ ARCH_SRC = $(ARCH_DIR)/src ARCH_INC = $(ARCH_DIR)/include BOARD_DIR = configs/$(CONFIG_ARCH_BOARD) -# This can be over-ridden from the command line: - -APPS_LOC = ../apps - # Add-on directories. These may or may not be in place in the # NuttX source tree (they must be specifically installed) +# +# APPS_LOC can be over-ridden from the command line: +ifeq ($(CONFIG_BUILTIN_APPS_NUTTX),y) +APPS_LOC = ../apps APPS_DIR := ${shell if [ -r $(APPS_LOC)/Makefile ]; then echo "$(APPS_LOC)"; fi} +endif + PCODE_DIR := ${shell if [ -r pcode/Makefile ]; then echo "pcode"; fi} ADDON_DIRS := $(PCODE_DIR) $(NX_DIR) $(APPS_DIR) diff --git a/nuttx/examples/nsh/Makefile b/nuttx/examples/nsh/Makefile index 66888599b..99e6f6b03 100644 --- a/nuttx/examples/nsh/Makefile +++ b/nuttx/examples/nsh/Makefile @@ -38,7 +38,11 @@ ASRCS = CSRCS = nsh_main.c nsh_fscmds.c nsh_ddcmd.c nsh_proccmds.c nsh_mmcmds.c \ - nsh_envcmds.c nsh_dbgcmds.c + nsh_envcmds.c nsh_dbgcmds.c + +ifeq ($(CONFIG_EXAMPLES_NSH_BUILTIN_APPS),y) +CSRCS += nsh_apps.c +endif ifeq ($(CONFIG_EXAMPLES_NSH_ROMFSETC),y) CSRCS += nsh_romfsetc.c diff --git a/nuttx/examples/nsh/nsh.h b/nuttx/examples/nsh/nsh.h index a7a04a908..4f6811a6d 100644 --- a/nuttx/examples/nsh/nsh.h +++ b/nuttx/examples/nsh/nsh.h @@ -326,6 +326,12 @@ extern int nsh_archinitialize(void); extern int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline); +/* Application interface */ + +#ifdef CONFIG_EXAMPLES_NSH_BUILTIN_APPS +extern int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, const char *cmd, char *argv[]); +#endif + /* I/O interfaces */ #ifdef CONFIG_EXAMPLES_NSH_CONSOLE diff --git a/nuttx/examples/nsh/nsh_apps.c b/nuttx/examples/nsh/nsh_apps.c new file mode 100644 index 000000000..e4391119f --- /dev/null +++ b/nuttx/examples/nsh/nsh_apps.c @@ -0,0 +1,118 @@ +/**************************************************************************** + * examples/nsh/nsh_apps.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011 Uros Platise. All rights reserved. + * Author: Uros Platise + * + * 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 + +#ifdef CONFIG_SCHED_WAITPID +# include +#endif + +#include +#include + +#include + +#include "nsh.h" + +#ifdef CONFIG_EXAMPLES_NSH_BUILTIN_APPS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nsh_execute + ****************************************************************************/ + +int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, const char *cmd, char *argv[]) +{ + int ret = OK; + + /* Try to find command within pre-built application list. */ + + ret = exec_nuttapp(cmd, argv); + if (ret < 0) + { + return -errno; + } + +#ifdef CONFIG_SCHED_WAITPID + if (vtbl->np.np_bg == false) + { + waitpid(ret, NULL, 0); + } + else +#endif + { + struct sched_param param; + sched_getparam(0, ¶m); + nsh_output(vtbl, "%s [%d:%d]\n", cmd, ret, param.sched_priority); + } + + return OK; +} + +#endif /* CONFIG_EXAMPLES_NSH_BUILTIN_APPS */ + + diff --git a/nuttx/examples/nsh/nsh_main.c b/nuttx/examples/nsh/nsh_main.c index 650b6a739..680267e43 100644 --- a/nuttx/examples/nsh/nsh_main.c +++ b/nuttx/examples/nsh/nsh_main.c @@ -40,6 +40,7 @@ #include #include + #include #include #include @@ -494,29 +495,9 @@ static int nsh_execute(FAR struct nsh_vtbl_s *vtbl, int argc, char *argv[]) #ifdef CONFIG_EXAMPLES_NSH_BUILTIN_APPS if (handler == cmd_unrecognized) { - /* Try to find command within pre-built application list. */ + /* Try to execute the command from a list of pre-built applications. */ - if ((ret = exec_nuttapp(cmd, argv)) < 0) - { - if (errno != ENOENT) - { - return -errno; - } - } - else - { -#ifdef CONFIG_SCHED_WAITPID - if (vtbl->np.np_bg == false) - { - waitpid(ret, NULL, 0); - } - else -#endif - { - nsh_output(vtbl, "%s [%d:%d]\n", cmd, ret, 128); // \todo get priority from new pid? - } - return ret; - } + return nsh_execapp(vtbl, cmd, argv); } #endif -- cgit v1.2.3