summaryrefslogtreecommitdiff
path: root/nuttx/binfmt/libelf
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-24 16:46:12 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-24 16:46:12 +0000
commit31d66d5fb2961c4c2df0d9f415f91ee5405f8d19 (patch)
tree199c1ac47d5ce30532f7b23121bc7df2c580a8c6 /nuttx/binfmt/libelf
parente2cd590a6f7e1a4132d2eda16e1f29c760b804bb (diff)
downloadpx4-nuttx-31d66d5fb2961c4c2df0d9f415f91ee5405f8d19.tar.gz
px4-nuttx-31d66d5fb2961c4c2df0d9f415f91ee5405f8d19.tar.bz2
px4-nuttx-31d66d5fb2961c4c2df0d9f415f91ee5405f8d19.zip
Add framework to support loadable ELF modules (not much logic in place yet)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5250 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/binfmt/libelf')
-rw-r--r--nuttx/binfmt/libelf/Kconfig9
-rw-r--r--nuttx/binfmt/libelf/Make.defs53
-rw-r--r--nuttx/binfmt/libelf/gnu-elf.ld187
-rw-r--r--nuttx/binfmt/libelf/libelf_bind.c106
-rw-r--r--nuttx/binfmt/libelf/libelf_init.c189
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c91
-rw-r--r--nuttx/binfmt/libelf/libelf_read.c165
-rw-r--r--nuttx/binfmt/libelf/libelf_uninit.c85
-rw-r--r--nuttx/binfmt/libelf/libelf_unload.c97
-rw-r--r--nuttx/binfmt/libelf/libelf_verify.c88
10 files changed, 1070 insertions, 0 deletions
diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig
new file mode 100644
index 000000000..c47bc9f9e
--- /dev/null
+++ b/nuttx/binfmt/libelf/Kconfig
@@ -0,0 +1,9 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config ELF_DUMPBUFFER
+ bool "Dump ELF buffers"
+ default n
+ depends on DEBUG && DEBUG_VERBOSE
diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs
new file mode 100644
index 000000000..629961863
--- /dev/null
+++ b/nuttx/binfmt/libelf/Make.defs
@@ -0,0 +1,53 @@
+############################################################################
+# 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_init.c libelf_uninit.c libelf_load.c \
+ libelf_unload.c libelf_verify.c libelf_read.c \
+ libelf_bind.c
+
+# Hook the libelf subdirectory into the build
+
+VPATH += libelf
+SUBDIRS += libelf
+
+endif
diff --git a/nuttx/binfmt/libelf/gnu-elf.ld b/nuttx/binfmt/libelf/gnu-elf.ld
new file mode 100644
index 000000000..703f36981
--- /dev/null
+++ b/nuttx/binfmt/libelf/gnu-elf.ld
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * examples/elf/gnu-elf-gotoff.ld
+ *
+ * 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
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+ ISPACE : ORIGIN = 0x0, LENGTH = 2097152
+ DSPACE : ORIGIN = 0x0, LENGTH = 2097152
+}
+
+/****************************************************************************
+ * The XFLAT program image is divided into two segments:
+ *
+ * (1) ISpace (Instruction Space). This is the segment that contains
+ * code (.text). Everything in the segment should be fetch-able
+ * machine PC instructions (jump, branch, call, etc.).
+ * (2) DSpace (Data Space). This is the segment that contains both
+ * read-write data (.data, .bss) as well as read-only data (.rodata).
+ * Everything in this segment should be access-able with machine
+ * PIC load and store instructions.
+ *
+ * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative
+ * addressing to access RO data. In that case, read-only data (.rodata) must
+ * reside in D-Space and this linker script should be used.
+ *
+ * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative
+ * addressing to access RO data. In that case, read-only data (.rodata) must
+ * reside in I-Space and this linker script should NOT be used with those
+ * newer tools.
+ *
+ ****************************************************************************/
+
+SECTIONS
+{
+ .text 0x00000000 :
+ {
+ /* ISpace is located at address 0. Every (unrelocated) ISpace
+ * address is an offset from the begining of this segment.
+ */
+
+ text_start = . ;
+
+ *(.text)
+ *(.text.*)
+ *(.gnu.warning)
+ *(.stub)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.jcr)
+
+ /* C++ support: The .init and .fini sections contain XFLAT-
+ * specific logic to manage static constructors and destructors.
+ */
+
+ *(.gnu.linkonce.t.*)
+ *(.init)
+ *(.fini)
+
+ /* This is special code area at the end of the normal
+ text section. It contains a small lookup table at
+ the start followed by the code pointed to by entries
+ in the lookup table. */
+
+ . = ALIGN (4) ;
+ PROVIDE(__ctbp = .);
+ *(.call_table_data)
+ *(.call_table_text)
+
+ _etext = . ;
+
+ } > ISPACE
+
+ /* DSpace is also located at address 0. Every (unrelocated) DSpace
+ * address is an offset from the begining of this segment.
+ */
+
+ .data 0x00000000 :
+ {
+ /* In this model, .rodata is access using PC-relative addressing
+ * and, hence, must also reside in the .text section.
+ */
+
+ __data_start = . ;
+ *(.rodata)
+ *(.rodata1)
+ *(.rodata.*)
+ *(.gnu.linkonce.r*)
+
+ *(.data)
+ *(.data1)
+ *(.data.*)
+ *(.gnu.linkonce.d*)
+ *(.data1)
+ *(.eh_frame)
+ *(.gcc_except_table)
+
+ *(.gnu.linkonce.s.*)
+ *(__libc_atexit)
+ *(__libc_subinit)
+ *(__libc_subfreeres)
+ *(.note.ABI-tag)
+
+ /* C++ support. For each global and static local C++ object,
+ * GCC creates a small subroutine to construct the object. Pointers
+ * to these routines (not the routines themselves) are stored as
+ * simple, linear arrays in the .ctors section of the object file.
+ * Similarly, pointers to global/static destructor routines are
+ * stored in .dtors.
+ */
+
+ *(.gnu.linkonce.d.*)
+
+ _ctors_start = . ;
+ *(.ctors)
+ _ctors_end = . ;
+ _dtors_start = . ;
+ *(.dtors)
+ _dtors_end = . ;
+
+ _edata = . ;
+ edata = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .bss :
+ {
+ __bss_start = _edata ;
+ *(.dynsbss)
+ *(.sbss)
+ *(.sbss.*)
+ *(.scommon)
+ *(.dynbss)
+ *(.bss)
+ *(.bss.*)
+ *(.bss*)
+ *(.gnu.linkonce.b*)
+ *(COMMON)
+ end = ALIGN( 0x10 ) ;
+ _end = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .got 0 : { *(.got.plt) *(.got) }
+ .junk 0 : { *(.rel*) *(.rela*) }
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c
new file mode 100644
index 000000000..44532ab88
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_bind.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * 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 <elf.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <arpa/inet.h>
+#include <nuttx/elf.h>
+#include <nuttx/symtab.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
+
+#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
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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)
+{
+#warning "Missing logic"
+ return -ENOSYS;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c
new file mode 100644
index 000000000..d72e96b62
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_init.c
@@ -0,0 +1,189 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_init.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/stat.h>
+#include <stdint.h>
+#include <string.h>
+#include <fcntl.h>
+#include <elf.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/elf.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
+
+#ifdef CONFIG_ELF_DUMPBUFFER
+# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
+#else
+# define elf_dumpbuffer(m,b,n)
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_init
+ *
+ * Description:
+ * This function is called to configure the library to process an ELF
+ * program binary.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo)
+{
+ uint32_t datastart;
+ uint32_t dataend;
+ uint32_t bssstart;
+ uint32_t bssend;
+ int ret;
+
+ bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo);
+
+ /* Clear the load info structure */
+
+ memset(loadinfo, 0, sizeof(struct elf_loadinfo_s));
+
+ /* Open the binary file */
+
+ loadinfo->filfd = open(filename, O_RDONLY);
+ if (loadinfo->filfd < 0)
+ {
+ bdbg("Failed to open ELF binary %s: %d\n", filename, ret);
+ return -errno;
+ }
+
+ /* Read the ELF header from offset 0 */
+
+ ret = elf_read(loadinfo, (char*)&loadinfo->header,
+ sizeof(struct elf_hdr_s), 0);
+ if (ret < 0)
+ {
+ bdbg("Failed to read ELF header: %d\n", ret);
+ return ret;
+ }
+
+ elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->header,
+ sizeof(struct elf_hdr_s));
+
+ /* Verify the ELF header */
+
+ if (elf_verifyheader(&loadinfo->header) != 0)
+ {
+ /* This is not an error because we will be called to attempt loading
+ * EVERY binary. Returning -ENOEXEC simply informs the system that
+ * the file is not an ELF file. Besides, if there is something worth
+ * complaining about, nelf_verifyheader() has already
+ * done so.
+ */
+
+ bdbg("Bad ELF header\n");
+ return -ENOEXEC;
+ }
+
+ /* Save all of the input values in the loadinfo structure
+ * and extract some additional information from the xflat
+ * header. Note that the information in the xflat header is in
+ * network order.
+ */
+
+ datastart = ntohl(loadinfo->header.h_datastart);
+ dataend = ntohl(loadinfo->header.h_dataend);
+ bssstart = dataend;
+ bssend = ntohl(loadinfo->header.h_bssend);
+
+ /* And put this information into the loadinfo structure as well.
+ *
+ * Note that:
+ *
+ * isize = the address range from 0 up to datastart.
+ * datasize = the address range from datastart up to dataend
+ * bsssize = the address range from dataend up to bssend.
+ */
+
+ loadinfo->entryoffs = ntohl(loadinfo->header.h_entry);
+ loadinfo->isize = datastart;
+
+ loadinfo->datasize = dataend - datastart;
+ loadinfo->bsssize = bssend - dataend;
+ loadinfo->stacksize = ntohl(loadinfo->header.h_stacksize);
+
+ /* This is the initial dspace size. We'll re-calculate this later
+ * after the memory has been allocated.
+ */
+
+ loadinfo->dsize = bssend - datastart;
+
+ /* Get the offset to the start of the relocations (we'll relocate
+ * this later).
+ */
+
+ loadinfo->relocstart = ntohl(loadinfo->header.h_relocstart);
+ loadinfo->reloccount = ntohs(loadinfo->header.h_reloccount);
+
+ return 0;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
new file mode 100644
index 000000000..94d200b56
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * 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 <sys/mman.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <elf.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/elf.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#ifndef MAX
+#define MAX(x,y) ((x) > (y) ? (x) : (y))
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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)
+{
+# warning "Missing logic"
+ return -ENOSYS;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c
new file mode 100644
index 000000000..5f00a531e
--- /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 <elf.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <arpa/inet.h>
+#include <nuttx/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'
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_read(struct elf_loadinfo_s *loadinfo, char *buffer, int readsize, int offset)
+{
+ ssize_t nbytes; /* Number of bytes read */
+ off_t rpos; /* Position returned by lseek */
+ char *bufptr; /* Next buffer location to read into */
+ int bytesleft; /* Number of bytes of .data left to read */
+ int bytesread; /* Total number of bytes read */
+
+ bvdbg("Read %d bytes from offset %d\n", readsize, offset);
+
+ /* Seek to the position in the object file where the initialized
+ * data is saved.
+ */
+
+ bytesread = 0;
+ bufptr = buffer;
+ bytesleft = readsize;
+ do
+ {
+ rpos = lseek(loadinfo->filfd, offset, SEEK_SET);
+ if (rpos != offset)
+ {
+ bdbg("Failed to seek to position %d: %d\n", offset, errno);
+ return -errno;
+ }
+
+ /* Read the file data at offset into the user buffer */
+
+ nbytes = read(loadinfo->filfd, bufptr, bytesleft);
+ if (nbytes < 0)
+ {
+ if (errno != EINTR)
+ {
+ bdbg("Read of .data failed: %d\n", errno);
+ return -errno;
+ }
+ }
+ else if (nbytes == 0)
+ {
+ bdbg("Unexpected end of file\n");
+ return -ENODATA;
+ }
+ else
+ {
+ bytesread += nbytes;
+ bytesleft -= nbytes;
+ bufptr += nbytes;
+ offset += nbytes;
+ }
+ }
+ while (bytesread < readsize);
+
+ elf_dumpreaddata(buffer, readsize);
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c
new file mode 100644
index 000000000..cd7ae7282
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_uninit.c
@@ -0,0 +1,85 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_uninit.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 <unistd.h>
+#include <debug.h>
+#include <errno.h>
+#include <nuttx/elf.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_uninit
+ *
+ * Description:
+ * Releases any resources committed by elf_init(). This essentially
+ * undoes the actions of elf_init.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_uninit(struct elf_loadinfo_s *loadinfo)
+{
+ if (loadinfo->filfd >= 0)
+ {
+ close(loadinfo->filfd);
+ }
+
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c
new file mode 100644
index 000000000..9e930e295
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_unload.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ * 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 <sys/mman.h>
+#include <stdlib.h>
+#include <debug.h>
+
+#include <nuttx/elf.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.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_unload(struct elf_loadinfo_s *loadinfo)
+{
+ /* Reset the contents of the info structure. */
+
+ /* Release the memory segments */
+
+ if (loadinfo->ispace)
+ {
+ kfree((void*)loadinfo->ispace, loadinfo->isize);
+ loadinfo->ispace = 0;
+ }
+
+ if (loadinfo->dspace)
+ {
+ kfree((void*)loadinfo->dspace);
+ loadinfo->dspace = 0;
+ }
+
+ return OK;
+}
+
diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c
new file mode 100644
index 000000000..9e265573a
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_verify.c
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * binfmt/libelf/elf_verify.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 <debug.h>
+#include <errno.h>
+#include <arpa/inet.h>
+#include <nuttx/elf.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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(const struct elf_hdr_s *header)
+{
+ if (!header)
+ {
+ bdbg("NULL ELF header!");
+ return -ENOEXEC;
+ }
+
+#warning "Missing Logic"
+ return -ENOSYS;
+}
+