summaryrefslogtreecommitdiff
path: root/nuttx/binfmt/libelf
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-25 19:21:47 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-25 19:21:47 +0000
commit8cbc20e05c24cc3e2b0b4774f4850357b9f46595 (patch)
tree862c04d5603d53111ee969409bc86b6e9739982a /nuttx/binfmt/libelf
parent573c3911fcc480294700bdd82b8509499babb2d2 (diff)
downloadpx4-nuttx-8cbc20e05c24cc3e2b0b4774f4850357b9f46595.tar.gz
px4-nuttx-8cbc20e05c24cc3e2b0b4774f4850357b9f46595.tar.bz2
px4-nuttx-8cbc20e05c24cc3e2b0b4774f4850357b9f46595.zip
Finishes basic coding of ELF file support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5259 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/binfmt/libelf')
-rw-r--r--nuttx/binfmt/libelf/Kconfig17
-rw-r--r--nuttx/binfmt/libelf/Make.defs4
-rw-r--r--nuttx/binfmt/libelf/libelf.h69
-rw-r--r--nuttx/binfmt/libelf/libelf_bind.c44
-rw-r--r--nuttx/binfmt/libelf/libelf_ctors.c134
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c12
-rw-r--r--nuttx/binfmt/libelf/libelf_symbols.c204
-rw-r--r--nuttx/binfmt/libelf/libelf_unload.c11
8 files changed, 487 insertions, 8 deletions
diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig
index f16dd4e90..5dc4a2d9f 100644
--- a/nuttx/binfmt/libelf/Kconfig
+++ b/nuttx/binfmt/libelf/Kconfig
@@ -15,6 +15,23 @@ config ELF_STACKSIZE
---help---
This is the default stack size that will will be used when starting ELF binaries.
+config ELF_BUFFERSIZE
+ int "ELF I/O Buffer Size"
+ default 128
+ ---help---
+ This is an I/O buffer that is used to access the ELF file. Variable length items
+ will need to be read (such as symbol names). This is really just this initial
+ size of the buffer; it will be reallocated as necessary to hold large symbol
+ names). Default: 128
+
+config ELF_BUFFERINCR
+ int "ELF I/O Buffer Realloc Increment"
+ default 32
+ ---help---
+ This is an I/O buffer that is used to access the ELF file. Variable length items
+ 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
diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs
index 82f5f3e64..9e06537bd 100644
--- a/nuttx/binfmt/libelf/Make.defs
+++ b/nuttx/binfmt/libelf/Make.defs
@@ -45,6 +45,10 @@ 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
+ifeq ($(CONFIG_ELF_CONSTRUCTORS),y)
+BINFMT_CSRCS += libelf_ctors.c
+endif
+
# Hook the libelf subdirectory into the build
VPATH += libelf
diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h
index a7ffbc6a6..37a2ad872 100644
--- a/nuttx/binfmt/libelf/libelf.h
+++ b/nuttx/binfmt/libelf/libelf.h
@@ -105,9 +105,78 @@ int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo);
* Description:
* Read the ELFT symbol structure at the specfied index into memory.
*
+ * Input Parameters:
+ * loadinfo - Load state information
+ * index - Symbol table index
+ * sym - Location to return the table entry
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
****************************************************************************/
int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
FAR Elf32_Sym *sym);
+/****************************************************************************
+ * Name: elf_symvalue
+ *
+ * Description:
+ * Get the value of a symbol. The updated value of the symbol is returned
+ * in the st_value field of the symbol table entry.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * sym - Symbol table entry (value might be undefined)
+ * exports - The symbol table to use for resolving undefined symbols.
+ * nexports - Number of symbols in the symbol table.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym,
+ FAR const struct symtab_s *exports, int nexports);
+
+/****************************************************************************
+ * Name: elf_findctors
+ *
+ * Description:
+ * Find 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_findctors(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_bind.c b/nuttx/binfmt/libelf/libelf_bind.c
index e9491af0e..e398521cc 100644
--- a/nuttx/binfmt/libelf/libelf_bind.c
+++ b/nuttx/binfmt/libelf/libelf_bind.c
@@ -46,6 +46,7 @@
#include <assert.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/elf.h>
#include <nuttx/binfmt/symtab.h>
@@ -63,6 +64,10 @@
# undef CONFIG_ELF_DUMPBUFFER
#endif
+#ifndef CONFIG_ELF_BUFFERSIZE
+# define CONFIG_ELF_BUFFERSIZE 128
+#endif
+
#ifdef CONFIG_ELF_DUMPBUFFER
# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
#else
@@ -124,7 +129,9 @@ static inline int elf_readrel(FAR struct elf_loadinfo_s *loadinfo,
*
****************************************************************************/
-static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx)
+static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx,
+ FAR const struct symtab_s *exports, int nexports)
+
{
FAR Elf32_Shdr *relsec = &loadinfo->shdr[relidx];
FAR Elf32_Shdr *dstsec = &loadinfo->shdr[relsec->sh_info];
@@ -165,6 +172,16 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx)
return ret;
}
+ /* Get the value of the symbol (in sym.st_value) */
+
+ ret = elf_symvalue(loadinfo, &sym, exports, nexports);
+ if (ret < 0)
+ {
+ bdbg("Section %d reloc %d: Failed to get value of 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))
@@ -189,7 +206,8 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx)
return OK;
}
-static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx)
+static int elf_relocateadd(FAR struct elf_loadinfo_s *loadinfo, int relidx,
+ FAR const struct symtab_s *exports, int nexports)
{
bdbg("Not implemented\n");
return -ENOSYS;
@@ -226,6 +244,18 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
return ret;
}
+ /* Allocate an I/O buffer. This buffer is used only by elf_symname() to
+ * accumulate the variable length symbol name.
+ */
+
+ loadinfo->iobuffer = (FAR uint8_t *)kmalloc(CONFIG_ELF_BUFFERSIZE);
+ if (!loadinfo->iobuffer)
+ {
+ bdbg("Failed to allocate an I/O buffer\n");
+ return -ENOMEM;
+ }
+ loadinfo->buflen = CONFIG_ELF_BUFFERSIZE;
+
/* Process relocations in every allocated section */
for (i = 1; i < loadinfo->ehdr.e_shnum; i++)
@@ -251,11 +281,11 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
if (loadinfo->shdr[i].sh_type == SHT_REL)
{
- ret = elf_relocate(loadinfo, i);
+ ret = elf_relocate(loadinfo, i, exports, nexports);
}
else if (loadinfo->shdr[i].sh_type == SHT_RELA)
{
- ret = elf_relocateadd(loadinfo, i);
+ ret = elf_relocateadd(loadinfo, i, exports, nexports);
}
if (ret < 0)
@@ -269,6 +299,12 @@ int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
#ifdef CONFIG_ELF_ICACHE
arch_flushicache((FAR void*)loadinfo->alloc, loadinfo->allocsize);
#endif
+
+ /* Free the I/O buffer */
+
+ kfree(loadinfo->iobuffer);
+ loadinfo->iobuffer = NULL;
+ loadinfo->buflen = 0;
return ret;
}
diff --git a/nuttx/binfmt/libelf/libelf_ctors.c b/nuttx/binfmt/libelf/libelf_ctors.c
new file mode 100644
index 000000000..e8b095bb7
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_ctors.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_ctors.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 <debug.h>
+
+#include <nuttx/binfmt/elf.h>
+
+#include "libelf"
+
+#ifdef CONFIG_ELF_CONSTRUCTORS
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+typedef FAR void (*ctor_t)(void);
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_findctors
+ *
+ * Description:
+ * Find 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.
+ *
+ ****************************************************************************/
+
+int elf_findctors(FAR struct elf_loadinfo_s *loadinfo)
+{
+ /* Search through the shdr[] array in loadinfo for a section named .ctors */
+#warning "Missing logic"
+
+ /* Get the address of the beginning of the constructros from the sh_addr
+ * field of the section. Save that in the ctors field of the loadinfo
+ * structure.
+ */
+#warning "Missing logic"
+
+ /* Get the number of constructors from the sh_size field of the section.
+ * Save that number in the nctors field of the loadinfo structure.
+ */
+#warning "Missing logic"
+ return -ENOSYS;
+}
+
+/****************************************************************************
+ * 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.
+ *
+ ****************************************************************************/
+
+int elf_doctors(FAR struct elf_loadinfo_s *loadinfo)
+{
+ ctor_t ctor = (ctor_t)loadinfo->ctors;
+ int i;
+
+ /* Execute each constructor */
+
+ for (i = 0; i < loadinfo->nctors; i++)
+ {
+ ctor();
+ ctor++;
+ }
+}
+
+#endif /* CONFIG_ELF_CONSTRUCTORS
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
index 127ebb314..758f96548 100644
--- a/nuttx/binfmt/libelf/libelf_load.c
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -327,6 +327,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
ret = elf_filelen(loadinfo);
{
+ bdbg("elf_filelen failed: %d\n", ret);
return ret;
}
@@ -335,6 +336,7 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
ret = elf_loadshdrs(loadinfo);
if (ret < 0)
{
+ bdbg("elf_loadshdrs failed: %d\n", ret);
return ret;
}
@@ -347,11 +349,19 @@ int elf_load(FAR struct elf_loadinfo_s *loadinfo)
ret = elf_loadfile(loadinfo);
if (ret < 0)
{
+ bdbg("elf_loadfile failed: %d\n", ret);
goto errout_with_shdrs;
}
/* Find static constructors. */
-#warning "Missing logic"
+
+#ifdef CONFIG_ELF_CONSTRUCTORS
+ ret = elf_findctors(loadinfo);
+ {
+ bdbg("elf_findctors failed: %d\n", ret);
+ goto errout_with_shdrs;
+ }
+#endif
return OK;
diff --git a/nuttx/binfmt/libelf/libelf_symbols.c b/nuttx/binfmt/libelf/libelf_symbols.c
index 4788c874c..05f827963 100644
--- a/nuttx/binfmt/libelf/libelf_symbols.c
+++ b/nuttx/binfmt/libelf/libelf_symbols.c
@@ -39,11 +39,14 @@
#include <nuttx/config.h>
+#include <stdlib.h>
+#include <string.h>
#include <elf.h>
-#include <debug.h>
#include <errno.h>
+#include <debug.h>
#include <nuttx/binfmt/elf.h>
+#include <nuttx/binfmt/symtab.h>
#include "libelf.h"
@@ -51,6 +54,10 @@
* Pre-Processor Definitions
****************************************************************************/
+#ifndef CONFIG_ELF_BUFFERINCR
+# define CONFIG_ELF_BUFFERINCR 32
+#endif
+
/****************************************************************************
* Private Constant Data
****************************************************************************/
@@ -60,6 +67,101 @@
****************************************************************************/
/****************************************************************************
+ * Name: elf_symname
+ *
+ * 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 int elf_symname(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const Elf32_Sym *sym)
+{
+ FAR uint8_t *buffer;
+ off_t offset;
+ size_t readlen;
+ size_t bytesread;
+ int ret;
+
+ /* Get the file offset to the string that is the name of the symbol. The
+ * st_name member holds an offset into the file's symbol string table.
+ */
+
+ if (sym->st_name == 0)
+ {
+ bdbg("Symbol has no name\n");
+ return -ENOENT;
+ }
+
+ offset = loadinfo->shdr[loadinfo->strtabidx].sh_offset + sym->st_name;
+
+ /* Loop until we get the entire symbol 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 symbol 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 */
+
+ buffer = realloc((FAR void *)loadinfo->iobuffer,
+ loadinfo->buflen + CONFIG_ELF_BUFFERINCR);
+ if (!buffer)
+ {
+ bdbg("Failed to reallocate the I/O buffer\n");
+ return -ENOMEM;
+ }
+
+ /* Save the new buffer info */
+
+ loadinfo->iobuffer = buffer;
+ loadinfo->buflen += CONFIG_ELF_BUFFERINCR;
+ }
+
+ /* We will not get here */
+
+ return OK;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -108,6 +210,15 @@ int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo)
* Description:
* Read the ELFT symbol structure at the specfied index into memory.
*
+ * Input Parameters:
+ * loadinfo - Load state information
+ * index - Symbol table index
+ * sym - Location to return the table entry
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
****************************************************************************/
int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
@@ -132,3 +243,94 @@ int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
return elf_read(loadinfo, (FAR uint8_t*)sym, sizeof(Elf32_Sym), offset);
}
+
+/****************************************************************************
+ * Name: elf_symvalue
+ *
+ * Description:
+ * Get the value of a symbol. The updated value of the symbol is returned
+ * in the st_value field of the symbol table entry.
+ *
+ * Input Parameters:
+ * loadinfo - Load state information
+ * sym - Symbol table entry (value might be undefined)
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym,
+ FAR const struct symtab_s *exports, int nexports)
+{
+ FAR const struct symtab_s *symbol;
+ uintptr_t secbase;
+ int ret;
+
+ switch (sym->st_shndx)
+ {
+ case SHN_COMMON:
+ {
+ /* NuttX ELF modules should be compiled with -fno-common. */
+
+ bdbg("SHN_COMMON: Re-compile with -fno-common\n");
+ return -EINVAL;
+ }
+
+ case SHN_ABS:
+ {
+ /* st_value already holds the correct value */
+
+ bvdbg("SHN_ABS: st_value=%08lx\n", (long)sym->st_value);
+ return OK;
+ }
+
+ case SHN_UNDEF:
+ {
+ /* Get the name of the undefined symbol */
+
+ ret = elf_symname(loadinfo, sym);
+ if (ret < 0)
+ {
+ bdbg("SHN_UNDEF: Failed to get symbol name: %d\n", ret);
+ return ret;
+ }
+
+ /* Check if the base code exports a symbol of this name */
+
+#ifdef CONFIG_SYMTAB_ORDEREDBYNAME
+ symbol = symtab_findorderedbyname(exports, (FAR char *)loadinfo->iobuffer, nexports);
+#else
+ symbol = symtab_findbyname(exports, (FAR char *)loadinfo->iobuffer, nexports);
+#endif
+ if (!symbol)
+ {
+ bdbg("SHN_UNDEF: Exported symbol \"%s\" not found\n", loadinfo->iobuffer);
+ return -ENOENT;
+ }
+
+ /* Yes... add the exported symbol value to the ELF symbol table entry */
+
+ bvdbg("SHN_ABS: name=%s %08x+%08x=%08x\n",
+ loadinfo->iobuffer, sym->st_value, symbol->sym_value,
+ sym->st_value + symbol->sym_value);
+
+ sym->st_value += (Elf32_Word)((uintptr_t)symbol->sym_value);
+ }
+ break;
+
+ default:
+ {
+ secbase = loadinfo->shdr[sym->st_shndx].sh_addr;
+
+ bvdbg("Other: %08x+%08x=%08x\n",
+ sym->st_value, secbase, sym->st_value + secbase);
+
+ sym->st_value += secbase;
+ }
+ break;
+ }
+
+ return OK;
+}
diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c
index ca8d2b708..335106407 100644
--- a/nuttx/binfmt/libelf/libelf_unload.c
+++ b/nuttx/binfmt/libelf/libelf_unload.c
@@ -80,17 +80,24 @@ int elf_unload(struct elf_loadinfo_s *loadinfo)
if (loadinfo->alloc)
{
- kfree((void*)loadinfo->alloc);
+ kfree((FAR void *)loadinfo->alloc);
loadinfo->alloc = 0;
loadinfo->allocsize = 0;
}
if (loadinfo->shdr)
{
- kfree((void*)loadinfo->shdr);
+ kfree((FAR void *)loadinfo->shdr);
loadinfo->shdr = NULL;
}
+ if (loadinfo->iobuffer)
+ {
+ kfree((FAR void *)loadinfo->iobuffer);
+ loadinfo->iobuffer = NULL;
+ loadinfo->buflen = 0;
+ }
+
return OK;
}