summaryrefslogtreecommitdiff
path: root/nuttx/examples
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-30 15:43:32 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-30 15:43:32 +0000
commit7cbb998f1479d9e8975cd3f1e5a98f3fffaa5670 (patch)
tree751094b8b61b72284b65b02886998faa7c365bf4 /nuttx/examples
parent19730f2f20d3244c684ba0cfeffea25df8b5fe78 (diff)
downloadpx4-nuttx-7cbb998f1479d9e8975cd3f1e5a98f3fffaa5670.tar.gz
px4-nuttx-7cbb998f1479d9e8975cd3f1e5a98f3fffaa5670.tar.bz2
px4-nuttx-7cbb998f1479d9e8975cd3f1e5a98f3fffaa5670.zip
Use pthreads instead of tasks in BG
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@855 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/examples')
-rw-r--r--nuttx/examples/nsh/nsh.h19
-rw-r--r--nuttx/examples/nsh/nsh_main.c283
-rw-r--r--nuttx/examples/nsh/nsh_serial.c62
-rw-r--r--nuttx/examples/nsh/nsh_telnetd.c165
4 files changed, 355 insertions, 174 deletions
diff --git a/nuttx/examples/nsh/nsh.h b/nuttx/examples/nsh/nsh.h
index 69ed0f030..76e2701ba 100644
--- a/nuttx/examples/nsh/nsh.h
+++ b/nuttx/examples/nsh/nsh.h
@@ -49,6 +49,14 @@
* Definitions
****************************************************************************/
+/* The telnetd interface requires pthread support */
+
+#ifdef CONFIG_DISABLE_PTHREAD
+# undef CONFIG_EXAMPLES_NSH_TELNET
+#endif
+
+/* One front end must be defined */
+
#if !defined(CONFIG_EXAMPLES_NSH_CONSOLE) && !defined(CONFIG_EXAMPLES_NSH_TELNET)
# error "No NSH front end defined"
#endif
@@ -97,7 +105,7 @@
/* Define to enable dumping of all input/output buffers */
-#undef CONFIG_EXAMPLES_NSH_TELNETD_DUMPBUFFER
+#define CONFIG_EXAMPLES_NSH_TELNETD_DUMPBUFFER 1
#undef CONFIG_EXAMPLES_NSH_FULLPATH
/* Make sure that the home directory is defined */
@@ -107,7 +115,6 @@
#endif
#define nsh_clone(v) (v)->clone(v)
-#define nsh_addref(v) (v)->addref(v)
#define nsh_release(v) (v)->release(v)
#define nsh_linebuffer(v) (v)->linebuffer(v)
#define nsh_redirect(v,f,s) (v)->redirect(v,f,s)
@@ -151,11 +158,15 @@ struct nsh_state_s
struct nsh_parser_s
{
+#ifndef CONFIG_DISABLE_PTHREAD
boolean np_bg; /* TRUE: The last command executed in background */
+#endif
boolean np_redirect; /* TRUE: Output from the last command was re-directed */
boolean np_fail; /* TRUE: The last command failed */
ubyte np_ndx; /* Current index into np_st[] */
+#ifndef CONFIG_DISABLE_PTHREAD
int np_nice; /* "nice" value applied to last background cmd */
+#endif
/* This is a stack of parser state information. It supports nested
* execution of commands that span multiple lines (like if-then-else-fi)
@@ -171,10 +182,12 @@ struct nsh_vtbl_s
* -- all of which must be done in a way that is unique to the nature
* of the front end.
*/
-
+
+#ifndef CONFIG_DISABLE_PTHREAD
FAR struct nsh_vtbl_s *(*clone)(FAR struct nsh_vtbl_s *vtbl);
void (*addref)(FAR struct nsh_vtbl_s *vtbl);
void (*release)(FAR struct nsh_vtbl_s *vtbl);
+#endif
int (*output)(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...);
FAR char *(*linebuffer)(FAR struct nsh_vtbl_s *vtbl);
void (*redirect)(FAR struct nsh_vtbl_s *vtbl, int fd, FAR ubyte *save);
diff --git a/nuttx/examples/nsh/nsh_main.c b/nuttx/examples/nsh/nsh_main.c
index 35f88b72a..7ca2937bb 100644
--- a/nuttx/examples/nsh/nsh_main.c
+++ b/nuttx/examples/nsh/nsh_main.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * nsh_main.c
+ * examples/nsh/nsh_main.c
*
* Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -48,6 +48,11 @@
#include <sched.h>
#include <fcntl.h>
#include <errno.h>
+#include <debug.h>
+
+#ifndef CONFIG_DISABLE_PTHREAD
+# include <pthread.h>
+#endif
#include "nsh.h"
@@ -55,6 +60,30 @@
* Definitions
****************************************************************************/
+/* Argument list size
+ *
+ * argv[0]: The command name.
+ * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS)
+ * argv[argc-3]: Possibly '>' or '>>'
+ * argv[argc-2]: Possibly <file>
+ * argv[argc-1]: Possibly '&' (if pthreads are enabled)
+ * argv[argc]: NULL terminating pointer
+ *
+ * Maximum size is NSH_MAX_ARGUMENTS+5
+ */
+
+#ifndef CONFIG_DISABLE_PTHREAD
+# define MAX_ARGV_ENTRIES (NSH_MAX_ARGUMENTS+5)
+#else
+# define MAX_ARGV_ENTRIES (NSH_MAX_ARGUMENTS+4)
+#endif
+
+#if CONFIG_RR_INTERVAL > 0
+# define SCHED_NSH SCHED_RR
+#else
+# define SCHED_NSH SCHED_FIFO
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -68,6 +97,16 @@ struct cmdmap_s
const char *usage; /* Usage instructions for 'help' command */
};
+#ifndef CONFIG_DISABLE_PTHREAD
+struct cmdarg_s
+{
+ FAR struct nsh_vtbl_s *vtbl; /* For front-end interaction */
+ int fd; /* FD for output redirection */
+ int argc; /* Number of arguments in argv */
+ FAR char *argv[MAX_ARGV_ENTRIES]; /* Argument list */
+};
+#endif
+
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -193,7 +232,11 @@ static int cmd_help(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
const struct cmdmap_s *ptr;
nsh_output(vtbl, "NSH command forms:\n");
- nsh_output(vtbl, " [nice [-d <niceness>>]] <cmd> [[> <file>|>> <file>] &]\n");
+#ifndef CONFIG_DISABLE_PTHREAD
+ nsh_output(vtbl, " [nice [-d <niceness>>]] <cmd> [> <file>|>> <file>] [&]\n");
+#else
+ nsh_output(vtbl, " <cmd> [> <file>|>> <file>]\n");
+#endif
nsh_output(vtbl, "OR\n");
nsh_output(vtbl, " if <cmd>\n");
nsh_output(vtbl, " then\n");
@@ -240,32 +283,22 @@ static int cmd_exit(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
* Name: nsh_execute
****************************************************************************/
-static int nsh_execute(int argc, char *argv[])
+static int nsh_execute(FAR struct nsh_vtbl_s *vtbl, int argc, char *argv[])
{
const struct cmdmap_s *cmdmap;
const char *cmd;
- struct nsh_vtbl_s *vtbl;
cmd_t handler = cmd_unrecognized;
int ret;
- /* Parse all of the arguments following the command name. The form
- * of argv is:
+ /* The form of argv is:
*
- * argv[0]: Task name "nsh_execute"
- * argv[1]: This is string version of the vtbl needed to execute
- * the command (under telnetd). It is a string because
- * binary values cannot be provided via char *argv[]
- * argv[2]: The command name. This is argv[0] when the arguments
+ * argv[0]: The command name. This is argv[0] when the arguments
* are, finally, received by the command vtblr
- * argv[3]: The beginning of argument (up to NSH_MAX_ARGUMENTS)
+ * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS)
* argv[argc]: NULL terminating pointer
- *
- * Maximum size is NSH_MAX_ARGUMENTS+4
*/
- vtbl = (struct nsh_vtbl_s*)strtol(argv[1], NULL, 16);
- cmd = argv[2];
- argc -= 2;
+ cmd = argv[0];
/* See if the command is one that we understand */
@@ -304,12 +337,93 @@ static int nsh_execute(int argc, char *argv[])
}
}
- ret = handler(vtbl, argc, &argv[2]);
- nsh_release(vtbl);
+ ret = handler(vtbl, argc, argv);
return ret;
}
/****************************************************************************
+ * Name: nsh_releaseargs
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_PTHREAD
+static void nsh_releaseargs(struct cmdarg_s *arg)
+{
+ FAR struct nsh_vtbl_s *vtbl = arg->vtbl;
+ int i;
+
+ /* If the output was redirected, then file descriptor should
+ * be closed. The created task has its one, independent copy of
+ * the file descriptor
+ */
+
+ if (vtbl->np.np_redirect)
+ {
+ (void)close(arg->fd);
+ }
+
+ /* Released the cloned vtbl instance */
+
+ nsh_release(vtbl);
+
+ /* Release the cloned args */
+
+ for (i = 0; i < arg->argc; i++)
+ {
+ free(arg->argv[i]);
+ }
+ free(arg);
+}
+#endif
+
+/****************************************************************************
+ * Name: nsh_child
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_PTHREAD
+static pthread_addr_t nsh_child(pthread_addr_t arg)
+{
+ struct cmdarg_s *carg = (struct cmdarg_s *)arg;
+ int ret;
+
+ dbg("BG %s\n", carg->argv[0]);
+
+ /* Execute the specified command on the child thread */
+
+ ret = nsh_execute(carg->vtbl, carg->argc, carg->argv);
+
+ /* Released the cloned arguments */
+
+ dbg("BG %s complete\n", carg->argv[0]);
+ nsh_releaseargs(carg);
+ return (void*)ret;
+}
+#endif
+
+/****************************************************************************
+ * Name: nsh_cloneargs
+ ****************************************************************************/
+
+static inline struct cmdarg_s *nsh_cloneargs(FAR struct nsh_vtbl_s *vtbl,
+ int fd, int argc, char *argv[])
+{
+ struct cmdarg_s *ret = (struct cmdarg_s *)zalloc(sizeof(struct cmdarg_s));
+ int i;
+
+ if (ret)
+ {
+ ret->vtbl = vtbl;
+ ret->fd = fd;
+ ret->argc = argc;
+
+ for (i = 0; i < argc; i++)
+ {
+ ret->argv[i] = strdup(argv[i]);
+ }
+ }
+ return ret;
+}
+
+/****************************************************************************
* Name: nsh_argument
****************************************************************************/
@@ -518,7 +632,7 @@ static inline int nsh_ifthenelse(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
if (np->np_ndx >= CONFIG_EXAMPLES_NSH_NESTDEPTH-1)
{
nsh_output(vtbl, g_fmtdeepnesting, "if");
- goto errout;
+ goto errout;
}
/* "Push" the old state and set the new state */
@@ -592,7 +706,7 @@ static inline int nsh_ifthenelse(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
if (np->np_ndx < 1) /* Shouldn't happen */
{
nsh_output(vtbl, g_fmtinternalerror, "if");
- goto errout;
+ goto errout;
}
/* "Pop" the previous state */
@@ -640,10 +754,11 @@ static inline int nsh_saveresult(FAR struct nsh_vtbl_s *vtbl, boolean result)
* Name: nsh_nice
****************************************************************************/
+#ifndef CONFIG_DISABLE_PTHREAD
static inline int nsh_nice(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd, FAR char **saveptr)
{
FAR char *cmd = *ppcmd;
-
+
vtbl->np.np_nice = 0;
if (cmd)
{
@@ -684,6 +799,7 @@ static inline int nsh_nice(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd, FAR ch
}
return OK;
}
+#endif
/****************************************************************************
* Public Functions
@@ -711,12 +827,12 @@ int user_start(int argc, char *argv[])
* can both raise and lower the priority.
*/
- mid_priority = (sched_get_priority_max(SCHED_RR) + sched_get_priority_min(SCHED_RR)) >> 1;
+ mid_priority = (sched_get_priority_max(SCHED_NSH) + sched_get_priority_min(SCHED_NSH)) >> 1;
{
struct sched_param param;
param.sched_priority = mid_priority;
- (void)sched_setscheduler(0, SCHED_RR, &param);
+ (void)sched_setscheduler(0, SCHED_NSH, &param);
}
/* If both the console and telnet are selected as front-ends, then run
@@ -754,8 +870,7 @@ int user_start(int argc, char *argv[])
int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
{
- FAR char *argv[NSH_MAX_ARGUMENTS+7];
- FAR char strvtbl[2*sizeof(FAR char*)+3];
+ FAR char *argv[MAX_ARGV_ENTRIES];
FAR char *saveptr;
FAR char *cmd;
FAR char *redirfile = NULL;
@@ -766,7 +881,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
/* Initialize parser state */
- memset(argv, 0, (NSH_MAX_ARGUMENTS+4)*sizeof(char*));
+ memset(argv, 0, MAX_ARGV_ENTRIES*sizeof(FAR char *));
vtbl->np.np_bg = FALSE;
vtbl->np.np_redirect = FALSE;
@@ -784,10 +899,12 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
/* Handle nice */
+#ifndef CONFIG_DISABLE_PTHREAD
if (nsh_nice(vtbl, &cmd, &saveptr) != 0)
{
goto errout;
}
+#endif
/* Check if any command was provided -OR- if command processing is
* currently disabled.
@@ -806,27 +923,18 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
/* Parse all of the arguments following the command name. The form
* of argv is:
*
- * argv[0]: Not really used. It is just a place hold for where the
- * task name would be if the same command were executed
- * in the "background"
- * argv[1]: This is string version of the vtbl needed to execute
- * the command (under telnetd). It is a string because
- * binary values cannot be provided via char *argv[]. NOTE
- * that this value is filled in later.
- * argv[2]: The command name. This is argv[0] when the arguments
- * are, finally, received by the command vtblr
- * argv[3]: The beginning of argument (up to NSH_MAX_ARGUMENTS)
- * argv[argc-3]: Possibly '>' or '>>'
- * argv[argc-2]: Possibly <file>
- * argv[argc-1]: Possibly '&'
- * argv[argc]: NULL terminating pointer
+ * argv[0]: The command name.
+ * argv[1]: The beginning of argument (up to NSH_MAX_ARGUMENTS)
+ * argv[argc-3]: Possibly '>' or '>>'
+ * argv[argc-2]: Possibly <file>
+ * argv[argc-1]: Possibly '&'
+ * argv[argc]: NULL terminating pointer
*
- * Maximum size is NSH_MAX_ARGUMENTS+7
+ * Maximum size is NSH_MAX_ARGUMENTS+5
*/
- argv[0] = "nsh_execute";
- argv[2] = cmd;
- for (argc = 3; argc < NSH_MAX_ARGUMENTS+6; argc++)
+ argv[0] = cmd;
+ for (argc = 1; argc < MAX_ARGV_ENTRIES-1; argc++)
{
argv[argc] = nsh_argument(vtbl, &saveptr);
if (!argv[argc])
@@ -838,7 +946,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
/* Check if the command should run in background */
- if (argc > 3 && strcmp(argv[argc-1], "&") == 0)
+ if (argc > 1 && strcmp(argv[argc-1], "&") == 0)
{
vtbl->np.np_bg = TRUE;
argv[argc-1] = NULL;
@@ -847,7 +955,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
/* Check if the output was re-directed using > or >> */
- if (argc > 5)
+ if (argc > 2)
{
/* Check for redirection to a new file */
@@ -893,30 +1001,41 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
/* Check if the maximum number of arguments was exceeded */
- if (argc > NSH_MAX_ARGUMENTS+3)
+ if (argc > NSH_MAX_ARGUMENTS)
{
nsh_output(vtbl, g_fmttoomanyargs, cmd);
}
/* Handle the case where the command is executed in background */
+#ifndef CONFIG_DISABLE_PTHREAD
if (vtbl->np.np_bg)
{
struct sched_param param;
- int priority;
struct nsh_vtbl_s *bkgvtbl;
+ struct cmdarg_s *args;
+ pthread_attr_t attr;
+ pthread_t thread;
/* Get a cloned copy of the vtbl with reference count=1.
* after the command has been processed, the nsh_release() call
- * at the end of nsh_execute() will destroy the clone.
+ * at the end of nsh_child() will destroy the clone.
*/
bkgvtbl = nsh_clone(vtbl);
+ if (!bkgvtbl)
+ {
+ goto errout_with_redirect;
+ }
- /* Place a string copy of the cloned vtbl in the argument list */
+ /* Create a container for the command arguments */
- sprintf(strvtbl, "%p\n", bkgvtbl);
- argv[1] = strvtbl;
+ args = nsh_cloneargs(bkgvtbl, fd, argc, argv);
+ if (!args)
+ {
+ nsh_release(bkgvtbl);
+ goto errout_with_redirect;
+ }
/* Handle redirection of output via a file descriptor */
@@ -931,18 +1050,19 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
if (ret != 0)
{
nsh_output(vtbl, g_fmtcmdfailed, cmd, "sched_getparm", NSH_ERRNO);
- goto errout_with_redirect;
+ nsh_releaseargs(args);
+ nsh_release(bkgvtbl);
+ goto errout;
}
/* Determine the priority to execute the command */
- priority = param.sched_priority;
if (vtbl->np.np_nice != 0)
{
- priority -= vtbl->np.np_nice;
+ int priority = param.sched_priority - vtbl->np.np_nice;
if (vtbl->np.np_nice < 0)
{
- int max_priority = sched_get_priority_max(SCHED_RR);
+ int max_priority = sched_get_priority_max(SCHED_NSH);
if (priority > max_priority)
{
priority = max_priority;
@@ -950,55 +1070,38 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
}
else
{
- int min_priority = sched_get_priority_min(SCHED_RR);
+ int min_priority = sched_get_priority_min(SCHED_NSH);
if (priority < min_priority)
{
priority = min_priority;
}
}
+ param.sched_priority = priority;
}
- /* Execute the command as a separate task at the appropriate priority */
+ /* Set up the thread attributes */
-#ifndef CONFIG_CUSTOM_STACK
- ret = task_create("nsh_execute", priority, CONFIG_EXAMPLES_NSH_STACKSIZE,
- nsh_execute, &argv[1]);
-#else
- ret = task_create("nsh_execute", priority, nsh_execute, &argv[1]);
-#endif
- if (ret < 0)
- {
- nsh_output(vtbl, g_fmtcmdfailed, cmd, "task_create", NSH_ERRNO);
- goto errout_with_redirect;
- }
- nsh_output(vtbl, "%s [%d:%d:%d]\n", cmd, ret, priority, param.sched_priority);
+ (void)pthread_attr_init(&attr);
+ (void)pthread_attr_setschedpolicy(&attr, SCHED_NSH);
+ (void)pthread_attr_setschedparam(&attr, &param);
- /* If the output was redirected, then file descriptor should
- * be closed. The created task has its one, independent copy of
- * the file descriptor
- */
+ /* Execute the command as a separate thread at the appropriate priority */
- if (vtbl->np.np_redirect)
+ ret = pthread_create(&thread, &attr, nsh_child, (pthread_addr_t)args);
+ if (ret != 0)
{
- (void)close(fd);
+ nsh_output(vtbl, g_fmtcmdfailed, cmd, "pthread_create", ret);
+ nsh_releaseargs(args);
+ nsh_release(bkgvtbl);
+ goto errout;
}
+ nsh_output(vtbl, "%s [%d:%d]\n", cmd, thread, param.sched_priority);
}
else
+#endif
{
ubyte save[SAVE_SIZE];
- /* Increment the reference count on the vtbl. This reference count will
- * be decremented at the end of nsh_execute() and exists only for compatibility
- * with the background command logic.
- */
-
- nsh_addref(vtbl);
-
- /* Place a string copy of the original vtbl in the argument list */
-
- sprintf(strvtbl, "%p\n", vtbl);
- argv[1] = strvtbl;
-
/* Handle redirection of output via a file descriptor */
if (vtbl->np.np_redirect)
@@ -1010,7 +1113,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
* for the next prompt.
*/
- ret = nsh_execute(argc, argv);
+ ret = nsh_execute(vtbl, argc, argv);
/* Restore the original output. Undirect will close the redirection
* file descriptor.
diff --git a/nuttx/examples/nsh/nsh_serial.c b/nuttx/examples/nsh/nsh_serial.c
index b3e60b75f..4ffcc84b2 100644
--- a/nuttx/examples/nsh/nsh_serial.c
+++ b/nuttx/examples/nsh/nsh_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * examples/nsh/nsh_serial.h
+ * examples/nsh/nsh_serial.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -59,7 +59,6 @@
struct serial_s
{
struct nsh_vtbl_s ss_vtbl;
- int ss_refs; /* Reference counts on the instance */
int ss_fd; /* Re-direct file descriptor */
FILE *ss_stream; /* Re-direct stream */
char ss_line[CONFIG_EXAMPLES_NSH_LINELEN];
@@ -75,9 +74,10 @@ struct serialsave_s
* Private Function Prototypes
****************************************************************************/
+#ifndef CONFIG_DISABLE_PTHREAD
static FAR struct nsh_vtbl_s *nsh_consoleclone(FAR struct nsh_vtbl_s *vtbl);
-static void nsh_consoleaddref(FAR struct nsh_vtbl_s *vtbl);
static void nsh_consolerelease(FAR struct nsh_vtbl_s *vtbl);
+#endif
static int nsh_consoleoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...);
static FAR char *nsh_consolelinebuffer(FAR struct nsh_vtbl_s *vtbl);
static void nsh_consoleredirect(FAR struct nsh_vtbl_s *vtbl, int fd, FAR ubyte *save);
@@ -102,21 +102,19 @@ static void nsh_consoleexit(FAR struct nsh_vtbl_s *vtbl);
static inline FAR struct serial_s *nsh_allocstruct(void)
{
- struct serial_s *pstate = (struct serial_s *)malloc(sizeof(struct serial_s));
+ struct serial_s *pstate = (struct serial_s *)zalloc(sizeof(struct serial_s));
if (pstate)
{
+#ifndef CONFIG_DISABLE_PTHREAD
pstate->ss_vtbl.clone = nsh_consoleclone;
- pstate->ss_vtbl.addref = nsh_consoleaddref;
pstate->ss_vtbl.release = nsh_consolerelease;
+#endif
pstate->ss_vtbl.output = nsh_consoleoutput;
pstate->ss_vtbl.linebuffer = nsh_consolelinebuffer;
pstate->ss_vtbl.redirect = nsh_consoleredirect;
pstate->ss_vtbl.undirect = nsh_consoleundirect;
pstate->ss_vtbl.exit = nsh_consoleexit;
- memset(&pstate->ss_vtbl.np, 0, sizeof(struct nsh_parser_s));
-
- pstate->ss_refs = 1;
pstate->ss_fd = 1;
pstate->ss_stream = stdout;
}
@@ -225,51 +223,43 @@ static FAR char *nsh_consolelinebuffer(FAR struct nsh_vtbl_s *vtbl)
*
****************************************************************************/
+#ifndef CONFIG_DISABLE_PTHREAD
static FAR struct nsh_vtbl_s *nsh_consoleclone(FAR struct nsh_vtbl_s *vtbl)
{
FAR struct serial_s *pstate = (FAR struct serial_s *)vtbl;
FAR struct serial_s *pclone = nsh_allocstruct();
- pclone->ss_fd = pstate->ss_fd;
- pclone->ss_stream = NULL;
- return &pclone->ss_vtbl;
-}
-
-/****************************************************************************
- * Name: nsh_consoleaddref
- *
- * Description:
- * Increment the reference count on the vtbl.
- *
- ****************************************************************************/
-static void nsh_consoleaddref(FAR struct nsh_vtbl_s *vtbl)
-{
- FAR struct serial_s *pstate = (FAR struct serial_s *)vtbl;
- pstate->ss_refs++;
+ if (pclone->ss_fd == 1)
+ {
+ pclone->ss_fd = 1;
+ pclone->ss_stream = stdout;
+ }
+ else
+ {
+ pclone->ss_fd = pstate->ss_fd;
+ pclone->ss_stream = NULL;
+ }
+ return &pclone->ss_vtbl;
}
+#endif
/****************************************************************************
* Name: nsh_consolerelease
*
* Description:
- * Decrement the reference count on the vtbl, releasing it when the count
- * decrements to zero.
+ * Release the cloned instance
*
****************************************************************************/
+#ifndef CONFIG_DISABLE_PTHREAD
static void nsh_consolerelease(FAR struct nsh_vtbl_s *vtbl)
{
FAR struct serial_s *pstate = (FAR struct serial_s *)vtbl;
- if (pstate->ss_refs > 1)
- {
- pstate->ss_refs--;
- }
- else
- {
- nsh_closeifnotclosed(pstate);
- free(vtbl);
- }
+
+ nsh_closeifnotclosed(pstate);
+ free(vtbl);
}
+#endif
/****************************************************************************
* Name: nsh_consoleredirect
diff --git a/nuttx/examples/nsh/nsh_telnetd.c b/nuttx/examples/nsh/nsh_telnetd.c
index 5cfe7ba50..9699aa651 100644
--- a/nuttx/examples/nsh/nsh_telnetd.c
+++ b/nuttx/examples/nsh/nsh_telnetd.c
@@ -51,7 +51,9 @@
#include <stdarg.h>
#include <string.h>
#include <pthread.h>
+#include <semaphore.h>
#include <assert.h>
+#include <errno.h>
#include <debug.h>
#include <net/if.h>
@@ -59,6 +61,8 @@
#include "nsh.h"
+#ifdef CONFIG_EXAMPLES_NSH_TELNET
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -86,10 +90,13 @@
struct telnetio_s
{
+ sem_t tio_sem;
+ pid_t tio_holder;
int tio_sockfd;
uint16 tio_sndlen;
uint8 tio_bufndx;
uint8 tio_state;
+ uint8 tio_semnest;
char tio_buffer[CONFIG_EXAMPLES_NSH_IOBUFFER_SIZE];
};
@@ -113,7 +120,6 @@ struct telnetd_s
{
struct nsh_vtbl_s tn_vtbl;
boolean tn_redirected;
- int tn_refs; /* Reference counts on the instance */
union
{
struct telnetio_s *tn;
@@ -127,7 +133,6 @@ struct telnetd_s
****************************************************************************/
static FAR struct nsh_vtbl_s *nsh_telnetclone(FAR struct nsh_vtbl_s *vtbl);
-static void nsh_telnetaddref(FAR struct nsh_vtbl_s *vtbl);
static void nsh_telnetrelease(FAR struct nsh_vtbl_s *vtbl);
static int nsh_telnetoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...);
static int nsh_redirectoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...);
@@ -141,6 +146,72 @@ static void nsh_telnetexit(FAR struct nsh_vtbl_s *vtbl);
****************************************************************************/
/****************************************************************************
+ * Name: tio_semtake
+ ****************************************************************************/
+
+static void tio_semtake(struct telnetio_s *tio)
+{
+ pid_t my_pid = getpid();
+
+ /* Does this task already have the semaphore? */
+
+ if (tio->tio_holder == my_pid)
+ {
+ /* Yes, just increment the number of references that the task holds */
+
+ tio->tio_semnest++;
+ }
+ else
+ {
+ /* No, Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(&tio->tio_sem) != 0)
+ {
+ /* The only case that an error should occur here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+
+ /* Stake the claim and return */
+
+ tio->tio_holder = my_pid;
+ tio->tio_semnest = 1;
+ }
+}
+
+/****************************************************************************
+ * Name: tio_semgive
+ ****************************************************************************/
+
+static void tio_semgive(struct telnetio_s *tio)
+{
+ pid_t my_pid = getpid();
+
+ /* I better be holding at least one count on the semaphore */
+
+ ASSERT(tio->tio_holder == my_pid);
+
+ /* Do I hold multiple references to the semphore */
+
+ if (tio->tio_semnest > 1)
+ {
+ /* Yes, just release one count and return */
+
+ tio->tio_semnest--;
+ }
+ else
+ {
+ /* Nope, this is the last reference I have */
+
+ tio->tio_holder = -1;
+ tio->tio_semnest = 0;
+ ASSERT(sem_post(&tio->tio_sem) == 0);
+ }
+}
+
+/****************************************************************************
* Name: nsh_dumpbuffer
*
* Description:
@@ -196,22 +267,16 @@ static void nsh_dumpbuffer(const char *msg, const char *buffer, ssize_t nbytes)
static FAR struct telnetd_s *nsh_allocstruct(void)
{
- struct telnetd_s *pstate = (struct telnetd_s *)malloc(sizeof(struct telnetd_s));
+ struct telnetd_s *pstate = (struct telnetd_s *)zalloc(sizeof(struct telnetd_s));
if (pstate)
{
- memset(pstate, 0, sizeof(struct telnetd_s));
pstate->tn_vtbl.clone = nsh_telnetclone;
- pstate->tn_vtbl.addref = nsh_telnetaddref;
pstate->tn_vtbl.release = nsh_telnetrelease;
pstate->tn_vtbl.output = nsh_telnetoutput;
pstate->tn_vtbl.linebuffer = nsh_telnetlinebuffer;
pstate->tn_vtbl.redirect = nsh_telnetredirect;
pstate->tn_vtbl.undirect = nsh_telnetundirect;
pstate->tn_vtbl.exit = nsh_telnetexit;
-
- memset(&pstate->tn_vtbl.np, 0, sizeof(struct nsh_parser_s));
-
- pstate->tn_refs = 1;
}
return pstate;
}
@@ -275,6 +340,9 @@ static void nsh_closeifnotclosed(struct telnetd_s *pstate)
* Description:
* Add another parsed character to the TELNET command string
*
+ * Assumption:
+ * Caller holds TIO semaphore
+ *
****************************************************************************/
static void nsh_putchar(struct telnetd_s *pstate, uint8 ch)
@@ -327,7 +395,7 @@ static void nsh_sendopt(struct telnetd_s *pstate, uint8 option, uint8 value)
nsh_dumpbuffer("Send optbuf", optbuf, 4);
if (send(tio->tio_sockfd, optbuf, 4, 0) < 0)
{
- dbg("[%d] Failed to send TELNET_IAC\n", tio->tio_sockfd);
+ dbg("[%d] Failed to send TELNET_IAC: %d\n", tio->tio_sockfd, errno);
}
}
@@ -343,15 +411,17 @@ static void nsh_flush(FAR struct telnetd_s *pstate)
{
struct telnetio_s *tio = pstate->u.tn;
+ tio_semtake(tio);
if (tio->tio_sndlen > 0)
{
nsh_dumpbuffer("Shell output", tio->tio_buffer, tio->tio_sndlen);
if (send(tio->tio_sockfd, tio->tio_buffer, tio->tio_sndlen, 0) < 0)
{
- dbg("[%d] Failed to send response\n", tio->tio_sockfd);
+ dbg("[%d] Failed to send response: %d\n", tio->tio_sockfd, errno);
}
}
tio->tio_sndlen = 0;
+ tio_semgive(tio);
}
/****************************************************************************
@@ -368,6 +438,7 @@ static int nsh_receive(struct telnetd_s *pstate, size_t len)
char *ptr = tio->tio_buffer;
uint8 ch;
+ tio_semtake(tio);
while (len > 0)
{
ch = *ptr++;
@@ -449,6 +520,7 @@ static int nsh_receive(struct telnetd_s *pstate, size_t len)
break;
}
}
+ tio_semgive(tio);
return OK;
}
@@ -465,7 +537,7 @@ static int nsh_receive(struct telnetd_s *pstate, size_t len)
static void *nsh_connection(void *arg)
{
struct telnetd_s *pstate = nsh_allocstruct();
- struct telnetio_s *tio = (struct telnetio_s *)malloc(sizeof(struct telnetio_s));
+ struct telnetio_s *tio = (struct telnetio_s *)zalloc(sizeof(struct telnetio_s));
int sockfd = (int)arg;
int ret = ERROR;
@@ -477,7 +549,7 @@ static void *nsh_connection(void *arg)
{
/* Initialize the thread state structure */
- memset(tio, 0, sizeof(struct telnetio_s));
+ sem_init(&tio->tio_sem, 0, 1);
tio->tio_sockfd = sockfd;
tio->tio_state = STATE_NORMAL;
pstate->u.tn = tio;
@@ -503,7 +575,7 @@ static void *nsh_connection(void *arg)
/* Process the received TELNET data */
- nsh_dumpbuffer("Received buffer", pstate->u.tn.tio_buffer, ret);
+ nsh_dumpbuffer("Received buffer", tio->tio_buffer, ret);
ret = nsh_receive(pstate, ret);
}
}
@@ -522,6 +594,7 @@ static void *nsh_connection(void *arg)
if (tio)
{
+ sem_destroy(&tio->tio_sem);
free(tio);
}
@@ -550,6 +623,8 @@ static int nsh_telnetoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...)
int len;
va_list ap;
+ tio_semtake(tio);
+
/* Put the new info into the buffer. Here we are counting on the fact that
* no output strings will exceed CONFIG_EXAMPLES_NSH_LINELEN!
*/
@@ -582,6 +657,7 @@ static int nsh_telnetoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...)
* maximum length string.
*/
+ tio_semgive(tio);
if (nbytes > CONFIG_EXAMPLES_NSH_IOBUFFER_SIZE - CONFIG_EXAMPLES_NSH_LINELEN)
{
nsh_flush(pstate);
@@ -613,11 +689,11 @@ static int nsh_redirectoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...)
{
return ERROR;
}
-
+
va_start(ap, fmt);
ret = vfprintf(pstate->u.rd.rd_stream, fmt, ap);
va_end(ap);
-
+
return ret;
}
@@ -645,52 +721,49 @@ static FAR char *nsh_telnetlinebuffer(FAR struct nsh_vtbl_s *vtbl)
static FAR struct nsh_vtbl_s *nsh_telnetclone(FAR struct nsh_vtbl_s *vtbl)
{
- FAR struct telnetd_s *pstate = (FAR struct telnetd_s *)vtbl;
- FAR struct telnetd_s *pclone = nsh_allocstruct();
-
- pclone->tn_redirected = TRUE;
- pclone->tn_vtbl.output = nsh_redirectoutput;
- pclone->u.rd.rd_fd = pstate->u.rd.rd_fd;
- pclone->u.rd.rd_stream = NULL;
- return &pclone->tn_vtbl;
-}
-
-/****************************************************************************
- * Name: nsh_telnetaddref
- *
- * Description:
- * Increment the reference count on the vtbl.
- *
- ****************************************************************************/
+ FAR struct telnetd_s *pstate = (FAR struct telnetd_s *)vtbl;
+ FAR struct telnetd_s *pclone = nsh_allocstruct();
+ FAR struct nsh_vtbl_s *ret = NULL;
-static void nsh_telnetaddref(FAR struct nsh_vtbl_s *vtbl)
-{
- FAR struct telnetd_s *pstate = (FAR struct telnetd_s *)vtbl;
- pstate->tn_refs++;
+ if (pclone)
+ {
+ if (pstate->tn_redirected)
+ {
+ pclone->tn_redirected = TRUE;
+ pclone->tn_vtbl.output = nsh_redirectoutput;
+ pclone->u.rd.rd_fd = pstate->u.rd.rd_fd;
+ pclone->u.rd.rd_stream = NULL;
+ }
+ else
+ {
+ pclone->u.tn = pstate->u.tn;
+ }
+ ret = &pclone->tn_vtbl;
+ }
+ return ret;
}
/****************************************************************************
* Name: nsh_telnetrelease
*
* Description:
- * Decrement the reference count on the vtbl, releasing it when the count
- * decrements to zero.
+ * Release the cloned instance
*
****************************************************************************/
static void nsh_telnetrelease(FAR struct nsh_vtbl_s *vtbl)
{
FAR struct telnetd_s *pstate = (FAR struct telnetd_s *)vtbl;
- if (pstate->tn_refs > 1)
+
+ if (pstate->tn_redirected)
{
- pstate->tn_refs--;
+ nsh_closeifnotclosed(pstate);
}
else
{
- DEBUGASSERT(pstate->tn_redirected);
- nsh_closeifnotclosed(pstate);
- free(vtbl);
+ nsh_flush(pstate);
}
+ free(pstate);
}
/****************************************************************************
@@ -768,7 +841,7 @@ static void nsh_telnetexit(FAR struct nsh_vtbl_s *vtbl)
****************************************************************************/
/****************************************************************************
- * Name: nsh_main
+ * Name: nsh_telnetmain
*
* Description:
* This is the main processing thread for telnetd. It never returns
@@ -857,3 +930,5 @@ int nsh_telnetmain(int argc, char *argv[])
uip_server(HTONS(23), nsh_connection, CONFIG_EXAMPLES_NSH_STACKSIZE);
return OK;
}
+
+#endif /* CONFIG_EXAMPLES_NSH_TELNET */