aboutsummaryrefslogtreecommitdiff
path: root/nuttx/binfmt/libelf
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-25 16:18:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-25 16:18:20 +0000
commit630862cd04e0f807f9d1d9d2ed8ba8f044dcedfa (patch)
treeeef8d62f4f6b69c9377ef1814144713d434eb43c /nuttx/binfmt/libelf
parenta91b6552cdb1b147461b75128576012192d9e933 (diff)
downloadpx4-firmware-630862cd04e0f807f9d1d9d2ed8ba8f044dcedfa.tar.gz
px4-firmware-630862cd04e0f807f9d1d9d2ed8ba8f044dcedfa.tar.bz2
px4-firmware-630862cd04e0f807f9d1d9d2ed8ba8f044dcedfa.zip
A little more ELF loader logic
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5257 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/binfmt/libelf')
-rw-r--r--nuttx/binfmt/libelf/Kconfig13
-rw-r--r--nuttx/binfmt/libelf/Make.defs3
-rw-r--r--nuttx/binfmt/libelf/arm.h53
-rw-r--r--nuttx/binfmt/libelf/libelf.h55
-rw-r--r--nuttx/binfmt/libelf/libelf_bind.c171
-rw-r--r--nuttx/binfmt/libelf/libelf_init.c4
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c57
-rw-r--r--nuttx/binfmt/libelf/libelf_symbols.c134
-rw-r--r--nuttx/binfmt/libelf/libelf_unload.c10
-rw-r--r--nuttx/binfmt/libelf/libelf_verify.c8
10 files changed, 406 insertions, 102 deletions
diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig
index ba931b57e..f16dd4e90 100644
--- a/nuttx/binfmt/libelf/Kconfig
+++ b/nuttx/binfmt/libelf/Kconfig
@@ -9,6 +9,12 @@ config ELF_ALIGN_LOG2
---help---
Align all sections to this Log2 value: 0->1, 1->2, 2->4, etc.
+config ELF_STACKSIZE
+ int "ELF Stack Size"
+ default 2048
+ ---help---
+ This is the default stack size that will will be used when starting ELF binaries.
+
config ELF_CONSTRUCTORS
bool "C++ Static Constructor Support"
default n
@@ -16,13 +22,6 @@ config ELF_CONSTRUCTORS
---help---
Build in support for C++ constructors in ELF modules.
-config ELF_SYMBOLS
- bool "Export symbols from ELF modules"
- default n
- ---help---
- Allow symbols from one ELF module to be used by another. NOT
- fully implemented!
-
config ELF_DUMPBUFFER
bool "Dump ELF buffers"
default n
diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs
index 629961863..82f5f3e64 100644
--- a/nuttx/binfmt/libelf/Make.defs
+++ b/nuttx/binfmt/libelf/Make.defs
@@ -43,11 +43,12 @@ BINFMT_CSRCS += elf.c
BINFMT_CSRCS = libelf_init.c libelf_uninit.c libelf_load.c \
libelf_unload.c libelf_verify.c libelf_read.c \
- libelf_bind.c
+ libelf_bind.c libelf_symbols.c
# Hook the libelf subdirectory into the build
VPATH += libelf
SUBDIRS += libelf
+DEPPATH += --dep-path libelf
endif
diff --git a/nuttx/binfmt/libelf/arm.h b/nuttx/binfmt/libelf/arm.h
deleted file mode 100644
index e80457b6e..000000000
--- a/nuttx/binfmt/libelf/arm.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/****************************************************************************
- * binfmt/libelf/arm.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_ARM_H
-#define __BINFMT_LIBELF_ARM_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-#endif /* __BINFMT_LIBELF_ARM_H */
diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h
index ed352865c..a7ffbc6a6 100644
--- a/nuttx/binfmt/libelf/libelf.h
+++ b/nuttx/binfmt/libelf/libelf.h
@@ -42,8 +42,11 @@
#include <nuttx/config.h>
+#include <sys/types.h>
#include <elf.h>
+#include <nuttx/binfmt/elf.h>
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -53,14 +56,58 @@
****************************************************************************/
/****************************************************************************
- * Name: arch_checkarch
+ * 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'
+ *
+ * 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_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:
- * Given the ELF header in hdr, verify that the ELF file is appropriate
- * for the current, configured architecture.
+ * Read the ELFT symbol structure at the specfied index into memory.
*
****************************************************************************/
-bool arch_checkarch(const struct Elf32_Ehdr *hdr);
+int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
+ FAR Elf32_Sym *sym);
#endif /* __BINFMT_LIBELF_LIBELF_H */
diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c
index 74b713b9e..dd75809ec 100644
--- a/nuttx/binfmt/libelf/libelf_bind.c
+++ b/nuttx/binfmt/libelf/libelf_bind.c
@@ -49,6 +49,8 @@
#include <nuttx/binfmt/elf.h>
#include <nuttx/binfmt/symtab.h>
+#include "libelf.h"
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -80,6 +82,120 @@
****************************************************************************/
/****************************************************************************
+ * Name: elf_readsym
+ *
+ * Description:
+ * Read the ELFT symbol structure at the specfied index 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 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 */
+
+ 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;
+ }
+
+ /* 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;
+
+ /* Now perform the architecture-specific relocation */
+
+ ret = arch_relocate(&rel, &sym, addr);
+ if (ret < 0)
+ {
+ bdbg("Section %d reloc %d: Relocation failed: %d\n", ret);
+ return ret;
+ }
+ }
+
+ return OK;
+}
+
+static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx)
+{
+ bdbg("Not implemented\n");
+ return -ENOSYS;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -99,7 +215,58 @@
int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
FAR const struct symtab_s *exports, int nexports)
{
-#warning "Missing logic"
- return -ENOSYS;
+ int ret;
+ int i;
+
+ /* Find the symbol and string tables */
+
+ ret = elf_findsymtab(loadinfo);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* 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);
+ }
+ else if (loadinfo->shdr[i].sh_type == SHT_RELA)
+ {
+ ret = elf_relocateadd(loadinfo, i);
+ }
+
+ if (ret < 0)
+ {
+ break;
+ }
+ }
+
+ /* Flush the instruction cache before starting the newly loaded module */
+
+ arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize);
+ return ret;
}
diff --git a/nuttx/binfmt/libelf/libelf_init.c b/nuttx/binfmt/libelf/libelf_init.c
index cf62666b9..a3a320b16 100644
--- a/nuttx/binfmt/libelf/libelf_init.c
+++ b/nuttx/binfmt/libelf/libelf_init.c
@@ -49,6 +49,8 @@
#include <nuttx/binfmt/elf.h>
+#include "libelf.h"
+
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -114,7 +116,7 @@ int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo)
/* Read the ELF ehdr from offset 0 */
- ret = elf_read(loadinfo, (char*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0);
+ ret = elf_read(loadinfo, (FAR uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0);
if (ret < 0)
{
bdbg("Failed to read ELF header: %d\n", ret);
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
index c30c109ce..127ebb314 100644
--- a/nuttx/binfmt/libelf/libelf_load.c
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -46,11 +46,15 @@
#include <stdlib.h>
#include <unistd.h>
#include <elf.h>
-#include <debug.h>
+#include <assert.h>
#include <errno.h>
+#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/elf.h>
+#include "libelf.h"
+
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -104,7 +108,7 @@ static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo)
if (!S_ISREG(buf.st_mode))
{
bdbg("Not a regular file. mode: %d\n", buf.st_mode);
- return -errval;
+ return -ENOENT;
}
/* TODO: Verify that the file is readable */
@@ -132,20 +136,20 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
size_t shdrsize;
int ret;
- DEBUGASSERT(loadinfo->shdrs == NULL);
+ DEBUGASSERT(loadinfo->shdr == NULL);
/* Verify that there are sections */
- if (loadinfo->e_shum < 1)
+ if (loadinfo->ehdr.e_shnum < 1)
{
- bdbg("No section(?)\n");
+ bdbg("No sections(?)\n");
return -EINVAL;
}
/* Get the total size of the section header table */
- shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->e_shum;
- if(loadinfo->e_shoff + shdrsize > loadinfo->filelen)
+ shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->ehdr.e_shnum;
+ if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen)
{
bdbg("Insufficent space in file for section header table\n");
return -ESPIPE;
@@ -153,8 +157,8 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
/* Allocate memory to hold a working copy of the sector header table */
- loadinfo->shdrs = (FAR Elf32_Shdr*)kmalloc(shdrsize);
- if (!loadinfo->shdrs)
+ loadinfo->shdr = (FAR Elf32_Shdr*)kmalloc(shdrsize);
+ if (!loadinfo->shdr)
{
bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize);
return -ENOMEM;
@@ -162,7 +166,7 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
/* Read the section header table into memory */
- ret = elf_read(loadinfo, loadinfo->shdrs, shdrsize, loadinfo->e_shoff);
+ ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->shdr, shdrsize, loadinfo->ehdr.e_shoff);
if (ret < 0)
{
bdbg("Failed to read section header table: %d\n", ret);
@@ -172,8 +176,8 @@ static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
return OK;
errout_with_alloc:
- kfree(loadinfo->shdrs);
- loadinfo->shdrs = 0;
+ kfree(loadinfo->shdr);
+ loadinfo->shdr = 0;
return ret;
}
@@ -189,7 +193,7 @@ errout_with_alloc:
*
****************************************************************************/
-static void elf_allocsize(struct load_info *loadinfo)
+static void elf_allocsize(struct elf_loadinfo_s *loadinfo)
{
size_t allocsize;
int i;
@@ -199,7 +203,7 @@ static void elf_allocsize(struct load_info *loadinfo)
allocsize = 0;
for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
{
- FAR Elf32_Shdr *shdr = &loadinfo->shdrs[i];
+ FAR Elf32_Shdr *shdr = &loadinfo->shdr[i];
/* SHF_ALLOC indicates that the section requires memory during
* execution.
@@ -213,7 +217,7 @@ static void elf_allocsize(struct load_info *loadinfo)
/* Save the allocation size */
- loadinfo->allocize = allocsize;
+ loadinfo->allocsize = allocsize;
}
/****************************************************************************
@@ -221,7 +225,8 @@ static void elf_allocsize(struct load_info *loadinfo)
*
* Description:
* Allocate memory for the file and read the section data into the
- * allocated memory.
+ * 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
@@ -229,14 +234,15 @@ static void elf_allocsize(struct load_info *loadinfo)
*
****************************************************************************/
-static inline int elf_loadfile(FAR struct load_info *loadinfo)
+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. */
- loadinfo->alloc = kzalloc(loadinfo->allocsize);
+ loadinfo->alloc = (uintptr_t)kzalloc(loadinfo->allocsize);
if (!loadinfo->alloc)
{
return -ENOMEM;
@@ -249,7 +255,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo)
for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
{
- FAR Elf32_Shdr *shdr = &loadinfo->shdrs[i];
+ FAR Elf32_Shdr *shdr = &loadinfo->shdr[i];
/* SHF_ALLOC indicates that the section requires memory during
* execution */
@@ -275,7 +281,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo)
}
}
- /* Update sh_addr to point to copy in image. */
+ /* Update sh_addr to point to copy in memory */
shdr->sh_addr = (uintptr_t)dest;
bvdbg("%d. 0x%lx %s\n", (long)shdr->sh_addr, loadinfo->secstrings + shdr->sh_name);
@@ -288,7 +294,7 @@ static inline int elf_loadfile(FAR struct load_info *loadinfo)
return OK;
errout_with_alloc:
- kfree(loadinfo->alloc);
+ kfree((FAR void*)loadinfo->alloc);
loadinfo->alloc = 0;
return ret;
}
@@ -344,15 +350,16 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
goto errout_with_shdrs;
}
+ /* Find static constructors. */
+#warning "Missing logic"
+
return OK;
/* Error exits */
-errout_with_alloc:
- kfree(loadinfo->alloc);
errout_with_shdrs:
- kfree(loadinfo->shdrs);
-errout:
+ kfree(loadinfo->shdr);
+ loadinfo->shdr = NULL;
return ret;
}
diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c
new file mode 100644
index 000000000..4788c874c
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_symbols.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_symbols.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 <elf.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt/elf.h>
+
+#include "libelf.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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)
+{
+ int i;
+
+ /* Find the symbol table section header and its associated string table */
+
+ for (i = 1; i < loadinfo->ehdr.e_shnum; i++)
+ {
+ if (loadinfo->shdr[i].sh_type == SHT_SYMTAB)
+ {
+ loadinfo->symtabidx = i;
+ loadinfo->strtabidx = loadinfo->shdr[i].sh_link;
+ break;
+ }
+ }
+
+ /* Verify that there is a symbol and string table */
+
+ if (loadinfo->symtabidx == 0)
+ {
+ bdbg("No symbols in ELF file\n");
+ return -EINVAL;
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: elf_readsym
+ *
+ * Description:
+ * Read the ELFT symbol structure at the specfied index into memory.
+ *
+ ****************************************************************************/
+
+int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
+ FAR Elf32_Sym *sym)
+{
+ FAR Elf32_Shdr *symtab = &loadinfo->shdr[loadinfo->symtabidx];
+ off_t offset;
+
+ /* Verify that the symbol table index lies within symbol table */
+
+ if (index < 0 || index > (symtab->sh_size / sizeof(Elf32_Sym)))
+ {
+ bdbg("Bad relocation symbol index: %d\n", index);
+ return -EINVAL;
+ }
+
+ /* Get the file offset to the symbol table entry */
+
+ offset = symtab->sh_offset + sizeof(Elf32_Sym) * index;
+
+ /* And, finally, read the symbol table entry into memory */
+
+ return elf_read(loadinfo, (FAR uint8_t*)sym, sizeof(Elf32_Sym), offset);
+}
diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c
index 217a1981e..ca8d2b708 100644
--- a/nuttx/binfmt/libelf/libelf_unload.c
+++ b/nuttx/binfmt/libelf/libelf_unload.c
@@ -39,10 +39,10 @@
#include <nuttx/config.h>
-#include <sys/mman.h>
#include <stdlib.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/elf.h>
/****************************************************************************
@@ -81,14 +81,14 @@ int elf_unload(struct elf_loadinfo_s *loadinfo)
if (loadinfo->alloc)
{
kfree((void*)loadinfo->alloc);
- loadinfo->alloc = NULL;
+ loadinfo->alloc = 0;
loadinfo->allocsize = 0;
}
- if (loadinfo->shdrs)
+ if (loadinfo->shdr)
{
- kfree((void*)loadinfo->shdrs);
- loadinfo->shdrs = 0;
+ kfree((void*)loadinfo->shdr);
+ loadinfo->shdr = NULL;
}
return OK;
diff --git a/nuttx/binfmt/libelf/libelf_verify.c b/nuttx/binfmt/libelf/libelf_verify.c
index 0e0dd8e1a..c5f185ec3 100644
--- a/nuttx/binfmt/libelf/libelf_verify.c
+++ b/nuttx/binfmt/libelf/libelf_verify.c
@@ -53,7 +53,7 @@
* Private Constant Data
****************************************************************************/
-static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' }
+static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' };
/****************************************************************************
* Private Functions
@@ -75,12 +75,12 @@ static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' }
* failure.
*
* -ENOEXEC : Not an ELF file
- * -EINVALID : Not a relocatable ELF file or not supported by the current,
+ * -EINVAL : Not a relocatable ELF file or not supported by the current,
* configured architecture.
*
****************************************************************************/
-int elf_verifyheader(const Elf32_Ehdr *ehdr)
+int elf_verifyheader(FAR const Elf32_Ehdr *ehdr)
{
if (!ehdr)
{
@@ -102,7 +102,7 @@ int elf_verifyheader(const Elf32_Ehdr *ehdr)
if (ehdr->e_type != ET_REL)
{
bdbg("Not a relocatable file: e_type=%d\n", ehdr->e_type);
- return -EINVALID;
+ return -EINVAL;
}
/* Verify that this file works with the currently configured architecture */