From 9cc7477faf3e49678aa827a6bc1ab99e2812c4d8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 15 Jan 2013 21:01:37 +0000 Subject: Implement redirection of output from NSH builtin commands to a file in a mounted volume git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5521 42af7a65-404d-4744-a932-0658087f49c3 --- apps/nshlib/Makefile | 2 +- apps/nshlib/nsh.h | 3 +- apps/nshlib/nsh_apps.c | 220 --------- apps/nshlib/nsh_builtin.c | 226 ++++++++++ apps/nshlib/nsh_codeccmd.c | 1076 ++++++++++++++++++++++---------------------- apps/nshlib/nsh_parse.c | 95 ++-- 6 files changed, 820 insertions(+), 802 deletions(-) delete mode 100644 apps/nshlib/nsh_apps.c create mode 100644 apps/nshlib/nsh_builtin.c (limited to 'apps/nshlib') diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index 7ddbb67bf..5c5269685 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -44,7 +44,7 @@ CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_fscmds.c nsh_ddcmd.c \ nsh_proccmds.c nsh_mmcmds.c nsh_envcmds.c nsh_dbgcmds.c ifeq ($(CONFIG_NSH_BUILTIN_APPS),y) -CSRCS += nsh_apps.c +CSRCS += nsh_builtin.c endif ifeq ($(CONFIG_NSH_ROMFSETC),y) diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h index a046a384f..253a803f8 100644 --- a/apps/nshlib/nsh.h +++ b/apps/nshlib/nsh.h @@ -491,7 +491,8 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline); /* Application interface */ #ifdef CONFIG_NSH_BUILTIN_APPS -int nsh_execapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, FAR char **argv); +int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, + FAR char **argv, FAR const char *redirfile, int oflags); #endif /* Working directory support */ diff --git a/apps/nshlib/nsh_apps.c b/apps/nshlib/nsh_apps.c deleted file mode 100644 index ea8791eef..000000000 --- a/apps/nshlib/nsh_apps.c +++ /dev/null @@ -1,220 +0,0 @@ -/**************************************************************************** - * apps/nshlib/nsh_apps.c - * - * Copyright (C) 2011-2012 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 - -#include "nsh.h" -#include "nsh_console.h" - -#ifdef CONFIG_NSH_BUILTIN_APPS - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: nsh_execapp - * - * 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_execapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, - FAR char **argv) -{ - int ret = OK; - - /* Lock the scheduler to prevent the application from running until the - * waitpid() has been called. - */ - - sched_lock(); - - /* Try to find and execute the command within the list of builtin - * applications. - */ - - ret = exec_builtin(cmd, (FAR const char **)argv); - 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: - * - * - 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 - - /* 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. 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. - */ - - ret = waitpid(ret, &rc, 0); - if (ret >= 0) - { - /* 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(0, ¶m); - 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(); - - /* If exec_builtin() or waitpid() failed, then return the negated errno - * value. - */ - - if (ret < 0) - { - return -errno; - } - - return ret; -} - -#endif /* CONFIG_NSH_BUILTIN_APPS */ diff --git a/apps/nshlib/nsh_builtin.c b/apps/nshlib/nsh_builtin.c new file mode 100644 index 000000000..16e3e9427 --- /dev/null +++ b/apps/nshlib/nsh_builtin.c @@ -0,0 +1,226 @@ +/**************************************************************************** + * apps/nshlib/nsh_builtin.c + * + * Originally by: + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * Author: Uros Platise + * + * With subsequent updates, modifications, and general maintenance by: + * + * Copyright (C) 2011-2013 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 + +#ifdef CONFIG_SCHED_WAITPID +# include +#endif + +#include +#include +#include + +#include + +#include "nsh.h" +#include "nsh_console.h" + +#ifdef CONFIG_NSH_BUILTIN_APPS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nsh_builtin + * + * 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_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, + FAR char **argv, FAR const char *redirfile, int oflags) +{ + int ret = OK; + + /* Lock the scheduler to prevent the application from running until the + * waitpid() has been called. + */ + + sched_lock(); + + /* Try to find and execute the command within the list of builtin + * applications. + */ + + 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: + * + * - 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 + + /* 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. 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. + */ + + ret = waitpid(ret, &rc, 0); + if (ret >= 0) + { + /* 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, ¶m); + 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(); + + /* If exec_builtin() or waitpid() failed, then return -1 (ERROR) with the + * errno value set appropriately. + */ + + if (ret < 0) + { + return ERROR; + } + + return ret; +} + +#endif /* CONFIG_NSH_BUILTIN_APPS */ diff --git a/apps/nshlib/nsh_codeccmd.c b/apps/nshlib/nsh_codeccmd.c index 8c1f5adbd..779fc5ecd 100644 --- a/apps/nshlib/nsh_codeccmd.c +++ b/apps/nshlib/nsh_codeccmd.c @@ -1,538 +1,538 @@ -/**************************************************************************** - * apps/nshlib/nsh_apps.c - * - * This file is part of NuttX, contributed by Darcy Gong - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Darcy Gong 2012-10-30 - * - * 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_NETUTILS_CODECS - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(CONFIG_NSH_DISABLE_URLENCODE) && defined(CONFIG_NSH_DISABLE_URLDECODE) -# undef CONFIG_CODECS_URLCODE -#endif - -#ifdef CONFIG_CODECS_URLCODE -#include -#endif - -#if defined(CONFIG_NSH_DISABLE_BASE64ENC) && defined(CONFIG_NSH_DISABLE_BASE64ENC) -# undef CONFIG_CODECS_BASE64 -#endif - -#ifdef CONFIG_CODECS_BASE64 -#include -#endif - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) -#include -#endif - -#include "nsh.h" -#include "nsh_console.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#ifndef CONFIG_NSH_CODECS_BUFSIZE -# define CONFIG_NSH_CODECS_BUFSIZE 128 -#endif - -#define CODEC_MODE_URLENCODE 1 -#define CODEC_MODE_URLDECODE 2 -#define CODEC_MODE_BASE64ENC 3 -#define CODEC_MODE_BASE64DEC 4 -#define CODEC_MODE_HASH_MD5 5 - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -typedef void (*codec_callback_t)(FAR char *src_buff, int src_buff_len, - FAR char *dst_buff, FAR int *dst_buff_len, - int mode); - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: urlencode_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) -static void urlencode_cb(FAR char *src_buff, int src_buff_len, - FAR char *dst_buff, FAR int *dst_buff_len, int mode) -{ - urlencode(src_buff,src_buff_len,dst_buff,dst_buff_len); -} -#endif - -/**************************************************************************** - * Name: urldecode_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) -static void urldecode_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - urldecode(src_buff,src_buff_len,dst_buff,dst_buff_len); -} -#endif - -/**************************************************************************** - * Name: b64enc_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) -static void b64enc_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - if (mode == 0) - { - //dst_buff = - base64_encode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff, (size_t *)dst_buff_len); - } - else - { - //dst_buff = - base64w_encode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff, (size_t *)dst_buff_len); - } -} -#endif - -/**************************************************************************** - * Name: b64dec_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) -static void b64dec_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - if (mode == 0) - { - //dst_buff = - base64_decode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff, (size_t *)dst_buff_len); - } - else - { - //dst_buff = - base64w_decode((unsigned char *)src_buff, src_buff_len, - (unsigned char *)dst_buff,(size_t *)dst_buff_len); - } -} -#endif - -/**************************************************************************** - * Name: md5_cb - ****************************************************************************/ - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) -static void md5_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, - FAR int *dst_buff_len, int mode) -{ - MD5Update((MD5_CTX *)dst_buff, (unsigned char *)src_buff, src_buff_len); -} -#endif - -/**************************************************************************** - * Name: calc_codec_buffsize - ****************************************************************************/ - -static int calc_codec_buffsize(int src_buffsize, uint8_t mode) -{ - switch (mode) - { - case CODEC_MODE_URLENCODE: - return src_buffsize*3+1; - case CODEC_MODE_URLDECODE: - return src_buffsize+1; - case CODEC_MODE_BASE64ENC: - return ((src_buffsize + 2)/ 3 * 4)+1; - case CODEC_MODE_BASE64DEC: - return (src_buffsize / 4 * 3 + 2)+1; - case CODEC_MODE_HASH_MD5: - return 32+1; - default: - return src_buffsize+1; - } -} - -/**************************************************************************** - * Name: cmd_codecs_proc - ****************************************************************************/ - -static int cmd_codecs_proc(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv, - uint8_t mode, codec_callback_t func) -{ -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - static const unsigned char hex_chars[] = "0123456789abcdef"; - MD5_CTX ctx; - unsigned char mac[16]; - char *pSrc; - char *pDest; -#endif - - char *localfile = NULL; - char *src_buffer = NULL; - char *buffer = NULL; - char *fullpath = NULL; - const char *fmt; - char *s_data; - bool badarg = false; - bool is_file = false; - bool is_websafe=false; - int option; - int fd = -1; - int buff_len = 0; - int src_buff_len = 0; - int i = 0; - int ret = OK; - - /* Get the command options */ - - while ((option = getopt(argc, argv, ":fw")) != ERROR) - { - switch (option) - { - case 'f': - is_file = true; - break; - -#ifdef CONFIG_CODECS_BASE64 - case 'w': - is_websafe = true; - - if (!(mode == CODEC_MODE_BASE64ENC || mode == CODEC_MODE_BASE64DEC)) - { - badarg = true; - } - break; -#endif - case ':': - nsh_output(vtbl, g_fmtargrequired, argv[0]); - badarg = true; - break; - - case '?': - default: - nsh_output(vtbl, g_fmtarginvalid, argv[0]); - badarg = true; - break; - } - } - - /* If a bad argument was encountered, then return without processing the command */ - - if (badarg) - { - return ERROR; - } - - /* There should be exactly on parameter left on the command-line */ - - if (optind == argc-1) - { - s_data = argv[optind]; - } - else if (optind >= argc) - { - fmt = g_fmttoomanyargs; - goto errout; - } - else - { - fmt = g_fmtargrequired; - goto errout; - } - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - MD5Init(&ctx); - } -#endif - - if (is_file) - { - /* Get the local file name */ - - localfile = s_data; - - /* Get the full path to the local file */ - - fullpath = nsh_getfullpath(vtbl, localfile); - - /* Open the local file for writing */ - - fd = open(fullpath, O_RDONLY|O_TRUNC, 0644); - if (fd < 0) - { - nsh_output(vtbl, g_fmtcmdfailed, argv[0], "open", NSH_ERRNO); - ret = ERROR; - goto exit; - } - - src_buffer = malloc(CONFIG_NSH_CODECS_BUFSIZE+2); -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) - if (mode == CODEC_MODE_BASE64ENC) - { - src_buff_len = CONFIG_NSH_CODECS_BUFSIZE / 3 * 3; - } - else -#endif - { - src_buff_len = CONFIG_NSH_CODECS_BUFSIZE; - } - - buff_len = calc_codec_buffsize(src_buff_len+2, mode); - buffer = malloc(buff_len); - while(true) - { - memset(src_buffer, 0, src_buff_len+2); - ret=read(fd, src_buffer, src_buff_len); - if (ret < 0) - { - nsh_output(vtbl, g_fmtcmdfailed, argv[0], "read", NSH_ERRNO); - ret = ERROR; - goto exit; - } - else if(ret==0) - { - break; - } - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) - if (mode == CODEC_MODE_URLDECODE) - { - if (src_buffer[src_buff_len-1]=='%') - { - ret += read(fd,&src_buffer[src_buff_len],2); - } - else if (src_buffer[src_buff_len-2]=='%') - { - ret += read(fd,&src_buffer[src_buff_len],1); - } - } -#endif - memset(buffer, 0, buff_len); - if (func) - { -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - func(src_buffer, ret, (char *)&ctx, &buff_len,0); - } - else -#endif - { - func(src_buffer, ret, buffer, &buff_len,(is_websafe)?1:0); - nsh_output(vtbl, "%s", buffer); - } - } - - buff_len = calc_codec_buffsize(src_buff_len+2, mode); - } - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - MD5Final(mac, &ctx); - pSrc = (char *)&mac; - pDest = buffer; - for(i=0;i<16;i++,pSrc++) - { - *pDest++ = hex_chars[(*pSrc) >> 4]; - *pDest++ = hex_chars[(*pSrc) & 0x0f]; - } - - *pDest='\0'; - nsh_output(vtbl, "%s\n", buffer); - } -#endif - ret = OK; - goto exit; - } - else - { - src_buffer = s_data; - src_buff_len = strlen(s_data); - buff_len = calc_codec_buffsize(src_buff_len, mode); - buffer = malloc(buff_len); - buffer[0]=0; - if (!buffer) - { - fmt = g_fmtcmdoutofmemory; - goto errout; - } - - memset(buffer, 0, buff_len); - if (func) - { -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) - if (mode == CODEC_MODE_HASH_MD5) - { - func(src_buffer, src_buff_len, (char *)&ctx, &buff_len, 0); - MD5Final(mac, &ctx); - pSrc = (char *)&mac; - pDest = buffer; - for(i=0;i<16;i++,pSrc++) - { - *pDest++ = hex_chars[(*pSrc) >> 4]; - *pDest++ = hex_chars[(*pSrc) & 0x0f]; - } - - *pDest='\0'; - } - else -#endif - { - func(src_buffer, src_buff_len, buffer, &buff_len,(is_websafe)?1:0); - } - } - - nsh_output(vtbl, "%s\n",buffer); - src_buffer = NULL; - goto exit; - } - -exit: - if (fd >= 0) - { - close(fd); - } - - if (fullpath) - { - free(fullpath); - } - - if (src_buffer) - { - free(src_buffer); - } - - if (buffer) - { - free(buffer); - } - - return ret; - -errout: - nsh_output(vtbl, fmt, argv[0]); - ret = ERROR; - goto exit; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cmd_urlencode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) -int cmd_urlencode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLENCODE, urlencode_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_urldecode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) -int cmd_urldecode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLDECODE, urldecode_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_base64encode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) -int cmd_base64encode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64ENC, b64enc_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_base64decode - ****************************************************************************/ - -#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) -int cmd_base64decode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64DEC, b64dec_cb); -} -#endif - -/**************************************************************************** - * Name: cmd_md5 - ****************************************************************************/ - -#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) -int cmd_md5(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) -{ - return cmd_codecs_proc(vtbl,argc,argv,CODEC_MODE_HASH_MD5,md5_cb); -} -#endif - -#endif /* CONFIG_NETUTILS_CODECS */ +/**************************************************************************** + * apps/nshlib/nsh_codeccmd.c + * + * This file is part of NuttX, contributed by Darcy Gong + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Darcy Gong 2012-10-30 + * + * 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_NETUTILS_CODECS + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(CONFIG_NSH_DISABLE_URLENCODE) && defined(CONFIG_NSH_DISABLE_URLDECODE) +# undef CONFIG_CODECS_URLCODE +#endif + +#ifdef CONFIG_CODECS_URLCODE +#include +#endif + +#if defined(CONFIG_NSH_DISABLE_BASE64ENC) && defined(CONFIG_NSH_DISABLE_BASE64ENC) +# undef CONFIG_CODECS_BASE64 +#endif + +#ifdef CONFIG_CODECS_BASE64 +#include +#endif + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) +#include +#endif + +#include "nsh.h" +#include "nsh_console.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef CONFIG_NSH_CODECS_BUFSIZE +# define CONFIG_NSH_CODECS_BUFSIZE 128 +#endif + +#define CODEC_MODE_URLENCODE 1 +#define CODEC_MODE_URLDECODE 2 +#define CODEC_MODE_BASE64ENC 3 +#define CODEC_MODE_BASE64DEC 4 +#define CODEC_MODE_HASH_MD5 5 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +typedef void (*codec_callback_t)(FAR char *src_buff, int src_buff_len, + FAR char *dst_buff, FAR int *dst_buff_len, + int mode); + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: urlencode_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) +static void urlencode_cb(FAR char *src_buff, int src_buff_len, + FAR char *dst_buff, FAR int *dst_buff_len, int mode) +{ + urlencode(src_buff,src_buff_len,dst_buff,dst_buff_len); +} +#endif + +/**************************************************************************** + * Name: urldecode_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) +static void urldecode_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + urldecode(src_buff,src_buff_len,dst_buff,dst_buff_len); +} +#endif + +/**************************************************************************** + * Name: b64enc_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) +static void b64enc_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + if (mode == 0) + { + //dst_buff = + base64_encode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff, (size_t *)dst_buff_len); + } + else + { + //dst_buff = + base64w_encode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff, (size_t *)dst_buff_len); + } +} +#endif + +/**************************************************************************** + * Name: b64dec_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) +static void b64dec_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + if (mode == 0) + { + //dst_buff = + base64_decode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff, (size_t *)dst_buff_len); + } + else + { + //dst_buff = + base64w_decode((unsigned char *)src_buff, src_buff_len, + (unsigned char *)dst_buff,(size_t *)dst_buff_len); + } +} +#endif + +/**************************************************************************** + * Name: md5_cb + ****************************************************************************/ + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) +static void md5_cb(FAR char *src_buff, int src_buff_len, FAR char *dst_buff, + FAR int *dst_buff_len, int mode) +{ + MD5Update((MD5_CTX *)dst_buff, (unsigned char *)src_buff, src_buff_len); +} +#endif + +/**************************************************************************** + * Name: calc_codec_buffsize + ****************************************************************************/ + +static int calc_codec_buffsize(int src_buffsize, uint8_t mode) +{ + switch (mode) + { + case CODEC_MODE_URLENCODE: + return src_buffsize*3+1; + case CODEC_MODE_URLDECODE: + return src_buffsize+1; + case CODEC_MODE_BASE64ENC: + return ((src_buffsize + 2)/ 3 * 4)+1; + case CODEC_MODE_BASE64DEC: + return (src_buffsize / 4 * 3 + 2)+1; + case CODEC_MODE_HASH_MD5: + return 32+1; + default: + return src_buffsize+1; + } +} + +/**************************************************************************** + * Name: cmd_codecs_proc + ****************************************************************************/ + +static int cmd_codecs_proc(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv, + uint8_t mode, codec_callback_t func) +{ +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + static const unsigned char hex_chars[] = "0123456789abcdef"; + MD5_CTX ctx; + unsigned char mac[16]; + char *pSrc; + char *pDest; +#endif + + char *localfile = NULL; + char *src_buffer = NULL; + char *buffer = NULL; + char *fullpath = NULL; + const char *fmt; + char *s_data; + bool badarg = false; + bool is_file = false; + bool is_websafe=false; + int option; + int fd = -1; + int buff_len = 0; + int src_buff_len = 0; + int i = 0; + int ret = OK; + + /* Get the command options */ + + while ((option = getopt(argc, argv, ":fw")) != ERROR) + { + switch (option) + { + case 'f': + is_file = true; + break; + +#ifdef CONFIG_CODECS_BASE64 + case 'w': + is_websafe = true; + + if (!(mode == CODEC_MODE_BASE64ENC || mode == CODEC_MODE_BASE64DEC)) + { + badarg = true; + } + break; +#endif + case ':': + nsh_output(vtbl, g_fmtargrequired, argv[0]); + badarg = true; + break; + + case '?': + default: + nsh_output(vtbl, g_fmtarginvalid, argv[0]); + badarg = true; + break; + } + } + + /* If a bad argument was encountered, then return without processing the command */ + + if (badarg) + { + return ERROR; + } + + /* There should be exactly on parameter left on the command-line */ + + if (optind == argc-1) + { + s_data = argv[optind]; + } + else if (optind >= argc) + { + fmt = g_fmttoomanyargs; + goto errout; + } + else + { + fmt = g_fmtargrequired; + goto errout; + } + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + MD5Init(&ctx); + } +#endif + + if (is_file) + { + /* Get the local file name */ + + localfile = s_data; + + /* Get the full path to the local file */ + + fullpath = nsh_getfullpath(vtbl, localfile); + + /* Open the local file for writing */ + + fd = open(fullpath, O_RDONLY|O_TRUNC, 0644); + if (fd < 0) + { + nsh_output(vtbl, g_fmtcmdfailed, argv[0], "open", NSH_ERRNO); + ret = ERROR; + goto exit; + } + + src_buffer = malloc(CONFIG_NSH_CODECS_BUFSIZE+2); +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) + if (mode == CODEC_MODE_BASE64ENC) + { + src_buff_len = CONFIG_NSH_CODECS_BUFSIZE / 3 * 3; + } + else +#endif + { + src_buff_len = CONFIG_NSH_CODECS_BUFSIZE; + } + + buff_len = calc_codec_buffsize(src_buff_len+2, mode); + buffer = malloc(buff_len); + while(true) + { + memset(src_buffer, 0, src_buff_len+2); + ret=read(fd, src_buffer, src_buff_len); + if (ret < 0) + { + nsh_output(vtbl, g_fmtcmdfailed, argv[0], "read", NSH_ERRNO); + ret = ERROR; + goto exit; + } + else if(ret==0) + { + break; + } + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) + if (mode == CODEC_MODE_URLDECODE) + { + if (src_buffer[src_buff_len-1]=='%') + { + ret += read(fd,&src_buffer[src_buff_len],2); + } + else if (src_buffer[src_buff_len-2]=='%') + { + ret += read(fd,&src_buffer[src_buff_len],1); + } + } +#endif + memset(buffer, 0, buff_len); + if (func) + { +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + func(src_buffer, ret, (char *)&ctx, &buff_len,0); + } + else +#endif + { + func(src_buffer, ret, buffer, &buff_len,(is_websafe)?1:0); + nsh_output(vtbl, "%s", buffer); + } + } + + buff_len = calc_codec_buffsize(src_buff_len+2, mode); + } + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + MD5Final(mac, &ctx); + pSrc = (char *)&mac; + pDest = buffer; + for(i=0;i<16;i++,pSrc++) + { + *pDest++ = hex_chars[(*pSrc) >> 4]; + *pDest++ = hex_chars[(*pSrc) & 0x0f]; + } + + *pDest='\0'; + nsh_output(vtbl, "%s\n", buffer); + } +#endif + ret = OK; + goto exit; + } + else + { + src_buffer = s_data; + src_buff_len = strlen(s_data); + buff_len = calc_codec_buffsize(src_buff_len, mode); + buffer = malloc(buff_len); + buffer[0]=0; + if (!buffer) + { + fmt = g_fmtcmdoutofmemory; + goto errout; + } + + memset(buffer, 0, buff_len); + if (func) + { +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) + if (mode == CODEC_MODE_HASH_MD5) + { + func(src_buffer, src_buff_len, (char *)&ctx, &buff_len, 0); + MD5Final(mac, &ctx); + pSrc = (char *)&mac; + pDest = buffer; + for(i=0;i<16;i++,pSrc++) + { + *pDest++ = hex_chars[(*pSrc) >> 4]; + *pDest++ = hex_chars[(*pSrc) & 0x0f]; + } + + *pDest='\0'; + } + else +#endif + { + func(src_buffer, src_buff_len, buffer, &buff_len,(is_websafe)?1:0); + } + } + + nsh_output(vtbl, "%s\n",buffer); + src_buffer = NULL; + goto exit; + } + +exit: + if (fd >= 0) + { + close(fd); + } + + if (fullpath) + { + free(fullpath); + } + + if (src_buffer) + { + free(src_buffer); + } + + if (buffer) + { + free(buffer); + } + + return ret; + +errout: + nsh_output(vtbl, fmt, argv[0]); + ret = ERROR; + goto exit; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cmd_urlencode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLENCODE) +int cmd_urlencode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLENCODE, urlencode_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_urldecode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_URLCODE) && !defined(CONFIG_NSH_DISABLE_URLDECODE) +int cmd_urldecode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_URLDECODE, urldecode_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_base64encode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64ENC) +int cmd_base64encode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64ENC, b64enc_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_base64decode + ****************************************************************************/ + +#if defined(CONFIG_CODECS_BASE64) && !defined(CONFIG_NSH_DISABLE_BASE64DEC) +int cmd_base64decode(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl, argc, argv, CODEC_MODE_BASE64DEC, b64dec_cb); +} +#endif + +/**************************************************************************** + * Name: cmd_md5 + ****************************************************************************/ + +#if defined(CONFIG_CODECS_HASH_MD5) && !defined(CONFIG_NSH_DISABLE_MD5) +int cmd_md5(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) +{ + return cmd_codecs_proc(vtbl,argc,argv,CODEC_MODE_HASH_MD5,md5_cb); +} +#endif + +#endif /* CONFIG_NETUTILS_CODECS */ diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c index 70fa39f62..15723b497 100644 --- a/apps/nshlib/nsh_parse.c +++ b/apps/nshlib/nsh_parse.c @@ -1,7 +1,7 @@ /**************************************************************************** * apps/nshlib/nsh_parse.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -72,7 +72,7 @@ /* Argument list size * - * argv[0]: The command name. + * argv[0]: The command name. * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) * argv[argc-3]: Possibly '>' or '>>' * argv[argc-2]: Possibly @@ -226,7 +226,7 @@ static const struct cmdmap_s g_cmdmap[] = { "help", cmd_help, 1, 3, "[-v] []" }, # endif #endif - + #if CONFIG_NFILE_DESCRIPTORS > 0 #ifndef CONFIG_NSH_DISABLE_HEXDUMP { "hexdump", cmd_hexdump, 2, 2, "" }, @@ -723,15 +723,11 @@ static int cmd_exit(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) * Name: nsh_execute * * Description: - * Exectue the command in argv[0] + * Execute the command in argv[0] * * Returned Value: - * <0 If exec_builtin() fails, then the negated errno value - * is returned. * -1 (ERRROR) if the command was unsuccessful * 0 (OK) if the command was successful - * 1 if an application task was spawned successfully, but - * returned failure exit status. * ****************************************************************************/ @@ -751,21 +747,6 @@ static int nsh_execute(FAR struct nsh_vtbl_s *vtbl, int argc, char *argv[]) */ cmd = argv[0]; - - /* Try to find a command in the application library. */ - -#ifdef CONFIG_NSH_BUILTIN_APPS - ret = nsh_execapp(vtbl, cmd, argv); - - /* If the built-in application was successfully started, return OK - * or 1 (if the application returned a non-zero exit status). - */ - - if (ret >= 0) - { - return ret; - } -#endif /* See if the command is one that we understand */ @@ -1352,7 +1333,7 @@ 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]: The command name. + * argv[0]: The command name. * argv[1]: The beginning of argument (up to CONFIG_NSH_MAXARGUMENTS) * argv[argc-3]: Possibly '>' or '>>' * argv[argc-2]: Possibly @@ -1410,6 +1391,47 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) } } + /* Check if the maximum number of arguments was exceeded */ + + if (argc > CONFIG_NSH_MAXARGUMENTS) + { + nsh_output(vtbl, g_fmttoomanyargs, cmd); + } + + /* Does this command correspond to a builtin command? + * nsh_builtin() 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_BUILTIN_APPS + ret = nsh_builtin(vtbl, argv[0], argv, redirfile, oflags); + if (ret >= 0) + { + /* nsh_builtin() 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 + /* Redirected output? */ if (vtbl->np.np_redirect) @@ -1431,23 +1453,13 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) } } - /* Check if the maximum number of arguments was exceeded */ - - if (argc > CONFIG_NSH_MAXARGUMENTS) - { - nsh_output(vtbl, g_fmttoomanyargs, cmd); - } - /* Handle the case where the command is executed in background. * However is app is to be started as builtin new process will - * be created anyway, so skip this step. */ + * be created anyway, so skip this step. + */ #ifndef CONFIG_NSH_DISABLEBG - if (vtbl->np.np_bg -#ifdef CONFIG_NSH_BUILTIN_APPS - && builtin_isavail(argv[0]) < 0 -#endif - ) + if (vtbl->np.np_bg) { struct sched_param param; struct nsh_vtbl_s *bkgvtbl; @@ -1514,6 +1526,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) priority = min_priority; } } + param.sched_priority = priority; } @@ -1553,8 +1566,6 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) * * -1 (ERRROR) if the command was unsuccessful * 0 (OK) if the command was successful - * 1 if an application task was spawned successfully, but - * returned failure exit status. */ ret = nsh_execute(vtbl, argc, argv); @@ -1568,11 +1579,11 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline) nsh_undirect(vtbl, save); } - /* Treat both errors and non-zero return codes as "errors" so that - * it is possible to test for non-zero returns in nsh scripts. + /* Mark errors so that it is possible to test for non-zero return values + * in nsh scripts. */ - if (ret != OK) + if (ret < 0) { goto errout; } -- cgit v1.2.3