aboutsummaryrefslogtreecommitdiff
path: root/nuttx/binfmt/libnxflat
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/binfmt/libnxflat')
-rw-r--r--nuttx/binfmt/libnxflat/Kconfig9
-rw-r--r--nuttx/binfmt/libnxflat/Make.defs54
-rw-r--r--nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld187
-rw-r--r--nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld187
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat.h136
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_addrenv.c235
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_bind.c615
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_init.c189
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c222
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_read.c167
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_uninit.c85
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_unload.c97
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_verify.c101
13 files changed, 0 insertions, 2284 deletions
diff --git a/nuttx/binfmt/libnxflat/Kconfig b/nuttx/binfmt/libnxflat/Kconfig
deleted file mode 100644
index fdb270cfb..000000000
--- a/nuttx/binfmt/libnxflat/Kconfig
+++ /dev/null
@@ -1,9 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see misc/tools/kconfig-language.txt.
-#
-
-config NXFLAT_DUMPBUFFER
- bool "Dump NXFLAT buffers"
- default n
- depends on DEBUG && DEBUG_VERBOSE
diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs
deleted file mode 100644
index 6a0bf1873..000000000
--- a/nuttx/binfmt/libnxflat/Make.defs
+++ /dev/null
@@ -1,54 +0,0 @@
-############################################################################
-# binfmt/libnxflat/Make.defs
-#
-# Copyright (C) 2009 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.
-#
-############################################################################
-
-ifeq ($(CONFIG_NXFLAT),y)
-
-# NXFLAT application interfaces
-
-BINFMT_CSRCS += nxflat.c
-
-# NXFLAT library
-
-BINFMT_CSRCS += libnxflat_init.c libnxflat_uninit.c libnxflat_addrenv.c
-BINFMT_CSRCS += libnxflat_load.c libnxflat_unload.c libnxflat_verify.c
-BINFMT_CSRCS += libnxflat_read.c libnxflat_bind.c
-
-# Hook the libnxflat subdirectory into the build
-
-VPATH += libnxflat
-SUBDIRS += libnxflat
-DEPPATH += --dep-path libnxflat
-
-endif
diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld
deleted file mode 100644
index 47debd663..000000000
--- a/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld
+++ /dev/null
@@ -1,187 +0,0 @@
-/****************************************************************************
- * examples/nxflat/gnu-nxflat-gotoff.ld
- *
- * Copyright (C) 2009, 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.
- *
- ****************************************************************************/
-
-MEMORY
-{
- ISPACE : ORIGIN = 0x0, LENGTH = 2097152
- DSPACE : ORIGIN = 0x0, LENGTH = 2097152
-}
-
-/****************************************************************************
- * The XFLAT program image is divided into two segments:
- *
- * (1) ISpace (Instruction Space). This is the segment that contains
- * code (.text). Everything in the segment should be fetch-able
- * machine PC instructions (jump, branch, call, etc.).
- * (2) DSpace (Data Space). This is the segment that contains both
- * read-write data (.data, .bss) as well as read-only data (.rodata).
- * Everything in this segment should be access-able with machine
- * PIC load and store instructions.
- *
- * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative
- * addressing to access RO data. In that case, read-only data (.rodata) must
- * reside in D-Space and this linker script should be used.
- *
- * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative
- * addressing to access RO data. In that case, read-only data (.rodata) must
- * reside in I-Space and this linker script should NOT be used with those
- * newer tools.
- *
- ****************************************************************************/
-
-SECTIONS
-{
- .text 0x00000000 :
- {
- /* ISpace is located at address 0. Every (unrelocated) ISpace
- * address is an offset from the begining of this segment.
- */
-
- text_start = . ;
-
- *(.text)
- *(.text.*)
- *(.gnu.warning)
- *(.stub)
- *(.glue_7)
- *(.glue_7t)
- *(.jcr)
-
- /* C++ support: The .init and .fini sections contain XFLAT-
- * specific logic to manage static constructors and destructors.
- */
-
- *(.gnu.linkonce.t.*)
- *(.init)
- *(.fini)
-
- /* This is special code area at the end of the normal
- text section. It contains a small lookup table at
- the start followed by the code pointed to by entries
- in the lookup table. */
-
- . = ALIGN (4) ;
- PROVIDE(__ctbp = .);
- *(.call_table_data)
- *(.call_table_text)
-
- _etext = . ;
-
- } > ISPACE
-
- /* DSpace is also located at address 0. Every (unrelocated) DSpace
- * address is an offset from the begining of this segment.
- */
-
- .data 0x00000000 :
- {
- /* In this model, .rodata is access using PC-relative addressing
- * and, hence, must also reside in the .text section.
- */
-
- __data_start = . ;
- *(.rodata)
- *(.rodata1)
- *(.rodata.*)
- *(.gnu.linkonce.r*)
-
- *(.data)
- *(.data1)
- *(.data.*)
- *(.gnu.linkonce.d*)
- *(.data1)
- *(.eh_frame)
- *(.gcc_except_table)
-
- *(.gnu.linkonce.s.*)
- *(__libc_atexit)
- *(__libc_subinit)
- *(__libc_subfreeres)
- *(.note.ABI-tag)
-
- /* C++ support. For each global and static local C++ object,
- * GCC creates a small subroutine to construct the object. Pointers
- * to these routines (not the routines themselves) are stored as
- * simple, linear arrays in the .ctors section of the object file.
- * Similarly, pointers to global/static destructor routines are
- * stored in .dtors.
- */
-
- *(.gnu.linkonce.d.*)
-
- _ctors_start = . ;
- *(.ctors)
- _ctors_end = . ;
- _dtors_start = . ;
- *(.dtors)
- _dtors_end = . ;
-
- _edata = . ;
- edata = ALIGN( 0x10 ) ;
- } > DSPACE
-
- .bss :
- {
- __bss_start = _edata ;
- *(.dynsbss)
- *(.sbss)
- *(.sbss.*)
- *(.scommon)
- *(.dynbss)
- *(.bss)
- *(.bss.*)
- *(.bss*)
- *(.gnu.linkonce.b*)
- *(COMMON)
- end = ALIGN( 0x10 ) ;
- _end = ALIGN( 0x10 ) ;
- } > DSPACE
-
- .got 0 : { *(.got.plt) *(.got) }
- .junk 0 : { *(.rel*) *(.rela*) }
- /* Stabs debugging sections. */
- .stab 0 : { *(.stab) }
- .stabstr 0 : { *(.stabstr) }
- .stab.excl 0 : { *(.stab.excl) }
- .stab.exclstr 0 : { *(.stab.exclstr) }
- .stab.index 0 : { *(.stab.index) }
- .stab.indexstr 0 : { *(.stab.indexstr) }
- .comment 0 : { *(.comment) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_info 0 : { *(.debug_info) }
- .debug_line 0 : { *(.debug_line) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- .debug_aranges 0 : { *(.debug_aranges) }
-}
diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld
deleted file mode 100644
index 71e4399ba..000000000
--- a/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld
+++ /dev/null
@@ -1,187 +0,0 @@
-/****************************************************************************
- * examples/nxflat/gnu-nxflat-pcrel.ld
- *
- * 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.
- *
- ****************************************************************************/
-
-MEMORY
-{
- ISPACE : ORIGIN = 0x0, LENGTH = 2097152
- DSPACE : ORIGIN = 0x0, LENGTH = 2097152
-}
-
-/****************************************************************************
- * The XFLAT program image is divided into two segments:
- *
- * (1) ISpace (Instruction Space). This is the segment that contains
- * code (.text) as well as read-only data (.rodata). Everything in the
- * segment should be fetch-able machine PC instructions (jump, branch,
- * call, etc.) or PC-relative loads.
- * (2) DSpace (Data Space). This is the segment that contains read-write
- * data (.data, .bss). Everything in this segment should be access-able
- * with machine PIC load and store instructions.
- *
- * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative
- * addressing to access RO data. In that case, read-only data (.rodata) must
- * reside in D-Space and this linker script should NOT be used with those
- * older tools.
- *
- * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative
- * addressing to access RO data. In that case, read-only data (.rodata) must
- * reside in I-Space and this linker script should be used.
- *
- ****************************************************************************/
-
-SECTIONS
-{
- .text 0x00000000 :
- {
- /* ISpace is located at address 0. Every (unrelocated) ISpace
- * address is an offset from the begining of this segment.
- */
-
- text_start = . ;
-
- *(.text)
- *(.text.*)
- *(.gnu.warning)
- *(.stub)
- *(.glue_7)
- *(.glue_7t)
- *(.jcr)
-
- /* C++ support: The .init and .fini sections contain XFLAT-
- * specific logic to manage static constructors and destructors.
- */
-
- *(.gnu.linkonce.t.*)
- *(.init)
- *(.fini)
-
- /* This is special code area at the end of the normal
- text section. It contains a small lookup table at
- the start followed by the code pointed to by entries
- in the lookup table. */
-
- . = ALIGN (4) ;
- PROVIDE(__ctbp = .);
- *(.call_table_data)
- *(.call_table_text)
-
- /* In this model, .rodata is access using PC-relative addressing
- * and, hence, must also reside in the .text section.
- */
-
- *(.rodata)
- *(.rodata1)
- *(.rodata.*)
- *(.gnu.linkonce.r*)
-
- _etext = . ;
-
- } > ISPACE
-
- /* DSpace is also located at address 0. Every (unrelocated) DSpace
- * address is an offset from the begining of this segment.
- */
-
- .data 0x00000000 :
- {
- __data_start = . ;
- *(.data)
- *(.data1)
- *(.data.*)
- *(.gnu.linkonce.d*)
- *(.data1)
- *(.eh_frame)
- *(.gcc_except_table)
-
- *(.gnu.linkonce.s.*)
- *(__libc_atexit)
- *(__libc_subinit)
- *(__libc_subfreeres)
- *(.note.ABI-tag)
-
- /* C++ support. For each global and static local C++ object,
- * GCC creates a small subroutine to construct the object. Pointers
- * to these routines (not the routines themselves) are stored as
- * simple, linear arrays in the .ctors section of the object file.
- * Similarly, pointers to global/static destructor routines are
- * stored in .dtors.
- */
-
- *(.gnu.linkonce.d.*)
-
- _ctors_start = . ;
- *(.ctors)
- _ctors_end = . ;
- _dtors_start = . ;
- *(.dtors)
- _dtors_end = . ;
-
- _edata = . ;
- edata = ALIGN( 0x10 ) ;
- } > DSPACE
-
- .bss :
- {
- __bss_start = _edata ;
- *(.dynsbss)
- *(.sbss)
- *(.sbss.*)
- *(.scommon)
- *(.dynbss)
- *(.bss)
- *(.bss.*)
- *(.bss*)
- *(.gnu.linkonce.b*)
- *(COMMON)
- end = ALIGN( 0x10 ) ;
- _end = ALIGN( 0x10 ) ;
- } > DSPACE
-
- .got 0 : { *(.got.plt) *(.got) }
- .junk 0 : { *(.rel*) *(.rela*) }
- /* Stabs debugging sections. */
- .stab 0 : { *(.stab) }
- .stabstr 0 : { *(.stabstr) }
- .stab.excl 0 : { *(.stab.excl) }
- .stab.exclstr 0 : { *(.stab.exclstr) }
- .stab.index 0 : { *(.stab.index) }
- .stab.indexstr 0 : { *(.stab.indexstr) }
- .comment 0 : { *(.comment) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_info 0 : { *(.debug_info) }
- .debug_line 0 : { *(.debug_line) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- .debug_aranges 0 : { *(.debug_aranges) }
-}
diff --git a/nuttx/binfmt/libnxflat/libnxflat.h b/nuttx/binfmt/libnxflat/libnxflat.h
deleted file mode 100644
index cb1cb7057..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat.h
+++ /dev/null
@@ -1,136 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat.h
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __BINFMT_LIBNXFLAT_LIBNXFLAT_H
-#define __BINFMT_LIBNXFLAT_LIBNXFLAT_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/binfmt/nxflat.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_addrenv_alloc
- *
- * Description:
- * Allocate memory for the ELF image (elfalloc). If CONFIG_ADDRENV=n,
- * elfalloc will be allocated using kzalloc(). If CONFIG_ADDRENV-y, then
- * elfalloc will be allocated using up_addrenv_create(). In either case,
- * there will be a unique instance of elfalloc (and stack) for each
- * instance of a process.
- *
- * Input Parameters:
- * loadinfo - Load state information
- * envsize - The size (in bytes) of the address environment needed for the
- * ELF image.
- *
- * Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-int nxflat_addrenv_alloc(FAR struct nxflat_loadinfo_s *loadinfo, size_t envsize);
-
-/****************************************************************************
- * Name: nxflat_addrenv_select
- *
- * Description:
- * Temporarity select the task's address environemnt.
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADDRENV
-# define nxflat_addrenv_select(l) up_addrenv_select((l)->addrenv, &(l)->oldenv)
-#endif
-
-/****************************************************************************
- * Name: nxflat_addrenv_restore
- *
- * Description:
- * Restore the address environment before nxflat_addrenv_select() was called..
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADDRENV
-# define nxflat_addrenv_restore(l) up_addrenv_restore((l)->oldenv)
-#endif
-
-/****************************************************************************
- * Name: nxflat_addrenv_free
- *
- * Description:
- * Release the address environment previously created by
- * nxflat_addrenv_create(). This function is called only under certain
- * error conditions after the the module has been loaded but not yet
- * started. After the module has been started, the address environment
- * will automatically be freed when the module exits.
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * None.
- *
- ****************************************************************************/
-
-void nxflat_addrenv_free(FAR struct nxflat_loadinfo_s *loadinfo);
-
-#endif /* __BINFMT_LIBNXFLAT_LIBNXFLAT_H */
diff --git a/nuttx/binfmt/libnxflat/libnxflat_addrenv.c b/nuttx/binfmt/libnxflat/libnxflat_addrenv.c
deleted file mode 100644
index 2d9255b28..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_addrenv.c
+++ /dev/null
@@ -1,235 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_addrenv.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 <debug.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/kmalloc.h>
-
-#include "libnxflat.h"
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_addrenv_alloc
- *
- * Description:
- * Allocate memory for the ELF image (elfalloc). If CONFIG_ADDRENV=n,
- * elfalloc will be allocated using kzalloc(). If CONFIG_ADDRENV-y, then
- * elfalloc will be allocated using up_addrenv_create(). In either case,
- * there will be a unique instance of elfalloc (and stack) for each
- * instance of a process.
- *
- * Input Parameters:
- * loadinfo - Load state information
- * envsize - The size (in bytes) of the address environment needed for the
- * ELF image.
- *
- * Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-int nxflat_addrenv_alloc(FAR struct nxflat_loadinfo_s *loadinfo, size_t envsize)
-{
- FAR struct dspace_s *dspace;
-#ifdef CONFIG_ADDRENV
- FAR void *vaddr;
- hw_addrenv_t oldenv;
- int ret;
-#endif
-
- DEBUGASSERT(!loadinfo->dspace);
-
- /* Allocate the struct dspace_s container for the D-Space allocation */
-
- dspace = (FAR struct dspace_s *)kmalloc(sizeof(struct dspace_s));
- if (dspace == 0)
- {
- bdbg("ERROR: Failed to allocate DSpace\n");
- return -ENOMEM;
- }
-
-#ifdef CONFIG_ADDRENV
- /* Create a D-Space address environment for the new NXFLAT task */
-
- ret = up_addrenv_create(envsize, &loadinfo->addrenv);
- if (ret < 0)
- {
- bdbg("ERROR: up_addrenv_create failed: %d\n", ret);
- goto errout_with_dspace;
- }
-
- /* Get the virtual address associated with the start of the address
- * environment. This is the base address that we will need to use to
- * access the D-Space region (but only if the address environment has been
- * selected.
- */
-
- ret = up_addrenv_vaddr(loadinfo->addrenv, &vaddr);
- if (ret < 0)
- {
- bdbg("ERROR: up_addrenv_vaddr failed: %d\n", ret);
- goto errout_with_addrenv;
- }
-
- /* Clear all of the allocated D-Space memory. We have to temporarily
- * selected the D-Space address environment to do this.
- */
-
- ret = up_addrenv_select(loadinfo->addrenv, &oldenv);
- if (ret < 0)
- {
- bdbg("ERROR: up_addrenv_select failed: %d\n", ret);
- goto errout_with_addrenv;
- }
-
- memset(vaddr, 0, envsize);
-
- ret = up_addrenv_restore(oldenv);
- if (ret < 0)
- {
- bdbg("ERROR: up_addrenv_restore failed: %d\n", ret);
- goto errout_with_addrenv;
- }
-
- /* Success... save the fruits of our labor */
-
- loadinfo->dspace = dspace;
- dspace->crefs = 1;
- dspace->region = (FAR uint8_t *)vaddr;
- return OK;
-
-errout_with_addrenv:
- (void)up_addrenv_destroy(loadinfo->addrenv);
- loadinfo->addrenv = 0;
-
-errout_with_dspace:
- kfree(dspace);
- return ret;
-#else
- /* Allocate (and zero) memory to hold the ELF image */
-
- dspace->region = (FAR uint8_t *)kzalloc(envsize);
- if (!dspace->region)
- {
- kfree(dspace);
- return -ENOMEM;
- }
-
- loadinfo->dspace = dspace;
- dspace->crefs = 1;
- return OK;
-#endif
-}
-
-/****************************************************************************
- * Name: nxflat_addrenv_free
- *
- * Description:
- * Release the address environment previously created by
- * nxflat_addrenv_create(). This function is called only under certain
- * error conditions after the the module has been loaded but not yet
- * started. After the module has been started, the address environment
- * will automatically be freed when the module exits.
- *
- * Input Parameters:
- * loadinfo - Load state information
- *
- * Returned Value:
- * None.
- *
- ****************************************************************************/
-
-void nxflat_addrenv_free(FAR struct nxflat_loadinfo_s *loadinfo)
-{
- FAR struct dspace_s *dspace;
-#ifdef CONFIG_ADDRENV
- int ret;
-#endif
-
- DEBUGASSERT(loadinfo);
- dspace = loadinfo->dspace;
-
- if (dspace)
- {
-#ifdef CONFIG_ADDRENV
- /* Destroy the address environment */
-
- ret = up_addrenv_destroy(loadinfo->addrenv);
- if (ret < 0)
- {
- bdbg("ERROR: up_addrenv_destroy failed: %d\n", ret);
- }
-
- loadinfo->addrenv = 0;
-#else
- /* Free the allocated D-Space region */
-
- if (dspace->region)
- {
- kfree(dspace->region);
- }
-#endif
-
- /* Now destroy the D-Space container */
-
- DEBUGASSERT(dspace->crefs == 1);
- kfree(dspace);
- loadinfo->dspace = NULL;
- }
-}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_bind.c b/nuttx/binfmt/libnxflat/libnxflat_bind.c
deleted file mode 100644
index 816810a46..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_bind.c
+++ /dev/null
@@ -1,615 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_bind.c
- *
- * Copyright (C) 2009 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 <nuttx/compiler.h>
-
-#include <stdint.h>
-#include <string.h>
-#include <nxflat.h>
-#include <errno.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <arpa/inet.h>
-
-#include <nuttx/binfmt/nxflat.h>
-#include <nuttx/binfmt/symtab.h>
-
-#include "libnxflat.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
- * defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
- */
-
-#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
-# undef CONFIG_NXFLAT_DUMPBUFFER
-#endif
-
-#ifdef CONFIG_NXFLAT_DUMPBUFFER
-# define nxflat_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
-#else
-# define nxflat_dumpbuffer(m,b,n)
-#endif
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_bindrel32i
- *
- * Description:
- * Perform the NXFLAT_RELOC_TYPE_REL32I binding:
- *
- * Meaning: Object file contains a 32-bit offset into I-Space at the offset.
- * Fixup: Add mapped I-Space address to the offset.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int nxflat_bindrel32i(FAR struct nxflat_loadinfo_s *loadinfo,
- uint32_t offset)
-{
- uint32_t *addr;
-
- bvdbg("NXFLAT_RELOC_TYPE_REL32I Offset: %08x I-Space: %p\n",
- offset, loadinfo->ispace + sizeof(struct nxflat_hdr_s));
-
- if (offset < loadinfo->dsize)
- {
- addr = (uint32_t*)(offset + loadinfo->dspace->region);
- bvdbg(" Before: %08x\n", *addr);
- *addr += (uint32_t)(loadinfo->ispace + sizeof(struct nxflat_hdr_s));
- bvdbg(" After: %08x\n", *addr);
- return OK;
- }
- else
- {
- bdbg("Offset: %08 does not lie in D-Space size: %08x\n",
- offset, loadinfo->dsize);
- return -EINVAL;
- }
-}
-
-/****************************************************************************
- * Name: nxflat_bindrel32d
- *
- * Description:
- * Perform the NXFLAT_RELOC_TYPE_REL32D binding:
- *
- * Meaning: Object file contains a 32-bit offset into D-Space at the offset.
- * Fixup: Add allocated D-Space address to the offset.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int nxflat_bindrel32d(FAR struct nxflat_loadinfo_s *loadinfo,
- uint32_t offset)
-{
- uint32_t *addr;
-
- bvdbg("NXFLAT_RELOC_TYPE_REL32D Offset: %08x D-Space: %p\n",
- offset, loadinfo->dspace->region);
-
- if (offset < loadinfo->dsize)
- {
- addr = (uint32_t*)(offset + loadinfo->dspace->region);
- bvdbg(" Before: %08x\n", *addr);
- *addr += (uint32_t)(loadinfo->dspace->region);
- bvdbg(" After: %08x\n", *addr);
- return OK;
- }
- else
- {
- bdbg("Offset: %08 does not lie in D-Space size: %08x\n",
- offset, loadinfo->dsize);
- return -EINVAL;
- }
-}
-
-/****************************************************************************
- * Name: nxflat_bindrel32id
- *
- * Description:
- * Perform the NXFLAT_RELOC_TYPE_REL32ID binding:
- *
- * Meaning: Object file contains a 32-bit offset into I-Space at the offset
- * that will unfortunately be references relative to the GOT
- * Fixup: Add allocated the mapped I-Space address MINUS the allocated
- * D-Space address to the offset.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-#ifdef NXFLAT_RELOC_TYPE_REL32ID
-static inline int nxflat_bindrel32id(FAR struct nxflat_loadinfo_s *loadinfo,
- uint32_t offset)
-{
- uint32_t *addr;
-
- bvdbg("NXFLAT_RELOC_TYPE_REL32D Offset: %08x D-Space: %p\n",
- offset, loadinfo->dspace->region);
-
- if (offset < loadinfo->dsize)
- {
- addr = (uint32_t*)(offset + loadinfo->dspace->region);
- bvdbg(" Before: %08x\n", *addr);
- *addr += ((uint32_t)loadinfo->ispace - (uint32_t)(loadinfo->dspace->region));
- bvdbg(" After: %08x\n", *addr);
- return OK;
- }
- else
- {
- bdbg("Offset: %08 does not lie in D-Space size: %08x\n",
- offset, loadinfo->dsize);
- return -EINVAL;
- }
-}
-#endif
-
-/****************************************************************************
- * Name: nxflat_gotrelocs
- *
- * Description:
- * Bind all of the GOT relocations in the loaded module described by
- * 'loadinfo'
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
-{
- FAR struct nxflat_reloc_s *relocs;
- FAR struct nxflat_reloc_s reloc;
- FAR struct nxflat_hdr_s *hdr;
- uint32_t offset;
- uint16_t nrelocs;
- int ret;
- int result;
- int i;
-
- /* The NXFLAT header is the first thing at the beginning of the ISpace. */
-
- hdr = (FAR struct nxflat_hdr_s*)loadinfo->ispace;
-
- /* From this, we can get the offset to the list of relocation entries */
-
- offset = ntohl(hdr->h_relocstart);
- nrelocs = ntohs(hdr->h_reloccount);
- bvdbg("offset: %08lx nrelocs: %d\n", (long)offset, nrelocs);
-
- /* The value of the relocation list that we get from the header is a
- * file offset. We will have to convert this to an offset into the
- * DSpace segment to get the pointer to the beginning of the relocation
- * list.
- */
-
- DEBUGASSERT(offset >= loadinfo->isize);
- DEBUGASSERT(offset + nrelocs * sizeof(struct nxflat_reloc_s)
- <= (loadinfo->isize + loadinfo->dsize));
-
- relocs = (FAR struct nxflat_reloc_s *)
- (offset - loadinfo->isize + loadinfo->dspace->region);
- bvdbg("isize: %08lx dpsace: %p relocs: %p\n",
- (long)loadinfo->isize, loadinfo->dspace->region, relocs);
-
- /* All relocations are performed within the D-Space allocation. If
- * CONFIG_ADDRENV=y, then that D-Space allocation lies in an address
- * environment that may not be in place. So, in that case, we must call
- * nxflat_addrenv_select to temporarily instantiate that address space
- * before the relocations can be performed.
- */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_select(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
- return ret;
- }
-#endif
-
- /* Now, traverse the relocation list of and bind each GOT relocation. */
-
- ret = OK; /* Assume success */
- for (i = 0; i < nrelocs; i++)
- {
- /* Handle the relocation by the relocation type */
-
-#ifdef CONFIG_CAN_PASS_STRUCTS
- reloc = *relocs++;
-#else
- memcpy(&reloc, relocs, sizeof(struct nxflat_reloc_s));
- relocs++;
-#endif
-
- result = OK;
- switch (NXFLAT_RELOC_TYPE(reloc.r_info))
- {
- /* NXFLAT_RELOC_TYPE_REL32I Meaning: Object file contains a 32-bit offset
- * into I-Space at the offset.
- * Fixup: Add mapped I-Space address to the offset.
- */
-
- case NXFLAT_RELOC_TYPE_REL32I:
- {
- result = nxflat_bindrel32i(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
- }
- break;
-
- /* NXFLAT_RELOC_TYPE_REL32D Meaning: Object file contains a 32-bit offset
- * into D-Space at the offset.
- * Fixup: Add allocated D-Space address to the
- * offset.
- */
-
- case NXFLAT_RELOC_TYPE_REL32D:
- {
- result = nxflat_bindrel32d(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
- }
- break;
-
- /* NXFLAT_RELOC_TYPE_REL32ID Meaning: Object file contains a 32-bit offset
- * into I-Space at the offset that will
- * unfortunately be references relative
- * to the GOT
- * Fixup: Add allocated the mapped I-Space
- * address MINUS the allocated D-Space
- * address to the offset.
- */
-
-#ifdef NXFLAT_RELOC_TYPE_REL32ID
- case NXFLAT_RELOC_TYPE_REL32ID:
- {
- result = nxflat_bindrel32id(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
- }
- break;
-#endif
-
- default:
- {
- bdbg("ERROR: Unrecognized relocation type: %d\n", NXFLAT_RELOC_TYPE(reloc.r_info));
- result = -EINVAL;
- }
- break;
- }
-
- /* Check for failures */
-
- if (result < 0 && ret == OK)
- {
- ret = result;
- }
- }
-
- /* Dump the relocation got */
-
-#ifdef CONFIG_NXFLAT_DUMPBUFFER
- if (ret == OK && nrelocs > 0)
- {
- relocs = (FAR struct nxflat_reloc_s*)(offset - loadinfo->isize + loadinfo->dspace->region);
- nxflat_dumpbuffer("GOT", (FAR const uint8_t*)relocs, nrelocs * sizeof(struct nxflat_reloc_s));
- }
-#endif
-
- /* Restore the original address environment */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_restore(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
- }
-#endif
-
- return ret;
-}
-
-/****************************************************************************
- * Name: nxflat_bindimports
- *
- * Description:
- * Bind the imported symbol names in the loaded module described by
- * 'loadinfo' using the exported symbol values provided by 'symtab'
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
- FAR const struct symtab_s *exports,
- int nexports)
-{
- FAR struct nxflat_import_s *imports;
- FAR struct nxflat_hdr_s *hdr;
- FAR const struct symtab_s *symbol;
-
- char *symname;
- uint32_t offset;
- uint16_t nimports;
-#ifdef CONFIG_ADDRENV
- int ret;
-#endif
- int i;
-
- /* The NXFLAT header is the first thing at the beginning of the ISpace. */
-
- hdr = (FAR struct nxflat_hdr_s*)loadinfo->ispace;
-
- /* From this, we can get the offset to the list of symbols imported by
- * this module and the number of symbols imported by this module.
- */
-
- offset = ntohl(hdr->h_importsymbols);
- nimports = ntohs(hdr->h_importcount);
- bvdbg("Imports offset: %08x nimports: %d\n", offset, nimports);
-
- /* The import[] table resides within the D-Space allocation. If
- * CONFIG_ADDRENV=y, then that D-Space allocation lies in an address
- * environment that may not be in place. So, in that case, we must call
- * nxflat_addrenv_select to temporarily instantiate that address space
- * before the import[] table can be modified.
- */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_select(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
- return ret;
- }
-#endif
-
- /* Verify that this module requires imported symbols */
-
- if (offset != 0 && nimports > 0)
- {
- /* It does.. make sure that exported symbols are provided */
-
- DEBUGASSERT(exports && nexports > 0);
-
- /* If non-zero, the value of the imported symbol list that we get
- * from the header is a file offset. We will have to convert this
- * to an offset into the DSpace segment to get the pointer to the
- * beginning of the imported symbol list.
- */
-
- DEBUGASSERT(offset >= loadinfo->isize &&
- offset < loadinfo->isize + loadinfo->dsize);
-
- imports = (struct nxflat_import_s*)
- (offset - loadinfo->isize + loadinfo->dspace->region);
-
- /* Now, traverse the list of imported symbols and attempt to bind
- * each symbol to the value exported by from the exported symbol
- * table.
- */
-
- for (i = 0; i < nimports; i++)
- {
- bvdbg("Import[%d] (%08p) offset: %08x func: %08x\n",
- i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress);
-
- /* Get a pointer to the imported symbol name. The name itself
- * lies in the TEXT segment. But the reference to the name
- * lies in DATA segment. Therefore, the name reference should
- * have been relocated when the module was loaded.
- */
-
- offset = imports[i].i_funcname;
- DEBUGASSERT(offset < loadinfo->isize);
-
- symname = (char*)(offset + loadinfo->ispace + sizeof(struct nxflat_hdr_s));
-
- /* Find the exported symbol value for this this symbol name. */
-
-#ifdef CONFIG_SYMTAB_ORDEREDBYNAME
- symbol = symtab_findorderedbyname(exports, symname, nexports);
-#else
- symbol = symtab_findbyname(exports, symname, nexports);
-#endif
- if (!symbol)
- {
- bdbg("Exported symbol \"%s\" not found\n", symname);
-#ifdef CONFIG_ADDRENV
- (void)nxflat_addrenv_restore(loadinfo);
-#endif
- return -ENOENT;
- }
-
- /* And put this into the module's import structure. */
-
- imports[i].i_funcaddress = (uint32_t)symbol->sym_value;
-
- bvdbg("Bound import[%d] (%08p) to export '%s' (%08x)\n",
- i, &imports[i], symname, imports[i].i_funcaddress);
- }
- }
-
- /* Dump the relocation import table */
-
-#ifdef CONFIG_NXFLAT_DUMPBUFFER
- if (nimports > 0)
- {
- nxflat_dumpbuffer("Imports", (FAR const uint8_t*)imports, nimports * sizeof(struct nxflat_import_s));
- }
-#endif
-
- /* Restore the original address environment */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_restore(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
- }
-
- return ret;
-#else
- return OK;
-#endif
-}
-
-/****************************************************************************
- * Name: nxflat_clearbss
- *
- * Description:
- * Clear uninitialized .bss memory
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-static inline int nxflat_clearbss(FAR struct nxflat_loadinfo_s *loadinfo)
-{
-#ifdef CONFIG_ADDRENV
- int ret;
-#endif
-
- /* .bss resides within the D-Space allocation. If CONFIG_ADDRENV=y, then
- * that D-Space allocation lies in an address environment that may not be
- * in place. So, in that case, we must call nxflat_addrenv_select to
- * temporarily instantiate that address space before the .bss can be
- * accessed.
- */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_select(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
- return ret;
- }
-#endif
-
- /* Zero the BSS area */
-
- memset((void*)(loadinfo->dspace->region + loadinfo->datasize), 0,
- loadinfo->bsssize);
-
- /* Restore the original address environment */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_restore(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
- }
-
- return ret;
-#else
- return OK;
-#endif
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_bind
- *
- * Description:
- * Bind the imported symbol names in the loaded module described by
- * 'loadinfo' using the exported symbol values provided by 'symtab'.
- * After binding the module, clear the BSS region (which held the relocation
- * data) in preparation for execution.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
- FAR const struct symtab_s *exports, int nexports)
-{
- /* Bind the imported symbol, absolute relocations separately. This is done
- * before the standard relocations because that logic may modify the
- * import list (for the better hopefully, but we don't want to depend on it).
- */
-
- int ret = nxflat_bindimports(loadinfo, exports, nexports);
- if (ret == OK)
- {
- /* Then bind all GOT relocations */
-
- ret = nxflat_gotrelocs(loadinfo);
- if (ret == OK)
- {
- /* Zero the BSS area, trashing the relocations that lived in that
- * space in the loaded file.
- */
-
- ret = nxflat_clearbss(loadinfo);
- }
- }
-
- return ret;
-}
-
diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c
deleted file mode 100644
index b7cac8d86..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_init.c
+++ /dev/null
@@ -1,189 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_init.c
- *
- * Copyright (C) 2009 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 <sys/stat.h>
-#include <stdint.h>
-#include <string.h>
-#include <fcntl.h>
-#include <nxflat.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <arpa/inet.h>
-#include <nuttx/binfmt/nxflat.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
- * defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
- */
-
-#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
-# undef CONFIG_NXFLAT_DUMPBUFFER
-#endif
-
-#ifdef CONFIG_NXFLAT_DUMPBUFFER
-# define nxflat_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
-#else
-# define nxflat_dumpbuffer(m,b,n)
-#endif
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_init
- *
- * Description:
- * This function is called to configure the library to process an NXFLAT
- * program binary.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo)
-{
- uint32_t datastart;
- uint32_t dataend;
- uint32_t bssstart;
- uint32_t bssend;
- int ret;
-
- bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo);
-
- /* Clear the load info structure */
-
- memset(loadinfo, 0, sizeof(struct nxflat_loadinfo_s));
-
- /* Open the binary file */
-
- loadinfo->filfd = open(filename, O_RDONLY);
- if (loadinfo->filfd < 0)
- {
- int errval = errno;
- bdbg("Failed to open NXFLAT binary %s: %d\n", filename, errval);
- return -errval;
- }
-
- /* Read the NXFLAT header from offset 0 */
-
- ret = nxflat_read(loadinfo, (char*)&loadinfo->header,
- sizeof(struct nxflat_hdr_s), 0);
- if (ret < 0)
- {
- bdbg("Failed to read NXFLAT header: %d\n", ret);
- return ret;
- }
- nxflat_dumpbuffer("NXFLAT header", (FAR const uint8_t*)&loadinfo->header,
- sizeof(struct nxflat_hdr_s));
-
- /* Verify the NXFLAT header */
-
- if (nxflat_verifyheader(&loadinfo->header) != 0)
- {
- /* This is not an error because we will be called to attempt loading
- * EVERY binary. Returning -ENOEXEC simply informs the system that
- * the file is not an NXFLAT file. Besides, if there is something worth
- * complaining about, nnxflat_verifyheader() has already
- * done so.
- */
-
- bdbg("Bad NXFLAT header\n");
- return -ENOEXEC;
- }
-
- /* Save all of the input values in the loadinfo structure
- * and extract some additional information from the xflat
- * header. Note that the information in the xflat header is in
- * network order.
- */
-
- datastart = ntohl(loadinfo->header.h_datastart);
- dataend = ntohl(loadinfo->header.h_dataend);
- bssstart = dataend;
- bssend = ntohl(loadinfo->header.h_bssend);
-
- /* And put this information into the loadinfo structure as well.
- *
- * Note that:
- *
- * isize = the address range from 0 up to datastart.
- * datasize = the address range from datastart up to dataend
- * bsssize = the address range from dataend up to bssend.
- */
-
- loadinfo->entryoffs = ntohl(loadinfo->header.h_entry);
- loadinfo->isize = datastart;
-
- loadinfo->datasize = dataend - datastart;
- loadinfo->bsssize = bssend - dataend;
- loadinfo->stacksize = ntohl(loadinfo->header.h_stacksize);
-
- /* This is the initial dspace size. We'll re-calculate this later
- * after the memory has been allocated.
- */
-
- loadinfo->dsize = bssend - datastart;
-
- /* Get the offset to the start of the relocations (we'll relocate
- * this later).
- */
-
- loadinfo->relocstart = ntohl(loadinfo->header.h_relocstart);
- loadinfo->reloccount = ntohs(loadinfo->header.h_reloccount);
-
- return 0;
-}
-
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
deleted file mode 100644
index 5f13b577a..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_load.c
+++ /dev/null
@@ -1,222 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_load.c
- *
- * Copyright (C) 2009 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 <sys/types.h>
-#include <sys/mman.h>
-
-#include <stdint.h>
-#include <stdlib.h>
-#include <nxflat.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <arpa/inet.h>
-
-#include <nuttx/binfmt/nxflat.h>
-
-#include "libnxflat.h"
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-#ifndef MAX
-#define MAX(x,y) ((x) > (y) ? (x) : (y))
-#endif
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_load
- *
- * Description:
- * Loads the binary specified by nxflat_init into memory, mapping
- * the I-space executable regions, allocating the D-Space region,
- * and inializing the data segment (relocation information is
- * temporarily loaded into the BSS region. BSS will be cleared
- * by nxflat_bind() after the relocation data has been processed).
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
-{
- off_t doffset; /* Offset to .data in the NXFLAT file */
- uint32_t dreadsize; /* Total number of bytes of .data to be read */
- uint32_t relocsize; /* Memory needed to hold relocations */
- uint32_t extrasize; /* MAX(BSS size, relocsize) */
- int ret = OK;
-
- /* Calculate the extra space we need to allocate. This extra space will be
- * the size of the BSS section. This extra space will also be used
- * temporarily to hold relocation information. So the allocated size of this
- * region will either be the size of .data + size of.bss section OR, the
- * size of .data + the relocation entries, whichever is larger
- *
- * This is the amount of memory that we have to have to hold the
- * relocations.
- */
-
- relocsize = loadinfo->reloccount * sizeof(struct nxflat_reloc_s);
-
- /* In the file, the relocations should lie at the same offset as BSS.
- * The additional amount that we allocate have to be either (1) the
- * BSS size, or (2) the size of the relocation records, whicher is
- * larger.
- */
-
- extrasize = MAX(loadinfo->bsssize, relocsize);
-
- /* Use this additional amount to adjust the total size of the dspace
- * region.
- */
-
- loadinfo->dsize = loadinfo->datasize + extrasize;
-
- /* The number of bytes of data that we have to read from the file is
- * the data size plus the size of the relocation table.
- */
-
- dreadsize = loadinfo->datasize + relocsize;
-
- /* We'll need this a few times. */
-
- doffset = loadinfo->isize;
-
- /* We will make two mmap calls create an address space for the executable.
- * We will attempt to map the file to get the ISpace address space and
- * to allocate RAM to get the DSpace address space. If the filesystem does
- * not support file mapping, the map() implementation should do the
- * right thing.
- */
-
- /* The following call will give as a pointer to the mapped file ISpace.
- * This may be in ROM, RAM, Flash, ... We don't really care where the memory
- * resides as long as it is fully initialized and ready to execute.
- */
-
- loadinfo->ispace = (uint32_t)mmap(NULL, loadinfo->isize, PROT_READ,
- MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
- if (loadinfo->ispace == (uint32_t)MAP_FAILED)
- {
- bdbg("Failed to map NXFLAT ISpace: %d\n", errno);
- return -errno;
- }
-
- bvdbg("Mapped ISpace (%d bytes) at %08x\n", loadinfo->isize, loadinfo->ispace);
-
- /* The following call allocate D-Space memory and will provide a pointer
- * to the allocated (but still uninitialized) D-Space memory.
- */
-
- ret = nxflat_addrenv_alloc(loadinfo, loadinfo->dsize);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_alloc() failed: %d\n", ret);
- return ret;
- }
-
- bvdbg("Allocated DSpace (%d bytes) at %p\n",
- loadinfo->dsize, loadinfo->dspace->region);
-
- /* If CONFIG_ADDRENV=y, then the D-Space allocation lies in an address
- * environment that may not be in place. So, in that case, we must call
- * nxflat_addrenv_select to temporarily instantiate that address space
- * it can be initialized.
- */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_select(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_select() failed: %d\n", ret);
- return ret;
- }
-#endif
-
- /* Now, read the data into allocated DSpace at doffset into the allocated
- * DSpace memory.
- */
-
- ret = nxflat_read(loadinfo, (char*)loadinfo->dspace->region, dreadsize, doffset);
- if (ret < 0)
- {
- bdbg("Failed to read .data section: %d\n", ret);
- goto errout;
- }
-
- bvdbg("TEXT: %08x Entry point offset: %08x Data offset: %08x\n",
- loadinfo->ispace, loadinfo->entryoffs, doffset);
-
- /* Restore the original address environment */
-
-#ifdef CONFIG_ADDRENV
- ret = nxflat_addrenv_restore(loadinfo);
- if (ret < 0)
- {
- bdbg("ERROR: nxflat_addrenv_restore() failed: %d\n", ret);
- return ret;
- }
-#endif
-
- return OK;
-
-errout:
-#ifdef CONFIG_ADDRENV
- (void)nxflat_addrenv_restore(loadinfo);
-#endif
- (void)nxflat_unload(loadinfo);
- return ret;
-}
-
diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c
deleted file mode 100644
index 103a81f81..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_read.c
+++ /dev/null
@@ -1,167 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_read.c
- *
- * Copyright (C) 2009 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 <sys/types.h>
-#include <stdint.h>
-#include <unistd.h>
-#include <string.h>
-#include <nxflat.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <arpa/inet.h>
-#include <nuttx/binfmt/nxflat.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-#undef NXFLAT_DUMP_READDATA /* Define to dump all file data read */
-#define DUMPER syslog /* If NXFLAT_DUMP_READDATA is defined, this
- * is the API used to dump data */
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_dumpreaddata
- ****************************************************************************/
-
-#if defined(NXFLAT_DUMP_READDATA)
-static inline void nxflat_dumpreaddata(char *buffer, int buflen)
-{
- uint32_t *buf32 = (uint32_t*)buffer;
- int i;
- int j;
-
- for (i = 0; i < buflen; i += 32)
- {
- DUMPER("%04x:", i);
- for (j = 0; j < 32; j += sizeof(uint32_t))
- {
- DUMPER(" %08x", *buf32++);
- }
- DUMPER("\n");
- }
-}
-#else
-# define nxflat_dumpreaddata(b,n)
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_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 nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer, int readsize, int offset)
-{
- ssize_t nbytes; /* Number of bytes read */
- off_t rpos; /* Position returned by lseek */
- char *bufptr; /* Next buffer location to read into */
- int bytesleft; /* Number of bytes of .data left to read */
- int bytesread; /* Total number of bytes read */
-
- bvdbg("Read %d bytes from offset %d\n", readsize, offset);
-
- /* Seek to the position in the object file where the initialized
- * data is saved.
- */
-
- bytesread = 0;
- bufptr = buffer;
- bytesleft = readsize;
- do
- {
- rpos = lseek(loadinfo->filfd, offset, SEEK_SET);
- if (rpos != offset)
- {
- int errval = errno;
- bdbg("Failed to seek to position %d: %d\n", offset, errval);
- return -errval;
- }
-
- /* Read the file data at offset into the user buffer */
-
- nbytes = read(loadinfo->filfd, bufptr, bytesleft);
- if (nbytes < 0)
- {
- int errval = errno;
- if (errval != EINTR)
- {
- bdbg("Read of .data failed: %d\n", errval);
- return -errval;
- }
- }
- else if (nbytes == 0)
- {
- bdbg("Unexpected end of file\n");
- return -ENODATA;
- }
- else
- {
- bytesread += nbytes;
- bytesleft -= nbytes;
- bufptr += nbytes;
- offset += nbytes;
- }
- }
- while (bytesread < readsize);
-
- nxflat_dumpreaddata(buffer, readsize);
- return OK;
-}
-
diff --git a/nuttx/binfmt/libnxflat/libnxflat_uninit.c b/nuttx/binfmt/libnxflat/libnxflat_uninit.c
deleted file mode 100644
index b9715196b..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_uninit.c
+++ /dev/null
@@ -1,85 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_uninit.c
- *
- * Copyright (C) 2009 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 <unistd.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/binfmt/nxflat.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_uninit
- *
- * Description:
- * Releases any resources committed by nxflat_init(). This essentially
- * undoes the actions of nxflat_init.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo)
-{
- if (loadinfo->filfd >= 0)
- {
- close(loadinfo->filfd);
- }
- return OK;
-}
-
diff --git a/nuttx/binfmt/libnxflat/libnxflat_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c
deleted file mode 100644
index eb1aa0343..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_unload.c
+++ /dev/null
@@ -1,97 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/libnxflat_unload.c
- *
- * Copyright (C) 2009 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 <sys/mman.h>
-
-#include <stdlib.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/binfmt/nxflat.h>
-
-#include "libnxflat.h"
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_unload
- *
- * Description:
- * This function unloads the object from memory. This essentially undoes
- * the actions of nxflat_load. It is called only under certain error
- * conditions after the the module has been loaded but not yet started.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
-{
- /* Release the memory segments */
- /* Release the I-Space mmap'ed file */
-
- if (loadinfo->ispace)
- {
- munmap((void*)loadinfo->ispace, loadinfo->isize);
- loadinfo->ispace = 0;
- }
-
- /* Release the D-Space address environment */
-
- nxflat_addrenv_free(loadinfo);
- return OK;
-}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c
deleted file mode 100644
index 20af5d2f7..000000000
--- a/nuttx/binfmt/libnxflat/libnxflat_verify.c
+++ /dev/null
@@ -1,101 +0,0 @@
-/****************************************************************************
- * binfmt/libnxflat/nxflat_verify.c
- *
- * Copyright (C) 2009 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 <debug.h>
-#include <errno.h>
-
-#include <arpa/inet.h>
-#include <nuttx/binfmt/nxflat.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxflat_verifyheader
- *
- * Description:
- * Given the header from a possible NXFLAT executable, verify that it
- * is an NXFLAT executable.
- *
- * Returned Value:
- * 0 (OK) is returned on success and a negated errno is returned on
- * failure.
- *
- ****************************************************************************/
-
-int nxflat_verifyheader(const struct nxflat_hdr_s *header)
-{
- if (!header)
- {
- bdbg("NULL NXFLAT header!");
- return -ENOEXEC;
- }
-
- /* Check the FLT header -- magic number and revision.
- *
- * If the magic number does not match. Just return
- * silently. This is not our binary.
- */
-
- if (strncmp(header->h_magic, NXFLAT_MAGIC, 4) != 0)
- {
- bdbg("Unrecognized magic=\"%c%c%c%c\"\n",
- header->h_magic[0], header->h_magic[1],
- header->h_magic[2], header->h_magic[3]);
- return -ENOEXEC;
- }
-
- return OK;
-}