summaryrefslogtreecommitdiff
path: root/nuttx/binfmt/libelf
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-29 19:32:05 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-29 19:32:05 +0000
commit9e45144d3ad1420908cfdf84306c76f637829023 (patch)
tree63a4ac04f182a282aac2d649973c99285b12cad5 /nuttx/binfmt/libelf
parentade5fb42679b7e890f29487ca850c65f9944fa1e (diff)
downloadpx4-nuttx-9e45144d3ad1420908cfdf84306c76f637829023.tar.gz
px4-nuttx-9e45144d3ad1420908cfdf84306c76f637829023.tar.bz2
px4-nuttx-9e45144d3ad1420908cfdf84306c76f637829023.zip
C++ constructors work with ELF load now
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5273 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/binfmt/libelf')
-rw-r--r--nuttx/binfmt/libelf/Kconfig7
-rw-r--r--nuttx/binfmt/libelf/Make.defs8
-rw-r--r--nuttx/binfmt/libelf/libelf.h54
-rw-r--r--nuttx/binfmt/libelf/libelf_ctors.c278
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c58
-rw-r--r--nuttx/binfmt/libelf/libelf_sections.c284
-rw-r--r--nuttx/binfmt/libelf/libelf_uninit.c9
-rw-r--r--nuttx/binfmt/libelf/libelf_unload.c20
8 files changed, 406 insertions, 312 deletions
diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig
index 5dc4a2d9f..f6f579276 100644
--- a/nuttx/binfmt/libelf/Kconfig
+++ b/nuttx/binfmt/libelf/Kconfig
@@ -32,13 +32,6 @@ config ELF_BUFFERINCR
will need to be read (such as symbol names). This value specifies the size
increment to use each time the buffer is reallocated. Default: 32
-config ELF_CONSTRUCTORS
- bool "C++ Static Constructor Support"
- default n
- depends on HAVE_CXX
- ---help---
- Build in support for C++ constructors in ELF modules.
-
config ELF_DUMPBUFFER
bool "Dump ELF buffers"
default n
diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs
index cf2507a99..26198ade2 100644
--- a/nuttx/binfmt/libelf/Make.defs
+++ b/nuttx/binfmt/libelf/Make.defs
@@ -41,11 +41,11 @@ 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 libelf_symbols.c libelf_iobuffer.c
+BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_iobuffer.c libelf_load.c \
+ libelf_read.c libelf_sections.c libelf_symbols.c libelf_uninit.c \
+ libelf_unload.c libelf_verify.c
-ifeq ($(CONFIG_ELF_CONSTRUCTORS),y)
+ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y)
BINFMT_CSRCS += libelf_ctors.c
endif
diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h
index 0d13515cc..bea92496a 100644
--- a/nuttx/binfmt/libelf/libelf.h
+++ b/nuttx/binfmt/libelf/libelf.h
@@ -86,6 +86,39 @@ int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR uint8_t *buffer,
size_t readsize, off_t offset);
/****************************************************************************
+ * Name: elf_loadshdrs
+ *
+ * Description:
+ * Loads section headers into memory.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_findsection
+ *
+ * Description:
+ * A section by its name.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * sectname - Name of the section to find
+ *
+ * Returned Value:
+ * On success, the index to the section is returned; A negated errno value
+ * is returned on failure.
+ *
+ ****************************************************************************/
+
+int elf_findsection(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const char *sectname);
+
+/****************************************************************************
* Name: elf_findsymtab
*
* Description:
@@ -199,27 +232,8 @@ int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment);
*
****************************************************************************/
-#ifdef CONFIG_ELF_CONSTRUCTORS
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo);
#endif
-/****************************************************************************
- * Name: elf_doctors
- *
- * Description:
- * Execute C++ static constructors.
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ELF_CONSTRUCTORS
-int elf_doctors(FAR struct elf_loadinfo_s *loadinfo);
-#endif
-
#endif /* __BINFMT_LIBELF_LIBELF_H */
diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c
index c53923d44..a57fc37d9 100644
--- a/nuttx/binfmt/libelf/libelf_ctors.c
+++ b/nuttx/binfmt/libelf/libelf_ctors.c
@@ -49,7 +49,7 @@
#include "libelf.h"
-#ifdef CONFIG_ELF_CONSTRUCTORS
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
/****************************************************************************
* Pre-Processor Definitions
@@ -68,166 +68,6 @@
****************************************************************************/
/****************************************************************************
- * Name: elf_sectname
- *
- * Description:
- * Get the symbol name in loadinfo->iobuffer[].
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo,
- FAR const Elf32_Shdr *shdr)
-{
- FAR Elf32_Shdr *shstr;
- FAR uint8_t *buffer;
- off_t offset;
- size_t readlen;
- size_t bytesread;
- int shstrndx;
- int ret;
-
- /* Get the section header table index of the entry associated with the
- * section name string table. If the file has no section name string table,
- * this member holds the value SH_UNDEF.
- */
-
- shstrndx = loadinfo->ehdr.e_shstrndx;
- if (shstrndx == SHN_UNDEF)
- {
- bdbg("No section header string table\n");
- return -EINVAL;
- }
-
- /* Get the section name string table section header */
-
- shstr = &loadinfo->shdr[shstrndx];
-
- /* Get the file offset to the string that is the name of the section. This
- * is the sum of:
- *
- * shstr->sh_offset: The file offset to the first byte of the section
- * header string table data.
- * shdr->sh_name: The offset to the name of the section in the section
- * name table
- */
-
- offset = shstr->sh_offset + shdr->sh_name;
-
- /* Loop until we get the entire section name into memory */
-
- buffer = loadinfo->iobuffer;
- bytesread = 0;
-
- for (;;)
- {
- /* Get the number of bytes to read */
-
- readlen = loadinfo->buflen - bytesread;
- if (offset + readlen > loadinfo->filelen)
- {
- readlen = loadinfo->filelen - offset;
- if (readlen <= 0)
- {
- bdbg("At end of file\n");
- return -EINVAL;
- }
- }
-
- /* Read that number of bytes into the array */
-
- buffer = &loadinfo->iobuffer[bytesread];
- ret = elf_read(loadinfo, buffer, readlen, offset);
- if (ret < 0)
- {
- bdbg("Failed to read section name\n");
- return ret;
- }
-
- bytesread += readlen;
-
- /* Did we read the NUL terminator? */
-
- if (memchr(buffer, '\0', readlen) != NULL)
- {
- /* Yes, the buffer contains a NUL terminator. */
-
- return OK;
- }
-
- /* No.. then we have to read more */
-
- ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR);
- if (ret < 0)
- {
- bdbg("elf_reallocbuffer failed: %d\n", ret);
- return ret;
- }
- }
-
- /* We will not get here */
-
- return OK;
-}
-
-/****************************************************************************
- * Name: elf_findctors
- *
- * Description:
- * Find C++ static constructors.
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * On success, the index to the CTOR section is returned; A negated errno
- * value is returned on failure.
- *
- ****************************************************************************/
-
-static inline int elf_findctors(FAR struct elf_loadinfo_s *loadinfo)
-{
- FAR const Elf32_Shdr *shdr;
- int ret;
- int i;
-
- /* Search through the shdr[] array in loadinfo for a section named .ctors */
-
- for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
- {
- /* Get the name of this section */
-
- shdr = &loadinfo->shdr[i];
- ret = elf_sectname(loadinfo, shdr);
- if (ret < 0)
- {
- bdbg("elf_sectname failed: %d\n", ret);
- return ret;
- }
-
- /* Check if the name of this section if ".ctors" */
-
- bvdbg("%d. Comparing \"%s\" and .ctors\"\n", i, loadinfo->iobuffer);
-
- if (strcmp(".ctors", (FAR const char *)loadinfo->iobuffer) == 0)
- {
- /* We found it... return the index */
-
- return i;
- }
- }
-
- /* We failed to find the .ctors sections. This may not be an error; maybe
- * there are no static constructors.
- */
-
- return -ENOENT;
-}
-
-/****************************************************************************
* Public Functions
****************************************************************************/
@@ -267,16 +107,21 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
return -ENOMEM;
}
- /* Find the index to the section named ".ctors" */
+ /* 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;
+ * 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"
+ * in either case.
+ */
- ctoridx = elf_findctors(loadinfo);
+ ctoridx = elf_findsection(loadinfo, ".ctors");
if (ctoridx < 0)
{
/* This may not be a failure. -ENOENT indicates that the file has no
* static constructor section.
*/
- bvdbg("elf_findctors failed: %d\n", ctoridx);
+ bvdbg("elf_findsection .ctors section failed: %d\n", ctoridx);
return ret == -ENOENT ? OK : ret;
}
@@ -286,7 +131,9 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
shdr = &loadinfo->shdr[ctoridx];
- /* Allocate memory to hold a copy of the .ctor section */
+ /* Get the size of the .ctor section and the number of constructors that
+ * will need to be called.
+ */
ctorsize = shdr->sh_size;
loadinfo->nctors = ctorsize / sizeof(elf_ctor_t);
@@ -302,71 +149,72 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
{
/* Check an assumption that we made above */
- DEBUGASSERT(shdr->sh_entsize == sizeof(elf_ctor_t));
-
- loadinfo->ctors = (elf_ctor_t)kmalloc(ctorsize);
- if (!loadinfo->ctors)
- {
- bdbg("Failed to allocate memory for .ctors\n");
- return -ENOMEM;
- }
+ DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(elf_ctor_t));
- /* Read the section header table into memory */
+ /* 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
+ * from the file into the allocated memory.
+ *
+ * SHF_ALLOC indicates that the section requires memory during
+ * execution.
+ */
- ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize,
- shdr->sh_offset);
- if (ret < 0)
+ if ((shdr->sh_flags & SHF_ALLOC) == 0)
{
- bdbg("Failed to allocate .ctors: %d\n", ret);
- }
+ /* Not loaded -> Old ABI. */
- /* Fix up all of the .ctor addresses */
+ loadinfo->newabi = false;
- for (i = 0; i < loadinfo->nctors; i++)
- {
- FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]);
+ /* Allocate memory to hold a copy of the .ctor section */
- bvdbg("ctor %d: %08lx + %08lx = %08lx\n", i,
- *ptr, loadinfo->alloc, *ptr + loadinfo->alloc);
+ loadinfo->ctors = (elf_ctor_t*)kmalloc(ctorsize);
+ if (!loadinfo->ctors)
+ {
+ bdbg("Failed to allocate memory for .ctors\n");
+ return -ENOMEM;
+ }
- *ptr += loadinfo->alloc;
- }
- }
+ /* Read the section header table into memory */
- return OK;
-}
+ ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize,
+ shdr->sh_offset);
+ if (ret < 0)
+ {
+ bdbg("Failed to allocate .ctors: %d\n", ret);
+ return ret;
+ }
-/****************************************************************************
- * Name: elf_doctors
- *
- * Description:
- * Execute C++ static constructors.
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
+ /* Fix up all of the .ctor addresses. Since the addresses
+ * do not lie in allocated memory, there will be no relocation
+ * section for them.
+ */
-int elf_doctors(FAR struct elf_loadinfo_s *loadinfo)
-{
- elf_ctor_t ctor = (elf_ctor_t)loadinfo->ctors;
- int i;
+ for (i = 0; i < loadinfo->nctors; i++)
+ {
+ FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]);
- /* Execute each constructor */
+ bvdbg("ctor %d: %08lx + %08lx = %08lx\n",
+ i, *ptr, loadinfo->alloc, *ptr + loadinfo->alloc);
- for (i = 0; i < loadinfo->nctors; i++)
- {
- bvdbg("Calling ctor %d at %p\n", i, (FAR void *)ctor);
+ *ptr += loadinfo->alloc;
+ }
+ }
+ else
+ {
+ /* Loaded -> New ABI. */
- ctor();
- ctor++;
+ loadinfo->newabi = true;
+
+ /* Save the address of the .ctors (actually, .init_array) where it was
+ * loaded into memory. Since the .ctors lie in allocated memory, they
+ * will be relocated via the normal mechanism.
+ */
+
+ loadinfo->ctors = (elf_ctor_t*)shdr->sh_addr;
+ }
}
return OK;
}
-#endif /* CONFIG_ELF_CONSTRUCTORS */
+#endif /* CONFIG_BINFMT_CONSTRUCTORS */
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
index 505e2c813..221ae8d43 100644
--- a/nuttx/binfmt/libelf/libelf_load.c
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -76,62 +76,6 @@
****************************************************************************/
/****************************************************************************
- * Name: elf_loadshdrs
- *
- * Description:
- * Loads section headers into memory.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
-{
- size_t shdrsize;
- int ret;
-
- DEBUGASSERT(loadinfo->shdr == NULL);
-
- /* Verify that there are sections */
-
- if (loadinfo->ehdr.e_shnum < 1)
- {
- 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->ehdr.e_shnum;
- if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen)
- {
- bdbg("Insufficent space in file for section header table\n");
- return -ESPIPE;
- }
-
- /* Allocate memory to hold a working copy of the sector header table */
-
- 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;
- }
-
- /* Read the section header table into memory */
-
- 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);
- }
-
- return ret;
-}
-
-/****************************************************************************
* Name: elf_allocsize
*
* Description:
@@ -292,7 +236,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
/* Find static constructors. */
-#ifdef CONFIG_ELF_CONSTRUCTORS
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
ret = elf_loadctors(loadinfo);
if (ret < 0)
{
diff --git a/nuttx/binfmt/libelf/libelf_sections.c b/nuttx/binfmt/libelf/libelf_sections.c
new file mode 100644
index 000000000..c41793544
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_sections.c
@@ -0,0 +1,284 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_sections.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+#include <string.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
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_sectname
+ *
+ * Description:
+ * Get the symbol name in loadinfo->iobuffer[].
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const Elf32_Shdr *shdr)
+{
+ FAR Elf32_Shdr *shstr;
+ FAR uint8_t *buffer;
+ off_t offset;
+ size_t readlen;
+ size_t bytesread;
+ int shstrndx;
+ int ret;
+
+ /* Get the section header table index of the entry associated with the
+ * section name string table. If the file has no section name string table,
+ * this member holds the value SH_UNDEF.
+ */
+
+ shstrndx = loadinfo->ehdr.e_shstrndx;
+ if (shstrndx == SHN_UNDEF)
+ {
+ bdbg("No section header string table\n");
+ return -EINVAL;
+ }
+
+ /* Get the section name string table section header */
+
+ shstr = &loadinfo->shdr[shstrndx];
+
+ /* Get the file offset to the string that is the name of the section. This
+ * is the sum of:
+ *
+ * shstr->sh_offset: The file offset to the first byte of the section
+ * header string table data.
+ * shdr->sh_name: The offset to the name of the section in the section
+ * name table
+ */
+
+ offset = shstr->sh_offset + shdr->sh_name;
+
+ /* Loop until we get the entire section name into memory */
+
+ buffer = loadinfo->iobuffer;
+ bytesread = 0;
+
+ for (;;)
+ {
+ /* Get the number of bytes to read */
+
+ readlen = loadinfo->buflen - bytesread;
+ if (offset + readlen > loadinfo->filelen)
+ {
+ readlen = loadinfo->filelen - offset;
+ if (readlen <= 0)
+ {
+ bdbg("At end of file\n");
+ return -EINVAL;
+ }
+ }
+
+ /* Read that number of bytes into the array */
+
+ buffer = &loadinfo->iobuffer[bytesread];
+ ret = elf_read(loadinfo, buffer, readlen, offset);
+ if (ret < 0)
+ {
+ bdbg("Failed to read section name\n");
+ return ret;
+ }
+
+ bytesread += readlen;
+
+ /* Did we read the NUL terminator? */
+
+ if (memchr(buffer, '\0', readlen) != NULL)
+ {
+ /* Yes, the buffer contains a NUL terminator. */
+
+ return OK;
+ }
+
+ /* No.. then we have to read more */
+
+ ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR);
+ if (ret < 0)
+ {
+ bdbg("elf_reallocbuffer failed: %d\n", ret);
+ return ret;
+ }
+ }
+
+ /* We will not get here */
+
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_loadshdrs
+ *
+ * Description:
+ * Loads section headers into memory.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
+{
+ size_t shdrsize;
+ int ret;
+
+ DEBUGASSERT(loadinfo->shdr == NULL);
+
+ /* Verify that there are sections */
+
+ if (loadinfo->ehdr.e_shnum < 1)
+ {
+ 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->ehdr.e_shnum;
+ if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen)
+ {
+ bdbg("Insufficent space in file for section header table\n");
+ return -ESPIPE;
+ }
+
+ /* Allocate memory to hold a working copy of the sector header table */
+
+ 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;
+ }
+
+ /* Read the section header table into memory */
+
+ 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);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: elf_findsection
+ *
+ * Description:
+ * A section by its name.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * sectname - Name of the section to find
+ *
+ * Returned Value:
+ * On success, the index to the section is returned; A negated errno value
+ * is returned on failure.
+ *
+ ****************************************************************************/
+
+int elf_findsection(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const char *sectname)
+{
+ FAR const Elf32_Shdr *shdr;
+ int ret;
+ int i;
+
+ /* Search through the shdr[] array in loadinfo for a section named 'sectname' */
+
+ for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
+ {
+ /* Get the name of this section */
+
+ shdr = &loadinfo->shdr[i];
+ ret = elf_sectname(loadinfo, shdr);
+ if (ret < 0)
+ {
+ bdbg("elf_sectname failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Check if the name of this section is 'sectname' */
+
+ bvdbg("%d. Comparing \"%s\" and .\"%s\"\n",
+ i, loadinfo->iobuffer, sectname);
+
+ if (strcmp((FAR const char *)loadinfo->iobuffer, sectname) == 0)
+ {
+ /* We found it... return the index */
+
+ return i;
+ }
+ }
+
+ /* We failed to find a section with this name. */
+
+ return -ENOENT;
+}
diff --git a/nuttx/binfmt/libelf/libelf_uninit.c b/nuttx/binfmt/libelf/libelf_uninit.c
index 06bb89681..3ec6f6c61 100644
--- a/nuttx/binfmt/libelf/libelf_uninit.c
+++ b/nuttx/binfmt/libelf/libelf_uninit.c
@@ -115,15 +115,6 @@ int elf_freebuffers(struct elf_loadinfo_s *loadinfo)
loadinfo->shdr = NULL;
}
-#ifdef CONFIG_ELF_CONSTRUCTORS
- if (loadinfo->ctors)
- {
- kfree((FAR void *)loadinfo->ctors);
- loadinfo->ctors = NULL;
- loadinfo->nctors = 0;
- }
-#endif
-
if (loadinfo->iobuffer)
{
kfree((FAR void *)loadinfo->iobuffer);
diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c
index d7a882711..8102f7bf2 100644
--- a/nuttx/binfmt/libelf/libelf_unload.c
+++ b/nuttx/binfmt/libelf/libelf_unload.c
@@ -91,6 +91,26 @@ int elf_unload(struct elf_loadinfo_s *loadinfo)
loadinfo->allocsize = 0;
}
+ /* Release any allocated constructor memory */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ if (loadinfo->ctors)
+ {
+ /* In the old ABI, the .ctors section is not make for allocation. In
+ * that case, we need to free the working buffer that was used to hold
+ * the constructors.
+ */
+
+ if (!loadinfo->newabi)
+ {
+ kfree((FAR void *)loadinfo->ctors);
+ }
+
+ loadinfo->ctors = NULL;
+ loadinfo->nctors = 0;
+ }
+#endif
+
return OK;
}