summaryrefslogtreecommitdiff
path: root/nuttx/examples/nsh
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-20 01:35:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-08-20 01:35:50 +0000
commit09a5b0ddd618c34db1697959ea519ec04b83e73d (patch)
treedcbd1a2cdf624d60aa7b6f8762237084fddef29d /nuttx/examples/nsh
parent8288d0621f1a25d2d20a22c974537e71108151f8 (diff)
downloadpx4-nuttx-09a5b0ddd618c34db1697959ea519ec04b83e73d.tar.gz
px4-nuttx-09a5b0ddd618c34db1697959ea519ec04b83e73d.tar.bz2
px4-nuttx-09a5b0ddd618c34db1697959ea519ec04b83e73d.zip
Add memory inspect modify commands to NSH
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@834 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/examples/nsh')
-rw-r--r--nuttx/examples/nsh/Makefile2
-rw-r--r--nuttx/examples/nsh/nsh.h4
-rw-r--r--nuttx/examples/nsh/nsh_dbgcmds.c279
-rw-r--r--nuttx/examples/nsh/nsh_main.c6
4 files changed, 290 insertions, 1 deletions
diff --git a/nuttx/examples/nsh/Makefile b/nuttx/examples/nsh/Makefile
index 931ba2b16..db2f26677 100644
--- a/nuttx/examples/nsh/Makefile
+++ b/nuttx/examples/nsh/Makefile
@@ -37,7 +37,7 @@
-include $(TOPDIR)/Make.defs
ASRCS =
-CSRCS = nsh_main.c nsh_fscmds.c nsh_proccmds.c nsh_envcmds.c
+CSRCS = nsh_main.c nsh_fscmds.c nsh_proccmds.c nsh_envcmds.c nsh_dbgcmds.c
ifeq ($(CONFIG_NET),y)
ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
diff --git a/nuttx/examples/nsh/nsh.h b/nuttx/examples/nsh/nsh.h
index 57c75e1bc..33f6d3d4d 100644
--- a/nuttx/examples/nsh/nsh.h
+++ b/nuttx/examples/nsh/nsh.h
@@ -182,6 +182,7 @@ typedef int (*cmd_t)(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
extern const char g_nshprompt[];
extern const char g_fmtargrequired[];
extern const char g_fmtarginvalid[];
+extern const char g_fmtargrange[];
extern const char g_fmtcmdnotfound[];
extern const char g_fmtcmdnotimpl[];
extern const char g_fmtnosuch[];
@@ -214,6 +215,9 @@ extern int nsh_telnetmain(int argc, char *argv[]);
extern int cmd_echo(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
extern int cmd_exec(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
+extern int cmd_mb(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
+extern int cmd_mh(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
+extern int cmd_mw(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
extern int cmd_ps(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
#if CONFIG_NFILE_DESCRIPTORS > 0
diff --git a/nuttx/examples/nsh/nsh_dbgcmds.c b/nuttx/examples/nsh/nsh_dbgcmds.c
new file mode 100644
index 000000000..5ae5d658e
--- /dev/null
+++ b/nuttx/examples/nsh/nsh_dbgcmds.c
@@ -0,0 +1,279 @@
+/****************************************************************************
+ * examples/nsh/dbg_proccmds.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <sys/types.h>
+
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <errno.h>
+
+#include "nsh.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct dbgmem_s
+{
+ boolean dm_write; /* TRUE: perfrom write operation */
+ void *dm_addr; /* Address to access */
+ uint32 dm_value; /* Value to write */
+ unsigned int dm_count; /* The number of bytes to access */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mem_parse
+ ****************************************************************************/
+
+int mem_parse(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv,
+ struct dbgmem_s *mem)
+{
+ char *pcvalue = strchr(argv[1], '=');
+ unsigned long lvalue = 0;
+
+ /* Check if we are writing a value */
+
+ if (pcvalue)
+ {
+ *pcvalue = '\0';
+ pcvalue++;
+
+ lvalue = (unsigned long)strtol(pcvalue, NULL, 16);
+ if (lvalue > 0xffffffff)
+ {
+ return -EINVAL;
+ }
+
+ mem->dm_write = TRUE;
+ mem->dm_value = (uint32)lvalue;
+ }
+ else
+ {
+ mem->dm_write = FALSE;
+ mem->dm_value = 0;
+ }
+
+ /* Get the address to be accessed */
+
+ mem->dm_addr = (void*)strtol(argv[1], NULL, 16);
+
+ /* Get the number of bytes to access */
+
+ if (argc > 2)
+ {
+ mem->dm_count = (unsigned int)strtol(argv[2], NULL, 16);
+ }
+ else
+ {
+ mem->dm_count = 1;
+ }
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: cmd_mb
+ ****************************************************************************/
+
+int cmd_mb(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
+{
+ struct dbgmem_s mem;
+ volatile ubyte *ptr;
+ int ret;
+ int i;
+
+ ret = mem_parse(vtbl, argc, argv, &mem);
+ if (ret == 0)
+ {
+ /* Loop for the number of requested bytes */
+
+ for (i = 0, ptr = (volatile ubyte*)mem.dm_addr; i < mem.dm_count; i++, ptr++)
+ {
+ /* Print the value at the address */
+
+ nsh_output(vtbl, " %p = 0x%02x", ptr, *ptr);
+
+ /* Are we supposed to write a value to this address? */
+
+ if (mem.dm_write)
+ {
+ /* Yes, was the supplied value within range? */
+
+ if (mem.dm_value > 0x000000ff)
+ {
+ nsh_output(vtbl, g_fmtargrange, argv[0]);
+ return ERROR;
+ }
+
+ /* Write the value and re-read the address so that we print its
+ * current value (if the address is a process address, then the
+ * value read might not necessarily be the value written).
+ */
+
+ *ptr = (ubyte)mem.dm_value;
+ nsh_output(vtbl, " -> 0x%02x", *ptr);
+ }
+
+ /* Make sure we end it with a newline */
+
+ nsh_output(vtbl, "\n", *ptr);
+ }
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: cmd_mh
+ ****************************************************************************/
+
+int cmd_mh(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
+{
+ struct dbgmem_s mem;
+ volatile uint16 *ptr;
+ int ret;
+ int i;
+
+ ret = mem_parse(vtbl, argc, argv, &mem);
+ if (ret == 0)
+ {
+ /* Loop for the number of requested bytes */
+
+ for (i = 0, ptr = (volatile uint16*)mem.dm_addr; i < mem.dm_count; i += 2, ptr++)
+ {
+ /* Print the value at the address */
+
+ nsh_output(vtbl, " %p = 0x%04x", ptr, *ptr);
+
+ /* Are we supposed to write a value to this address? */
+
+ if (mem.dm_write)
+ {
+ /* Yes, was the supplied value within range? */
+
+ if (mem.dm_value > 0x0000ffff)
+ {
+ nsh_output(vtbl, g_fmtargrange, argv[0]);
+ return ERROR;
+ }
+
+ /* Write the value and re-read the address so that we print its
+ * current value (if the address is a process address, then the
+ * value read might not necessarily be the value written).
+ */
+
+ *ptr = (uint16)mem.dm_value;
+ nsh_output(vtbl, " -> 0x%04x", *ptr);
+ }
+
+ /* Make sure we end it with a newline */
+
+ nsh_output(vtbl, "\n", *ptr);
+ }
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: cmd_mw
+ ****************************************************************************/
+
+int cmd_mw(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
+{
+ struct dbgmem_s mem;
+ volatile uint32 *ptr;
+ int ret;
+ int i;
+
+ ret = mem_parse(vtbl, argc, argv, &mem);
+ if (ret == 0)
+ {
+ /* Loop for the number of requested bytes */
+
+ for (i = 0, ptr = (volatile uint32*)mem.dm_addr; i < mem.dm_count; i += 4, ptr++)
+ {
+ /* Print the value at the address */
+
+ nsh_output(vtbl, " %p = 0x%08x", ptr, *ptr);
+
+ /* Are we supposed to write a value to this address? */
+
+ if (mem.dm_write)
+ {
+ /* Write the value and re-read the address so that we print its
+ * current value (if the address is a process address, then the
+ * value read might not necessarily be the value written).
+ */
+
+ *ptr = mem.dm_value;
+ nsh_output(vtbl, " -> 0x%08x", *ptr);
+ }
+
+ /* Make sure we end it with a newline */
+
+ nsh_output(vtbl, "\n", *ptr);
+ }
+ }
+ return ret;
+}
+
diff --git a/nuttx/examples/nsh/nsh_main.c b/nuttx/examples/nsh/nsh_main.c
index ff3398ea1..b7070f439 100644
--- a/nuttx/examples/nsh/nsh_main.c
+++ b/nuttx/examples/nsh/nsh_main.c
@@ -107,16 +107,21 @@ static const struct cmdmap_s g_cmdmap[] =
#if CONFIG_NFILE_DESCRIPTORS > 0
{ "ls", cmd_ls, 2, 5, "[-lRs] <dir-path>" },
#endif
+ { "mb", cmd_mb, 2, 3, "<hex-address>[=<hex-value>][ <hex-byte-count>]" },
#if !defined(CONFIG_DISABLE_MOUNTPOINT) && CONFIG_NFILE_DESCRIPTORS > 0
{ "mkdir", cmd_mkdir, 2, 2, "<path>" },
#ifdef CONFIG_FS_FAT
{ "mkfatfs", cmd_mkfatfs, 2, 2, "<path>" },
#endif
{ "mkfifo", cmd_mkfifo, 2, 2, "<path>" },
+#endif
+ { "mh", cmd_mh, 2, 3, "<hex-address>[=<hex-value>][ <hex-byte-count>]" },
+#if !defined(CONFIG_DISABLE_MOUNTPOINT) && CONFIG_NFILE_DESCRIPTORS > 0
#ifdef CONFIG_FS_FAT /* Need at least one filesytem in configuration */
{ "mount", cmd_mount, 4, 5, "-t <fstype> <block-device> <dir-path>" },
#endif
#endif
+ { "mw", cmd_mw, 2, 3, "<hex-address>[=<hex-value>][ <hex-byte-count>]" },
{ "ps", cmd_ps, 1, 1, NULL },
#ifndef CONFIG_DISABLE_ENVIRON
{ "set", cmd_set, 3, 3, "<name> <value>" },
@@ -152,6 +157,7 @@ static const struct cmdmap_s g_cmdmap[] =
const char g_nshprompt[] = "nsh> ";
const char g_fmtargrequired[] = "nsh: %s: missing required argument(s)\n";
const char g_fmtarginvalid[] = "nsh: %s: argument invalid\n";
+const char g_fmtargrange[] = "nsh: %s: value out of range\n";
const char g_fmtcmdnotfound[] = "nsh: %s: command not found\n";
const char g_fmtcmdnotimpl[] = "nsh: %s: command not implemented\n";
const char g_fmtnosuch[] = "nsh: %s: no such %s: %s\n";