A little more ELF loader logic

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5257 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2012-10-25 16:18:20 +00:00
parent a91b6552cd
commit 630862cd04
15 changed files with 568 additions and 153 deletions

View File

@ -1,5 +1,5 @@
/****************************************************************************
* binfmt/libelf/arm.h
* arch/arm/src/common/arm-elf.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -33,8 +33,8 @@
*
****************************************************************************/
#ifndef __BINFMT_LIBELF_ARM_H
#define __BINFMT_LIBELF_ARM_H
#ifndef __ARCH_ARM_SRC_ARM_ELF_H
#define __ARCH_ARM_SRC_ARM_ELF_H
/****************************************************************************
* Included Files
@ -50,4 +50,4 @@
* Public Types
****************************************************************************/
#endif /* __BINFMT_LIBELF_ARM_H */
#endif /* __ARCH_ARM_SRC_ARM_ELF_H */

View File

@ -56,6 +56,7 @@ BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \
VPATH =
SUBDIRS =
DEPPATH = --dep-path .
include libnxflat/Make.defs
include libelf/Make.defs
@ -82,8 +83,7 @@ $(BIN): $(BINFMT_OBJS)
done ; )
.depend: Makefile $(BINFMT_SRCS)
@$(MKDEP) --dep-path . --dep-path libnxflat \
$(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
@$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(BINFMT_SRCS) >Make.dep
@touch $@
depend: .depend

View File

@ -64,6 +64,10 @@
# 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
@ -104,33 +108,55 @@ static struct binfmt_s g_elfbinfmt =
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo)
{
unsigned long dsize = loadinfo->datasize + loadinfo->bsssize;
int i;
bdbg("LOAD_INFO:\n");
bdbg(" ISPACE:\n");
bdbg(" ispace: %08lx\n", loadinfo->ispace);
bdbg(" entryoffs: %08lx\n", loadinfo->entryoffs);
bdbg(" isize: %08lx\n", loadinfo->isize);
bdbg(" alloc: %08lx\n", (long)loadinfo->alloc);
bdbg(" allocsize: %ld\n", (long)loadinfo->allocsize);
bdbg(" filelen: %ld\n", (long)loadinfo->filelen);
#ifdef CONFIG_ELF_CONSTRUCTORS
bdbg(" ctors: %08lx\n", (long)loadinfo->ctors);
#endif
bdbg(" filfd: %d\n", loadinfo->filfd);
bdbg(" symtabidx: %d\n", loadinfo->symtabidx);
bdbg(" strtabidx: %d\n", loadinfo->strtabidx);
bdbg(" DSPACE:\n");
bdbg(" dspace: %08lx\n", loadinfo->dspace);
if (loadinfo->dspace != NULL)
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_shum > 0)
{
bdbg(" crefs: %d\n", loadinfo->dspace->crefs);
bdbg(" region: %08lx\n", loadinfo->dspace->region);
for (i = 0; i < loadinfo->ehdr.e_shum; 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);
}
}
bdbg(" datasize: %08lx\n", loadinfo->datasize);
bdbg(" bsssize: %08lx\n", loadinfo->bsssize);
bdbg(" (pad): %08lx\n", loadinfo->dsize - dsize);
bdbg(" stacksize: %08lx\n", loadinfo->stacksize);
bdbg(" dsize: %08lx\n", loadinfo->dsize);
bdbg(" RELOCS:\n");
bdbg(" relocstart: %08lx\n", loadinfo->relocstart);
bdbg(" reloccount: %d\n", loadinfo->reloccount);
bdbg(" HANDLES:\n");
bdbg(" filfd: %d\n", loadinfo->filfd);
}
#else
# define elf_dumploadinfo(i)
@ -148,7 +174,7 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo)
static int elf_loadbinary(struct binary_s *binp)
{
struct elf_loadinfo_s loadinfo; /* Contains globals for libelf */
int ret;
int ret;
bvdbg("Loading file: %s\n", binp->filename);
@ -183,14 +209,14 @@ static int elf_loadbinary(struct binary_s *binp)
/* Return the load information */
binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs);
binp->ispace = (void*)loadinfo.ispace;
binp->dspace = (void*)loadinfo.dspace;
binp->isize = loadinfo.isize;
binp->stacksize = loadinfo.stacksize;
binp->entrypt = (main_t)(loadinfo.alloc + loadinfo.ehdr.e_entry);
binp->ispace = (void*)loadinfo.alloc;
binp->dspace = NULL;
binp->isize = loadinfo.allocsize;
binp->stacksize = CONFIG_ELF_STACKSIZE;
elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,
MIN(binp->isize - loadinfo.entryoffs,512));
MIN(binp->isize - loadinfo.ehdr.e_entry, 512));
elf_uninit(&loadinfo);
return OK;

View File

@ -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

View File

@ -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

View File

@ -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 ELF header in hdr, verify that the ELF file is appropriate
* for the current, configured architecture.
* 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.
*
****************************************************************************/
bool arch_checkarch(const struct Elf32_Ehdr *hdr);
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:
* 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);
#endif /* __BINFMT_LIBELF_LIBELF_H */

View File

@ -49,6 +49,8 @@
#include <nuttx/binfmt/elf.h>
#include <nuttx/binfmt/symtab.h>
#include "libelf.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@ -79,6 +81,120 @@
* Private Functions
****************************************************************************/
/****************************************************************************
* 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;
}

View File

@ -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);

View File

@ -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;
}

View File

@ -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);
}

View File

@ -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;

View File

@ -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 */

View File

@ -49,5 +49,6 @@ BINFMT_CSRCS = libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \
VPATH += libnxflat
SUBDIRS += libnxflat
DEPPATH += --dep-path libnxflat
endif

View File

@ -231,73 +231,73 @@
/* Figure 4.2: 32-Bit Data Types */
typedef uint32_t ELF32_Addr /* Unsigned program address */
typedef uint16_t ELF32_Half /* Unsigned medium integer */
typedef uint32_t ELF32_Off /* Unsigned file offset */
typedef int32_t ELF32_Sword /* Signed large integer */
typedef uint32_t ELF32_Word /* Unsigned large integer */
typedef uint32_t Elf32_Addr; /* Unsigned program address */
typedef uint16_t Elf32_Half; /* Unsigned medium integer */
typedef uint32_t Elf32_Off; /* Unsigned file offset */
typedef int32_t Elf32_Sword; /* Signed large integer */
typedef uint32_t Elf32_Word; /* Unsigned large integer */
/* Figure 4-3: ELF Header */
typedef struct
{
unsigned char e_ident[EI_NIDENT];
ELF32_Half e_type;
ELF32_Half e_machine;
ELF32_Word e_version;
ELF32_Addr e_entry;
ELF32_Off e_phoff;
ELF32_Off e_shoff;
ELF32_Word e_flags;
ELF32_Half e_ehsize;
ELF32_Half e_phentsize;
ELF32_Half e_phnum;
ELF32_Half e_shentsize;
ELF32_Half e_shnum;
ELF32_Half e_shstrndx;
Elf32_Half e_type;
Elf32_Half e_machine;
Elf32_Word e_version;
Elf32_Addr e_entry;
Elf32_Off e_phoff;
Elf32_Off e_shoff;
Elf32_Word e_flags;
Elf32_Half e_ehsize;
Elf32_Half e_phentsize;
Elf32_Half e_phnum;
Elf32_Half e_shentsize;
Elf32_Half e_shnum;
Elf32_Half e_shstrndx;
} Elf32_Ehdr;
/* Figure 4-8: Section Header */
typedef struct
{
ELF32_Word sh_name;
ELF32_Word sh_type;
ELF32_Word sh_flags;
ELF32_Addr sh_addr;
ELF32_Off sh_offset;
ELF32_Word sh_size;
ELF32_Word sh_link;
ELF32_Word sh_info;
ELF32_Word sh_addralign;
ELF32_Word sh_entsize;
Elf32_Word sh_name;
Elf32_Word sh_type;
Elf32_Word sh_flags;
Elf32_Addr sh_addr;
Elf32_Off sh_offset;
Elf32_Word sh_size;
Elf32_Word sh_link;
Elf32_Word sh_info;
Elf32_Word sh_addralign;
Elf32_Word sh_entsize;
} Elf32_Shdr;
/* Figure 4-15: Symbol Table Entry */
typedef struct
{
ELF32_Word st_name;
ELF32_Addr st_value;
ELF32_Word st_size;
Elf32_Word st_name;
Elf32_Addr st_value;
Elf32_Word st_size;
unsigned char st_info;
unsigned char st_other;
ELF32_Half st_shndx;
Elf32_Half st_shndx;
} Elf32_Sym;
/* Figure 4-19: Relocation Entries */
typedef struct
{
ELF32_Addr r_offset;
ELF32_Word r_info;
Elf32_Addr r_offset;
Elf32_Word r_info;
} Elf32_Rel;
typedef struct
{
ELF32_Addr r_offset;
ELF32_Word r_info;
ELF32_Sword r_addend;
Elf32_Addr r_offset;
Elf32_Word r_info;
Elf32_Sword r_addend;
} Elf32_Rela;
/* Figure 5-1: Program Header */

View File

@ -42,9 +42,10 @@
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <elf.h>
#include <nuttx/sched.h>
/****************************************************************************
* Pre-processor Definitions
@ -72,6 +73,8 @@ struct elf_loadinfo_s
uintptr_t ctors; /* Static constructors */
#endif
int filfd; /* Descriptor for the file being loaded */
uint16_t symtabidx; /* Symbol table section index */
uint16_t strtabidx; /* String table section index */
Elf32_Ehdr ehdr; /* Buffered ELF file header */
FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */
};
@ -89,24 +92,9 @@ extern "C" {
#endif
/****************************************************************************
* These are APIs exported by libelf (and may be used outside of NuttX):
* These are APIs exported by libelf (but are used only by the binfmt logic):
****************************************************************************/
/****************************************************************************
* 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.
*
****************************************************************************/
EXTERN int elf_verifyheader(FAR const Elf32_Ehdr *header);
/****************************************************************************
* Name: elf_init
*
@ -153,21 +141,6 @@ EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo);
EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo);
/****************************************************************************
* 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.
*
****************************************************************************/
EXTER int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer,
size_t readsize, off_t offset);
/****************************************************************************
* Name: elf_bind
*
@ -233,6 +206,64 @@ EXTERN int elf_initialize(void);
EXTERN void elf_uninitialize(void);
/****************************************************************************
* Name: arch_checkarch
*
* Description:
* Given the ELF header in 'hdr', verify that the ELF file is appropriate
* for the current, configured architecture. Every architecture that uses
* the ELF loader must provide this function.
*
* Input Parameters:
* hdr - The ELF header read from the ELF file.
*
* Returned Value:
* True if the architecture supports this ELF file.
*
****************************************************************************/
EXTERN bool arch_checkarch(FAR const Elf32_Ehdr *hdr);
/****************************************************************************
* Name: arch_relocate and arch_relocateadd
*
* Description:
* Perform on architecture-specific ELF relocation. Every architecture
* that uses the ELF loader must provide this function.
*
* Input Parameters:
* rel - The relocation type
* sym - The ELF symbol structure containing the fully resolved value.
* addr - The address that requires the relocation.
*
* Returned Value:
* Zero (OK) if the relocation was successful. Otherwise, a negated errno
* value indicating the cause of the relocation failure.
*
****************************************************************************/
EXTERN int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym,
uintptr_t addr);
EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel,
FAR const Elf32_Sym *sym, uintptr_t addr);
/****************************************************************************
* Name: arch_flushicache
*
* Description:
* Flush the instruction cache.
*
* Input Parameters:
* addr - Start address to flush
* len - Number of bytes to flush
*
* Returned Value:
* True if the architecture supports this ELF file.
*
****************************************************************************/
EXTERN bool arch_flushicache(FAR void *addr, size_t len);
#undef EXTERN
#if defined(__cplusplus)
}