aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-25 19:29:29 -0800
committerpx4dev <px4@purgatory.org>2013-01-25 19:29:29 -0800
commit24f6c6b121ea87b26a2c5cac933089be496a28b6 (patch)
treec3b8fdab88b12c72197348873caa03d22eb46b60 /apps
parent0bc836ae1d90b1805940ec8ae271639f0074a792 (diff)
parentbeb45222985f1eb9fbe21b22b95c30ab8ca5bbac (diff)
downloadpx4-firmware-24f6c6b121ea87b26a2c5cac933089be496a28b6.tar.gz
px4-firmware-24f6c6b121ea87b26a2c5cac933089be496a28b6.tar.bz2
px4-firmware-24f6c6b121ea87b26a2c5cac933089be496a28b6.zip
Merge branch 'master' into px4io-i2c
Diffstat (limited to 'apps')
-rw-r--r--apps/ChangeLog.txt7
-rw-r--r--apps/builtin/Makefile2
-rw-r--r--apps/builtin/builtin.c33
-rw-r--r--apps/builtin/builtin_list.c79
-rw-r--r--apps/builtin/exec_builtin.c72
-rw-r--r--apps/drivers/blinkm/blinkm.cpp60
-rw-r--r--apps/examples/nsh/nsh_main.c38
-rw-r--r--apps/nshlib/Kconfig11
-rw-r--r--apps/nshlib/Makefile4
-rw-r--r--apps/nshlib/nsh.h5
-rw-r--r--apps/nshlib/nsh_builtin.c63
-rw-r--r--apps/nshlib/nsh_fileapps.c314
-rw-r--r--apps/nshlib/nsh_netcmds.c5
-rw-r--r--apps/nshlib/nsh_parse.c37
14 files changed, 655 insertions, 75 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index 14eb78950..bcc0ac172 100644
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -485,3 +485,10 @@
argument is now optional. Many files systems do not need
a source and it is really stupid to have to enter a bogus
source parameter.
+ * apps/nshlib/nsh_fileapp.c: Add the ability to execute a file
+ from a file system using posix_spawn().
+ * apps/builtin/: Extensions from Mike Smith.
+ * apps/examples/ftpd/Makefile: Name ftpd_start is not the name of
+ the entrypoint. Should be ftpd_main (from Yan T.)
+ * apps/netutils/telnetd/telnetd_driver: Was stuck in a loop if
+ recv[from]() ever returned a value <= 0.
diff --git a/apps/builtin/Makefile b/apps/builtin/Makefile
index d77054f41..f89532871 100644
--- a/apps/builtin/Makefile
+++ b/apps/builtin/Makefile
@@ -39,7 +39,7 @@ include $(APPDIR)/Make.defs
# Source and object files
ASRCS =
-CSRCS = builtin.c exec_builtin.c
+CSRCS = builtin.c builtin_list.c exec_builtin.c
AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/apps/builtin/builtin.c b/apps/builtin/builtin.c
index 7655a531d..d26f0a044 100644
--- a/apps/builtin/builtin.c
+++ b/apps/builtin/builtin.c
@@ -55,27 +55,8 @@
* Public Data
****************************************************************************/
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-#include "builtin_proto.h"
-
-const struct builtin_s g_builtins[] =
-{
-# include "builtin_list.h"
- { NULL, 0, 0, 0 }
-};
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
+extern const struct builtin_s g_builtins[];
+extern const int g_builtin_count;
/****************************************************************************
* Private Data
@@ -89,9 +70,11 @@ const struct builtin_s g_builtins[] =
* Public Functions
****************************************************************************/
-int number_builtins(void)
+FAR const struct builtin_s *builtin_for_index(int index)
{
- return sizeof(g_builtins)/sizeof(struct builtin_s) - 1;
+ if (index < g_builtin_count)
+ {
+ return &g_builtins[index];
+ }
+ return NULL;
}
-
-
diff --git a/apps/builtin/builtin_list.c b/apps/builtin/builtin_list.c
new file mode 100644
index 000000000..a5556bf54
--- /dev/null
+++ b/apps/builtin/builtin_list.c
@@ -0,0 +1,79 @@
+/****************************************************************************
+ * apps/builtin/builtin_list.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <nuttx/config.h>
+
+#include <nuttx/binfmt/builtin.h>
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#include "builtin_proto.h"
+
+const struct builtin_s g_builtins[] =
+{
+# include "builtin_list.h"
+ { NULL, 0, 0, 0 }
+};
+
+const int g_builtin_count = sizeof(g_builtins) / sizeof(g_builtins[0]);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
diff --git a/apps/builtin/exec_builtin.c b/apps/builtin/exec_builtin.c
index 9fde813d6..60e8b742d 100644
--- a/apps/builtin/exec_builtin.c
+++ b/apps/builtin/exec_builtin.c
@@ -46,6 +46,7 @@
#include <nuttx/config.h>
+#include <sys/wait.h>
#include <sched.h>
#include <string.h>
#include <fcntl.h>
@@ -92,7 +93,9 @@ struct builtin_parms_s
****************************************************************************/
static sem_t g_builtin_parmsem = SEM_INITIALIZER(1);
+#ifndef CONFIG_SCHED_WAITPID
static sem_t g_builtin_execsem = SEM_INITIALIZER(0);
+#endif
static struct builtin_parms_s g_builtin_parms;
/****************************************************************************
@@ -121,7 +124,7 @@ static void bultin_semtake(FAR sem_t *sem)
do
{
ret = sem_wait(sem);
- ASSERT(ret == 0 || errno == EINTR);
+ ASSERT(ret == 0 || get_errno() == EINTR);
}
while (ret != 0);
}
@@ -142,8 +145,17 @@ static void bultin_semtake(FAR sem_t *sem)
static int builtin_taskcreate(int index, FAR const char **argv)
{
+ FAR const struct builtin_s *b;
int ret;
+ b = builtin_for_index(index);
+
+ if (b == NULL)
+ {
+ set_errno(ENOENT);
+ return ERROR;
+ }
+
/* Disable pre-emption. This means that although we start the builtin
* application here, it will not actually run until pre-emption is
* re-enabled below.
@@ -153,8 +165,7 @@ static int builtin_taskcreate(int index, FAR const char **argv)
/* Start the builtin application task */
- ret = TASK_CREATE(g_builtins[index].name, g_builtins[index].priority,
- g_builtins[index].stacksize, g_builtins[index].main,
+ ret = TASK_CREATE(b->name, b->priority, b->stacksize, b->main,
(argv) ? &argv[1] : (FAR const char **)NULL);
/* If robin robin scheduling is enabled, then set the scheduling policy
@@ -171,7 +182,7 @@ static int builtin_taskcreate(int index, FAR const char **argv)
* new task cannot yet have changed from its initial value.
*/
- param.sched_priority = g_builtins[index].priority;
+ param.sched_priority = b->priority;
(void)sched_setscheduler(ret, SCHED_RR, &param);
}
#endif
@@ -217,7 +228,7 @@ static int builtin_proxy(int argc, char *argv[])
{
/* Remember the errno value. ret is already set to ERROR */
- g_builtin_parms.errcode = errno;
+ g_builtin_parms.errcode = get_errno();
sdbg("ERROR: open of %s failed: %d\n",
g_builtin_parms.redirfile, g_builtin_parms.errcode);
}
@@ -235,7 +246,7 @@ static int builtin_proxy(int argc, char *argv[])
ret = dup2(fd, 1);
if (ret < 0)
{
- g_builtin_parms.errcode = errno;
+ g_builtin_parms.errcode = get_errno();
sdbg("ERROR: dup2 failed: %d\n", g_builtin_parms.errcode);
}
@@ -255,18 +266,26 @@ static int builtin_proxy(int argc, char *argv[])
ret = builtin_taskcreate(g_builtin_parms.index, g_builtin_parms.argv);
if (ret < 0)
{
- g_builtin_parms.errcode = errno;
+ g_builtin_parms.errcode = get_errno();
sdbg("ERROR: builtin_taskcreate failed: %d\n",
g_builtin_parms.errcode);
}
}
+ /* NOTE: There is a logical error here if CONFIG_SCHED_HAVE_PARENT is
+ * defined: The new task is the child of this proxy task, not the
+ * original caller. As a consequence, operations like waitpid() will
+ * fail on the caller's thread.
+ */
+
/* Post the semaphore to inform the parent task that we have completed
* what we need to do.
*/
g_builtin_parms.result = ret;
+#ifndef CONFIG_SCHED_WAITPID
builtin_semgive(&g_builtin_execsem);
+#endif
return 0;
}
@@ -291,10 +310,11 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
struct sched_param param;
pid_t proxy;
int errcode;
+#ifdef CONFIG_SCHED_WAITPID
+ int status;
+#endif
int ret;
-// DEBUGASSERT(path);
-
svdbg("index=%d argv=%p redirfile=%s oflags=%04x\n",
index, argv, redirfile, oflags);
@@ -326,11 +346,21 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
ret = sched_getparam(0, &param);
if (ret < 0)
{
- errcode = errno;
+ errcode = get_errno();
sdbg("ERROR: sched_getparam failed: %d\n", errcode);
- goto errout;
+ goto errout_with_sem;
}
+ /* Disable pre-emption so that the proxy does not run until we waitpid
+ * is called. This is probably unnecessary since the builtin_proxy has
+ * the same priority as this thread; it should be schedule behind this
+ * task in the ready-to-run list.
+ */
+
+#ifdef CONFIG_SCHED_WAITPID
+ sched_lock();
+#endif
+
/* Start the intermediary/proxy task at the same priority as the parent task. */
proxy = TASK_CREATE("builtin_proxy", param.sched_priority,
@@ -338,16 +368,25 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
(FAR const char **)NULL);
if (proxy < 0)
{
- errcode = errno;
+ errcode = get_errno();
sdbg("ERROR: Failed to start builtin_proxy: %d\n", errcode);
- goto errout;
+ goto errout_with_lock;
}
/* Wait for the proxy to complete its job. We could use waitpid()
* for this.
*/
+#ifdef CONFIG_SCHED_WAITPID
+ ret = waitpid(proxy, &status, 0);
+ if (ret < 0)
+ {
+ sdbg("ERROR: waitpid() failed: %d\n", get_errno());
+ goto errout_with_lock;
+ }
+#else
bultin_semtake(&g_builtin_execsem);
+#endif
/* Get the result and relinquish our access to the parameter structure */
@@ -355,7 +394,12 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
builtin_semgive(&g_builtin_parmsem);
return g_builtin_parms.result;
-errout:
+errout_with_lock:
+#ifdef CONFIG_SCHED_WAITPID
+ sched_unlock();
+#endif
+
+errout_with_sem:
set_errno(errcode);
builtin_semgive(&g_builtin_parmsem);
return ERROR;
diff --git a/apps/drivers/blinkm/blinkm.cpp b/apps/drivers/blinkm/blinkm.cpp
index aeee80905..bc5c74de1 100644
--- a/apps/drivers/blinkm/blinkm.cpp
+++ b/apps/drivers/blinkm/blinkm.cpp
@@ -57,7 +57,7 @@
* System armed:
* One message is made of 4 Blinks and a pause in the same length as the 4 blinks.
*
- * X-X-X-X-_-_-_-_-
+ * X-X-X-X-_-_-_-_-_-_-
* -------------------------
* G G G M
* P P P O
@@ -67,26 +67,26 @@
* (X = on, _=off)
*
* The first 3 blinks indicates the status of the GPS-Signal (red):
- * 0-4 satellites = X-X-X-X-_-_-_-_-
- * 5 satellites = X-X-_-X-_-_-_-_-
- * 6 satellites = X-_-_-X-_-_-_-_-
- * >=7 satellites = _-_-_-X-_-_-_-_-
+ * 0-4 satellites = X-X-X-X-_-_-_-_-_-_-
+ * 5 satellites = X-X-_-X-_-_-_-_-_-_-
+ * 6 satellites = X-_-_-X-_-_-_-_-_-_-
+ * >=7 satellites = _-_-_-X-_-_-_-_-_-_-
* If no GPS is found the first 3 blinks are white
*
* The fourth Blink indicates the Flightmode:
- * MANUAL : off
+ * MANUAL : amber
* STABILIZED : yellow
* HOLD : blue
* AUTO : green
*
* Battery Warning (low Battery Level):
- * Continuously blinking in yellow X-X-X-X-X-X-X-X
+ * Continuously blinking in yellow X-X-X-X-X-X-X-X-X-X
*
* Battery Alert (critical Battery Level)
- * Continuously blinking in red X-X-X-X-X-X-X-X
+ * Continuously blinking in red X-X-X-X-X-X-X-X-X-X
*
* General Error (no uOrb Data)
- * Continuously blinking in white X-X-X-X-X-X-X-X
+ * Continuously blinking in white X-X-X-X-X-X-X-X-X-X
*
*/
@@ -118,8 +118,8 @@
#include <uORB/topics/vehicle_gps_position.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
-static const int LED_ONTIME = 100;
-static const int LED_OFFTIME = 100;
+static const int LED_ONTIME = 120;
+static const int LED_OFFTIME = 120;
static const int LED_BLINK = 1;
static const int LED_NOBLINK = 0;
@@ -167,7 +167,8 @@ private:
LED_PURPLE,
LED_GREEN,
LED_BLUE,
- LED_WHITE
+ LED_WHITE,
+ LED_AMBER
};
work_s _work;
@@ -178,6 +179,8 @@ private:
int led_color_4;
int led_color_5;
int led_color_6;
+ int led_color_7;
+ int led_color_8;
int led_blink;
bool systemstate_run;
@@ -250,6 +253,8 @@ BlinkM::BlinkM(int bus) :
led_color_4(LED_OFF),
led_color_5(LED_OFF),
led_color_6(LED_OFF),
+ led_color_7(LED_OFF),
+ led_color_8(LED_OFF),
led_blink(LED_NOBLINK),
systemstate_run(false)
{
@@ -374,7 +379,7 @@ BlinkM::led()
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
- static int t_led_color[6] = { 0, 0, 0, 0, 0, 0};
+ static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
static int t_led_blink = 0;
static int led_thread_runcount=0;
static int led_interval = 1000;
@@ -416,6 +421,8 @@ BlinkM::led()
t_led_color[4] = LED_PURPLE;
}
t_led_color[5] = LED_OFF;
+ t_led_color[6] = LED_OFF;
+ t_led_color[7] = LED_OFF;
t_led_blink = LED_BLINK;
} else {
t_led_color[0] = led_color_1;
@@ -424,6 +431,8 @@ BlinkM::led()
t_led_color[3] = led_color_4;
t_led_color[4] = led_color_5;
t_led_color[5] = led_color_6;
+ t_led_color[6] = led_color_7;
+ t_led_color[7] = led_color_8;
t_led_blink = led_blink;
}
led_thread_ready = false;
@@ -434,16 +443,19 @@ BlinkM::led()
setLEDColor(LED_OFF);
led_interval = LED_OFFTIME;
} else {
- setLEDColor(t_led_color[(led_thread_runcount / 2) % 6]);
+ setLEDColor(t_led_color[(led_thread_runcount / 2) % 8]);
//led_interval = (led_thread_runcount & 1) : LED_ONTIME;
led_interval = LED_ONTIME;
}
- if (led_thread_runcount == 11) {
+ if (led_thread_runcount == 15) {
/* obtained data for the first file descriptor */
struct vehicle_status_s vehicle_status_raw;
struct vehicle_gps_position_s vehicle_gps_position_raw;
+ memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
+ memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
+
bool new_data_vehicle_status;
bool new_data_vehicle_gps_position;
@@ -473,7 +485,8 @@ BlinkM::led()
/* get number of used satellites in navigation */
num_of_used_sats = 0;
- for(int satloop=0; satloop<20; satloop++) {
+ //for(int satloop=0; satloop<20; satloop++) {
+ for(int satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
if(vehicle_gps_position_raw.satellite_used[satloop] == 1) {
num_of_used_sats++;
}
@@ -497,6 +510,8 @@ BlinkM::led()
led_color_4 = LED_YELLOW;
led_color_5 = LED_YELLOW;
led_color_6 = LED_YELLOW;
+ led_color_7 = LED_YELLOW;
+ led_color_8 = LED_YELLOW;
led_blink = LED_BLINK;
} else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
@@ -507,6 +522,8 @@ BlinkM::led()
led_color_4 = LED_RED;
led_color_5 = LED_RED;
led_color_6 = LED_RED;
+ led_color_7 = LED_RED;
+ led_color_8 = LED_RED;
led_blink = LED_BLINK;
} else {
@@ -520,6 +537,8 @@ BlinkM::led()
led_color_4 = LED_RED;
led_color_5 = LED_RED;
led_color_6 = LED_RED;
+ led_color_7 = LED_RED;
+ led_color_8 = LED_RED;
led_blink = LED_NOBLINK;
} else {
@@ -530,12 +549,14 @@ BlinkM::led()
led_color_4 = LED_OFF;
led_color_5 = LED_OFF;
led_color_6 = LED_OFF;
+ led_color_7 = LED_OFF;
+ led_color_8 = LED_OFF;
led_blink = LED_BLINK;
/* handle 4th led - flightmode indicator */
switch((int)vehicle_status_raw.flight_mode) {
case VEHICLE_FLIGHT_MODE_MANUAL:
- led_color_4 = LED_OFF;
+ led_color_4 = LED_AMBER;
break;
case VEHICLE_FLIGHT_MODE_STAB:
@@ -583,6 +604,8 @@ BlinkM::led()
led_color_4 = LED_WHITE;
led_color_5 = LED_WHITE;
led_color_6 = LED_WHITE;
+ led_color_7 = LED_WHITE;
+ led_color_8 = LED_WHITE;
led_blink = LED_BLINK;
}
@@ -646,6 +669,9 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_WHITE: // white
set_rgb(255,255,255);
break;
+ case LED_AMBER: // amber
+ set_rgb(255,20,0);
+ break;
}
}
diff --git a/apps/examples/nsh/nsh_main.c b/apps/examples/nsh/nsh_main.c
index 97792cb2a..d9bfc2018 100644
--- a/apps/examples/nsh/nsh_main.c
+++ b/apps/examples/nsh/nsh_main.c
@@ -46,6 +46,12 @@
#include <errno.h>
#include <nuttx/arch.h>
+#if defined(CONFIG_FS_BINFS) && (CONFIG_BUILTIN)
+#include <nuttx/binfmt/builtin.h>
+#endif
+#if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB)
+#include <nuttx/binfmt/symtab.h>
+#endif
#include <apps/nsh.h>
@@ -75,6 +81,21 @@
* Public Data
****************************************************************************/
+/* If posix_spawn() is enabled as required for CONFIG_NSH_FILE_APPS, then
+ * a symbol table is needed by the internals of posix_spawn(). The symbol
+ * table is needed to support ELF and NXFLAT binaries to dynamically link to
+ * the base code. However, if only the BINFS file system is supported, then
+ * no Makefile is needed.
+ *
+ * This is a kludge to plug the missing file system in the case where BINFS
+ * is used. REVISIT: This will, of course, be in the way if you want to
+ * support ELF or NXFLAT binaries!
+ */
+
+#if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB)
+const struct symtab_s CONFIG_EXECFUNCS_SYMTAB[1];
+#endif
+
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -98,6 +119,23 @@ int nsh_main(int argc, char *argv[])
up_cxxinitialize();
#endif
+ /* Make sure that we are using our symbol take */
+
+#if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB)
+ exec_setsymtab(CONFIG_EXECFUNCS_SYMTAB, 0);
+#endif
+
+ /* Register the BINFS file system */
+
+#if defined(CONFIG_FS_BINFS) && (CONFIG_BUILTIN)
+ ret = builtin_initialize();
+ if (ret < 0)
+ {
+ fprintf(stderr, "ERROR: builtin_initialize failed: %d\n", ret);
+ exitval = 1;
+ }
+#endif
+
/* Initialize the NSH library */
nsh_initialize();
diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig
index e60e9c480..f6a5aa045 100644
--- a/apps/nshlib/Kconfig
+++ b/apps/nshlib/Kconfig
@@ -14,7 +14,7 @@ config NSH_LIBRARY
if NSH_LIBRARY
config NSH_BUILTIN_APPS
bool "Enable built-in applications"
- default y
+ default n
depends on BUILTIN
---help---
Support external registered, "built-in" applications that can be
@@ -22,6 +22,15 @@ config NSH_BUILTIN_APPS
more information). This options requires support for builtin
applications (BUILTIN).
+config NSH_FILE_APPS
+ bool "Enable execution of program files"
+ default n
+ depends on LIBC_EXECFUNCS
+ ---help---
+ Support execution of program files residing within a file
+ system. This options requires support for the posix_spawn()
+ interface (LIBC_EXECFUNCS).
+
menu "Disable Individual commands"
config NSH_DISABLE_BASE64DEC
diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
index 5c5269685..948f43d52 100644
--- a/apps/nshlib/Makefile
+++ b/apps/nshlib/Makefile
@@ -47,6 +47,10 @@ ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
CSRCS += nsh_builtin.c
endif
+ifeq ($(CONFIG_NSH_FILE_APPS),y)
+CSRCS += nsh_fileapps.c
+endif
+
ifeq ($(CONFIG_NSH_ROMFSETC),y)
CSRCS += nsh_romfsetc.c
endif
diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h
index 253a803f8..64099a8df 100644
--- a/apps/nshlib/nsh.h
+++ b/apps/nshlib/nsh.h
@@ -495,6 +495,11 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
FAR char **argv, FAR const char *redirfile, int oflags);
#endif
+#ifdef CONFIG_NSH_FILE_APPS
+int nsh_fileapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
+ FAR char **argv, FAR const char *redirfile, int oflags);
+#endif
+
/* Working directory support */
#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
diff --git a/apps/nshlib/nsh_builtin.c b/apps/nshlib/nsh_builtin.c
index ba39e8dfe..0d5a0231c 100644
--- a/apps/nshlib/nsh_builtin.c
+++ b/apps/nshlib/nsh_builtin.c
@@ -116,8 +116,8 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
{
int ret = OK;
- /* Lock the scheduler to prevent the application from running until the
- * waitpid() has been called.
+ /* Lock the scheduler in an attempt to prevent the application from
+ * running until waitpid() has been called.
*/
sched_lock();
@@ -129,16 +129,20 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
ret = exec_builtin(cmd, (FAR const char **)argv, redirfile, oflags);
if (ret >= 0)
{
- /* The application was successfully started (but still blocked because
- * the scheduler is locked). If the application was not backgrounded,
- * then we need to wait here for the application to exit. These really
- * only works works with the following options:
+ /* The application was successfully started with pre-emption disabled.
+ * In the simplest cases, the application will not have run because the
+ * the scheduler is locked. But in the case where I/O was redirected, a
+ * proxy task ran and broke our lock. As result, the application may
+ * have aso ran if its priority was higher than than the priority of
+ * this thread.
+ *
+ * If the application did not run to completion and if the application
+ * was not backgrounded, then we need to wait here for the application
+ * to exit. This only works works with the following options:
*
* - CONFIG_NSH_DISABLEBG - Do not run commands in background
* - CONFIG_SCHED_WAITPID - Required to run external commands in
* foreground
- *
- * These concepts do not apply cleanly to the external applications.
*/
#ifdef CONFIG_SCHED_WAITPID
@@ -154,15 +158,46 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
{
int rc = 0;
- /* Wait for the application to exit. Since we have locked the
- * scheduler above, we know that the application has not yet
- * started and there is no possibility that it has already exited.
- * The scheduler will be unlocked while waitpid is waiting and the
- * application will be able to run.
+ /* Wait for the application to exit. We did lock the scheduler
+ * above, but that does not guarantee that the application did not
+ * already run to completion in the case where I/O was redirected.
+ * Here the scheduler will be unlocked while waitpid is waiting
+ * and if the application has not yet run, it will now be able to
+ * do so.
+ *
+ * Also, if CONFIG_SCHED_HAVE_PARENT is defined waitpid() might fail
+ * even if task is still active: If the I/O was re-directed by a
+ * proxy task, then the ask is a child of the proxy, and not this
+ * task. waitpid() fails with ECHILD in either case.
*/
ret = waitpid(ret, &rc, 0);
- if (ret >= 0)
+ if (ret < 0)
+ {
+ /* If the child thread does not exist, waitpid() will return
+ * the error ECHLD. Since we know that the task was successfully
+ * started, this must be one of the cases described above; we
+ * have to assume that the task already exit'ed. In this case,
+ * we have no idea if the application ran successfully or not
+ * (because NuttX does not retain exit status of child tasks).
+ * Let's assume that is did run successfully.
+ */
+
+ int errcode = errno;
+ if (errcode == ECHILD)
+ {
+ ret = OK;
+ }
+ else
+ {
+ nsh_output(vtbl, g_fmtcmdfailed, cmd, "waitpid",
+ NSH_ERRNO_OF(errcode));
+ }
+ }
+
+ /* Waitpid completed the wait successfully */
+
+ else
{
/* We can't return the exact status (nsh has nowhere to put it)
* so just pass back zero/nonzero in a fashion that doesn't look
diff --git a/apps/nshlib/nsh_fileapps.c b/apps/nshlib/nsh_fileapps.c
new file mode 100644
index 000000000..9ff230f1a
--- /dev/null
+++ b/apps/nshlib/nsh_fileapps.c
@@ -0,0 +1,314 @@
+/****************************************************************************
+ * apps/nshlib/nsh_fileapps.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <nuttx/config.h>
+
+#ifdef CONFIG_SCHED_WAITPID
+# include <sys/wait.h>
+#endif
+
+#include <stdbool.h>
+#include <spawn.h>
+#include <errno.h>
+#include <string.h>
+
+#include "nsh.h"
+#include "nsh_console.h"
+
+#ifdef CONFIG_NSH_FILE_APPS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_fileapp
+ *
+ * Description:
+ * Attempt to execute the application task whose name is 'cmd'
+ *
+ * Returned Value:
+ * <0 If exec_builtin() fails, then the negated errno value
+ * is returned.
+ * -1 (ERROR) if the application task corresponding to 'cmd' could not
+ * be started (possibly because it doesn not exist).
+ * 0 (OK) if the application task corresponding to 'cmd' was
+ * and successfully started. If CONFIG_SCHED_WAITPID is
+ * defined, this return value also indicates that the
+ * application returned successful status (EXIT_SUCCESS)
+ * 1 If CONFIG_SCHED_WAITPID is defined, then this return value
+ * indicates that the application task was spawned successfully
+ * but returned failure exit status.
+ *
+ ****************************************************************************/
+
+int nsh_fileapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
+ FAR char **argv, FAR const char *redirfile, int oflags)
+{
+ posix_spawn_file_actions_t file_actions;
+ posix_spawnattr_t attr;
+ pid_t pid;
+ int ret;
+
+ /* Initialize the attributes file actions structure */
+
+ ret = posix_spawn_file_actions_init(&file_actions);
+ if (ret != 0)
+ {
+ /* posix_spawn_file_actions_init returns a positive errno value on
+ * failure.
+ */
+
+ nsh_output(vtbl, g_fmtcmdfailed, cmd, "posix_spawn_file_actions_init",
+ NSH_ERRNO_OF(ret));
+ goto errout;
+ }
+
+ ret = posix_spawnattr_init(&attr);
+ if (ret != 0)
+ {
+ /* posix_spawnattr_init returns a positive errno value on failure. */
+
+ nsh_output(vtbl, g_fmtcmdfailed, cmd, "posix_spawnattr_init",
+ NSH_ERRNO);
+ goto errout_with_actions;
+ }
+
+ /* Handle re-direction of output */
+
+ if (redirfile)
+ {
+ ret = posix_spawn_file_actions_addopen(&file_actions, 1, redirfile,
+ oflags, 0644);
+ if (ret != 0)
+ {
+ /* posix_spawn_file_actions_addopen returns a positive errno
+ * value on failure.
+ */
+
+ nsh_output(vtbl, g_fmtcmdfailed, cmd,
+ "posix_spawn_file_actions_addopen",
+ NSH_ERRNO);
+ goto errout_with_attrs;
+ }
+ }
+
+ /* Lock the scheduler in an attempt to prevent the application from
+ * running until waitpid() has been called.
+ */
+
+ sched_lock();
+
+ /* Execute the program. posix_spawnp returns a positive errno value on
+ * failure.
+ */
+
+ ret = posix_spawnp(&pid, cmd, &file_actions, &attr, &argv[1], NULL);
+ if (ret == OK)
+ {
+ /* The application was successfully started with pre-emption disabled.
+ * In the simplest cases, the application will not have run because the
+ * the scheduler is locked. But in the case where I/O was redirected, a
+ * proxy task ran and broke our lock. As result, the application may
+ * have aso ran if its priority was higher than than the priority of
+ * this thread.
+ *
+ * If the application did not run to completion and if the application
+ * was not backgrounded, then we need to wait here for the application
+ * to exit. This only works works with the following options:
+ *
+ * - CONFIG_NSH_DISABLEBG - Do not run commands in background
+ * - CONFIG_SCHED_WAITPID - Required to run external commands in
+ * foreground
+ */
+
+#ifdef CONFIG_SCHED_WAITPID
+
+ /* CONFIG_SCHED_WAITPID is selected, so we may run the command in
+ * foreground unless we were specifically requested to run the command
+ * in background (and running commands in background is enabled).
+ */
+
+# ifndef CONFIG_NSH_DISABLEBG
+ if (vtbl->np.np_bg == false)
+# endif /* CONFIG_NSH_DISABLEBG */
+ {
+ int rc = 0;
+
+ /* Wait for the application to exit. We did lock the scheduler
+ * above, but that does not guarantee that the application did not
+ * already run to completion in the case where I/O was redirected.
+ * Here the scheduler will be unlocked while waitpid is waiting
+ * and if the application has not yet run, it will now be able to
+ * do so.
+ */
+
+ ret = waitpid(pid, &rc, 0);
+ if (ret < 0)
+ {
+ /* If the child thread does not exist, waitpid() will return
+ * the error ECHLD. Since we know that the task was successfully
+ * started, this must be one of the cases described above; we
+ * have to assume that the task already exit'ed. In this case,
+ * we have no idea if the application ran successfully or not
+ * (because NuttX does not retain exit status of child tasks).
+ * Let's assume that is did run successfully.
+ */
+
+ int errcode = errno;
+ if (errcode == ECHILD)
+ {
+ ret = OK;
+ }
+ else
+ {
+ nsh_output(vtbl, g_fmtcmdfailed, cmd, "waitpid",
+ NSH_ERRNO_OF(errcode));
+ }
+ }
+
+ /* Waitpid completed the wait successfully */
+
+ else
+ {
+ /* We can't return the exact status (nsh has nowhere to put it)
+ * so just pass back zero/nonzero in a fashion that doesn't look
+ * like an error.
+ */
+
+ ret = (rc == 0) ? OK : 1;
+
+ /* TODO: Set the environment variable '?' to a string corresponding
+ * to WEXITSTATUS(rc) so that $? will expand to the exit status of
+ * the most recently executed task.
+ */
+ }
+ }
+# ifndef CONFIG_NSH_DISABLEBG
+ else
+# endif /* CONFIG_NSH_DISABLEBG */
+#endif /* CONFIG_SCHED_WAITPID */
+
+ /* We get here if either:
+ *
+ * - CONFIG_SCHED_WAITPID is not selected meaning that all commands
+ * have to be run in background, or
+ * - CONFIG_SCHED_WAITPID and CONFIG_NSH_DISABLEBG are both selected, but the
+ * user requested to run the command in background.
+ *
+ * NOTE that the case of a) CONFIG_SCHED_WAITPID is not selected and
+ * b) CONFIG_NSH_DISABLEBG selected cannot be supported. In that event, all
+ * commands will have to run in background. The waitpid() API must be
+ * available to support running the command in foreground.
+ */
+
+#if !defined(CONFIG_SCHED_WAITPID) || !defined(CONFIG_NSH_DISABLEBG)
+ {
+ struct sched_param param;
+ sched_getparam(ret, &param);
+ nsh_output(vtbl, "%s [%d:%d]\n", cmd, ret, param.sched_priority);
+
+ /* Backgrounded commands always 'succeed' as long as we can start
+ * them.
+ */
+
+ ret = OK;
+ }
+#endif /* !CONFIG_SCHED_WAITPID || !CONFIG_NSH_DISABLEBG */
+ }
+
+ sched_unlock();
+
+ /* Free attibutes and file actions. Ignoring return values in the case
+ * of an error.
+ */
+
+errout_with_actions:
+ (void)posix_spawn_file_actions_destroy(&file_actions);
+
+errout_with_attrs:
+ (void)posix_spawnattr_destroy(&attr);
+
+errout:
+ /* Most posix_spawn interfaces return a positive errno value on failure
+ * and do not set the errno variable.
+ */
+
+ if (ret > 0)
+ {
+ /* Set the errno value and return -1 */
+
+ set_errno(ret);
+ ret = ERROR;
+ }
+ else if (ret < 0)
+ {
+ /* Return -1 on failure. errno should have been set. */
+
+ ret = ERROR;
+ }
+
+ return ret;
+}
+
+#endif /* CONFIG_NSH_FILE_APPS */
diff --git a/apps/nshlib/nsh_netcmds.c b/apps/nshlib/nsh_netcmds.c
index 506950e14..473045c40 100644
--- a/apps/nshlib/nsh_netcmds.c
+++ b/apps/nshlib/nsh_netcmds.c
@@ -53,12 +53,13 @@
#include <errno.h>
#include <debug.h>
+#include <net/ethernet.h>
+#include <netinet/ether.h>
+
#include <nuttx/net/net.h>
#include <nuttx/clock.h>
-#include <net/ethernet.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/uip/uip-arch.h>
-#include <netinet/ether.h>
#ifdef CONFIG_NET_STATISTICS
# include <nuttx/net/uip/uip.h>
diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c
index ef4125a63..f679d9b32 100644
--- a/apps/nshlib/nsh_parse.c
+++ b/apps/nshlib/nsh_parse.c
@@ -61,6 +61,7 @@
#ifdef CONFIG_NSH_BUILTIN_APPS
# include <nuttx/binfmt/builtin.h>
#endif
+
#include <apps/nsh.h>
#include "nsh.h"
@@ -1398,6 +1399,40 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
nsh_output(vtbl, g_fmttoomanyargs, cmd);
}
+ /* Does this command correspond to an application filename?
+ * nsh_fileapp() returns:
+ *
+ * -1 (ERROR) if the application task corresponding to 'argv[0]' could not
+ * be started (possibly because it doesn not exist).
+ * 0 (OK) if the application task corresponding to 'argv[0]' was
+ * and successfully started. If CONFIG_SCHED_WAITPID is
+ * defined, this return value also indicates that the
+ * application returned successful status (EXIT_SUCCESS)
+ * 1 If CONFIG_SCHED_WAITPID is defined, then this return value
+ * indicates that the application task was spawned successfully
+ * but returned failure exit status.
+ *
+ * Note the priority if not effected by nice-ness.
+ */
+
+#ifdef CONFIG_NSH_FILE_APPS
+ ret = nsh_fileapp(vtbl, argv[0], argv, redirfile, oflags);
+ if (ret >= 0)
+ {
+ /* nsh_fileapp() returned 0 or 1. This means that the builtin
+ * command was successfully started (although it may not have ran
+ * successfully). So certainly it is not an NSH command.
+ */
+
+ return nsh_saveresult(vtbl, ret != OK);
+ }
+
+ /* No, not a built in command (or, at least, we were unable to start a
+ * builtin command of that name). Treat it like an NSH command.
+ */
+
+#endif
+
/* Does this command correspond to a builtin command?
* nsh_builtin() returns:
*
@@ -1414,7 +1449,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
* Note the priority if not effected by nice-ness.
*/
-#ifdef CONFIG_NSH_BUILTIN_APPS
+#if defined(CONFIG_NSH_BUILTIN_APPS) && (!defined(CONFIG_NSH_FILE_APPS) || !defined(CONFIG_FS_BINFS))
ret = nsh_builtin(vtbl, argv[0], argv, redirfile, oflags);
if (ret >= 0)
{