C++ static destructors work with ELF load too now

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5274 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2012-10-29 20:43:35 +00:00
parent 5681b615ec
commit b48508c844
13 changed files with 344 additions and 89 deletions

View File

@ -91,7 +91,7 @@ int dump_module(FAR const struct binary_s *bin)
bdbg(" argv: %p\n", bin->argv); bdbg(" argv: %p\n", bin->argv);
bdbg(" entrypt: %p\n", bin->entrypt); bdbg(" entrypt: %p\n", bin->entrypt);
bdbg(" mapped: %p size=%d\n", bin->mapped, bin->mapsize); bdbg(" mapped: %p size=%d\n", bin->mapped, bin->mapsize);
bdbg(" alloc: %p %p\n", bin->alloc[0], bin->alloc[1]); bdbg(" alloc: %p %p %p\n", bin->alloc[0], bin->alloc[1], bin->alloc[2]);
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors); bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors);
bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors); bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors);

View File

@ -88,7 +88,7 @@
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
static inline void exec_ctors(FAR const struct binary_s *binp) static inline void exec_ctors(FAR const struct binary_s *binp)
{ {
elf_ctor_t *ctor = binp->ctors; binfmt_ctor_t *ctor = binp->ctors;
int i; int i;
/* Execute each constructor */ /* Execute each constructor */

View File

@ -85,7 +85,7 @@
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
static inline void exec_dtors(FAR const struct binary_s *binp) static inline void exec_dtors(FAR const struct binary_s *binp)
{ {
elf_dtor_t *dtor = binp->dtors; binfmt_dtor_t *dtor = binp->dtors;
int i; int i;
/* Execute each destructor */ /* Execute each destructor */

View File

@ -111,12 +111,16 @@ static void elf_dumploadinfo(FAR struct elf_loadinfo_s *loadinfo)
int i; int i;
bdbg("LOAD_INFO:\n"); bdbg("LOAD_INFO:\n");
bdbg(" alloc: %08lx\n", (long)loadinfo->alloc); bdbg(" elfalloc: %08lx\n", (long)loadinfo->elfalloc);
bdbg(" allocsize: %ld\n", (long)loadinfo->allocsize); bdbg(" elfsize: %ld\n", (long)loadinfo->elfsize);
bdbg(" filelen: %ld\n", (long)loadinfo->filelen); bdbg(" filelen: %ld\n", (long)loadinfo->filelen);
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
bdbg(" ctoralloc: %08lx\n", (long)loadinfo->ctoralloc);
bdbg(" ctors: %08lx\n", (long)loadinfo->ctors); bdbg(" ctors: %08lx\n", (long)loadinfo->ctors);
bdbg(" nctors: %d\n", loadinfo->nctors); bdbg(" nctors: %d\n", loadinfo->nctors);
bdbg(" dtoralloc: %08lx\n", (long)loadinfo->dtoralloc);
bdbg(" dtors: %08lx\n", (long)loadinfo->dtors);
bdbg(" ndtors: %d\n", loadinfo->ndtors);
#endif #endif
bdbg(" filfd: %d\n", loadinfo->filfd); bdbg(" filfd: %d\n", loadinfo->filfd);
bdbg(" symtabidx: %d\n", loadinfo->symtabidx); bdbg(" symtabidx: %d\n", loadinfo->symtabidx);
@ -210,8 +214,8 @@ static int elf_loadbinary(struct binary_s *binp)
/* Return the load information */ /* Return the load information */
binp->entrypt = (main_t)(loadinfo.alloc + loadinfo.ehdr.e_entry); binp->entrypt = (main_t)(loadinfo.elfalloc + loadinfo.ehdr.e_entry);
binp->alloc[0] = (FAR void *)loadinfo.alloc; binp->alloc[0] = (FAR void *)loadinfo.elfalloc;
binp->stacksize = CONFIG_ELF_STACKSIZE; binp->stacksize = CONFIG_ELF_STACKSIZE;
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
@ -219,19 +223,13 @@ static int elf_loadbinary(struct binary_s *binp)
* yet supported. * yet supported.
*/ */
binp->ctors = loadinfo.ctors; binp->alloc[1] = loadinfo.ctoralloc;
binp->nctors = loadinfo.nctors; binp->ctors = loadinfo.ctors;
binp->nctors = loadinfo.nctors;
/* Was memory allocated for constructors? */ binp->alloc[2] = loadinfo.dtoralloc;
binp->dtors = loadinfo.dtors;
if (!loadinfo.newabi) binp->ndtors = loadinfo.ndtors;
{
/* Yes.. save the allocation address so that it can be freed by
* unload module.
*/
binp->alloc[1] = (FAR void *)loadinfo.ctors;
}
#endif #endif
elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt, elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,

View File

@ -46,7 +46,7 @@ BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_iobuffer.c libelf_load.c \
libelf_unload.c libelf_verify.c libelf_unload.c libelf_verify.c
ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y) ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y)
BINFMT_CSRCS += libelf_ctors.c BINFMT_CSRCS += libelf_ctors.c libelf_dtors.c
endif endif
# Hook the libelf subdirectory into the build # Hook the libelf subdirectory into the build

View File

@ -236,4 +236,23 @@ int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment);
int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo); int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo);
#endif #endif
/****************************************************************************
* Name: elf_loaddtors
*
* Description:
* Load pointers to static destructors into an in-memory array.
*
* Input Parameters:
* loadinfo - Load state information
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
****************************************************************************/
#ifdef CONFIG_BINFMT_CONSTRUCTORS
int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo);
#endif
#endif /* __BINFMT_LIBELF_LIBELF_H */ #endif /* __BINFMT_LIBELF_LIBELF_H */

View File

@ -298,7 +298,7 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
/* Flush the instruction cache before starting the newly loaded module */ /* Flush the instruction cache before starting the newly loaded module */
#ifdef CONFIG_ELF_ICACHE #ifdef CONFIG_ELF_ICACHE
arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize); arch_flushicache((FAR void*)loadinfo->elfalloc, loadinfo->elfsize);
#endif #endif
return ret; return ret;

View File

@ -75,7 +75,7 @@
* Name: elf_loadctors * Name: elf_loadctors
* *
* Description: * Description:
* Load points to static constructors into an in-memory array. * Load pointers to static constructors into an in-memory array.
* *
* Input Parameters: * Input Parameters:
* loadinfo - Load state information * loadinfo - Load state information
@ -96,8 +96,8 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
DEBUGASSERT(loadinfo->ctors == NULL); DEBUGASSERT(loadinfo->ctors == NULL);
/* Allocate an I/O buffer. This buffer is used by elf_sectname() to /* Allocate an I/O buffer if necessary. This buffer is used by
* accumulate the variable length symbol name. * elf_sectname() to accumulate the variable length symbol name.
*/ */
ret = elf_allocbuffer(loadinfo); ret = elf_allocbuffer(loadinfo);
@ -110,7 +110,7 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
/* Find the index to the section named ".ctors." NOTE: On old ABI system, /* Find the index to the section named ".ctors." NOTE: On old ABI system,
* .ctors is the name of the section containing the list of constructors; * .ctors is the name of the section containing the list of constructors;
* On newer systems, the similar section is called .init_array. It is * On newer systems, the similar section is called .init_array. It is
* expected that the linker script will force the sectino name to be ".ctors" * expected that the linker script will force the section name to be ".ctors"
* in either case. * in either case.
*/ */
@ -136,10 +136,10 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
*/ */
ctorsize = shdr->sh_size; ctorsize = shdr->sh_size;
loadinfo->nctors = ctorsize / sizeof(elf_ctor_t); loadinfo->nctors = ctorsize / sizeof(binfmt_ctor_t);
bvdbg("ctoridx=%d ctorsize=%d sizeof(elf_ctor_t)=%d nctors=%d\n", bvdbg("ctoridx=%d ctorsize=%d sizeof(binfmt_ctor_t)=%d nctors=%d\n",
ctoridx, ctorsize, sizeof(elf_ctor_t), loadinfo->nctors); ctoridx, ctorsize, sizeof(binfmt_ctor_t), loadinfo->nctors);
/* Check if there are any constructors. It is not an error if there /* Check if there are any constructors. It is not an error if there
* are none. * are none.
@ -149,7 +149,7 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
{ {
/* Check an assumption that we made above */ /* Check an assumption that we made above */
DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(elf_ctor_t)); DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(binfmt_ctor_t));
/* In the old ABI, the .ctors section is not allocated. In that case, /* In the old ABI, the .ctors section is not allocated. In that case,
* we need to allocate memory to hold the .ctors and then copy the * we need to allocate memory to hold the .ctors and then copy the
@ -161,19 +161,17 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
if ((shdr->sh_flags & SHF_ALLOC) == 0) if ((shdr->sh_flags & SHF_ALLOC) == 0)
{ {
/* Not loaded -> Old ABI. */
loadinfo->newabi = false;
/* Allocate memory to hold a copy of the .ctor section */ /* Allocate memory to hold a copy of the .ctor section */
loadinfo->ctors = (elf_ctor_t*)kmalloc(ctorsize); loadinfo->ctoralloc = (binfmt_ctor_t*)kmalloc(ctorsize);
if (!loadinfo->ctors) if (!loadinfo->ctoralloc)
{ {
bdbg("Failed to allocate memory for .ctors\n"); bdbg("Failed to allocate memory for .ctors\n");
return -ENOMEM; return -ENOMEM;
} }
loadinfo->ctors = (binfmt_ctor_t *)loadinfo->ctoralloc;
/* Read the section header table into memory */ /* Read the section header table into memory */
ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize, ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize,
@ -194,23 +192,20 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]); FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]);
bvdbg("ctor %d: %08lx + %08lx = %08lx\n", bvdbg("ctor %d: %08lx + %08lx = %08lx\n",
i, *ptr, loadinfo->alloc, *ptr + loadinfo->alloc); i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc);
*ptr += loadinfo->alloc; *ptr += loadinfo->elfalloc;
} }
} }
else else
{ {
/* Loaded -> New ABI. */
loadinfo->newabi = true;
/* Save the address of the .ctors (actually, .init_array) where it was /* Save the address of the .ctors (actually, .init_array) where it was
* loaded into memory. Since the .ctors lie in allocated memory, they * loaded into memory. Since the .ctors lie in allocated memory, they
* will be relocated via the normal mechanism. * will be relocated via the normal mechanism.
*/ */
loadinfo->ctors = (elf_ctor_t*)shdr->sh_addr; loadinfo->ctors = (binfmt_ctor_t*)shdr->sh_addr;
} }
} }

View File

@ -0,0 +1,215 @@
/****************************************************************************
* binfmt/libelf/libelf_dtors.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <string.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/elf.h>
#include "libelf.h"
#ifdef CONFIG_BINFMT_CONSTRUCTORS
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Constant Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: elf_loaddtors
*
* Description:
* Load pointers to static destructors into an in-memory array.
*
* Input Parameters:
* loadinfo - Load state information
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
****************************************************************************/
int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo)
{
FAR Elf32_Shdr *shdr;
size_t dtorsize;
int dtoridx;
int ret;
int i;
DEBUGASSERT(loadinfo->dtors == NULL);
/* Allocate an I/O buffer if necessary. This buffer is used by
* elf_sectname() to accumulate the variable length symbol name.
*/
ret = elf_allocbuffer(loadinfo);
if (ret < 0)
{
bdbg("elf_allocbuffer failed: %d\n", ret);
return -ENOMEM;
}
/* Find the index to the section named ".dtors." NOTE: On old ABI system,
* .dtors is the name of the section containing the list of destructors;
* On newer systems, the similar section is called .fini_array. It is
* expected that the linker script will force the section name to be ".dtors"
* in either case.
*/
dtoridx = elf_findsection(loadinfo, ".dtors");
if (dtoridx < 0)
{
/* This may not be a failure. -ENOENT indicates that the file has no
* static destructor section.
*/
bvdbg("elf_findsection .dtors section failed: %d\n", dtoridx);
return ret == -ENOENT ? OK : ret;
}
/* Now we can get a pointer to the .dtor section in the section header
* table.
*/
shdr = &loadinfo->shdr[dtoridx];
/* Get the size of the .dtor section and the number of destructors that
* will need to be called.
*/
dtorsize = shdr->sh_size;
loadinfo->ndtors = dtorsize / sizeof(binfmt_dtor_t);
bvdbg("dtoridx=%d dtorsize=%d sizeof(binfmt_dtor_t)=%d ndtors=%d\n",
dtoridx, dtorsize, sizeof(binfmt_dtor_t), loadinfo->ndtors);
/* Check if there are any destructors. It is not an error if there
* are none.
*/
if (loadinfo->ndtors > 0)
{
/* Check an assumption that we made above */
DEBUGASSERT(shdr->sh_size == loadinfo->ndtors * sizeof(binfmt_dtor_t));
/* In the old ABI, the .dtors section is not allocated. In that case,
* we need to allocate memory to hold the .dtors and then copy the
* from the file into the allocated memory.
*
* SHF_ALLOC indicates that the section requires memory during
* execution.
*/
if ((shdr->sh_flags & SHF_ALLOC) == 0)
{
/* Allocate memory to hold a copy of the .dtor section */
loadinfo->ctoralloc = (binfmt_dtor_t*)kmalloc(dtorsize);
if (!loadinfo->ctoralloc)
{
bdbg("Failed to allocate memory for .dtors\n");
return -ENOMEM;
}
loadinfo->dtors = (binfmt_dtor_t *)loadinfo->ctoralloc;
/* Read the section header table into memory */
ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->dtors, dtorsize,
shdr->sh_offset);
if (ret < 0)
{
bdbg("Failed to allocate .dtors: %d\n", ret);
return ret;
}
/* Fix up all of the .dtor addresses. Since the addresses
* do not lie in allocated memory, there will be no relocation
* section for them.
*/
for (i = 0; i < loadinfo->ndtors; i++)
{
FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->dtors)[i]);
bvdbg("dtor %d: %08lx + %08lx = %08lx\n",
i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc);
*ptr += loadinfo->elfalloc;
}
}
else
{
/* Save the address of the .dtors (actually, .init_array) where it was
* loaded into memory. Since the .dtors lie in allocated memory, they
* will be relocated via the normal mechanism.
*/
loadinfo->dtors = (binfmt_dtor_t*)shdr->sh_addr;
}
}
return OK;
}
#endif /* CONFIG_BINFMT_CONSTRUCTORS */

View File

@ -76,7 +76,7 @@
****************************************************************************/ ****************************************************************************/
/**************************************************************************** /****************************************************************************
* Name: elf_allocsize * Name: elf_elfsize
* *
* Description: * Description:
* Calculate total memory allocation for the ELF file. * Calculate total memory allocation for the ELF file.
@ -87,14 +87,14 @@
* *
****************************************************************************/ ****************************************************************************/
static void elf_allocsize(struct elf_loadinfo_s *loadinfo) static void elf_elfsize(struct elf_loadinfo_s *loadinfo)
{ {
size_t allocsize; size_t elfsize;
int i; int i;
/* Accumulate the size each section into memory that is marked SHF_ALLOC */ /* Accumulate the size each section into memory that is marked SHF_ALLOC */
allocsize = 0; elfsize = 0;
for (i = 0; i < loadinfo->ehdr.e_shnum; i++) for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
{ {
FAR Elf32_Shdr *shdr = &loadinfo->shdr[i]; FAR Elf32_Shdr *shdr = &loadinfo->shdr[i];
@ -105,13 +105,13 @@ static void elf_allocsize(struct elf_loadinfo_s *loadinfo)
if ((shdr->sh_flags & SHF_ALLOC) != 0) if ((shdr->sh_flags & SHF_ALLOC) != 0)
{ {
allocsize += ELF_ALIGNUP(shdr->sh_size); elfsize += ELF_ALIGNUP(shdr->sh_size);
} }
} }
/* Save the allocation size */ /* Save the allocation size */
loadinfo->allocsize = allocsize; loadinfo->elfsize = elfsize;
} }
/**************************************************************************** /****************************************************************************
@ -136,8 +136,8 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
/* Allocate (and zero) memory for the ELF file. */ /* Allocate (and zero) memory for the ELF file. */
loadinfo->alloc = (uintptr_t)kzalloc(loadinfo->allocsize); loadinfo->elfalloc = (uintptr_t)kzalloc(loadinfo->elfsize);
if (!loadinfo->alloc) if (!loadinfo->elfalloc)
{ {
return -ENOMEM; return -ENOMEM;
} }
@ -145,7 +145,7 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
/* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */ /* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */
bvdbg("Loaded sections:\n"); bvdbg("Loaded sections:\n");
dest = (FAR uint8_t*)loadinfo->alloc; dest = (FAR uint8_t*)loadinfo->elfalloc;
for (i = 0; i < loadinfo->ehdr.e_shnum; i++) for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
{ {
@ -223,7 +223,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
/* Determine total size to allocate */ /* Determine total size to allocate */
elf_allocsize(loadinfo); elf_elfsize(loadinfo);
/* Allocate memory and load sections into memory */ /* Allocate memory and load sections into memory */
@ -234,7 +234,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
goto errout_with_buffers; goto errout_with_buffers;
} }
/* Find static constructors. */ /* Load static constructors and destructors. */
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
ret = elf_loadctors(loadinfo); ret = elf_loadctors(loadinfo);
@ -243,6 +243,13 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
bdbg("elf_loadctors failed: %d\n", ret); bdbg("elf_loadctors failed: %d\n", ret);
goto errout_with_buffers; goto errout_with_buffers;
} }
ret = elf_loaddtors(loadinfo);
if (ret < 0)
{
bdbg("elf_loaddtors failed: %d\n", ret);
goto errout_with_buffers;
}
#endif #endif
return OK; return OK;
@ -250,7 +257,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
/* Error exits */ /* Error exits */
errout_with_buffers: errout_with_buffers:
elf_freebuffers(loadinfo); elf_unload(loadinfo);
return ret; return ret;
} }

View File

@ -84,31 +84,34 @@ int elf_unload(struct elf_loadinfo_s *loadinfo)
/* Release memory holding the relocated ELF image */ /* Release memory holding the relocated ELF image */
if (loadinfo->alloc) if (loadinfo->elfalloc != 0)
{ {
kfree((FAR void *)loadinfo->alloc); kfree((FAR void *)loadinfo->elfalloc);
loadinfo->alloc = 0; loadinfo->elfalloc = 0;
loadinfo->allocsize = 0;
} }
/* Release any allocated constructor memory */ loadinfo->elfsize = 0;
/* Release memory used to hold static constructors and destructors */
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
if (loadinfo->ctors) if (loadinfo->ctoralloc != 0)
{ {
/* In the old ABI, the .ctors section is not make for allocation. In kfree(loadinfo->ctoralloc);
* that case, we need to free the working buffer that was used to hold loadinfo->ctoralloc = NULL;
* the constructors.
*/
if (!loadinfo->newabi)
{
kfree((FAR void *)loadinfo->ctors);
}
loadinfo->ctors = NULL;
loadinfo->nctors = 0;
} }
loadinfo->ctors = NULL;
loadinfo->nctors = 0;
if (loadinfo->dtoralloc != 0)
{
kfree(loadinfo->dtoralloc);
loadinfo->dtoralloc = NULL;
}
loadinfo->dtors = NULL;
loadinfo->ndtors = 0;
#endif #endif
return OK; return OK;

View File

@ -49,15 +49,15 @@
* Pre-processor Definitions * Pre-processor Definitions
****************************************************************************/ ****************************************************************************/
#define BINFMT_NALLOC 2 #define BINFMT_NALLOC 3
/**************************************************************************** /****************************************************************************
* Public Types * Public Types
****************************************************************************/ ****************************************************************************/
/* The type of one C++ constructor or destructor */ /* The type of one C++ constructor or destructor */
typedef FAR void (*elf_ctor_t)(void); typedef FAR void (*binfmt_ctor_t)(void);
typedef FAR void (*elf_dtor_t)(void); typedef FAR void (*binfmt_dtor_t)(void);
/* This describes the file to be loaded */ /* This describes the file to be loaded */
@ -79,8 +79,8 @@ struct binary_s
FAR void *mapped; /* Memory-mapped, address space */ FAR void *mapped; /* Memory-mapped, address space */
FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */ FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
elf_ctor_t *ctors; /* Pointer to a list of constructors */ FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */
elf_dtor_t *dtors; /* Pointer to a list of destructors */ FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */
uint16_t nctors; /* Number of constructors in the list */ uint16_t nctors; /* Number of constructors in the list */
uint16_t ndtors; /* Number of destructors in the list */ uint16_t ndtors; /* Number of destructors in the list */
#endif #endif

View File

@ -59,6 +59,17 @@
# define CONFIG_ELF_ALIGN_LOG2 2 # define CONFIG_ELF_ALIGN_LOG2 2
#endif #endif
/* Allocation array size and indices */
#define LIBELF_ELF_ALLOC 0
#ifdef CONFIG_BINFMT_CONSTRUCTORS
# define LIBELF_CTORS_ALLOC 1
# define LIBELF_CTPRS_ALLOC 2
# define LIBELF_NALLOC 3
#else
# define LIBELF_NALLOC 1
#endif
/**************************************************************************** /****************************************************************************
* Public Types * Public Types
****************************************************************************/ ****************************************************************************/
@ -69,21 +80,28 @@
struct elf_loadinfo_s struct elf_loadinfo_s
{ {
uintptr_t alloc; /* Allocated memory with the ELF file is loaded */ /* The alloc[] array holds memory that persists after the ELF module has
size_t allocsize; /* Size of the memory allocation */ * been loaded.
off_t filelen; /* Length of the entire ELF file */ */
Elf32_Ehdr ehdr; /* Buffered ELF file header */
FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */ uintptr_t elfalloc; /* Memory allocated when ELF file was loaded */
uint8_t *iobuffer; /* File I/O buffer */ size_t elfsize; /* Size of the ELF memory allocation */
off_t filelen; /* Length of the entire ELF file */
Elf32_Ehdr ehdr; /* Buffered ELF file header */
FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */
uint8_t *iobuffer; /* File I/O buffer */
#ifdef CONFIG_BINFMT_CONSTRUCTORS #ifdef CONFIG_BINFMT_CONSTRUCTORS
elf_ctor_t *ctors; /* Pointer to a list of constructors */ FAR void *ctoralloc; /* Memory allocated for ctors */
bool newabi; /* True: ctors in 'alloc' */ FAR void *dtoralloc; /* Memory allocated dtors */
uint16_t nctors; /* Number of constructors */ FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */
FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */
uint16_t nctors; /* Number of constructors */
uint16_t ndtors; /* Number of destructors */
#endif #endif
uint16_t symtabidx; /* Symbol table section index */ uint16_t symtabidx; /* Symbol table section index */
uint16_t strtabidx; /* String table section index */ uint16_t strtabidx; /* String table section index */
uint16_t buflen; /* size of iobuffer[] */ uint16_t buflen; /* size of iobuffer[] */
int filfd; /* Descriptor for the file being loaded */ int filfd; /* Descriptor for the file being loaded */
}; };
/**************************************************************************** /****************************************************************************