aboutsummaryrefslogtreecommitdiff
path: root/nuttx/binfmt
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/binfmt')
-rw-r--r--nuttx/binfmt/Kconfig63
-rw-r--r--nuttx/binfmt/Makefile76
-rw-r--r--nuttx/binfmt/binfmt_dumpmodule.c17
-rw-r--r--nuttx/binfmt/binfmt_exec.c2
-rw-r--r--nuttx/binfmt/binfmt_execmodule.c103
-rw-r--r--nuttx/binfmt/binfmt_exepath.c286
-rw-r--r--nuttx/binfmt/binfmt_globals.c2
-rw-r--r--nuttx/binfmt/binfmt_internal.h2
-rw-r--r--nuttx/binfmt/binfmt_loadmodule.c127
-rw-r--r--nuttx/binfmt/binfmt_register.c2
-rw-r--r--nuttx/binfmt/binfmt_unloadmodule.c113
-rw-r--r--nuttx/binfmt/binfmt_unregister.c2
-rw-r--r--nuttx/binfmt/elf.c323
-rw-r--r--nuttx/binfmt/libelf/Make.defs58
-rw-r--r--nuttx/binfmt/libelf/libelf.h341
-rw-r--r--nuttx/binfmt/libelf/libelf_addrenv.c176
-rw-r--r--nuttx/binfmt/libelf/libelf_bind.c334
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c288
-rw-r--r--nuttx/binfmt/libelf/libelf_read.c165
-rw-r--r--nuttx/binfmt/libelf/libelf_unload.c114
-rw-r--r--nuttx/binfmt/libnxflat/Kconfig5
-rw-r--r--nuttx/binfmt/libnxflat/Make.defs25
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat.h136
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_addrenv.c235
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_bind.c185
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_init.c7
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c76
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_read.c14
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_uninit.c7
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_unload.c22
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_verify.c9
-rw-r--r--nuttx/binfmt/nxflat.c41
-rw-r--r--nuttx/binfmt/symtab_findbyname.c2
-rw-r--r--nuttx/binfmt/symtab_findbyvalue.c2
-rw-r--r--nuttx/binfmt/symtab_findorderedbyname.c2
-rw-r--r--nuttx/binfmt/symtab_findorderedbyvalue.c2
36 files changed, 3165 insertions, 199 deletions
diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig
index ae2bf3130..495bd050f 100644
--- a/nuttx/binfmt/Kconfig
+++ b/nuttx/binfmt/Kconfig
@@ -2,3 +2,66 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
+config BINFMT_DISABLE
+ bool "Disble BINFMT support"
+ default n
+ ---help---
+ By default, support for loadable binary formats is built. This logic
+ may be suppressed be defining this setting.
+
+if !BINFMT_DISABLE
+
+config BINFMT_EXEPATH
+ bool "Support PATH variable"
+ default n
+ depends on !DISABLE_ENVIRON
+ ---help---
+ Use the contents of the PATH environment variable to locate executable
+ files. Default: n
+
+config PATH_INITIAL
+ string "Initial PATH Value"
+ default ""
+ depends on BINFMT_EXEPATH
+ ---help---
+ The initial value of the PATH variable. This is the colon-separated
+ list of absolute paths. E.g., "/bin:/usr/bin:/sbin"
+
+config NXFLAT
+ bool "Enable the NXFLAT Binary Format"
+ default n
+ select PIC
+ ---help---
+ Enable support for the NXFLAT binary format. Default: n
+
+if NXFLAT
+source binfmt/libnxflat/Kconfig
+endif
+
+config ELF
+ bool "Enable the ELF Binary Format"
+ default n
+ ---help---
+ Enable support for the ELF binary format. Default: n
+
+if ELF
+source binfmt/libelf/Kconfig
+endif
+
+endif
+
+config PIC
+ bool
+ default n
+
+config BINFMT_CONSTRUCTORS
+ bool "C++ Static Constructor Support"
+ default n
+ depends on HAVE_CXX && ELF # FIX ME: Currently only supported for ELF
+ ---help---
+ Build in support for C++ constructors in loaded modules.
+
+config SYMTAB_ORDEREDBYNAME
+ bool "Symbol Tables Ordered by Name"
+ default n
diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
index b3a9269b3..8ec0d877c 100644
--- a/nuttx/binfmt/Makefile
+++ b/nuttx/binfmt/Makefile
@@ -1,7 +1,7 @@
############################################################################
# nxflat/Makefile
#
-# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -34,69 +34,69 @@
############################################################################
-include $(TOPDIR)/Make.defs
+DELIM ?= $(strip /)
ifeq ($(WINTOOL),y)
-INCDIROPT = -w
+INCDIROPT = -w
endif
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/sched}
+CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" "$(TOPDIR)$(DELIM)sched"}
-ifeq ($(CONFIG_NXFLAT),y)
-include libnxflat/Make.defs
-LIBNXFLAT_CSRCS += nxflat.c
+# Basic BINFMT source files
+
+BINFMT_ASRCS =
+BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c
+BINFMT_CSRCS += binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c
+BINFMT_CSRCS += binfmt_exec.c binfmt_dumpmodule.c
+
+ifeq ($(CONFIG_BINFMT_EXEPATH),y)
+BINFMT_CSRCS += binfmt_exepath.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
+# Symbol table source files
-SYMTAB_ASRCS =
-SYMTAB_CSRCS = symtab_findbyname.c symtab_findbyvalue.c \
- symtab_findorderedbyname.c symtab_findorderedbyvalue.c
+BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c
+BINFMT_CSRCS += symtab_findorderedbyname.c symtab_findorderedbyvalue.c
-SUBDIRS = libnxflat
+# Add configured binary modules
-ASRCS = $(BINFMT_ASRCS) $(SYMTAB_ASRCS) $(LIBNXFLAT_ASRCS)
-AOBJS = $(ASRCS:.S=$(OBJEXT))
+VPATH =
+SUBDIRS =
+DEPPATH = --dep-path .
-CSRCS = $(BINFMT_CSRCS) $(SYMTAB_CSRCS) $(LIBNXFLAT_CSRCS)
-COBJS = $(CSRCS:.c=$(OBJEXT))
+include libnxflat$(DELIM)Make.defs
+include libelf$(DELIM)Make.defs
-SRCS = $(ASRCS) $(CSRCS)
-OBJS = $(AOBJS) $(COBJS)
+BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT))
+BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT))
-BIN = libbinfmt$(LIBEXT)
+BINFMT_SRCS = $(BINFMT_ASRCS) $(BINFMT_CSRCS)
+BINFMT_OBJS = $(BINFMT_AOBJS) $(BINFMT_COBJS)
-VPATH = libnxflat
+BIN = libbinfmt$(LIBEXT)
-all: $(BIN)
+all: $(BIN)
-$(AOBJS): %$(OBJEXT): %.S
+$(BINFMT_AOBJS): %$(OBJEXT): %.S
$(call ASSEMBLE, $<, $@)
-$(COBJS): %$(OBJEXT): %.c
+$(BINFMT_COBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
-$(BIN): $(OBJS)
- @( for obj in $(OBJS) ; do \
- $(call ARCHIVE, $@, $${obj}); \
- done ; )
+$(BIN): $(BINFMT_OBJS)
+ $(call ARCHIVE, $@, $(BINFMT_OBJS))
-.depend: Makefile $(SRCS)
- @$(MKDEP) --dep-path . --dep-path libnxflat \
- $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
- @touch $@
+.depend: Makefile $(BINFMT_SRCS)
+ $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
+ $(Q) touch $@
depend: .depend
clean:
- @rm -f $(BIN) *~ .*.swp
+ $(call DELFILE, $(BIN))
$(call CLEAN)
- @( for dir in $(SUBDIRS); do \
- rm -f $${dir}/*~ $${dir}/.*.swp; \
- done ; )
distclean: clean
- @rm -f Make.dep .depend
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
-include Make.dep
diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c
index 32a3fef3e..d320bc830 100644
--- a/nuttx/binfmt/binfmt_dumpmodule.c
+++ b/nuttx/binfmt/binfmt_dumpmodule.c
@@ -1,7 +1,7 @@
/****************************************************************************
* binfmt/binfmt_dumpmodule.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,7 +43,7 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#include "binfmt_internal.h"
@@ -70,7 +70,7 @@
***********************************************************************/
/***********************************************************************
- * Name: load_module
+ * Name: dump_module
*
* Description:
* Load a module into memory and prep it for execution.
@@ -90,8 +90,15 @@ int dump_module(FAR const struct binary_s *bin)
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(" mapped: %p size=%d\n", bin->mapped, bin->mapsize);
+ bdbg(" alloc: %p %p %p\n", bin->alloc[0], bin->alloc[1], bin->alloc[2]);
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors);
+ bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors);
+#endif
+#ifdef CONFIG_ADDRENV
+ bdbg(" addrenv: %p\n", bin->addrenv);
+#endif
bdbg(" stacksize: %d\n", bin->stacksize);
}
return OK;
diff --git a/nuttx/binfmt/binfmt_exec.c b/nuttx/binfmt/binfmt_exec.c
index c070324c3..60e8d8efd 100644
--- a/nuttx/binfmt/binfmt_exec.c
+++ b/nuttx/binfmt/binfmt_exec.c
@@ -44,7 +44,7 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#include "binfmt_internal.h"
diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c
index 1b511b0cb..400451c40 100644
--- a/nuttx/binfmt/binfmt_execmodule.c
+++ b/nuttx/binfmt/binfmt_execmodule.c
@@ -47,7 +47,7 @@
#include <errno.h>
#include <nuttx/arch.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#include "os_internal.h"
#include "binfmt_internal.h"
@@ -71,6 +71,62 @@
****************************************************************************/
/****************************************************************************
+ * Name: exec_ctors
+ *
+ * Description:
+ * Execute C++ static constructors.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+static inline int exec_ctors(FAR const struct binary_s *binp)
+{
+ binfmt_ctor_t *ctor = binp->ctors;
+#ifdef CONFIG_ADDRENV
+ hw_addrenv_t oldenv;
+ int ret;
+#endif
+ int i;
+
+ /* Instantiate the address enviroment containing the constructors */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_select(binp->addrenv, &oldenv);
+ if (ret < 0)
+ {
+ bdbg("up_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ /* Execute each constructor */
+
+ for (i = 0; i < binp->nctors; i++)
+ {
+ bvdbg("Calling ctor %d at %p\n", i, (FAR void *)ctor);
+
+ (*ctor)();
+ ctor++;
+ }
+
+ /* Restore the address enviroment */
+
+#ifdef CONFIG_ADDRENV
+ return up_addrenv_restore(oldenv);
+#else
+ return OK;
+#endif
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -87,7 +143,7 @@
*
****************************************************************************/
-int exec_module(FAR const struct binary_s *bin, int priority)
+int exec_module(FAR const struct binary_s *binp, int priority)
{
FAR _TCB *tcb;
#ifndef CONFIG_CUSTOM_STACK
@@ -100,14 +156,14 @@ int exec_module(FAR const struct binary_s *bin, int priority)
/* Sanity checking */
#ifdef CONFIG_DEBUG
- if (!bin || !bin->ispace || !bin->entrypt || bin->stacksize <= 0)
+ if (!binp || !binp->entrypt || binp->stacksize <= 0)
{
err = EINVAL;
goto errout;
}
#endif
- bdbg("Executing %s\n", bin->filename);
+ bdbg("Executing %s\n", binp->filename);
/* Allocate a TCB for the new task. */
@@ -121,7 +177,7 @@ int exec_module(FAR const struct binary_s *bin, int priority)
/* Allocate the stack for the new task */
#ifndef CONFIG_CUSTOM_STACK
- stack = (FAR uint32_t*)malloc(bin->stacksize);
+ stack = (FAR uint32_t*)malloc(binp->stacksize);
if (!tcb)
{
err = ENOMEM;
@@ -130,11 +186,13 @@ int exec_module(FAR const struct binary_s *bin, int priority)
/* Initialize the task */
- ret = task_init(tcb, bin->filename, priority, stack, bin->stacksize, bin->entrypt, bin->argv);
+ ret = task_init(tcb, binp->filename, priority, stack,
+ binp->stacksize, binp->entrypt, binp->argv);
#else
/* Initialize the task */
- ret = task_init(tcb, bin->filename, priority, stack, bin->entrypt, bin->argv);
+ ret = task_init(tcb, binp->filename, priority, stack,
+ binp->entrypt, binp->argv);
#endif
if (ret < 0)
{
@@ -143,20 +201,46 @@ int exec_module(FAR const struct binary_s *bin, int priority)
goto errout_with_stack;
}
- /* Add the DSpace address as the PIC base address */
+ /* Add the D-Space address as the PIC base address. By convention, this
+ * must be the first allocated address space.
+ */
#ifdef CONFIG_PIC
- tcb->dspace = bin->dspace;
+ tcb->dspace = binp->alloc[0];
/* Re-initialize the task's initial state to account for the new PIC base */
up_initial_state(tcb);
#endif
+ /* Assign the address environment to the task */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_assign(binp->addrenv, tcb);
+ if (ret < 0)
+ {
+ err = -ret;
+ bdbg("up_addrenv_assign() failed: %d\n", ret);
+ goto errout_with_stack;
+ }
+#endif
+
/* Get the assigned pid before we start the task */
pid = tcb->pid;
+ /* Execute all of the C++ static constructors */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ ret = exec_ctors(binp);
+ if (ret < 0)
+ {
+ err = -ret;
+ bdbg("exec_ctors() failed: %d\n", ret);
+ goto errout_with_stack;
+ }
+#endif
+
/* Then activate the task at the provided priority */
ret = task_activate(tcb);
@@ -166,6 +250,7 @@ int exec_module(FAR const struct binary_s *bin, int priority)
bdbg("task_activate() failed: %d\n", err);
goto errout_with_stack;
}
+
return (int)pid;
errout_with_stack:
diff --git a/nuttx/binfmt/binfmt_exepath.c b/nuttx/binfmt/binfmt_exepath.c
new file mode 100644
index 000000000..4fd7ad918
--- /dev/null
+++ b/nuttx/binfmt/binfmt_exepath.c
@@ -0,0 +1,286 @@
+/****************************************************************************
+ * binfmt/binfmt_exepath.c
+ *
+ * Copyright (C) 2012 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/stat.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/binfmt/binfmt.h>
+
+#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct exepath_s
+{
+ FAR char *next; /* Pointer to the next (unterminated) value in the PATH variable */
+ char path[1];
+};
+#define SIZEOF_EXEPATH_S(n) (sizeof(struct exepath_s) + (n) - 1)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: exepath_init
+ *
+ * Description:
+ * Initialize for the traversal of each value in the PATH variable. The
+ * usage is sequence is as follows:
+ *
+ * 1) Call exepath_init() to initialize for the traversal. exepath_init()
+ * will return an opaque handle that can then be provided to
+ * exepath_next() and exepath_release().
+ * 2) Call exepath_next() repeatedly to examine every file that lies
+ * in the directories of the PATH variable
+ * 3) Call exepath_release() to free resources set aside by exepath_init().
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * On success, exepath_init() return a non-NULL, opaque handle that may
+ * subsequently be used in calls to exepath_next() and exepath_release().
+ * On error, a NULL handle value will be returned. The most likely cause
+ * of an error would be that the there is no value associated with the
+ * PATH variable.
+ *
+ ****************************************************************************/
+
+EXEPATH_HANDLE exepath_init(void)
+{
+ FAR struct exepath_s *exepath;
+ FAR char *path;
+
+ /* Get the value of the PATH variable */
+
+ path = getenv("PATH");
+ if (!path)
+ {
+ /* getenv() will return a NULL value if the PATH variable does not
+ * exist in the environment.
+ */
+
+ return (EXEPATH_HANDLE)NULL;
+ }
+
+ /* Allocate a container for the PATH variable contents */
+
+ exepath = (FAR struct exepath_s *)kmalloc(SIZEOF_EXEPATH_S(strlen(path) + 1));
+ if (!exepath)
+ {
+ /* Ooops.. we are out of memory */
+
+ return (EXEPATH_HANDLE)NULL;
+ }
+
+ /* Populate the container */
+
+ strcpy(exepath->path, path);
+ exepath->next = exepath->path;
+
+ /* And return the containing cast to an opaque handle */
+
+ return (EXEPATH_HANDLE)exepath;
+}
+
+ /****************************************************************************
+ * Name: exepath_next
+ *
+ * Description:
+ * Traverse all possible values in the PATH variable in attempt to find
+ * the full path to an executable file when only a relative path is
+ * provided.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by exepath_init
+ * relpath - The relative path to the file to be found.
+ *
+ * Returned Value:
+ * On success, a non-NULL pointer to a null-terminated string is provided.
+ * This is the full path to a file that exists in the file system. This
+ * function will verify that the file exists (but will not verify that it
+ * is marked executable).
+ *
+ * NOTE: The string pointer return in the success case points to allocated
+ * memory. This memory must be freed by the called by calling kfree().
+ *
+ * NULL is returned if no path is found to any file with the provided
+ * 'relpath' from any absolute path in the PATH variable. In this case,
+ * there is no point in calling exepath_next() further; exepath_release()
+ * must be called to release resources set aside by expath_init().
+ *
+ ****************************************************************************/
+
+FAR char *exepath_next(EXEPATH_HANDLE handle, FAR const char *relpath)
+{
+ FAR struct exepath_s *exepath = (FAR struct exepath_s *)handle;
+ struct stat buf;
+ FAR char *endptr;
+ FAR char *path;
+ FAR char *fullpath;
+ int pathlen;
+ int ret;
+
+ /* Verify that a value handle and relative path were provided */
+
+ DEBUGASSERT(exepath && relpath);
+ DEBUGASSERT(relpath[0] != '\0' && relpath[0] != '/');
+
+ /* Loop until (1) we find a file with this relative path from one of the
+ * absolute paths in the PATH variable, or (2) all of the absolute paths
+ * in the PATH variable have been considered.
+ */
+
+ for (;;)
+ {
+ /* Make sure that exepath->next points to the beginning of a string */
+
+ path = exepath->next;
+ if (*path == '\0')
+ {
+ /* If it points to a NULL it means that either (1) the PATH varialbe
+ * is empty, or (2) we have already examined all of the paths in the
+ * path variable.
+ */
+
+ return (FAR char *)NULL;
+ }
+
+ /* Okay... 'path' points to the beginning of the string. The string may
+ * be termined either with (1) ':' which separates the path from the
+ * next path in the list, or (2) NUL which marks the end of the list.
+ */
+
+ endptr = strchr(path, ':');
+ if (!endptr)
+ {
+ /* If strchr returns NUL it means that ':' does not appear in the
+ * string. Therefore, this must be the final path in the PATH
+ * variable content.
+ */
+
+ endptr = &path[strlen(path)];
+ exepath->next = endptr;
+ DEBUGASSERT(*endptr == '\0');
+ }
+ else
+ {
+ DEBUGASSERT(*endptr == ':');
+ exepath->next = endptr + 1;
+ *endptr = '\0';
+ }
+
+ pathlen = strlen(path) + strlen(relpath) + 2;
+ fullpath = (FAR char *)kmalloc(pathlen);
+ if (!fullpath)
+ {
+ /* Failed to allocate memory */
+
+ return (FAR char *)NULL;
+ }
+
+ /* Construct the full path */
+
+ sprintf(fullpath, "%s/%s", path, relpath);
+
+ /* Verify that a regular file exists at this path */
+
+ ret = stat(fullpath, &buf);;
+ if (ret == OK && S_ISREG(buf.st_mode))
+ {
+ return fullpath;
+ }
+
+ /* Failed to stat the file. Just free the allocated memory and
+ * continue to try the next path.
+ */
+
+ kfree(fullpath);
+ }
+
+ /* We will not get here */
+}
+
+/****************************************************************************
+ * Name: exepath_release
+ *
+ * Description:
+ * Release all resources set aside by exepath_init() when the handle value
+ * was created. The handle value is invalid on return from this function.
+ * Attempts to all exepath_next() or exepath_release() with such a 'stale'
+ * handle will result in undefined (i.e., not good) behavior.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by exepath_init
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void exepath_release(EXEPATH_HANDLE handle)
+{
+ kfree(handle);
+}
+
+#endif /* !CONFIG_BINFMT_DISABLE && CONFIG_BINFMT_EXEPATH */
+
diff --git a/nuttx/binfmt/binfmt_globals.c b/nuttx/binfmt/binfmt_globals.c
index 069d3a2aa..d3246bd50 100644
--- a/nuttx/binfmt/binfmt_globals.c
+++ b/nuttx/binfmt/binfmt_globals.c
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#ifndef CONFIG_BINFMT_DISABLE
diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h
index da67f5350..4fab9724d 100644
--- a/nuttx/binfmt/binfmt_internal.h
+++ b/nuttx/binfmt/binfmt_internal.h
@@ -42,7 +42,7 @@
#include <nuttx/config.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/binfmt/binfmt_loadmodule.c b/nuttx/binfmt/binfmt_loadmodule.c
index 01ab8cc88..112a6b35b 100644
--- a/nuttx/binfmt/binfmt_loadmodule.c
+++ b/nuttx/binfmt/binfmt_loadmodule.c
@@ -43,7 +43,8 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/binfmt/binfmt.h>
#include "binfmt_internal.h"
@@ -66,6 +67,57 @@
****************************************************************************/
/****************************************************************************
+ * Name: load_absmodule
+ *
+ * Description:
+ * Load a module into memory, bind it to an exported symbol take, and
+ * prep the module for execution. bin->filename is known to be an absolute
+ * path to the file to be loaded.
+ *
+ * Returned Value:
+ * Zero (OK) is returned on success; a negated errno value is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static int load_absmodule(FAR struct binary_s *bin)
+{
+ FAR struct binfmt_s *binfmt;
+ int ret = -ENOENT;
+
+ 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();
+ return ret;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -85,42 +137,72 @@
int load_module(FAR struct binary_s *bin)
{
- FAR struct binfmt_s *binfmt;
- int ret = -ENOENT;
+ int ret = -EINVAL;
+
+ /* Verify that we were provided something to work with */
#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.
+ /* Were we given a relative path? Or an absolute path to the file to
+ * be loaded? Absolute paths start with '/'.
*/
- sched_lock();
+#ifdef CONFIG_BINFMT_EXEPATH
+ if (bin->filename[0] != '/')
+ {
+ FAR const char *relpath;
+ FAR char *fullpath;
+ EXEPATH_HANDLE handle;
- /* 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.
- */
+ /* Set aside the relative path */
- for (binfmt = g_binfmts; binfmt; binfmt = binfmt->next)
- {
- /* Use this handler to try to load the format */
+ relpath = bin->filename;
+ ret = -ENOENT;
+
+ /* Initialize to traverse the PATH variable */
- ret = binfmt->load(bin);
- if (ret == OK)
+ handle = exepath_init();
+ if (handle)
{
- /* Successfully loaded -- break out with ret == 0 */
+ /* Get the next absolute file path */
- bvdbg("Successfully loaded module %s\n", bin->filename);
- dump_module(bin);
- break;
+ while ((fullpath = exepath_next(handle, relpath)) != NULL)
+ {
+ /* Try to load the file at this path */
+
+ bin->filename = fullpath;
+ ret = load_absmodule(bin);
+
+ /* Free the allocated fullpath */
+
+ kfree(fullpath);
+
+ /* Break out of the loop with ret == OK on success */
+
+ if (ret == OK)
+ {
+ break;
+ }
+ }
}
+
+ /* Restore the relative path. This is not needed for anything
+ * but debug output after the file has been loaded.
+ */
+
+ bin->filename = relpath;
}
+ else
+#endif
+ {
+ /* We already have the one and only absolute path to the file to
+ * be loaded.
+ */
- sched_unlock();
+ ret = load_absmodule(bin);
+ }
}
/* This is an end-user function. Return failures via errno */
@@ -131,6 +213,7 @@ int load_module(FAR struct binary_s *bin)
errno = -ret;
return ERROR;
}
+
return OK;
}
diff --git a/nuttx/binfmt/binfmt_register.c b/nuttx/binfmt/binfmt_register.c
index 7f6eef671..925f29353 100644
--- a/nuttx/binfmt/binfmt_register.c
+++ b/nuttx/binfmt/binfmt_register.c
@@ -44,7 +44,7 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#include "binfmt_internal.h"
diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c
index 04859a291..365f26a34 100644
--- a/nuttx/binfmt/binfmt_unloadmodule.c
+++ b/nuttx/binfmt/binfmt_unloadmodule.c
@@ -1,7 +1,7 @@
/****************************************************************************
* binfmt/binfmt_loadmodule.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -45,7 +45,7 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#include "binfmt_internal.h"
@@ -68,6 +68,62 @@
****************************************************************************/
/****************************************************************************
+ * Name: exec_dtors
+ *
+ * Description:
+ * Execute C++ static constructors.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+static inline int exec_dtors(FAR const struct binary_s *binp)
+{
+ binfmt_dtor_t *dtor = binp->dtors;
+#ifdef CONFIG_ADDRENV
+ hw_addrenv_t oldenv;
+ int ret;
+#endif
+ int i;
+
+ /* Instantiate the address enviroment containing the destructors */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_select(binp->addrenv, &oldenv);
+ if (ret < 0)
+ {
+ bdbg("up_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ /* Execute each destructor */
+
+ for (i = 0; i < binp->ndtors; i++)
+ {
+ bvdbg("Calling dtor %d at %p\n", i, (FAR void *)dtor);
+
+ (*dtor)();
+ dtor++;
+ }
+
+ /* Restore the address enviroment */
+
+#ifdef CONFIG_ADDRENV
+ return up_addrenv_restore(oldenv);
+#else
+ return OK;
+#endif
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -76,7 +132,12 @@
*
* Description:
* Unload a (non-executing) module from memory. If the module has
- * been started (via exec_module), calling this will be fatal.
+ * been started (via exec_module) and has not exited, calling this will
+ * be fatal.
+ *
+ * However, this function must be called after the module exist. How
+ * this is done is up to your logic. Perhaps you register it to be
+ * called by on_exit()?
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
@@ -85,22 +146,52 @@
*
****************************************************************************/
-int unload_module(FAR const struct binary_s *bin)
+int unload_module(FAR const struct binary_s *binp)
{
- if (bin)
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ int ret;
+#endif
+ int i;
+
+ if (binp)
{
- if (bin->ispace)
+ /* Execute C++ desctructors */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ ret = exec_dtors(binp);
+ if (ret < 0)
{
- bvdbg("Unmapping ISpace: %p\n", bin->ispace);
- munmap(bin->ispace, bin->isize);
+ bdbg("exec_ctors() failed: %d\n", ret);
+ set_errno(-ret);
+ return ERROR;
}
+#endif
- if (bin->dspace)
+ /* Unmap mapped address spaces */
+
+ if (binp->mapped)
+ {
+ bvdbg("Unmapping address space: %p\n", binp->mapped);
+
+ munmap(binp->mapped, binp->mapsize);
+ }
+
+ /* Free allocated address spaces */
+
+ for (i = 0; i < BINFMT_NALLOC; i++)
{
- bvdbg("Freeing DSpace: %p\n", bin->dspace);
- free(bin->dspace);
+ if (binp->alloc[i])
+ {
+ bvdbg("Freeing alloc[%d]: %p\n", i, binp->alloc[i]);
+ free((FAR void *)binp->alloc[i]);
+ }
}
+
+ /* Notice that the address environment is not destroyed. This should
+ * happen automatically when the task exits.
+ */
}
+
return OK;
}
diff --git a/nuttx/binfmt/binfmt_unregister.c b/nuttx/binfmt/binfmt_unregister.c
index b97b9b67d..f895e354d 100644
--- a/nuttx/binfmt/binfmt_unregister.c
+++ b/nuttx/binfmt/binfmt_unregister.c
@@ -44,7 +44,7 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/binfmt.h>
+#include <nuttx/binfmt/binfmt.h>
#include "binfmt_internal.h"
diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c
new file mode 100644
index 000000000..bcebf13ca
--- /dev/null
+++ b/nuttx/binfmt/elf.c
@@ -0,0 +1,323 @@
+/****************************************************************************
+ * binfmt/elf.c
+ *
+ * Copyright (C) 2012 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 <elf32.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/binfmt/binfmt.h>
+#include <nuttx/binfmt/elf.h>
+
+#ifdef CONFIG_ELF
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
+ * defined or CONFIG_ELF_DUMPBUFFER does nothing.
+ */
+
+#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
+# undef CONFIG_ELF_DUMPBUFFER
+#endif
+
+#ifndef CONFIG_ELF_STACKSIZE
+# define CONFIG_ELF_STACKSIZE 2048
+#endif
+
+#ifdef CONFIG_ELF_DUMPBUFFER
+# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
+#else
+# define elf_dumpbuffer(m,b,n)
+#endif
+
+#ifndef MIN
+# define MIN(a,b) (a < b ? a : b)
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int elf_loadbinary(FAR struct binary_s *binp);
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo);
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct binfmt_s g_elfbinfmt =
+{
+ NULL, /* next */
+ elf_loadbinary, /* load */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_dumploadinfo
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo)
+{
+ int i;
+
+ bdbg("LOAD_INFO:\n");
+ bdbg(" elfalloc: %08lx\n", (long)loadinfo->elfalloc);
+ bdbg(" elfsize: %ld\n", (long)loadinfo->elfsize);
+ bdbg(" filelen: %ld\n", (long)loadinfo->filelen);
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ bdbg(" ctoralloc: %08lx\n", (long)loadinfo->ctoralloc);
+ bdbg(" ctors: %08lx\n", (long)loadinfo->ctors);
+ bdbg(" nctors: %d\n", loadinfo->nctors);
+ bdbg(" dtoralloc: %08lx\n", (long)loadinfo->dtoralloc);
+ bdbg(" dtors: %08lx\n", (long)loadinfo->dtors);
+ bdbg(" ndtors: %d\n", loadinfo->ndtors);
+#endif
+ bdbg(" filfd: %d\n", loadinfo->filfd);
+ bdbg(" symtabidx: %d\n", loadinfo->symtabidx);
+ bdbg(" strtabidx: %d\n", loadinfo->strtabidx);
+
+ bdbg("ELF Header:\n");
+ bdbg(" e_ident: %02x %02x %02x %02x\n",
+ loadinfo->ehdr.e_ident[0], loadinfo->ehdr.e_ident[1],
+ loadinfo->ehdr.e_ident[2], loadinfo->ehdr.e_ident[3]);
+ bdbg(" e_type: %04x\n", loadinfo->ehdr.e_type);
+ bdbg(" e_machine: %04x\n", loadinfo->ehdr.e_machine);
+ bdbg(" e_version: %08x\n", loadinfo->ehdr.e_version);
+ bdbg(" e_entry: %08lx\n", (long)loadinfo->ehdr.e_entry);
+ bdbg(" e_phoff: %d\n", loadinfo->ehdr.e_phoff);
+ bdbg(" e_shoff: %d\n", loadinfo->ehdr.e_shoff);
+ bdbg(" e_flags: %08x\n" , loadinfo->ehdr.e_flags);
+ bdbg(" e_ehsize: %d\n", loadinfo->ehdr.e_ehsize);
+ bdbg(" e_phentsize: %d\n", loadinfo->ehdr.e_phentsize);
+ bdbg(" e_phnum: %d\n", loadinfo->ehdr.e_phnum);
+ bdbg(" e_shentsize: %d\n", loadinfo->ehdr.e_shentsize);
+ bdbg(" e_shnum: %d\n", loadinfo->ehdr.e_shnum);
+ bdbg(" e_shstrndx: %d\n", loadinfo->ehdr.e_shstrndx);
+
+ if (loadinfo->shdr && loadinfo->ehdr.e_shnum > 0)
+ {
+ for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
+ {
+ FAR Elf32_Shdr *shdr = &loadinfo->shdr[i];
+ bdbg("Sections %d:\n", i);
+ bdbg(" sh_name: %08x\n", shdr->sh_name);
+ bdbg(" sh_type: %08x\n", shdr->sh_type);
+ bdbg(" sh_flags: %08x\n", shdr->sh_flags);
+ bdbg(" sh_addr: %08x\n", shdr->sh_addr);
+ bdbg(" sh_offset: %d\n", shdr->sh_offset);
+ bdbg(" sh_size: %d\n", shdr->sh_size);
+ bdbg(" sh_link: %d\n", shdr->sh_link);
+ bdbg(" sh_info: %d\n", shdr->sh_info);
+ bdbg(" sh_addralign: %d\n", shdr->sh_addralign);
+ bdbg(" sh_entsize: %d\n", shdr->sh_entsize);
+ }
+ }
+}
+#else
+# define elf_dumploadinfo(i)
+#endif
+
+/****************************************************************************
+ * Name: elf_loadbinary
+ *
+ * Description:
+ * Verify that the file is an ELF binary and, if so, load the ELF
+ * binary into memory
+ *
+ ****************************************************************************/
+
+static int elf_loadbinary(struct binary_s *binp)
+{
+ struct elf_loadinfo_s loadinfo; /* Contains globals for libelf */
+ int ret;
+
+ bvdbg("Loading file: %s\n", binp->filename);
+
+ /* Initialize the xflat library to load the program binary. */
+
+ ret = elf_init(binp->filename, &loadinfo);
+ elf_dumploadinfo(&loadinfo);
+ if (ret != 0)
+ {
+ bdbg("Failed to initialize for load of ELF program: %d\n", ret);
+ goto errout;
+ }
+
+ /* Load the program binary */
+
+ ret = elf_load(&loadinfo);
+ elf_dumploadinfo(&loadinfo);
+ if (ret != 0)
+ {
+ bdbg("Failed to load ELF program binary: %d\n", ret);
+ goto errout_with_init;
+ }
+
+ /* Bind the program to the exported symbol table */
+
+ ret = elf_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.elfalloc + loadinfo.ehdr.e_entry);
+ binp->stacksize = CONFIG_ELF_STACKSIZE;
+
+ /* Add the ELF allocation to the alloc[] only if there is no address
+ * enironment. If there is an address environment, it will automatically
+ * be freed when the function exits
+ *
+ * REVISIT: If the module is loaded then unloaded, wouldn't this cause
+ * a memory leak?
+ */
+
+#ifdef CONFIG_ADDRENV
+# warning "REVISIT"
+#else
+ binp->alloc[0] = (FAR void *)loadinfo.elfalloc;
+#endif
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ /* Save information about constructors. NOTE: desctructors are not
+ * yet supported.
+ */
+
+ binp->alloc[1] = loadinfo.ctoralloc;
+ binp->ctors = loadinfo.ctors;
+ binp->nctors = loadinfo.nctors;
+
+ binp->alloc[2] = loadinfo.dtoralloc;
+ binp->dtors = loadinfo.dtors;
+ binp->ndtors = loadinfo.ndtors;
+#endif
+
+#ifdef CONFIG_ADDRENV
+ /* Save the address environment. This will be needed when the module is
+ * executed for the up_addrenv_assign() call.
+ */
+
+ binp->addrenv = loadinfo.addrenv;
+#endif
+
+ elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,
+ MIN(loadinfo.allocsize - loadinfo.ehdr.e_entry, 512));
+
+ elf_uninit(&loadinfo);
+ return OK;
+
+errout_with_load:
+ elf_unload(&loadinfo);
+errout_with_init:
+ elf_uninit(&loadinfo);
+errout:
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_initialize
+ *
+ * Description:
+ * ELF 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 ELF 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 elf_initialize(void)
+{
+ int ret;
+
+ /* Register ourselves as a binfmt loader */
+
+ bvdbg("Registering ELF\n");
+
+ ret = register_binfmt(&g_elfbinfmt);
+ if (ret != 0)
+ {
+ bdbg("Failed to register binfmt: %d\n", ret);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: elf_uninitialize
+ *
+ * Description:
+ * Unregister the ELF binary loader
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void elf_uninitialize(void)
+{
+ unregister_binfmt(&g_elfbinfmt);
+}
+
+#endif /* CONFIG_ELF */
+
diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs
new file mode 100644
index 000000000..93d95a23c
--- /dev/null
+++ b/nuttx/binfmt/libelf/Make.defs
@@ -0,0 +1,58 @@
+############################################################################
+# binfmt/libelf/Make.defs
+#
+# Copyright (C) 2012 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.
+#
+############################################################################
+
+ifeq ($(CONFIG_ELF),y)
+
+# ELF application interfaces
+
+BINFMT_CSRCS += elf.c
+
+# ELF library
+
+BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_addrenv.c libelf_iobuffer.c
+BINFMT_CSRCS += libelf_load.c libelf_read.c libelf_sections.c libelf_symbols.c
+BINFMT_CSRCS += libelf_uninit.c libelf_unload.c libelf_verify.c
+
+ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y)
+BINFMT_CSRCS += libelf_ctors.c libelf_dtors.c
+endif
+
+# Hook the libelf subdirectory into the build
+
+VPATH += libelf
+SUBDIRS += libelf
+DEPPATH += --dep-path libelf
+
+endif
diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h
new file mode 100644
index 000000000..04c9144f6
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf.h
@@ -0,0 +1,341 @@
+/****************************************************************************
+ * binfmt/libelf/libelf.h
+ *
+ * Copyright (C) 2012 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_LIBELF_LIBELF_H
+#define __BINFMT_LIBELF_LIBELF_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <elf32.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/binfmt/elf.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_verifyheader
+ *
+ * Description:
+ * Given the header from a possible ELF executable, verify that it is
+ * an ELF executable.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_verifyheader(FAR const Elf32_Ehdr *header);
+
+/****************************************************************************
+ * Name: elf_read
+ *
+ * Description:
+ * Read 'readsize' bytes from the object file at 'offset'. The data is
+ * read into 'buffer.' If 'buffer' is part of the ELF address environment,
+ * then the caller is responsibile for assuring that that address
+ * environment is in place before calling this function (i.e., that
+ * elf_addrenv_select() has been called if CONFIG_ADDRENV=y).
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer,
+ size_t readsize, off_t offset);
+
+/****************************************************************************
+ * Name: elf_loadshdrs
+ *
+ * Description:
+ * Loads section headers into memory.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_findsection
+ *
+ * Description:
+ * A section by its name.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * sectname - Name of the section to find
+ *
+ * Returned Value:
+ * On success, the index to the section is returned; A negated errno value
+ * is returned on failure.
+ *
+ ****************************************************************************/
+
+int elf_findsection(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const char *sectname);
+
+/****************************************************************************
+ * Name: elf_findsymtab
+ *
+ * Description:
+ * Find the symbol table section.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_readsym
+ *
+ * Description:
+ * Read the ELFT symbol structure at the specfied index into memory.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * index - Symbol table index
+ * sym - Location to return the table entry
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
+ FAR Elf32_Sym *sym);
+
+/****************************************************************************
+ * Name: elf_symvalue
+ *
+ * Description:
+ * Get the value of a symbol. The updated value of the symbol is returned
+ * in the st_value field of the symbol table entry.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * sym - Symbol table entry (value might be undefined)
+ * exports - The symbol table to use for resolving undefined symbols.
+ * nexports - Number of symbols in the symbol table.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym,
+ FAR const struct symtab_s *exports, int nexports);
+
+/****************************************************************************
+ * Name: elf_freebuffers
+ *
+ * Description:
+ * Release all working buffers.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_freebuffers(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_allocbuffer
+ *
+ * Description:
+ * Perform the initial allocation of the I/O buffer, if it has not already
+ * been allocated.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_allocbuffer(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_reallocbuffer
+ *
+ * Description:
+ * Increase the size of I/O buffer by the specified buffer increment.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment);
+
+/****************************************************************************
+ * Name: elf_findctors
+ *
+ * Description:
+ * Find C++ static constructors.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo);
+#endif
+
+/****************************************************************************
+ * Name: elf_loaddtors
+ *
+ * Description:
+ * Load pointers to static destructors into an in-memory array.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo);
+#endif
+
+/****************************************************************************
+ * Name: elf_addrenv_alloc
+ *
+ * Description:
+ * Allocate memory for the ELF image (elfalloc). If CONFIG_ADDRENV=n,
+ * elfalloc will be allocated using kzalloc(). If CONFIG_ADDRENV-y, then
+ * elfalloc will be allocated using up_addrenv_create(). In either case,
+ * there will be a unique instance of elfalloc (and stack) for each
+ * instance of a process.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * envsize - The size (in bytes) of the address environment needed for the
+ * ELF image.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int elf_addrenv_alloc(FAR struct elf_loadinfo_s *loadinfo, size_t envsize);
+
+/****************************************************************************
+ * Name: elf_addrenv_select
+ *
+ * Description:
+ * Temporarity select the task's address environemnt.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+# define elf_addrenv_select(l) up_addrenv_select((l)->addrenv, &(l)->oldenv)
+#endif
+
+/****************************************************************************
+ * Name: elf_addrenv_restore
+ *
+ * Description:
+ * Restore the address environment before elf_addrenv_select() was called..
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+# define elf_addrenv_restore(l) up_addrenv_restore((l)->oldenv)
+#endif
+
+/****************************************************************************
+ * Name: elf_addrenv_free
+ *
+ * Description:
+ * Release the address environment previously created by
+ * elf_addrenv_alloc(). This function is called only under certain error
+ * conditions after the the module has been loaded but not yet started.
+ * After the module has been started, the address environment will
+ * automatically be freed when the module exits.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void elf_addrenv_free(FAR struct elf_loadinfo_s *loadinfo);
+
+#endif /* __BINFMT_LIBELF_LIBELF_H */
diff --git a/nuttx/binfmt/libelf/libelf_addrenv.c b/nuttx/binfmt/libelf/libelf_addrenv.c
new file mode 100644
index 000000000..193062a54
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_addrenv.c
@@ -0,0 +1,176 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_addrenv.c
+ *
+ * Copyright (C) 2012 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 <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
+
+#include "libelf.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_addrenv_alloc
+ *
+ * Description:
+ * Allocate memory for the ELF image (elfalloc). If CONFIG_ADDRENV=n,
+ * elfalloc will be allocated using kzalloc(). If CONFIG_ADDRENV-y, then
+ * elfalloc will be allocated using up_addrenv_create(). In either case,
+ * there will be a unique instance of elfalloc (and stack) for each
+ * instance of a process.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * envsize - The size (in bytes) of the address environment needed for the
+ * ELF image.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int elf_addrenv_alloc(FAR struct elf_loadinfo_s *loadinfo, size_t envsize)
+{
+#ifdef CONFIG_ADDRENV
+ FAR void *vaddr;
+ int ret;
+
+ /* Create an address environment for the new ELF task */
+
+ ret = up_addrenv_create(envsize, &loadinfo->addrenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_create failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Get the virtual address associated with the start of the address
+ * environment. This is the base address that we will need to use to
+ * access the ELF image (but only if the address environment has been
+ * selected.
+ */
+
+ ret = up_addrenv_vaddr(loadinfo->addrenv, &vaddr);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_vaddr failed: %d\n", ret);
+ return ret;
+ }
+
+ loadinfo->elfalloc = (uintptr_t)vaddr;
+ return OK;
+#else
+ /* Allocate memory to hold the ELF image */
+
+ loadinfo->elfalloc = (uintptr_t)kzalloc(envsize);
+ if (!loadinfo->elfalloc)
+ {
+ return -ENOMEM;
+ }
+
+ return OK;
+#endif
+}
+
+/****************************************************************************
+ * Name: elf_addrenv_free
+ *
+ * Description:
+ * Release the address environment previously created by
+ * elf_addrenv_create(). This function is called only under certain error
+ * conditions after the the module has been loaded but not yet started.
+ * After the module has been started, the address environment will
+ * automatically be freed when the module exits.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void elf_addrenv_free(FAR struct elf_loadinfo_s *loadinfo)
+{
+#ifdef CONFIG_ADDRENV
+ int ret;
+
+ /* Free the address environemnt */
+
+ ret = up_addrenv_destroy(loadinfo->addrenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_destroy failed: %d\n", ret);
+ }
+
+ /* Clear out all indications of the allocated address environment */
+
+ loadinfo->elfalloc = 0;
+ loadinfo->elfsize = 0;
+ loadinfo->addrenv = 0;
+#else
+ /* If there is an allocation for the ELF image, free it */
+
+ if (loadinfo->elfalloc != 0)
+ {
+ kfree((FAR void *)loadinfo->elfalloc);
+ loadinfo->elfalloc = 0;
+ }
+
+ loadinfo->elfsize = 0;
+#endif
+}
diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c
new file mode 100644
index 000000000..ccdb5108e
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_bind.c
@@ -0,0 +1,334 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_bind.c
+ *
+ * Copyright (C) 2012 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 <elf32.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/binfmt/elf.h>
+#include <nuttx/binfmt/symtab.h>
+
+#include "libelf.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
+ * defined or CONFIG_ELF_DUMPBUFFER does nothing.
+ */
+
+#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
+# undef CONFIG_ELF_DUMPBUFFER
+#endif
+
+#ifndef CONFIG_ELF_BUFFERSIZE
+# define CONFIG_ELF_BUFFERSIZE 128
+#endif
+
+#ifdef CONFIG_ELF_DUMPBUFFER
+# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
+#else
+# define elf_dumpbuffer(m,b,n)
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_readrel
+ *
+ * Description:
+ * Read the ELF32_Rel structure into memory.
+ *
+ ****************************************************************************/
+
+static inline int elf_readrel(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const Elf32_Shdr *relsec,
+ int index, FAR Elf32_Rel *rel)
+{
+ off_t offset;
+
+ /* Verify that the symbol table index lies within symbol table */
+
+ if (index < 0 || index > (relsec->sh_size / sizeof(Elf32_Rel)))
+ {
+ bdbg("Bad relocation symbol index: %d\n", index);
+ return -EINVAL;
+ }
+
+ /* Get the file offset to the symbol table entry */
+
+ offset = relsec->sh_offset + sizeof(Elf32_Rel) * index;
+
+ /* And, finally, read the symbol table entry into memory */
+
+ return elf_read(loadinfo, (FAR uint8_t*)rel, sizeof(Elf32_Rel), offset);
+}
+
+/****************************************************************************
+ * Name: elf_relocate and elf_relocateadd
+ *
+ * Description:
+ * Perform all relocations associated with a section.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx,
+ FAR const struct symtab_s *exports, int nexports)
+
+{
+ FAR Elf32_Shdr *relsec = &loadinfo->shdr[relidx];
+ FAR Elf32_Shdr *dstsec = &loadinfo->shdr[relsec->sh_info];
+ Elf32_Rel rel;
+ Elf32_Sym sym;
+ uintptr_t addr;
+ int symidx;
+ int ret;
+ int i;
+
+ /* Examine each relocation in the section. 'relsec' is the section
+ * containing the relations. 'dstsec' is the section containing the data
+ * to be relocated.
+ */
+
+ for (i = 0; i < relsec->sh_size / sizeof(Elf32_Rel); i++)
+ {
+ /* Read the relocation entry into memory */
+
+ ret = elf_readrel(loadinfo, relsec, i, &rel);
+ if (ret < 0)
+ {
+ bdbg("Section %d reloc %d: Failed to read relocation entry: %d\n",
+ relidx, i, ret);
+ return ret;
+ }
+
+ /* Get the symbol table index for the relocation. This is contained
+ * in a bit-field within the r_info element.
+ */
+
+ symidx = ELF32_R_SYM(rel.r_info);
+
+ /* Read the symbol table entry into memory */
+
+ ret = elf_readsym(loadinfo, symidx, &sym);
+ if (ret < 0)
+ {
+ bdbg("Section %d reloc %d: Failed to read symbol[%d]: %d\n",
+ relidx, i, symidx, ret);
+ return ret;
+ }
+
+ /* Get the value of the symbol (in sym.st_value) */
+
+ ret = elf_symvalue(loadinfo, &sym, exports, nexports);
+ if (ret < 0)
+ {
+ bdbg("Section %d reloc %d: Failed to get value of symbol[%d]: %d\n",
+ relidx, i, symidx, ret);
+ return ret;
+ }
+
+ /* Calculate the relocation address. */
+
+ if (rel.r_offset < 0 || rel.r_offset > dstsec->sh_size - sizeof(uint32_t))
+ {
+ bdbg("Section %d reloc %d: Relocation address out of range, offset %d size %d\n",
+ relidx, i, rel.r_offset, dstsec->sh_size);
+ return -EINVAL;
+ }
+
+ addr = dstsec->sh_addr + rel.r_offset;
+
+ /* If CONFIG_ADDRENV=y, then 'addr' lies in a virtual address space that
+ * may not be in place now. elf_addrenv_select() will temporarily
+ * instantiate that address space.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ /* Now perform the architecture-specific relocation */
+
+ ret = arch_relocate(&rel, &sym, addr);
+ if (ret < 0)
+ {
+#ifdef CONFIG_ADDRENV
+ (void)elf_addrenv_restore(loadinfo);
+#endif
+ bdbg("ERROR: Section %d reloc %d: Relocation failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_restore() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+ }
+
+ return OK;
+}
+
+static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx,
+ FAR const struct symtab_s *exports, int nexports)
+{
+ bdbg("Not implemented\n");
+ return -ENOSYS;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_bind
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports, int nexports)
+{
+ int ret;
+ int i;
+
+ /* Find the symbol and string tables */
+
+ ret = elf_findsymtab(loadinfo);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* Allocate an I/O buffer. This buffer is used by elf_symname() to
+ * accumulate the variable length symbol name.
+ */
+
+ ret = elf_allocbuffer(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("elf_allocbuffer failed: %d\n", ret);
+ return -ENOMEM;
+ }
+
+ /* Process relocations in every allocated section */
+
+ for (i = 1; i < loadinfo->ehdr.e_shnum; i++)
+ {
+ /* Get the index to the relocation section */
+
+ int infosec = loadinfo->shdr[i].sh_info;
+ if (infosec >= loadinfo->ehdr.e_shnum)
+ {
+ continue;
+ }
+
+ /* Make sure that the section is allocated. We can't relocated
+ * sections that were not loaded into memory.
+ */
+
+ if ((loadinfo->shdr[infosec].sh_flags & SHF_ALLOC) == 0)
+ {
+ continue;
+ }
+
+ /* Process the relocations by type */
+
+ if (loadinfo->shdr[i].sh_type == SHT_REL)
+ {
+ ret = elf_relocate(loadinfo, i, exports, nexports);
+ }
+ else if (loadinfo->shdr[i].sh_type == SHT_RELA)
+ {
+ ret = elf_relocateadd(loadinfo, i, exports, nexports);
+ }
+
+ if (ret < 0)
+ {
+ break;
+ }
+ }
+
+ /* Flush the instruction cache before starting the newly loaded module */
+
+#ifdef CONFIG_ELF_ICACHE
+ arch_flushicache((FAR void*)loadinfo->elfalloc, loadinfo->elfsize);
+#endif
+
+ return ret;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
new file mode 100644
index 000000000..0e4ad9798
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -0,0 +1,288 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_load.c
+ *
+ * Copyright (C) 2012 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 <unistd.h>
+#include <elf32.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/binfmt/elf.h>
+
+#include "libelf.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#define ELF_ALIGN_MASK ((1 << CONFIG_ELF_ALIGN_LOG2) - 1)
+#define ELF_ALIGNUP(a) (((unsigned long)(a) + ELF_ALIGN_MASK) & ~ELF_ALIGN_MASK)
+#define ELF_ALIGNDOWN(a) ((unsigned long)(a) & ~ELF_ALIGN_MASK)
+
+
+#ifndef MAX
+#define MAX(x,y) ((x) > (y) ? (x) : (y))
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_elfsize
+ *
+ * Description:
+ * Calculate total memory allocation for the ELF file.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static void elf_elfsize(struct elf_loadinfo_s *loadinfo)
+{
+ size_t elfsize;
+ int i;
+
+ /* Accumulate the size each section into memory that is marked SHF_ALLOC */
+
+ elfsize = 0;
+ for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
+ {
+ FAR Elf32_Shdr *shdr = &loadinfo->shdr[i];
+
+ /* SHF_ALLOC indicates that the section requires memory during
+ * execution.
+ */
+
+ if ((shdr->sh_flags & SHF_ALLOC) != 0)
+ {
+ elfsize += ELF_ALIGNUP(shdr->sh_size);
+ }
+ }
+
+ /* Save the allocation size */
+
+ loadinfo->elfsize = elfsize;
+}
+
+/****************************************************************************
+ * Name: elf_loadfile
+ *
+ * Description:
+ * Allocate memory for the file and read the section data into the
+ * allocated memory. Section addresses in the shdr[] are updated to point
+ * to the corresponding position in the allocated memory.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
+{
+ FAR uint8_t *dest;
+ int ret;
+ int i;
+
+ /* Allocate (and zero) memory for the ELF file. */
+
+ ret = elf_addrenv_alloc(loadinfo, loadinfo->elfsize);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_alloc() failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */
+
+ bvdbg("Loaded sections:\n");
+ dest = (FAR uint8_t*)loadinfo->elfalloc;
+
+ for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
+ {
+ FAR Elf32_Shdr *shdr = &loadinfo->shdr[i];
+
+ /* SHF_ALLOC indicates that the section requires memory during
+ * execution */
+
+ if ((shdr->sh_flags & SHF_ALLOC) == 0)
+ {
+ continue;
+ }
+
+ /* SHT_NOBITS indicates that there is no data in the file for the
+ * section.
+ */
+
+ if (shdr->sh_type != SHT_NOBITS)
+ {
+ /* If CONFIG_ADDRENV=y, then 'dest' lies in a virtual address space
+ * that may not be in place now. elf_addrenv_select() will
+ * temporarily instantiate that address space.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ /* Read the section data from sh_offset to dest */
+
+ ret = elf_read(loadinfo, dest, shdr->sh_size, shdr->sh_offset);
+ if (ret < 0)
+ {
+ bdbg("Failed to read section %d: %d\n", i, ret);
+ return ret;
+ }
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_restore() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+ }
+
+ /* Update sh_addr to point to copy in memory */
+
+ bvdbg("%d. %08x->%08x\n", i, (long)shdr->sh_addr, (long)dest);
+ shdr->sh_addr = (uintptr_t)dest;
+
+ /* Setup the memory pointer for the next time through the loop */
+
+ dest += ELF_ALIGNUP(shdr->sh_size);
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_load
+ *
+ * Description:
+ * Loads the binary into memory, allocating memory, performing relocations
+ * and inializing the data and bss segments.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_load(FAR struct elf_loadinfo_s *loadinfo)
+{
+ int ret;
+
+ bvdbg("loadinfo: %p\n", loadinfo);
+ DEBUGASSERT(loadinfo && loadinfo->filfd >= 0);
+
+ /* Load section headers into memory */
+
+ ret = elf_loadshdrs(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("elf_loadshdrs failed: %d\n", ret);
+ goto errout_with_buffers;
+ }
+
+ /* Determine total size to allocate */
+
+ elf_elfsize(loadinfo);
+
+ /* Allocate memory and load sections into memory */
+
+ ret = elf_loadfile(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("elf_loadfile failed: %d\n", ret);
+ goto errout_with_buffers;
+ }
+
+ /* Load static constructors and destructors. */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ ret = elf_loadctors(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("elf_loadctors failed: %d\n", ret);
+ goto errout_with_buffers;
+ }
+
+ ret = elf_loaddtors(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("elf_loaddtors failed: %d\n", ret);
+ goto errout_with_buffers;
+ }
+#endif
+
+ return OK;
+
+ /* Error exits */
+
+errout_with_buffers:
+ elf_unload(loadinfo);
+ return ret;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c
new file mode 100644
index 000000000..f4b725183
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_read.c
@@ -0,0 +1,165 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_read.c
+ *
+ * Copyright (C) 2012 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 <elf32.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt/elf.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#undef ELF_DUMP_READDATA /* Define to dump all file data read */
+#define DUMPER lib_rawprintf /* If ELF_DUMP_READDATA is defined, this
+ * is the API used to dump data */
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_dumpreaddata
+ ****************************************************************************/
+
+#if defined(ELF_DUMP_READDATA)
+static inline void elf_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 elf_dumpreaddata(b,n)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_read
+ *
+ * Description:
+ * Read 'readsize' bytes from the object file at 'offset'. The data is
+ * read into 'buffer.' If 'buffer' is part of the ELF address environment,
+ * then the caller is responsibile for assuring that that address
+ * environment is in place before calling this function (i.e., that
+ * elf_addrenv_select() has been called if CONFIG_ADDRENV=y).
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer,
+ size_t readsize, off_t offset)
+{
+ ssize_t nbytes; /* Number of bytes read */
+ off_t rpos; /* Position returned by lseek */
+
+ bvdbg("Read %ld bytes from offset %ld\n", (long)readsize, (long)offset);
+
+ /* Loop until all of the requested data has been read. */
+
+ while (readsize > 0)
+ {
+ /* Seek to the next read position */
+
+ rpos = lseek(loadinfo->filfd, offset, SEEK_SET);
+ if (rpos != offset)
+ {
+ int errval = errno;
+ bdbg("Failed to seek to position %ld: %d\n", (long)offset, errval);
+ return -errval;
+ }
+
+ /* Read the file data at offset into the user buffer */
+
+ nbytes = read(loadinfo->filfd, buffer, readsize);
+ if (nbytes < 0)
+ {
+ int errval = errno;
+
+ /* EINTR just means that we received a signal */
+
+ if (errval != EINTR)
+ {
+ bdbg("Read of .data failed: %d\n", errval);
+ return -errval;
+ }
+ }
+ else if (nbytes == 0)
+ {
+ bdbg("Unexpected end of file\n");
+ return -ENODATA;
+ }
+ else
+ {
+ readsize -= nbytes;
+ buffer += nbytes;
+ offset += nbytes;
+ }
+ }
+
+ elf_dumpreaddata(buffer, readsize);
+ return OK;
+}
diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c
new file mode 100644
index 000000000..539e5faf7
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_unload.c
@@ -0,0 +1,114 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_unload.c
+ *
+ * Copyright (C) 2012 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 <stdlib.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/binfmt/elf.h>
+
+#include "libelf.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_unload
+ *
+ * Description:
+ * This function unloads the object from memory. This essentially undoes
+ * the actions of elf_load. It is called only under certain error
+ * conditions after the the module has been loaded but not yet started.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_unload(struct elf_loadinfo_s *loadinfo)
+{
+ /* Free all working buffers */
+
+ elf_freebuffers(loadinfo);
+
+ /* Release memory holding the relocated ELF image */
+
+ elf_addrenv_free(loadinfo);
+
+ /* Release memory used to hold static constructors and destructors */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ if (loadinfo->ctoralloc != 0)
+ {
+ kfree(loadinfo->ctoralloc);
+ loadinfo->ctoralloc = NULL;
+ }
+
+ loadinfo->ctors = NULL;
+ loadinfo->nctors = 0;
+
+ if (loadinfo->dtoralloc != 0)
+ {
+ kfree(loadinfo->dtoralloc);
+ loadinfo->dtoralloc = NULL;
+ }
+
+ loadinfo->dtors = NULL;
+ loadinfo->ndtors = 0;
+#endif
+
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libnxflat/Kconfig b/nuttx/binfmt/libnxflat/Kconfig
index ae2bf3130..fdb270cfb 100644
--- a/nuttx/binfmt/libnxflat/Kconfig
+++ b/nuttx/binfmt/libnxflat/Kconfig
@@ -2,3 +2,8 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
+config NXFLAT_DUMPBUFFER
+ bool "Dump NXFLAT buffers"
+ default n
+ depends on DEBUG && DEBUG_VERBOSE
diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs
index f979741e5..6a0bf1873 100644
--- a/nuttx/binfmt/libnxflat/Make.defs
+++ b/nuttx/binfmt/libnxflat/Make.defs
@@ -1,5 +1,5 @@
############################################################################
-# nxflat/lib/Make.defs
+# binfmt/libnxflat/Make.defs
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,7 +33,22 @@
#
############################################################################
-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
+ifeq ($(CONFIG_NXFLAT),y)
+
+# NXFLAT application interfaces
+
+BINFMT_CSRCS += nxflat.c
+
+# NXFLAT library
+
+BINFMT_CSRCS += libnxflat_init.c libnxflat_uninit.c libnxflat_addrenv.c
+BINFMT_CSRCS += libnxflat_load.c libnxflat_unload.c libnxflat_verify.c
+BINFMT_CSRCS += libnxflat_read.c libnxflat_bind.c
+
+# Hook the libnxflat subdirectory into the build
+
+VPATH += libnxflat
+SUBDIRS += libnxflat
+DEPPATH += --dep-path libnxflat
+
+endif
diff --git a/nuttx/binfmt/libnxflat/libnxflat.h b/nuttx/binfmt/libnxflat/libnxflat.h
new file mode 100644
index 000000000..cb1cb7057
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat.h
@@ -0,0 +1,136 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat.h
+ *
+ * Copyright (C) 2012 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_LIBNXFLAT_LIBNXFLAT_H
+#define __BINFMT_LIBNXFLAT_LIBNXFLAT_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/binfmt/nxflat.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_addrenv_alloc
+ *
+ * Description:
+ * Allocate memory for the ELF image (elfalloc). If CONFIG_ADDRENV=n,
+ * elfalloc will be allocated using kzalloc(). If CONFIG_ADDRENV-y, then
+ * elfalloc will be allocated using up_addrenv_create(). In either case,
+ * there will be a unique instance of elfalloc (and stack) for each
+ * instance of a process.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * envsize - The size (in bytes) of the address environment needed for the
+ * ELF image.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int nxflat_addrenv_alloc(FAR struct nxflat_loadinfo_s *loadinfo, size_t envsize);
+
+/****************************************************************************
+ * Name: nxflat_addrenv_select
+ *
+ * Description:
+ * Temporarity select the task's address environemnt.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+# define nxflat_addrenv_select(l) up_addrenv_select((l)->addrenv, &(l)->oldenv)
+#endif
+
+/****************************************************************************
+ * Name: nxflat_addrenv_restore
+ *
+ * Description:
+ * Restore the address environment before nxflat_addrenv_select() was called..
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+# define nxflat_addrenv_restore(l) up_addrenv_restore((l)->oldenv)
+#endif
+
+/****************************************************************************
+ * Name: nxflat_addrenv_free
+ *
+ * Description:
+ * Release the address environment previously created by
+ * nxflat_addrenv_create(). This function is called only under certain
+ * error conditions after the the module has been loaded but not yet
+ * started. After the module has been started, the address environment
+ * will automatically be freed when the module exits.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void nxflat_addrenv_free(FAR struct nxflat_loadinfo_s *loadinfo);
+
+#endif /* __BINFMT_LIBNXFLAT_LIBNXFLAT_H */
diff --git a/nuttx/binfmt/libnxflat/libnxflat_addrenv.c b/nuttx/binfmt/libnxflat/libnxflat_addrenv.c
new file mode 100644
index 000000000..2d9255b28
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_addrenv.c
@@ -0,0 +1,235 @@
+/****************************************************************************
+ * binfmt/libnxflat/libnxflat_addrenv.c
+ *
+ * Copyright (C) 2012 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 <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
+
+#include "libnxflat.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_addrenv_alloc
+ *
+ * Description:
+ * Allocate memory for the ELF image (elfalloc). If CONFIG_ADDRENV=n,
+ * elfalloc will be allocated using kzalloc(). If CONFIG_ADDRENV-y, then
+ * elfalloc will be allocated using up_addrenv_create(). In either case,
+ * there will be a unique instance of elfalloc (and stack) for each
+ * instance of a process.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * envsize - The size (in bytes) of the address environment needed for the
+ * ELF image.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int nxflat_addrenv_alloc(FAR struct nxflat_loadinfo_s *loadinfo, size_t envsize)
+{
+ FAR struct dspace_s *dspace;
+#ifdef CONFIG_ADDRENV
+ FAR void *vaddr;
+ hw_addrenv_t oldenv;
+ int ret;
+#endif
+
+ DEBUGASSERT(!loadinfo->dspace);
+
+ /* Allocate the struct dspace_s container for the D-Space allocation */
+
+ dspace = (FAR struct dspace_s *)kmalloc(sizeof(struct dspace_s));
+ if (dspace == 0)
+ {
+ bdbg("ERROR: Failed to allocate DSpace\n");
+ return -ENOMEM;
+ }
+
+#ifdef CONFIG_ADDRENV
+ /* Create a D-Space address environment for the new NXFLAT task */
+
+ ret = up_addrenv_create(envsize, &loadinfo->addrenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_create failed: %d\n", ret);
+ goto errout_with_dspace;
+ }
+
+ /* Get the virtual address associated with the start of the address
+ * environment. This is the base address that we will need to use to
+ * access the D-Space region (but only if the address environment has been
+ * selected.
+ */
+
+ ret = up_addrenv_vaddr(loadinfo->addrenv, &vaddr);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_vaddr failed: %d\n", ret);
+ goto errout_with_addrenv;
+ }
+
+ /* Clear all of the allocated D-Space memory. We have to temporarily
+ * selected the D-Space address environment to do this.
+ */
+
+ ret = up_addrenv_select(loadinfo->addrenv, &oldenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_select failed: %d\n", ret);
+ goto errout_with_addrenv;
+ }
+
+ memset(vaddr, 0, envsize);
+
+ ret = up_addrenv_restore(oldenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_restore failed: %d\n", ret);
+ goto errout_with_addrenv;
+ }
+
+ /* Success... save the fruits of our labor */
+
+ loadinfo->dspace = dspace;
+ dspace->crefs = 1;
+ dspace->region = (FAR uint8_t *)vaddr;
+ return OK;
+
+errout_with_addrenv:
+ (void)up_addrenv_destroy(loadinfo->addrenv);
+ loadinfo->addrenv = 0;
+
+errout_with_dspace:
+ kfree(dspace);
+ return ret;
+#else
+ /* Allocate (and zero) memory to hold the ELF image */
+
+ dspace->region = (FAR uint8_t *)kzalloc(envsize);
+ if (!dspace->region)
+ {
+ kfree(dspace);
+ return -ENOMEM;
+ }
+
+ loadinfo->dspace = dspace;
+ dspace->crefs = 1;
+ return OK;
+#endif
+}
+
+/****************************************************************************
+ * Name: nxflat_addrenv_free
+ *
+ * Description:
+ * Release the address environment previously created by
+ * nxflat_addrenv_create(). This function is called only under certain
+ * error conditions after the the module has been loaded but not yet
+ * started. After the module has been started, the address environment
+ * will automatically be freed when the module exits.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void nxflat_addrenv_free(FAR struct nxflat_loadinfo_s *loadinfo)
+{
+ FAR struct dspace_s *dspace;
+#ifdef CONFIG_ADDRENV
+ int ret;
+#endif
+
+ DEBUGASSERT(loadinfo);
+ dspace = loadinfo->dspace;
+
+ if (dspace)
+ {
+#ifdef CONFIG_ADDRENV
+ /* Destroy the address environment */
+
+ ret = up_addrenv_destroy(loadinfo->addrenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_destroy failed: %d\n", ret);
+ }
+
+ loadinfo->addrenv = 0;
+#else
+ /* Free the allocated D-Space region */
+
+ if (dspace->region)
+ {
+ kfree(dspace->region);
+ }
+#endif
+
+ /* Now destroy the D-Space container */
+
+ DEBUGASSERT(dspace->crefs == 1);
+ kfree(dspace);
+ loadinfo->dspace = NULL;
+ }
+}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_bind.c b/nuttx/binfmt/libnxflat/libnxflat_bind.c
index ca348178d..816810a46 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_bind.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_bind.c
@@ -38,6 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <stdint.h>
#include <string.h>
@@ -47,8 +48,11 @@
#include <debug.h>
#include <arpa/inet.h>
-#include <nuttx/nxflat.h>
-#include <nuttx/symtab.h>
+
+#include <nuttx/binfmt/nxflat.h>
+#include <nuttx/binfmt/symtab.h>
+
+#include "libnxflat.h"
/****************************************************************************
* Pre-processor Definitions
@@ -229,8 +233,6 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
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);
@@ -247,11 +249,27 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
DEBUGASSERT(offset + nrelocs * sizeof(struct nxflat_reloc_s)
<= (loadinfo->isize + loadinfo->dsize));
- relocs = (FAR struct nxflat_reloc_s*)
+ 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);
+ /* All relocations are performed within the D-Space allocation. If
+ * CONFIG_ADDRENV=y, then that D-Space allocation lies in an address
+ * environment that may not be in place. So, in that case, we must call
+ * nxflat_addrenv_select to temporarily instantiate that address space
+ * before the relocations can be performed.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Now, traverse the relocation list of and bind each GOT relocation. */
ret = OK; /* Assume success */
@@ -259,11 +277,16 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
{
/* Handle the relocation by the relocation type */
+#ifdef CONFIG_CAN_PASS_STRUCTS
reloc = *relocs++;
+#else
+ memcpy(&reloc, relocs, sizeof(struct nxflat_reloc_s));
+ relocs++;
+#endif
+
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.
@@ -329,6 +352,17 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
nxflat_dumpbuffer("GOT", (FAR const uint8_t*)relocs, nrelocs * sizeof(struct nxflat_reloc_s));
}
#endif
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
+ }
+#endif
+
return ret;
}
@@ -346,16 +380,19 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
****************************************************************************/
static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
- FAR const struct symtab_s *exports,
- int nexports)
+ 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;
+ FAR const struct symtab_s *symbol;
char *symname;
uint32_t offset;
uint16_t nimports;
+#ifdef CONFIG_ADDRENV
+ int ret;
+#endif
int i;
/* The NXFLAT header is the first thing at the beginning of the ISpace. */
@@ -370,6 +407,22 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
nimports = ntohs(hdr->h_importcount);
bvdbg("Imports offset: %08x nimports: %d\n", offset, nimports);
+ /* The import[] table resides within the D-Space allocation. If
+ * CONFIG_ADDRENV=y, then that D-Space allocation lies in an address
+ * environment that may not be in place. So, in that case, we must call
+ * nxflat_addrenv_select to temporarily instantiate that address space
+ * before the import[] table can be modified.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Verify that this module requires imported symbols */
if (offset != 0 && nimports > 0)
@@ -388,7 +441,7 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
offset < loadinfo->isize + loadinfo->dsize);
imports = (struct nxflat_import_s*)
- (offset - loadinfo->isize + loadinfo->dspace->region);
+ (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
@@ -396,41 +449,44 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
*/
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);
+ {
+ 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.
- */
+ /* 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));
+ symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s));
- /* Find the exported symbol value for this this symbol name. */
+ /* 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);
+ if (!symbol)
+ {
+ bdbg("Exported symbol \"%s\" not found\n", symname);
+#ifdef CONFIG_ADDRENV
+ (void)nxflat_addrenv_restore(loadinfo);
+#endif
return -ENOENT;
- }
+ }
- /* And put this into the module's import structure. */
+ /* And put this into the module's import structure. */
- imports[i].i_funcaddress = (uint32_t)symbol->sym_value;
+ 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);
- }
+ bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n",
+ i, &imports[i], symname, imports[i].i_funcaddress);
+ }
}
/* Dump the relocation import table */
@@ -441,7 +497,74 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
nxflat_dumpbuffer("Imports", (FAR const uint8_t*)imports, nimports * sizeof(struct nxflat_import_s));
}
#endif
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
+ }
+
+ return ret;
+#else
+ return OK;
+#endif
+}
+
+/****************************************************************************
+ * Name: nxflat_clearbss
+ *
+ * Description:
+ * Clear uninitialized .bss memory
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int nxflat_clearbss(FAR struct nxflat_loadinfo_s *loadinfo)
+{
+#ifdef CONFIG_ADDRENV
+ int ret;
+#endif
+
+ /* .bss resides within the D-Space allocation. If CONFIG_ADDRENV=y, then
+ * that D-Space allocation lies in an address environment that may not be
+ * in place. So, in that case, we must call nxflat_addrenv_select to
+ * temporarily instantiate that address space before the .bss can be
+ * accessed.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ /* Zero the BSS area */
+
+ memset((void*)(loadinfo->dspace->region + loadinfo->datasize), 0,
+ loadinfo->bsssize);
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
+ }
+
+ return ret;
+#else
return OK;
+#endif
}
/****************************************************************************
@@ -483,10 +606,10 @@ int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
* space in the loaded file.
*/
- memset((void*)(loadinfo->dspace->region + loadinfo->datasize),
- 0, loadinfo->bsssize);
+ ret = nxflat_clearbss(loadinfo);
}
}
+
return ret;
}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c
index 5b6375ff1..b7cac8d86 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_init.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_init.c
@@ -48,7 +48,7 @@
#include <errno.h>
#include <arpa/inet.h>
-#include <nuttx/nxflat.h>
+#include <nuttx/binfmt/nxflat.h>
/****************************************************************************
* Pre-Processor Definitions
@@ -112,8 +112,9 @@ int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo)
loadinfo->filfd = open(filename, O_RDONLY);
if (loadinfo->filfd < 0)
{
- bdbg("Failed to open NXFLAT binary %s: %d\n", filename, ret);
- return -errno;
+ int errval = errno;
+ bdbg("Failed to open NXFLAT binary %s: %d\n", filename, errval);
+ return -errval;
}
/* Read the NXFLAT header from offset 0 */
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
index 0991d0c2d..5f13b577a 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_load.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_load.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <sys/mman.h>
+
#include <stdint.h>
#include <stdlib.h>
#include <nxflat.h>
@@ -48,7 +49,10 @@
#include <errno.h>
#include <arpa/inet.h>
-#include <nuttx/nxflat.h>
+
+#include <nuttx/binfmt/nxflat.h>
+
+#include "libnxflat.h"
/****************************************************************************
* Pre-Processor Definitions
@@ -62,24 +66,6 @@
* 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
****************************************************************************/
@@ -161,7 +147,7 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
*/
loadinfo->ispace = (uint32_t)mmap(NULL, loadinfo->isize, PROT_READ,
- MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
+ MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
if (loadinfo->ispace == (uint32_t)MAP_FAILED)
{
bdbg("Failed to map NXFLAT ISpace: %d\n", errno);
@@ -170,23 +156,37 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
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.
+ /* The following call allocate D-Space memory and will provide a pointer
+ * to the allocated (but still uninitialized) D-Space memory.
*/
- loadinfo->dspace = (struct dspace_s *)malloc(SIZEOF_DSPACE_S(loadinfo->dsize));
- if (loadinfo->dspace == 0)
+ ret = nxflat_addrenv_alloc(loadinfo, loadinfo->dsize);
+ if (ret < 0)
{
- bdbg("Failed to allocate DSpace\n");
- ret = -ENOMEM;
- goto errout;
+ bdbg("ERROR: nxflat_addrenv_alloc() failed: %d\n", ret);
+ return ret;
}
- loadinfo->dspace->crefs = 1;
- bvdbg("Allocated DSpace (%d bytes) at %p\n", loadinfo->dsize, loadinfo->dspace->region);
+ 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.
+ /* If CONFIG_ADDRENV=y, then the D-Space allocation lies in an address
+ * environment that may not be in place. So, in that case, we must call
+ * nxflat_addrenv_select to temporarily instantiate that address space
+ * it can be initialized.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ /* Now, read the data into allocated DSpace at doffset into the allocated
+ * DSpace memory.
*/
ret = nxflat_read(loadinfo, (char*)loadinfo->dspace->region, dreadsize, doffset);
@@ -199,9 +199,23 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
bvdbg("TEXT: %08x Entry point offset: %08x Data offset: %08x\n",
loadinfo->ispace, loadinfo->entryoffs, doffset);
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = nxflat_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
return OK;
errout:
+#ifdef CONFIG_ADDRENV
+ (void)nxflat_addrenv_restore(loadinfo);
+#endif
(void)nxflat_unload(loadinfo);
return ret;
}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c
index dbcd54279..8deeb0805 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_read.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_read.c
@@ -48,7 +48,7 @@
#include <errno.h>
#include <arpa/inet.h>
-#include <nuttx/nxflat.h>
+#include <nuttx/binfmt/nxflat.h>
/****************************************************************************
* Pre-Processor Definitions
@@ -129,8 +129,9 @@ int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize,
rpos = lseek(loadinfo->filfd, offset, SEEK_SET);
if (rpos != offset)
{
- bdbg("Failed to seek to position %d: %d\n", offset, errno);
- return -errno;
+ int errval = errno;
+ bdbg("Failed to seek to position %d: %d\n", offset, errval);
+ return -errval;
}
/* Read the file data at offset into the user buffer */
@@ -138,10 +139,11 @@ int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize,
nbytes = read(loadinfo->filfd, bufptr, bytesleft);
if (nbytes < 0)
{
- if (errno != EINTR)
+ int errval = errno;
+ if (errval != EINTR)
{
- bdbg("Read of .data failed: %d\n", errno);
- return -errno;
+ bdbg("Read of .data failed: %d\n", errval);
+ return -errval;
}
}
else if (nbytes == 0)
diff --git a/nuttx/binfmt/libnxflat/libnxflat_uninit.c b/nuttx/binfmt/libnxflat/libnxflat_uninit.c
index 5d06296c7..b9715196b 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_uninit.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_uninit.c
@@ -42,7 +42,8 @@
#include <unistd.h>
#include <debug.h>
#include <errno.h>
-#include <nuttx/nxflat.h>
+
+#include <nuttx/binfmt/nxflat.h>
/****************************************************************************
* Pre-Processor Definitions
@@ -57,10 +58,6 @@
****************************************************************************/
/****************************************************************************
- * Name: nxflat_swap32
- ****************************************************************************/
-
-/****************************************************************************
* Public Functions
****************************************************************************/
diff --git a/nuttx/binfmt/libnxflat/libnxflat_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c
index 55a2e45e6..eb1aa0343 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_unload.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_unload.c
@@ -40,10 +40,14 @@
#include <nuttx/config.h>
#include <sys/mman.h>
+
#include <stdlib.h>
#include <debug.h>
-#include <nuttx/nxflat.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/binfmt/nxflat.h>
+
+#include "libnxflat.h"
/****************************************************************************
* Pre-Processor Definitions
@@ -65,8 +69,9 @@
* Name: nxflat_unload
*
* Description:
- * This function unloads the object from memory. This essentially
- * undoes the actions of nxflat_load.
+ * This function unloads the object from memory. This essentially undoes
+ * the actions of nxflat_load. It is called only under certain error
+ * conditions after the the module has been loaded but not yet started.
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
@@ -76,9 +81,8 @@
int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
{
- /* Reset the contents of the info structure. */
-
/* Release the memory segments */
+ /* Release the I-Space mmap'ed file */
if (loadinfo->ispace)
{
@@ -86,12 +90,8 @@ int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
loadinfo->ispace = 0;
}
- if (loadinfo->dspace)
- {
- free((void*)loadinfo->dspace);
- loadinfo->dspace = 0;
- }
+ /* Release the D-Space address environment */
+ nxflat_addrenv_free(loadinfo);
return OK;
}
-
diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c
index f799aca4f..20af5d2f7 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_verify.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c
@@ -42,8 +42,9 @@
#include <string.h>
#include <debug.h>
#include <errno.h>
+
#include <arpa/inet.h>
-#include <nuttx/nxflat.h>
+#include <nuttx/binfmt/nxflat.h>
/****************************************************************************
* Pre-processor Definitions
@@ -91,10 +92,10 @@ int nxflat_verifyheader(const struct nxflat_hdr_s *header)
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]);
+ 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
index 4f5869bd9..db29941ca 100644
--- a/nuttx/binfmt/nxflat.c
+++ b/nuttx/binfmt/nxflat.c
@@ -47,8 +47,8 @@
#include <errno.h>
#include <arpa/inet.h>
-#include <nuttx/binfmt.h>
-#include <nuttx/nxflat.h>
+#include <nuttx/binfmt/binfmt.h>
+#include <nuttx/binfmt/nxflat.h>
#ifdef CONFIG_NXFLAT
@@ -158,7 +158,7 @@ static int nxflat_loadbinary(struct binary_s *binp)
nxflat_dumploadinfo(&loadinfo);
if (ret != 0)
{
- bdbg("Failed to initialize for load of NXFLT program: %d\n", ret);
+ bdbg("Failed to initialize for load of NXFLAT program: %d\n", ret);
goto errout;
}
@@ -168,7 +168,7 @@ static int nxflat_loadbinary(struct binary_s *binp)
nxflat_dumploadinfo(&loadinfo);
if (ret != 0)
{
- bdbg("Failed to load NXFLT program binary: %d\n", ret);
+ bdbg("Failed to load NXFLAT program binary: %d\n", ret);
goto errout_with_init;
}
@@ -181,16 +181,39 @@ static int nxflat_loadbinary(struct binary_s *binp)
goto errout_with_load;
}
- /* Return the load information */
+ /* Return the load information. By convention, D-space address
+ * space is stored as the first allocated memory.
+ */
binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs);
- binp->ispace = (void*)loadinfo.ispace;
- binp->dspace = (void*)loadinfo.dspace;
- binp->isize = loadinfo.isize;
+ binp->mapped = (void*)loadinfo.ispace;
+ binp->mapsize = loadinfo.isize;
binp->stacksize = loadinfo.stacksize;
+ /* Add the ELF allocation to the alloc[] only if there is no address
+ * enironment. If there is an address environment, it will automatically
+ * be freed when the function exits
+ *
+ * REVISIT: If the module is loaded then unloaded, wouldn't this cause
+ * a memory leak?
+ */
+
+#ifdef CONFIG_ADDRENV
+# warning "REVISIT"
+#else
+ binp->alloc[0] = (void*)loadinfo.dspace;
+#endif
+
+#ifdef CONFIG_ADDRENV
+ /* Save the address environment. This will be needed when the module is
+ * executed for the up_addrenv_assign() call.
+ */
+
+ binp->addrenv = loadinfo.addrenv;
+#endif
+
nxflat_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,
- MIN(binp->isize - loadinfo.entryoffs,512));
+ MIN(loadinfo.isize - loadinfo.entryoffs, 512));
nxflat_uninit(&loadinfo);
return OK;
diff --git a/nuttx/binfmt/symtab_findbyname.c b/nuttx/binfmt/symtab_findbyname.c
index 201d7ba07..c0343e270 100644
--- a/nuttx/binfmt/symtab_findbyname.c
+++ b/nuttx/binfmt/symtab_findbyname.c
@@ -44,7 +44,7 @@
#include <assert.h>
#include <errno.h>
-#include <nuttx/symtab.h>
+#include <nuttx/binfmt/symtab.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/binfmt/symtab_findbyvalue.c b/nuttx/binfmt/symtab_findbyvalue.c
index 4382ed5d8..c47d5c751 100644
--- a/nuttx/binfmt/symtab_findbyvalue.c
+++ b/nuttx/binfmt/symtab_findbyvalue.c
@@ -44,7 +44,7 @@
#include <assert.h>
#include <errno.h>
-#include <nuttx/symtab.h>
+#include <nuttx/binfmt/symtab.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/binfmt/symtab_findorderedbyname.c b/nuttx/binfmt/symtab_findorderedbyname.c
index 61decf49a..a678788e7 100644
--- a/nuttx/binfmt/symtab_findorderedbyname.c
+++ b/nuttx/binfmt/symtab_findorderedbyname.c
@@ -44,7 +44,7 @@
#include <assert.h>
#include <errno.h>
-#include <nuttx/symtab.h>
+#include <nuttx/binfmt/symtab.h>
/****************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/binfmt/symtab_findorderedbyvalue.c b/nuttx/binfmt/symtab_findorderedbyvalue.c
index 92b107856..bad4bf8cd 100644
--- a/nuttx/binfmt/symtab_findorderedbyvalue.c
+++ b/nuttx/binfmt/symtab_findorderedbyvalue.c
@@ -44,7 +44,7 @@
#include <assert.h>
#include <errno.h>
-#include <nuttx/symtab.h>
+#include <nuttx/binfmt/symtab.h>
/****************************************************************************
* Pre-processor Definitions