aboutsummaryrefslogtreecommitdiff
path: root/nuttx/binfmt
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:18:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:18:44 +0000
commit57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff (patch)
tree25d07d14e920d31c0b1947c9ca586f2a01fc32d8 /nuttx/binfmt
downloadpx4-firmware-57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff.tar.gz
px4-firmware-57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff.tar.bz2
px4-firmware-57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff.zip
Resync new repository with old repo r5166
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5153 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/binfmt')
-rw-r--r--nuttx/binfmt/Kconfig4
-rw-r--r--nuttx/binfmt/Makefile102
-rw-r--r--nuttx/binfmt/binfmt_dumpmodule.c101
-rw-r--r--nuttx/binfmt/binfmt_exec.c123
-rw-r--r--nuttx/binfmt/binfmt_execmodule.c190
-rw-r--r--nuttx/binfmt/binfmt_globals.c71
-rw-r--r--nuttx/binfmt/binfmt_internal.h88
-rw-r--r--nuttx/binfmt/binfmt_loadmodule.c138
-rw-r--r--nuttx/binfmt/binfmt_register.c104
-rw-r--r--nuttx/binfmt/binfmt_unloadmodule.c108
-rw-r--r--nuttx/binfmt/binfmt_unregister.c138
-rw-r--r--nuttx/binfmt/libnxflat/Kconfig4
-rw-r--r--nuttx/binfmt/libnxflat/Make.defs39
-rw-r--r--nuttx/binfmt/libnxflat/gnu-nxflat.ld172
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_bind.c492
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_init.c188
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c208
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_read.c165
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_uninit.c88
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_unload.c97
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_verify.c100
-rw-r--r--nuttx/binfmt/nxflat.c257
-rw-r--r--nuttx/binfmt/symtab_findbyname.c97
-rw-r--r--nuttx/binfmt/symtab_findbyvalue.c121
-rw-r--r--nuttx/binfmt/symtab_findorderedbyname.c139
-rw-r--r--nuttx/binfmt/symtab_findorderedbyvalue.c127
26 files changed, 3461 insertions, 0 deletions
diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig
new file mode 100644
index 000000000..ae2bf3130
--- /dev/null
+++ b/nuttx/binfmt/Kconfig
@@ -0,0 +1,4 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
new file mode 100644
index 000000000..b3a9269b3
--- /dev/null
+++ b/nuttx/binfmt/Makefile
@@ -0,0 +1,102 @@
+############################################################################
+# nxflat/Makefile
+#
+# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+ifeq ($(WINTOOL),y)
+INCDIROPT = -w
+endif
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/sched}
+
+ifeq ($(CONFIG_NXFLAT),y)
+include libnxflat/Make.defs
+LIBNXFLAT_CSRCS += nxflat.c
+endif
+
+BINFMT_ASRCS =
+BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \
+ binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \
+ binfmt_exec.c binfmt_dumpmodule.c
+
+SYMTAB_ASRCS =
+SYMTAB_CSRCS = symtab_findbyname.c symtab_findbyvalue.c \
+ symtab_findorderedbyname.c symtab_findorderedbyvalue.c
+
+SUBDIRS = libnxflat
+
+ASRCS = $(BINFMT_ASRCS) $(SYMTAB_ASRCS) $(LIBNXFLAT_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = $(BINFMT_CSRCS) $(SYMTAB_CSRCS) $(LIBNXFLAT_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+BIN = libbinfmt$(LIBEXT)
+
+VPATH = libnxflat
+
+all: $(BIN)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+$(BIN): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) --dep-path . --dep-path libnxflat \
+ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f $(BIN) *~ .*.swp
+ $(call CLEAN)
+ @( for dir in $(SUBDIRS); do \
+ rm -f $${dir}/*~ $${dir}/.*.swp; \
+ done ; )
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c
new file mode 100644
index 000000000..32a3fef3e
--- /dev/null
+++ b/nuttx/binfmt/binfmt_dumpmodule.c
@@ -0,0 +1,101 @@
+/****************************************************************************
+ * binfmt/binfmt_dumpmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) && !defined(CONFIG_BINFMT_DISABLE)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: load_module
+ *
+ * Description:
+ * Load a module into memory and prep it for execution.
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ***********************************************************************/
+
+int dump_module(FAR const struct binary_s *bin)
+{
+ if (bin)
+ {
+ bdbg("Module:\n");
+ bdbg(" filename: %s\n", bin->filename);
+ bdbg(" argv: %p\n", bin->argv);
+ bdbg(" entrypt: %p\n", bin->entrypt);
+ bdbg(" ispace: %p size=%d\n", bin->ispace, bin->isize);
+ bdbg(" dspace: %p\n", bin->dspace);
+ bdbg(" stacksize: %d\n", bin->stacksize);
+ }
+ return OK;
+}
+#endif
+
+
diff --git a/nuttx/binfmt/binfmt_exec.c b/nuttx/binfmt/binfmt_exec.c
new file mode 100644
index 000000000..c070324c3
--- /dev/null
+++ b/nuttx/binfmt/binfmt_exec.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ * binfmt/binfmt_exec.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: exec
+ *
+ * Description:
+ * This is a convenience function that wraps load_ and exec_module into
+ * one call.
+ *
+ * Input Parameter:
+ * filename - Fulll path to the binary to be loaded
+ * argv - Argument list
+ * exports - Table of exported symbols
+ * nexports - The number of symbols in exports
+ *
+ * Returned Value:
+ * This is an end-user function, so it follows the normal convention:
+ * Returns the PID of the exec'ed module. On failure, it.returns
+ * -1 (ERROR) and sets errno appropriately.
+ *
+ ****************************************************************************/
+
+int exec(FAR const char *filename, FAR const char **argv,
+ FAR const struct symtab_s *exports, int nexports)
+{
+ struct binary_s bin;
+ int ret;
+
+ memset(&bin, 0, sizeof(struct binary_s));
+ bin.filename = filename;
+ bin.exports = exports;
+ bin.nexports = nexports;
+
+ ret = load_module(&bin);
+ if (ret < 0)
+ {
+ bdbg("ERROR: Failed to load program '%s'\n", filename);
+ return ERROR;
+ }
+
+ ret = exec_module(&bin, 50);
+ if (ret < 0)
+ {
+ bdbg("ERROR: Failed to execute program '%s'\n", filename);
+ unload_module(&bin);
+ return ERROR;
+ }
+
+ return ret;
+}
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c
new file mode 100644
index 000000000..1b511b0cb
--- /dev/null
+++ b/nuttx/binfmt/binfmt_execmodule.c
@@ -0,0 +1,190 @@
+/****************************************************************************
+ * binfmt/binfmt_execmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/binfmt.h>
+
+#include "os_internal.h"
+#include "binfmt_internal.h"
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: exec_module
+ *
+ * Description:
+ * Execute a module that has been loaded into memory by load_module().
+ *
+ * Returned Value:
+ * This is an end-user function, so it follows the normal convention:
+ * Returns the PID of the exec'ed module. On failure, it.returns
+ * -1 (ERROR) and sets errno appropriately.
+ *
+ ****************************************************************************/
+
+int exec_module(FAR const struct binary_s *bin, int priority)
+{
+ FAR _TCB *tcb;
+#ifndef CONFIG_CUSTOM_STACK
+ FAR uint32_t *stack;
+#endif
+ pid_t pid;
+ int err;
+ int ret;
+
+ /* Sanity checking */
+
+#ifdef CONFIG_DEBUG
+ if (!bin || !bin->ispace || !bin->entrypt || bin->stacksize <= 0)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+#endif
+
+ bdbg("Executing %s\n", bin->filename);
+
+ /* Allocate a TCB for the new task. */
+
+ tcb = (FAR _TCB*)zalloc(sizeof(_TCB));
+ if (!tcb)
+ {
+ err = ENOMEM;
+ goto errout;
+ }
+
+ /* Allocate the stack for the new task */
+
+#ifndef CONFIG_CUSTOM_STACK
+ stack = (FAR uint32_t*)malloc(bin->stacksize);
+ if (!tcb)
+ {
+ err = ENOMEM;
+ goto errout_with_tcb;
+ }
+
+ /* Initialize the task */
+
+ ret = task_init(tcb, bin->filename, priority, stack, bin->stacksize, bin->entrypt, bin->argv);
+#else
+ /* Initialize the task */
+
+ ret = task_init(tcb, bin->filename, priority, stack, bin->entrypt, bin->argv);
+#endif
+ if (ret < 0)
+ {
+ err = errno;
+ bdbg("task_init() failed: %d\n", err);
+ goto errout_with_stack;
+ }
+
+ /* Add the DSpace address as the PIC base address */
+
+#ifdef CONFIG_PIC
+ tcb->dspace = bin->dspace;
+
+ /* Re-initialize the task's initial state to account for the new PIC base */
+
+ up_initial_state(tcb);
+#endif
+
+ /* Get the assigned pid before we start the task */
+
+ pid = tcb->pid;
+
+ /* Then activate the task at the provided priority */
+
+ ret = task_activate(tcb);
+ if (ret < 0)
+ {
+ err = errno;
+ bdbg("task_activate() failed: %d\n", err);
+ goto errout_with_stack;
+ }
+ return (int)pid;
+
+errout_with_stack:
+#ifndef CONFIG_CUSTOM_STACK
+ tcb->stack_alloc_ptr = NULL;
+ sched_releasetcb(tcb);
+ free(stack);
+#else
+ sched_releasetcb(tcb);
+#endif
+ goto errout;
+
+errout_with_tcb:
+ free(tcb);
+errout:
+ errno = err;
+ bdbg("returning errno: %d\n", err);
+ return ERROR;
+}
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
diff --git a/nuttx/binfmt/binfmt_globals.c b/nuttx/binfmt/binfmt_globals.c
new file mode 100644
index 000000000..069d3a2aa
--- /dev/null
+++ b/nuttx/binfmt/binfmt_globals.c
@@ -0,0 +1,71 @@
+/****************************************************************************
+ * binfmt/binfmt_globals.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/binfmt.h>
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* This is a list of registered handlers for different binary formats. This
+ * list should only be accessed by normal user programs. It should be sufficient
+ * protection to simply disable pre-emption when accessing this list.
+ */
+
+FAR struct binfmt_s *g_binfmts;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
+
diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h
new file mode 100644
index 000000000..da67f5350
--- /dev/null
+++ b/nuttx/binfmt/binfmt_internal.h
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * binfmt/binfmt_internal.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __BINFMT_BINFMT_INTERNAL_H
+#define __BINFMT_BINFMT_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/binfmt.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* This is a list of registered handlers for different binary formats. This
+ * list should only be accessed by normal user programs. It should be sufficient
+ * protection to simply disable pre-emption when accessing this list.
+ */
+
+EXTERN FAR struct binfmt_s *g_binfmts;
+
+/***********************************************************************
+ * Public Function Prototypes
+ ***********************************************************************/
+
+/* Dump the contents of strtuc binary_s */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+EXTERN int dump_module(FAR const struct binary_s *bin);
+#else
+# define dump_module(bin)
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __BINFMT_BINFMT_INTERNAL_H */
+
diff --git a/nuttx/binfmt/binfmt_loadmodule.c b/nuttx/binfmt/binfmt_loadmodule.c
new file mode 100644
index 000000000..01ab8cc88
--- /dev/null
+++ b/nuttx/binfmt/binfmt_loadmodule.c
@@ -0,0 +1,138 @@
+/****************************************************************************
+ * binfmt/binfmt_loadmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: load_module
+ *
+ * Description:
+ * Load a module into memory, bind it to an exported symbol take, and
+ * prep the module for execution.
+ *
+ * Returned Value:
+ * This is an end-user function, so it follows the normal convention:
+ * Returns 0 (OK) on success. On failure, it returns -1 (ERROR) with
+ * errno set appropriately.
+ *
+ ****************************************************************************/
+
+int load_module(FAR struct binary_s *bin)
+{
+ FAR struct binfmt_s *binfmt;
+ int ret = -ENOENT;
+
+#ifdef CONFIG_DEBUG
+ if (bin && bin->filename)
+#endif
+ {
+ bdbg("Loading %s\n", bin->filename);
+
+ /* Disabling pre-emption should be sufficient protection while
+ * accessing the list of registered binary format handlers.
+ */
+
+ sched_lock();
+
+ /* Traverse the list of registered binary format handlers. Stop
+ * when either (1) a handler recognized and loads the format, or
+ * (2) no handler recognizes the format.
+ */
+
+ for (binfmt = g_binfmts; binfmt; binfmt = binfmt->next)
+ {
+ /* Use this handler to try to load the format */
+
+ ret = binfmt->load(bin);
+ if (ret == OK)
+ {
+ /* Successfully loaded -- break out with ret == 0 */
+
+ bvdbg("Successfully loaded module %s\n", bin->filename);
+ dump_module(bin);
+ break;
+ }
+ }
+
+ sched_unlock();
+ }
+
+ /* This is an end-user function. Return failures via errno */
+
+ if (ret < 0)
+ {
+ bdbg("Returning errno %d\n", -ret);
+ errno = -ret;
+ return ERROR;
+ }
+ return OK;
+}
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
diff --git a/nuttx/binfmt/binfmt_register.c b/nuttx/binfmt/binfmt_register.c
new file mode 100644
index 000000000..7f6eef671
--- /dev/null
+++ b/nuttx/binfmt/binfmt_register.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ * binfmt/binfmt_register.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: register_binfmt
+ *
+ * Description:
+ * Register a loader for a binary format
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int register_binfmt(FAR struct binfmt_s *binfmt)
+{
+ if (binfmt)
+ {
+ /* Add the new binary format handler to the head of the list of
+ * handlers
+ */
+
+ sched_lock();
+ binfmt->next = g_binfmts;
+ g_binfmts = binfmt;
+ sched_unlock();
+ return OK;
+ }
+ return -EINVAL;
+}
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c
new file mode 100644
index 000000000..04859a291
--- /dev/null
+++ b/nuttx/binfmt/binfmt_unloadmodule.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ * binfmt/binfmt_loadmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/mman.h>
+#include <stdlib.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: unload_module
+ *
+ * Description:
+ * Unload a (non-executing) module from memory. If the module has
+ * been started (via exec_module), calling this will be fatal.
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int unload_module(FAR const struct binary_s *bin)
+{
+ if (bin)
+ {
+ if (bin->ispace)
+ {
+ bvdbg("Unmapping ISpace: %p\n", bin->ispace);
+ munmap(bin->ispace, bin->isize);
+ }
+
+ if (bin->dspace)
+ {
+ bvdbg("Freeing DSpace: %p\n", bin->dspace);
+ free(bin->dspace);
+ }
+ }
+ return OK;
+}
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
diff --git a/nuttx/binfmt/binfmt_unregister.c b/nuttx/binfmt/binfmt_unregister.c
new file mode 100644
index 000000000..b97b9b67d
--- /dev/null
+++ b/nuttx/binfmt/binfmt_unregister.c
@@ -0,0 +1,138 @@
+/****************************************************************************
+ * binfmt/binfmt_unregister.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#ifndef CONFIG_BINFMT_DISABLE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: unregister_binfmt
+ *
+ * Description:
+ * Register a loader for a binary format
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int unregister_binfmt(FAR struct binfmt_s *binfmt)
+{
+ FAR struct binfmt_s *curr;
+ FAR struct binfmt_s *prev;
+ int ret = -EINVAL;
+
+ if (binfmt)
+ {
+ /* Disabling pre-emption should be sufficient protection while
+ * accessing the list of registered binary format handlers.
+ */
+
+ sched_lock();
+
+ /* Search the list of registered binary format handlers for the
+ * one to be unregistered.
+ */
+
+ for (prev = NULL, curr = g_binfmts;
+ curr && curr != binfmt;
+ prev = curr, curr = curr->next);
+
+ /* Was it in the list? */
+
+ if (curr)
+ {
+ /* Yes.. was it at the head of the list? */
+
+ if (!prev)
+ {
+ /* Yes.. remove it from the head of the list */
+
+ g_binfmts = binfmt->next;
+ }
+ else
+ {
+ /* No.. remove it from the middle/end of the list */
+
+ prev->next = binfmt->next;
+ }
+
+ binfmt->next = NULL;
+ ret = OK;
+ }
+
+ sched_unlock();
+ }
+
+ return ret;
+}
+
+#endif /* CONFIG_BINFMT_DISABLE */
+
diff --git a/nuttx/binfmt/libnxflat/Kconfig b/nuttx/binfmt/libnxflat/Kconfig
new file mode 100644
index 000000000..ae2bf3130
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/Kconfig
@@ -0,0 +1,4 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs
new file mode 100644
index 000000000..f979741e5
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/Make.defs
@@ -0,0 +1,39 @@
+############################################################################
+# nxflat/lib/Make.defs
+#
+# Copyright (C) 2009 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+LIBNXFLAT_ASRCS =
+LIBNXFLAT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \
+ libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \
+ libnxflat_bind.c
diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat.ld b/nuttx/binfmt/libnxflat/gnu-nxflat.ld
new file mode 100644
index 000000000..e66b1dff5
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/gnu-nxflat.ld
@@ -0,0 +1,172 @@
+/****************************************************************************
+ * examples/nxflat/nxflat.ld
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+ ISPACE : ORIGIN = 0x0, LENGTH = 2097152
+ DSPACE : ORIGIN = 0x0, LENGTH = 2097152
+}
+
+/****************************************************************************
+ * The XFLAT program image is divided into two segments:
+ *
+ * (1) ISpace (Instruction Space). This is the segment that contains
+ * code (.text). Everything in the segment should be fetch-able
+ * machine PC instructions (jump, branch, call, etc.).
+ * (2) DSpace (Data Space). This is the segment that contains both
+ * read-write data (.data, .bss) as well as read-only data (.rodata).
+ * Everything in this segment should be access-able with machine
+ * with machine load and store instructions.
+ ****************************************************************************/
+
+SECTIONS
+{
+ .text 0x00000000 :
+ {
+ /* ISpace is located at address 0. Every (unrelocated) ISpace
+ * address is an offset from the begining of this segment.
+ */
+
+ text_start = . ;
+
+ *(.text)
+ *(.text.*)
+ *(.gnu.warning)
+ *(.stub)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.jcr)
+
+ /* C++ support: The .init and .fini sections contain XFLAT-
+ * specific logic to manage static constructors and destructors.
+ */
+
+ *(.gnu.linkonce.t.*)
+ *(.init)
+ *(.fini)
+
+ /* This is special code area at the end of the normal
+ text section. It contains a small lookup table at
+ the start followed by the code pointed to by entries
+ in the lookup table. */
+
+ . = ALIGN (4) ;
+ PROVIDE(__ctbp = .);
+ *(.call_table_data)
+ *(.call_table_text)
+
+ _etext = . ;
+
+ } > ISPACE
+
+ /* DSpace is also located at address 0. Every (unrelocated) DSpace
+ * address is an offset from the begining of this segment.
+ */
+
+ .data 0x00000000 :
+ {
+ __data_start = . ;
+ *(.rodata)
+ *(.rodata1)
+ *(.rodata.*)
+ *(.gnu.linkonce.r*)
+ *(.data)
+ *(.data1)
+ *(.data.*)
+ *(.gnu.linkonce.d*)
+ *(.data1)
+ *(.eh_frame)
+ *(.gcc_except_table)
+
+ *(.gnu.linkonce.s.*)
+ *(__libc_atexit)
+ *(__libc_subinit)
+ *(__libc_subfreeres)
+ *(.note.ABI-tag)
+
+ /* C++ support. For each global and static local C++ object,
+ * GCC creates a small subroutine to construct the object. Pointers
+ * to these routines (not the routines themselves) are stored as
+ * simple, linear arrays in the .ctors section of the object file.
+ * Similarly, pointers to global/static destructor routines are
+ * stored in .dtors.
+ */
+
+ *(.gnu.linkonce.d.*)
+
+ _ctors_start = . ;
+ *(.ctors)
+ _ctors_end = . ;
+ _dtors_start = . ;
+ *(.dtors)
+ _dtors_end = . ;
+
+ _edata = . ;
+ edata = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .bss :
+ {
+ __bss_start = _edata ;
+ *(.dynsbss)
+ *(.sbss)
+ *(.sbss.*)
+ *(.scommon)
+ *(.dynbss)
+ *(.bss)
+ *(.bss.*)
+ *(.bss*)
+ *(.gnu.linkonce.b*)
+ *(COMMON)
+ end = ALIGN( 0x10 ) ;
+ _end = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .got 0 : { *(.got.plt) *(.got) }
+ .junk 0 : { *(.rel*) *(.rela*) }
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_bind.c b/nuttx/binfmt/libnxflat/libnxflat_bind.c
new file mode 100644
index 000000000..ca348178d
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_bind.c
@@ -0,0 +1,492 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_bind.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <string.h>
+#include <nxflat.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+#include <nuttx/symtab.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
+ * defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
+ */
+
+#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
+# undef CONFIG_NXFLAT_DUMPBUFFER
+#endif
+
+#ifdef CONFIG_NXFLAT_DUMPBUFFER
+# define nxflat_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
+#else
+# define nxflat_dumpbuffer(m,b,n)
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_bindrel32i
+ *
+ * Description:
+ * Perform the NXFLAT_RELOC_TYPE_REL32I binding:
+ *
+ * Meaning: Object file contains a 32-bit offset into I-Space at the offset.
+ * Fixup: Add mapped I-Space address to the offset.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int nxflat_bindrel32i(FAR struct nxflat_loadinfo_s *loadinfo,
+ uint32_t offset)
+{
+ uint32_t *addr;
+
+ bvdbg("NXFLAT_RELOC_TYPE_REL32I Offset: %08x I-Space: %p\n",
+ offset, loadinfo->ispace + sizeof(struct nxflat_hdr_s));
+
+ if (offset < loadinfo->dsize)
+ {
+ addr = (uint32_t*)(offset + loadinfo->dspace->region);
+ bvdbg(" Before: %08x\n", *addr);
+ *addr += (uint32_t)(loadinfo->ispace + sizeof(struct nxflat_hdr_s));
+ bvdbg(" After: %08x\n", *addr);
+ return OK;
+ }
+ else
+ {
+ bdbg("Offset: %08 does not lie in D-Space size: %08x\n",
+ offset, loadinfo->dsize);
+ return -EINVAL;
+ }
+}
+
+/****************************************************************************
+ * Name: nxflat_bindrel32d
+ *
+ * Description:
+ * Perform the NXFLAT_RELOC_TYPE_REL32D binding:
+ *
+ * Meaning: Object file contains a 32-bit offset into D-Space at the offset.
+ * Fixup: Add allocated D-Space address to the offset.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int nxflat_bindrel32d(FAR struct nxflat_loadinfo_s *loadinfo,
+ uint32_t offset)
+{
+ uint32_t *addr;
+
+ bvdbg("NXFLAT_RELOC_TYPE_REL32D Offset: %08x D-Space: %p\n",
+ offset, loadinfo->dspace->region);
+
+ if (offset < loadinfo->dsize)
+ {
+ addr = (uint32_t*)(offset + loadinfo->dspace->region);
+ bvdbg(" Before: %08x\n", *addr);
+ *addr += (uint32_t)(loadinfo->dspace->region);
+ bvdbg(" After: %08x\n", *addr);
+ return OK;
+ }
+ else
+ {
+ bdbg("Offset: %08 does not lie in D-Space size: %08x\n",
+ offset, loadinfo->dsize);
+ return -EINVAL;
+ }
+}
+
+/****************************************************************************
+ * Name: nxflat_bindrel32id
+ *
+ * Description:
+ * Perform the NXFLAT_RELOC_TYPE_REL32ID binding:
+ *
+ * Meaning: Object file contains a 32-bit offset into I-Space at the offset
+ * that will unfortunately be references relative to the GOT
+ * Fixup: Add allocated the mapped I-Space address MINUS the allocated
+ * D-Space address to the offset.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+#ifdef NXFLAT_RELOC_TYPE_REL32ID
+static inline int nxflat_bindrel32id(FAR struct nxflat_loadinfo_s *loadinfo,
+ uint32_t offset)
+{
+ uint32_t *addr;
+
+ bvdbg("NXFLAT_RELOC_TYPE_REL32D Offset: %08x D-Space: %p\n",
+ offset, loadinfo->dspace->region);
+
+ if (offset < loadinfo->dsize)
+ {
+ addr = (uint32_t*)(offset + loadinfo->dspace->region);
+ bvdbg(" Before: %08x\n", *addr);
+ *addr += ((uint32_t)loadinfo->ispace - (uint32_t)(loadinfo->dspace->region));
+ bvdbg(" After: %08x\n", *addr);
+ return OK;
+ }
+ else
+ {
+ bdbg("Offset: %08 does not lie in D-Space size: %08x\n",
+ offset, loadinfo->dsize);
+ return -EINVAL;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: nxflat_gotrelocs
+ *
+ * Description:
+ * Bind all of the GOT relocations in the loaded module described by
+ * 'loadinfo'
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
+{
+ FAR struct nxflat_reloc_s *relocs;
+ FAR struct nxflat_reloc_s reloc;
+ FAR struct nxflat_hdr_s *hdr;
+ uint32_t offset;
+ uint16_t nrelocs;
+ int ret;
+ int result;
+ int i;
+
+ /* The NXFLAT header is the first thing at the beginning of the ISpace. */
+
+ hdr = (FAR struct nxflat_hdr_s*)loadinfo->ispace;
+
+ /* From this, we can get the list of relocation entries. */
+
+ /* From this, we can get the offset to the list of relocation entries */
+
+ offset = ntohl(hdr->h_relocstart);
+ nrelocs = ntohs(hdr->h_reloccount);
+ bvdbg("offset: %08lx nrelocs: %d\n", (long)offset, nrelocs);
+
+ /* The value of the relocation list that we get from the header is a
+ * file offset. We will have to convert this to an offset into the
+ * DSpace segment to get the pointer to the beginning of the relocation
+ * list.
+ */
+
+ DEBUGASSERT(offset >= loadinfo->isize);
+ DEBUGASSERT(offset + nrelocs * sizeof(struct nxflat_reloc_s)
+ <= (loadinfo->isize + loadinfo->dsize));
+
+ relocs = (FAR struct nxflat_reloc_s*)
+ (offset - loadinfo->isize + loadinfo->dspace->region);
+ bvdbg("isize: %08lx dpsace: %p relocs: %p\n",
+ (long)loadinfo->isize, loadinfo->dspace->region, relocs);
+
+ /* Now, traverse the relocation list of and bind each GOT relocation. */
+
+ ret = OK; /* Assume success */
+ for (i = 0; i < nrelocs; i++)
+ {
+ /* Handle the relocation by the relocation type */
+
+ reloc = *relocs++;
+ result = OK;
+ switch (NXFLAT_RELOC_TYPE(reloc.r_info))
+ {
+
+ /* NXFLAT_RELOC_TYPE_REL32I Meaning: Object file contains a 32-bit offset
+ * into I-Space at the offset.
+ * Fixup: Add mapped I-Space address to the offset.
+ */
+
+ case NXFLAT_RELOC_TYPE_REL32I:
+ {
+ result = nxflat_bindrel32i(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
+ }
+ break;
+
+ /* NXFLAT_RELOC_TYPE_REL32D Meaning: Object file contains a 32-bit offset
+ * into D-Space at the offset.
+ * Fixup: Add allocated D-Space address to the
+ * offset.
+ */
+
+ case NXFLAT_RELOC_TYPE_REL32D:
+ {
+ result = nxflat_bindrel32d(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
+ }
+ break;
+
+ /* NXFLAT_RELOC_TYPE_REL32ID Meaning: Object file contains a 32-bit offset
+ * into I-Space at the offset that will
+ * unfortunately be references relative
+ * to the GOT
+ * Fixup: Add allocated the mapped I-Space
+ * address MINUS the allocated D-Space
+ * address to the offset.
+ */
+
+#ifdef NXFLAT_RELOC_TYPE_REL32ID
+ case NXFLAT_RELOC_TYPE_REL32ID:
+ {
+ result = nxflat_bindrel32id(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
+ }
+ break;
+#endif
+
+ default:
+ {
+ bdbg("ERROR: Unrecognized relocation type: %d\n", NXFLAT_RELOC_TYPE(reloc.r_info));
+ result = -EINVAL;
+ }
+ break;
+ }
+
+ /* Check for failures */
+
+ if (result < 0 && ret == OK)
+ {
+ ret = result;
+ }
+ }
+
+ /* Dump the relocation got */
+
+#ifdef CONFIG_NXFLAT_DUMPBUFFER
+ if (ret == OK && nrelocs > 0)
+ {
+ relocs = (FAR struct nxflat_reloc_s*)(offset - loadinfo->isize + loadinfo->dspace->region);
+ nxflat_dumpbuffer("GOT", (FAR const uint8_t*)relocs, nrelocs * sizeof(struct nxflat_reloc_s));
+ }
+#endif
+ return ret;
+}
+
+/****************************************************************************
+ * Name: nxflat_bindimports
+ *
+ * Description:
+ * Bind the imported symbol names in the loaded module described by
+ * 'loadinfo' using the exported symbol values provided by 'symtab'
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports,
+ int nexports)
+{
+ FAR struct nxflat_import_s *imports;
+ FAR struct nxflat_hdr_s *hdr;
+ FAR const struct symtab_s *symbol;
+
+ char *symname;
+ uint32_t offset;
+ uint16_t nimports;
+ int i;
+
+ /* The NXFLAT header is the first thing at the beginning of the ISpace. */
+
+ hdr = (FAR struct nxflat_hdr_s*)loadinfo->ispace;
+
+ /* From this, we can get the offset to the list of symbols imported by
+ * this module and the number of symbols imported by this module.
+ */
+
+ offset = ntohl(hdr->h_importsymbols);
+ nimports = ntohs(hdr->h_importcount);
+ bvdbg("Imports offset: %08x nimports: %d\n", offset, nimports);
+
+ /* Verify that this module requires imported symbols */
+
+ if (offset != 0 && nimports > 0)
+ {
+ /* It does.. make sure that exported symbols are provided */
+
+ DEBUGASSERT(exports && nexports > 0);
+
+ /* If non-zero, the value of the imported symbol list that we get
+ * from the header is a file offset. We will have to convert this
+ * to an offset into the DSpace segment to get the pointer to the
+ * beginning of the imported symbol list.
+ */
+
+ DEBUGASSERT(offset >= loadinfo->isize &&
+ offset < loadinfo->isize + loadinfo->dsize);
+
+ imports = (struct nxflat_import_s*)
+ (offset - loadinfo->isize + loadinfo->dspace->region);
+
+ /* Now, traverse the list of imported symbols and attempt to bind
+ * each symbol to the value exported by from the exported symbol
+ * table.
+ */
+
+ for (i = 0; i < nimports; i++)
+ {
+ bvdbg("Import[%d] (%08p) offset: %08x func: %08x\n",
+ i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress);
+
+ /* Get a pointer to the imported symbol name. The name itself
+ * lies in the TEXT segment. But the reference to the name
+ * lies in DATA segment. Therefore, the name reference should
+ * have been relocated when the module was loaded.
+ */
+
+ offset = imports[i].i_funcname;
+ DEBUGASSERT(offset < loadinfo->isize);
+
+ symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s));
+
+ /* Find the exported symbol value for this this symbol name. */
+
+#ifdef CONFIG_SYMTAB_ORDEREDBYNAME
+ symbol = symtab_findorderedbyname(exports, symname, nexports);
+#else
+ symbol = symtab_findbyname(exports, symname, nexports);
+#endif
+ if (!symbol)
+ {
+ bdbg("Exported symbol \"%s\" not found\n", symname);
+ return -ENOENT;
+ }
+
+ /* And put this into the module's import structure. */
+
+ imports[i].i_funcaddress = (uint32_t)symbol->sym_value;
+
+ bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n",
+ i, &imports[i], symname, imports[i].i_funcaddress);
+ }
+ }
+
+ /* Dump the relocation import table */
+
+#ifdef CONFIG_NXFLAT_DUMPBUFFER
+ if (nimports > 0)
+ {
+ nxflat_dumpbuffer("Imports", (FAR const uint8_t*)imports, nimports * sizeof(struct nxflat_import_s));
+ }
+#endif
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_bind
+ *
+ * Description:
+ * Bind the imported symbol names in the loaded module described by
+ * 'loadinfo' using the exported symbol values provided by 'symtab'.
+ * After binding the module, clear the BSS region (which held the relocation
+ * data) in preparation for execution.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports, int nexports)
+{
+ /* Bind the imported symbol, absolute relocations separately. This is done
+ * before the standard relocations because that logic may modify the
+ * import list (for the better hopefully, but we don't want to depend on it).
+ */
+
+ int ret = nxflat_bindimports(loadinfo, exports, nexports);
+ if (ret == OK)
+ {
+ /* Then bind all GOT relocations */
+
+ ret = nxflat_gotrelocs(loadinfo);
+ if (ret == OK)
+ {
+ /* Zero the BSS area, trashing the relocations that lived in that
+ * space in the loaded file.
+ */
+
+ memset((void*)(loadinfo->dspace->region + loadinfo->datasize),
+ 0, loadinfo->bsssize);
+ }
+ }
+ return ret;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c
new file mode 100644
index 000000000..5b6375ff1
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_init.c
@@ -0,0 +1,188 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_init.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/stat.h>
+#include <stdint.h>
+#include <string.h>
+#include <fcntl.h>
+#include <nxflat.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
+ * defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
+ */
+
+#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
+# undef CONFIG_NXFLAT_DUMPBUFFER
+#endif
+
+#ifdef CONFIG_NXFLAT_DUMPBUFFER
+# define nxflat_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
+#else
+# define nxflat_dumpbuffer(m,b,n)
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_init
+ *
+ * Description:
+ * This function is called to configure the library to process an NXFLAT
+ * program binary.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo)
+{
+ uint32_t datastart;
+ uint32_t dataend;
+ uint32_t bssstart;
+ uint32_t bssend;
+ int ret;
+
+ bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo);
+
+ /* Clear the load info structure */
+
+ memset(loadinfo, 0, sizeof(struct nxflat_loadinfo_s));
+
+ /* Open the binary file */
+
+ loadinfo->filfd = open(filename, O_RDONLY);
+ if (loadinfo->filfd < 0)
+ {
+ bdbg("Failed to open NXFLAT binary %s: %d\n", filename, ret);
+ return -errno;
+ }
+
+ /* Read the NXFLAT header from offset 0 */
+
+ ret = nxflat_read(loadinfo, (char*)&loadinfo->header,
+ sizeof(struct nxflat_hdr_s), 0);
+ if (ret < 0)
+ {
+ bdbg("Failed to read NXFLAT header: %d\n", ret);
+ return ret;
+ }
+ nxflat_dumpbuffer("NXFLAT header", (FAR const uint8_t*)&loadinfo->header,
+ sizeof(struct nxflat_hdr_s));
+
+ /* Verify the NXFLAT header */
+
+ if (nxflat_verifyheader(&loadinfo->header) != 0)
+ {
+ /* This is not an error because we will be called to attempt loading
+ * EVERY binary. Returning -ENOEXEC simply informs the system that
+ * the file is not an NXFLAT file. Besides, if there is something worth
+ * complaining about, nnxflat_verifyheader() has already
+ * done so.
+ */
+
+ bdbg("Bad NXFLAT header\n");
+ return -ENOEXEC;
+ }
+
+ /* Save all of the input values in the loadinfo structure
+ * and extract some additional information from the xflat
+ * header. Note that the information in the xflat header is in
+ * network order.
+ */
+
+ datastart = ntohl(loadinfo->header.h_datastart);
+ dataend = ntohl(loadinfo->header.h_dataend);
+ bssstart = dataend;
+ bssend = ntohl(loadinfo->header.h_bssend);
+
+ /* And put this information into the loadinfo structure as well.
+ *
+ * Note that:
+ *
+ * isize = the address range from 0 up to datastart.
+ * datasize = the address range from datastart up to dataend
+ * bsssize = the address range from dataend up to bssend.
+ */
+
+ loadinfo->entryoffs = ntohl(loadinfo->header.h_entry);
+ loadinfo->isize = datastart;
+
+ loadinfo->datasize = dataend - datastart;
+ loadinfo->bsssize = bssend - dataend;
+ loadinfo->stacksize = ntohl(loadinfo->header.h_stacksize);
+
+ /* This is the initial dspace size. We'll re-calculate this later
+ * after the memory has been allocated.
+ */
+
+ loadinfo->dsize = bssend - datastart;
+
+ /* Get the offset to the start of the relocations (we'll relocate
+ * this later).
+ */
+
+ loadinfo->relocstart = ntohl(loadinfo->header.h_relocstart);
+ loadinfo->reloccount = ntohs(loadinfo->header.h_reloccount);
+
+ return 0;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
new file mode 100644
index 000000000..0991d0c2d
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_load.c
@@ -0,0 +1,208 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_load.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/mman.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <nxflat.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#ifndef MAX
+#define MAX(x,y) ((x) > (y) ? (x) : (y))
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_BINFMT)
+static const char g_relocrel32i[] = "RELOC_REL32I";
+static const char g_relocrel32d[] = "RELOC_REL32D";
+static const char g_relocabs32[] = "RELOC_AB32";
+static const char g_undefined[] = "UNDEFINED";
+
+static const char *g_reloctype[] =
+{
+ g_relocrel32i,
+ g_relocrel32d,
+ g_relocabs32,
+ g_undefined
+};
+# define RELONAME(rl) g_reloctype[NXFLAT_RELOC_TYPE(rl)]
+#else
+# define RELONAME(rl) "(no name)"
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_load
+ *
+ * Description:
+ * Loads the binary specified by nxflat_init into memory, mapping
+ * the I-space executable regions, allocating the D-Space region,
+ * and inializing the data segment (relocation information is
+ * temporarily loaded into the BSS region. BSS will be cleared
+ * by nxflat_bind() after the relocation data has been processed).
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
+{
+ off_t doffset; /* Offset to .data in the NXFLAT file */
+ uint32_t dreadsize; /* Total number of bytes of .data to be read */
+ uint32_t relocsize; /* Memory needed to hold relocations */
+ uint32_t extrasize; /* MAX(BSS size, relocsize) */
+ int ret = OK;
+
+ /* Calculate the extra space we need to allocate. This extra space will be
+ * the size of the BSS section. This extra space will also be used
+ * temporarily to hold relocation information. So the allocated size of this
+ * region will either be the size of .data + size of.bss section OR, the
+ * size of .data + the relocation entries, whichever is larger
+ *
+ * This is the amount of memory that we have to have to hold the
+ * relocations.
+ */
+
+ relocsize = loadinfo->reloccount * sizeof(struct nxflat_reloc_s);
+
+ /* In the file, the relocations should lie at the same offset as BSS.
+ * The additional amount that we allocate have to be either (1) the
+ * BSS size, or (2) the size of the relocation records, whicher is
+ * larger.
+ */
+
+ extrasize = MAX(loadinfo->bsssize, relocsize);
+
+ /* Use this additional amount to adjust the total size of the dspace
+ * region.
+ */
+
+ loadinfo->dsize = loadinfo->datasize + extrasize;
+
+ /* The number of bytes of data that we have to read from the file is
+ * the data size plus the size of the relocation table.
+ */
+
+ dreadsize = loadinfo->datasize + relocsize;
+
+ /* We'll need this a few times. */
+
+ doffset = loadinfo->isize;
+
+ /* We will make two mmap calls create an address space for the executable.
+ * We will attempt to map the file to get the ISpace address space and
+ * to allocate RAM to get the DSpace address space. If the filesystem does
+ * not support file mapping, the map() implementation should do the
+ * right thing.
+ */
+
+ /* The following call will give as a pointer to the mapped file ISpace.
+ * This may be in ROM, RAM, Flash, ... We don't really care where the memory
+ * resides as long as it is fully initialized and ready to execute.
+ */
+
+ loadinfo->ispace = (uint32_t)mmap(NULL, loadinfo->isize, PROT_READ,
+ MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
+ if (loadinfo->ispace == (uint32_t)MAP_FAILED)
+ {
+ bdbg("Failed to map NXFLAT ISpace: %d\n", errno);
+ return -errno;
+ }
+
+ bvdbg("Mapped ISpace (%d bytes) at %08x\n", loadinfo->isize, loadinfo->ispace);
+
+ /* The following call will give a pointer to the allocated but
+ * uninitialized ISpace memory.
+ */
+
+ loadinfo->dspace = (struct dspace_s *)malloc(SIZEOF_DSPACE_S(loadinfo->dsize));
+ if (loadinfo->dspace == 0)
+ {
+ bdbg("Failed to allocate DSpace\n");
+ ret = -ENOMEM;
+ goto errout;
+ }
+ loadinfo->dspace->crefs = 1;
+
+ bvdbg("Allocated DSpace (%d bytes) at %p\n", loadinfo->dsize, loadinfo->dspace->region);
+
+ /* Now, read the data into allocated DSpace at doffset into the
+ * allocated DSpace memory.
+ */
+
+ ret = nxflat_read(loadinfo, (char*)loadinfo->dspace->region, dreadsize, doffset);
+ if (ret < 0)
+ {
+ bdbg("Failed to read .data section: %d\n", ret);
+ goto errout;
+ }
+
+ bvdbg("TEXT: %08x Entry point offset: %08x Data offset: %08x\n",
+ loadinfo->ispace, loadinfo->entryoffs, doffset);
+
+ return OK;
+
+errout:
+ (void)nxflat_unload(loadinfo);
+ return ret;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c
new file mode 100644
index 000000000..dbcd54279
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_read.c
@@ -0,0 +1,165 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_read.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <unistd.h>
+#include <string.h>
+#include <nxflat.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#undef NXFLAT_DUMP_READDATA /* Define to dump all file data read */
+#define DUMPER lib_rawprintf /* If NXFLAT_DUMP_READDATA is defined, this
+ * is the API used to dump data */
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_dumpreaddata
+ ****************************************************************************/
+
+#if defined(NXFLAT_DUMP_READDATA)
+static inline void nxflat_dumpreaddata(char *buffer, int buflen)
+{
+ uint32_t *buf32 = (uint32_t*)buffer;
+ int i;
+ int j;
+
+ for (i = 0; i < buflen; i += 32)
+ {
+ DUMPER("%04x:", i);
+ for (j = 0; j < 32; j += sizeof(uint32_t))
+ {
+ DUMPER(" %08x", *buf32++);
+ }
+ DUMPER("\n");
+ }
+}
+#else
+# define nxflat_dumpreaddata(b,n)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_read
+ *
+ * Description:
+ * Read 'readsize' bytes from the object file at 'offset'
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, int offset)
+{
+ ssize_t nbytes; /* Number of bytes read */
+ off_t rpos; /* Position returned by lseek */
+ char *bufptr; /* Next buffer location to read into */
+ int bytesleft; /* Number of bytes of .data left to read */
+ int bytesread; /* Total number of bytes read */
+
+ bvdbg("Read %d bytes from offset %d\n", readsize, offset);
+
+ /* Seek to the position in the object file where the initialized
+ * data is saved.
+ */
+
+ bytesread = 0;
+ bufptr = buffer;
+ bytesleft = readsize;
+ do
+ {
+ rpos = lseek(loadinfo->filfd, offset, SEEK_SET);
+ if (rpos != offset)
+ {
+ bdbg("Failed to seek to position %d: %d\n", offset, errno);
+ return -errno;
+ }
+
+ /* Read the file data at offset into the user buffer */
+
+ nbytes = read(loadinfo->filfd, bufptr, bytesleft);
+ if (nbytes < 0)
+ {
+ if (errno != EINTR)
+ {
+ bdbg("Read of .data failed: %d\n", errno);
+ return -errno;
+ }
+ }
+ else if (nbytes == 0)
+ {
+ bdbg("Unexpected end of file\n");
+ return -ENODATA;
+ }
+ else
+ {
+ bytesread += nbytes;
+ bytesleft -= nbytes;
+ bufptr += nbytes;
+ offset += nbytes;
+ }
+ }
+ while (bytesread < readsize);
+
+ nxflat_dumpreaddata(buffer, readsize);
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_uninit.c b/nuttx/binfmt/libnxflat/libnxflat_uninit.c
new file mode 100644
index 000000000..5d06296c7
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_uninit.c
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_uninit.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <unistd.h>
+#include <debug.h>
+#include <errno.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_swap32
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_uninit
+ *
+ * Description:
+ * Releases any resources committed by nxflat_init(). This essentially
+ * undoes the actions of nxflat_init.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo)
+{
+ if (loadinfo->filfd >= 0)
+ {
+ close(loadinfo->filfd);
+ }
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c
new file mode 100644
index 000000000..55a2e45e6
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_unload.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_unload.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/mman.h>
+#include <stdlib.h>
+#include <debug.h>
+
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_unload
+ *
+ * Description:
+ * This function unloads the object from memory. This essentially
+ * undoes the actions of nxflat_load.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
+{
+ /* Reset the contents of the info structure. */
+
+ /* Release the memory segments */
+
+ if (loadinfo->ispace)
+ {
+ munmap((void*)loadinfo->ispace, loadinfo->isize);
+ loadinfo->ispace = 0;
+ }
+
+ if (loadinfo->dspace)
+ {
+ free((void*)loadinfo->dspace);
+ loadinfo->dspace = 0;
+ }
+
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c
new file mode 100644
index 000000000..f799aca4f
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * binfmt/libnxflat/nxflat_verify.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <debug.h>
+#include <errno.h>
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_verifyheader
+ *
+ * Description:
+ * Given the header from a possible NXFLAT executable, verify that it
+ * is an NXFLAT executable.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int nxflat_verifyheader(const struct nxflat_hdr_s *header)
+{
+ if (!header)
+ {
+ bdbg("NULL NXFLAT header!");
+ return -ENOEXEC;
+ }
+
+ /* Check the FLT header -- magic number and revision.
+ *
+ * If the magic number does not match. Just return
+ * silently. This is not our binary.
+ */
+
+ if (strncmp(header->h_magic, NXFLAT_MAGIC, 4) != 0)
+ {
+ bdbg("Unrecognized magic=\"%c%c%c%c\"\n",
+ header->h_magic[0], header->h_magic[1],
+ header->h_magic[2], header->h_magic[3]);
+ return -ENOEXEC;
+ }
+ return OK;
+}
+
diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c
new file mode 100644
index 000000000..4f5869bd9
--- /dev/null
+++ b/nuttx/binfmt/nxflat.c
@@ -0,0 +1,257 @@
+/****************************************************************************
+ * binfmt/nxflat.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <string.h>
+#include <nxflat.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/binfmt.h>
+#include <nuttx/nxflat.h>
+
+#ifdef CONFIG_NXFLAT
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
+ * defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
+ */
+
+#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
+# undef CONFIG_NXFLAT_DUMPBUFFER
+#endif
+
+#ifdef CONFIG_NXFLAT_DUMPBUFFER
+# define nxflat_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
+#else
+# define nxflat_dumpbuffer(m,b,n)
+#endif
+
+#ifndef MIN
+# define MIN(a,b) (a < b ? a : b)
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int nxflat_loadbinary(struct binary_s *binp);
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+static void nxflat_dumploadinfo(struct nxflat_loadinfo_s *loadinfo);
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct binfmt_s g_nxflatbinfmt =
+{
+ NULL, /* next */
+ nxflat_loadbinary, /* load */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_dumploadinfo
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+static void nxflat_dumploadinfo(struct nxflat_loadinfo_s *loadinfo)
+{
+ unsigned long dsize = loadinfo->datasize + loadinfo->bsssize;
+
+ bdbg("LOAD_INFO:\n");
+ bdbg(" ISPACE:\n");
+ bdbg(" ispace: %08lx\n", loadinfo->ispace);
+ bdbg(" entryoffs: %08lx\n", loadinfo->entryoffs);
+ bdbg(" isize: %08lx\n", loadinfo->isize);
+
+ bdbg(" DSPACE:\n");
+ bdbg(" dspace: %08lx\n", loadinfo->dspace);
+ if (loadinfo->dspace != NULL)
+ {
+ bdbg(" crefs: %d\n", loadinfo->dspace->crefs);
+ bdbg(" region: %08lx\n", loadinfo->dspace->region);
+ }
+ bdbg(" datasize: %08lx\n", loadinfo->datasize);
+ bdbg(" bsssize: %08lx\n", loadinfo->bsssize);
+ bdbg(" (pad): %08lx\n", loadinfo->dsize - dsize);
+ bdbg(" stacksize: %08lx\n", loadinfo->stacksize);
+ bdbg(" dsize: %08lx\n", loadinfo->dsize);
+
+ bdbg(" RELOCS:\n");
+ bdbg(" relocstart: %08lx\n", loadinfo->relocstart);
+ bdbg(" reloccount: %d\n", loadinfo->reloccount);
+
+ bdbg(" HANDLES:\n");
+ bdbg(" filfd: %d\n", loadinfo->filfd);
+}
+#else
+# define nxflat_dumploadinfo(i)
+#endif
+
+/****************************************************************************
+ * Name: nxflat_loadbinary
+ *
+ * Description:
+ * Verify that the file is an NXFLAT binary and, if so, load the NXFLAT
+ * binary into memory
+ *
+ ****************************************************************************/
+
+static int nxflat_loadbinary(struct binary_s *binp)
+{
+ struct nxflat_loadinfo_s loadinfo; /* Contains globals for libnxflat */
+ int ret;
+
+ bvdbg("Loading file: %s\n", binp->filename);
+
+ /* Initialize the xflat library to load the program binary. */
+
+ ret = nxflat_init(binp->filename, &loadinfo);
+ nxflat_dumploadinfo(&loadinfo);
+ if (ret != 0)
+ {
+ bdbg("Failed to initialize for load of NXFLT program: %d\n", ret);
+ goto errout;
+ }
+
+ /* Load the program binary */
+
+ ret = nxflat_load(&loadinfo);
+ nxflat_dumploadinfo(&loadinfo);
+ if (ret != 0)
+ {
+ bdbg("Failed to load NXFLT program binary: %d\n", ret);
+ goto errout_with_init;
+ }
+
+ /* Bind the program to the exported symbol table */
+
+ ret = nxflat_bind(&loadinfo, binp->exports, binp->nexports);
+ if (ret != 0)
+ {
+ bdbg("Failed to bind symbols program binary: %d\n", ret);
+ goto errout_with_load;
+ }
+
+ /* Return the load information */
+
+ binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs);
+ binp->ispace = (void*)loadinfo.ispace;
+ binp->dspace = (void*)loadinfo.dspace;
+ binp->isize = loadinfo.isize;
+ binp->stacksize = loadinfo.stacksize;
+
+ nxflat_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,
+ MIN(binp->isize - loadinfo.entryoffs,512));
+
+ nxflat_uninit(&loadinfo);
+ return OK;
+
+errout_with_load:
+ nxflat_unload(&loadinfo);
+errout_with_init:
+ nxflat_uninit(&loadinfo);
+errout:
+ return ret;
+}
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: nxflat_initialize
+ *
+ * Description:
+ * NXFLAT support is built unconditionally. However, it order to
+ * use this binary format, this function must be called during system
+ * format in order to register the NXFLAT binary format.
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ***********************************************************************/
+
+int nxflat_initialize(void)
+{
+ int ret;
+
+ /* Register ourselves as a binfmt loader */
+
+ bvdbg("Registering NXFLAT\n");
+ ret = register_binfmt(&g_nxflatbinfmt);
+ if (ret != 0)
+ {
+ bdbg("Failed to register binfmt: %d\n", ret);
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: nxflat_uninitialize
+ *
+ * Description:
+ * Unregister the NXFLAT binary loader
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void nxflat_uninitialize(void)
+{
+ unregister_binfmt(&g_nxflatbinfmt);
+}
+
+#endif /* CONFIG_NXFLAT */
+
diff --git a/nuttx/binfmt/symtab_findbyname.c b/nuttx/binfmt/symtab_findbyname.c
new file mode 100644
index 000000000..201d7ba07
--- /dev/null
+++ b/nuttx/binfmt/symtab_findbyname.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ * binfmt/symtab_findbyname.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/symtab.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/****************************************************************************
+ * Name: symtab_findbyname
+ *
+ * Description:
+ * Find the symbol in the symbol table with the matching name.
+ * This version assumes that table is not ordered with respect to symbol
+ * name and, hence, access time will be linear with respect to nsyms.
+ *
+ * Returned Value:
+ * A reference to the symbol table entry if an entry with the matching
+ * name is found; NULL is returned if the entry is not found.
+ *
+ ****************************************************************************/
+
+FAR const struct symtab_s *
+symtab_findbyname(FAR const struct symtab_s *symtab,
+ FAR const char *name, int nsyms)
+{
+ DEBUGASSERT(symtab != NULL && name != NULL);
+ for (; nsyms > 0; symtab++, nsyms--)
+ {
+ if (strcmp(name, symtab->sym_name) == 0)
+ {
+ return symtab;
+ }
+ }
+ return NULL;
+}
+
diff --git a/nuttx/binfmt/symtab_findbyvalue.c b/nuttx/binfmt/symtab_findbyvalue.c
new file mode 100644
index 000000000..4382ed5d8
--- /dev/null
+++ b/nuttx/binfmt/symtab_findbyvalue.c
@@ -0,0 +1,121 @@
+/****************************************************************************
+ * binfmt/symtab_findbyvalue.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stddef.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/symtab.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/****************************************************************************
+ * Name: symtab_findbyvalue
+ *
+ * Description:
+ * Find the symbol in the symbol table whose value closest (but not greater
+ * than), the provided value. This version assumes that table is not ordered
+ * with respect to symbol name and, hence, access time will be linear with
+ * respect to nsyms.
+ *
+ * Returned Value:
+ * A reference to the symbol table entry if an entry with the matching
+ * name is found; NULL is returned if the entry is not found.
+ *
+ ****************************************************************************/
+
+FAR const struct symtab_s *
+symtab_findbyvalue(FAR const struct symtab_s *symtab,
+ FAR void *value, int nsyms)
+{
+ FAR const struct symtab_s *retval = NULL;
+
+ DEBUGASSERT(symtab != NULL);
+ for (; nsyms > 0; symtab++, nsyms--)
+ {
+ /* Look for symbols of lesser or equal value (probably address) to value */
+
+ if (symtab->sym_value <= value)
+ {
+ /* Found one. Is it the largest we have found so far? */
+
+ if (!retval || symtab->sym_value > retval->sym_value)
+ {
+ /* Yes, then it is the new candidate for the symbol whose value
+ * just below 'value'
+ */
+
+ retval = symtab;
+
+ /* If it is exactly equal to the search 'value', then we might as
+ * well terminate early because we can't do any better than that.
+ */
+
+ if (retval->sym_value == value)
+ {
+ break;
+ }
+ }
+ }
+ }
+
+ return retval;
+}
+
diff --git a/nuttx/binfmt/symtab_findorderedbyname.c b/nuttx/binfmt/symtab_findorderedbyname.c
new file mode 100644
index 000000000..61decf49a
--- /dev/null
+++ b/nuttx/binfmt/symtab_findorderedbyname.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * binfmt/symtab_findorderedbyname.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/symtab.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/****************************************************************************
+ * Name: symtab_findorderedbyname
+ *
+ * Description:
+ * Find the symbol in the symbol table with the matching name.
+ * This version assumes that table ordered with respect to symbol name.
+ *
+ * This function uses qsort() to implement the search and, hence, is a lot
+ * larger than symbtab_findbyname(). This function not be used, unless
+ * the symbol table is large and the performance benefit is worth the
+ * increased size.
+ *
+ * Returned Value:
+ * A reference to the symbol table entry if an entry with the matching
+ * name is found; NULL is returned if the entry is not found.
+ *
+ ****************************************************************************/
+
+FAR const struct symtab_s *
+symtab_findorderedbyname(FAR const struct symtab_s *symtab,
+ FAR const char *name, int nsyms)
+{
+ int low = 0;
+ int high = nsyms -1;
+ int mid;
+ int cmp;
+
+ /* Loop until the range has been isolated to a single symbol table
+ * entry that may or may not match the search name.
+ */
+
+ DEBUGASSERT(symtab != NULL && name != NULL);
+ while (low < high)
+ {
+ /* Compare the name to the one in the middle. (or just below
+ * the middle in the case where one is even and one is odd).
+ */
+
+ mid = (low + high) >> 1;
+ cmp = strcmp(name, symtab[mid].sym_name);
+ if (cmp < 0)
+ {
+ /* name < symtab[mid].sym_name */
+
+ high = mid - 1;
+ }
+ else if (cmp > 0)
+ {
+ /* name > symtab[mid].sym_name */
+
+ low = mid + 1;
+ }
+ else
+ {
+ /* symtab[mid].sym_name == name */
+
+ return &symtab[mid];
+ }
+ }
+
+ /* low == high... One final check. We might not have actually tested
+ * the final symtab[] name.
+ *
+ * Example: Only the last pass through loop, suppose low = 1, high = 2,
+ * mid = 1, and symtab[high].sym_name == name. Then we would get here with
+ * low = 2, high = 2, but symtab[2].sym_name was never tested.
+ */
+
+ return strcmp(name, symtab[low].sym_name) == 0 ? &symtab[low] : NULL;
+}
+
diff --git a/nuttx/binfmt/symtab_findorderedbyvalue.c b/nuttx/binfmt/symtab_findorderedbyvalue.c
new file mode 100644
index 000000000..92b107856
--- /dev/null
+++ b/nuttx/binfmt/symtab_findorderedbyvalue.c
@@ -0,0 +1,127 @@
+/****************************************************************************
+ * binfmt/symtab_findorderedbyvalue.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stddef.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/symtab.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/****************************************************************************
+ * Name: symtab_findorderedbyvalue
+ *
+ * Description:
+ * Find the symbol in the symbol table whose value closest (but not greater
+ * than), the provided value. This version assumes that table is ordered
+ * with respect to symbol name.
+ *
+ * Returned Value:
+ * A reference to the symbol table entry if an entry with the matching
+ * name is found; NULL is returned if the entry is not found.
+ *
+ ****************************************************************************/
+
+FAR const struct symtab_s *
+symtab_findorderedbyvalue(FAR const struct symtab_s *symtab,
+ FAR void *value, int nsyms)
+{
+ int low = 0;
+ int high = nsyms -1;
+ int mid;
+
+ /* Loop until the range has been isolated to a single symbol table
+ * entry that may or may not match the search name.
+ */
+
+ DEBUGASSERT(symtab != NULL);
+ while (low < high)
+ {
+ /* Compare the name to the one in the middle. (or just below
+ * the middle in the case where one is even and one is odd).
+ */
+
+ mid = (low + high) >> 1;
+ if ( value < symtab[mid].sym_value)
+ {
+ high = mid - 1;
+ }
+ else if (value > symtab[mid].sym_value)
+ {
+ low = mid + 1;
+ }
+ else /* if (value == symtab[mid].sym_value) */
+ {
+ return &symtab[mid];
+ }
+ }
+
+ /* low == high... One final check. We might not have actually tested
+ * the final symtab[] name.
+ *
+ * Example: Only the last pass through loop, suppose low = 1, high = 2,
+ * mid = 1, and symtab[high].sym_name == name. Then we would get here with
+ * low = 2, high = 2, but symtab[2].sym_name was never tested.
+ */
+
+ return value == symtab[low].sym_value ? &symtab[low] : NULL;
+}
+