summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-19 17:54:26 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-19 17:54:26 +0000
commit913f876fac94f21a683809d9f648e4793f61e237 (patch)
tree1587afb37a0e1b5a87f007f452e147ff3c2dcc04
parentbbef9f93daeb6a3565c4c28572d73130dfb6ac85 (diff)
downloadpx4-nuttx-913f876fac94f21a683809d9f648e4793f61e237.tar.gz
px4-nuttx-913f876fac94f21a683809d9f648e4793f61e237.tar.bz2
px4-nuttx-913f876fac94f21a683809d9f648e4793f61e237.zip
Incorporate address environment interfaces in binfmt/ logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5443 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--apps/examples/nxflat/Makefile2
-rw-r--r--nuttx/ChangeLog7
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html8
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_ssi.c5
-rw-r--r--nuttx/binfmt/binfmt_dumpmodule.c3
-rw-r--r--nuttx/binfmt/binfmt_execmodule.c45
-rw-r--r--nuttx/binfmt/binfmt_unloadmodule.c39
-rw-r--r--nuttx/binfmt/elf.c23
-rw-r--r--nuttx/binfmt/libelf/Make.defs6
-rw-r--r--nuttx/binfmt/libelf/libelf.h85
-rw-r--r--nuttx/binfmt/libelf/libelf_addrenv.c176
-rw-r--r--nuttx/binfmt/libelf/libelf_bind.c36
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c35
-rw-r--r--nuttx/binfmt/libelf/libelf_read.c6
-rw-r--r--nuttx/binfmt/libelf/libelf_unload.c13
-rw-r--r--nuttx/binfmt/libnxflat/Make.defs6
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat.h136
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_addrenv.c234
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_bind.c128
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c56
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_unload.c19
-rw-r--r--nuttx/binfmt/nxflat.c23
-rwxr-xr-xnuttx/configs/eagle100/httpd/setenv.sh26
-rwxr-xr-xnuttx/configs/eagle100/nettest/setenv.sh26
-rwxr-xr-xnuttx/configs/eagle100/nsh/setenv.sh26
-rwxr-xr-xnuttx/configs/eagle100/nxflat/setenv.sh26
-rw-r--r--nuttx/include/nuttx/binfmt/binfmt.h17
-rw-r--r--nuttx/include/nuttx/binfmt/elf.h46
-rw-r--r--nuttx/include/nuttx/binfmt/nxflat.h39
-rw-r--r--nuttx/include/nuttx/sched.h32
30 files changed, 1225 insertions, 104 deletions
diff --git a/apps/examples/nxflat/Makefile b/apps/examples/nxflat/Makefile
index 344ee9c6d..94092bd39 100644
--- a/apps/examples/nxflat/Makefile
+++ b/apps/examples/nxflat/Makefile
@@ -76,7 +76,7 @@ $(COBJS): %$(OBJEXT): %.c
headers:
@$(MAKE) -C tests TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" CROSSDEV=$(CROSSDEV)
-.built: $(OBJS)
+.built: headers $(OBJS)
$(call ARCHIVE, $(BIN), $(OBJS))
@touch .built
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index c932a1f2d..1296076b6 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3792,3 +3792,10 @@
logic on initial check-in
* binfmt/binfmt_loadmodule.c: load_module() will now traverse the PATH
variable to locate files from their relative path.
+ * include/nuttx/arch.h and arch/z80/src/z180/z180_mmu.c: Restructure the
+ address environment interfaces so that they will better integrate with
+ binfmt/.
+ * binfmt/libelf/*, binfmt/libnxflat/* and other files: Integrate the
+ address environment interfaces. If CONFIG_ADDRENV=y, then binfmt/
+ will now create an address environment for new tasks (instead of
+ just malloc'ing the task memory).
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 526892d3e..0408f82ac 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -2130,7 +2130,7 @@ else
<p>
<b>Binary Loader Support</b>.
These are low-level interfaces used in <code>binfmt/</code> to instantiate tasks with address environments.
- These interfaces all operate on type <code>task_addrenv_t</code> which is an abstract representation of a asks's address environment and must be defined in arch/arch.h if <code>CONFIG_ADDRENVM</code> is defined.
+ These interfaces all operate on type <code>task_addrenv_t</code> which is an abstract representation of a asks's address environment and must be defined in arch/arch.h if <code>CONFIG_ADDRENV</code> is defined.
These low-level interfaces include:
</p>
<ul>
@@ -2174,7 +2174,7 @@ else
</li>
<li>
<a href="#up_addrenv_release">4.1.21.8 <code>up_addrenv_release()</code></a>:
- ARelease the TCBs reference to an address environment when a task/thread exits.
+ Release the TCB's reference to an address environment when a task/thread exits.
</li>
</ul>
</li>
@@ -3930,7 +3930,9 @@ void (*notify)(FAR struct pm_callback_s *cb, enum pm_state_e pmstate);
up_prioritize_irq() API.</li>
<li><code>CONFIG_ADDRENV</code>:
The CPU supports an MMU and CPU port supports provision of address
- environments for tasks (making the, perhaps, processes).</li>
+ environments for tasks (making the, perhaps, processes).
+ In this case, the CPU-specific logic must provide a set of address environment interfaces as defined in the <a href="#addrenv">Address Environments</a> paragraph.
+ </li>
</ul>
<p>
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
index c756e2b6a..8d1987992 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
@@ -209,8 +209,11 @@ static inline void ssi_putreg(struct lm3s_ssidev_s *priv, unsigned int offset,
static uint32_t ssi_disable(struct lm3s_ssidev_s *priv);
static void ssi_enable(struct lm3s_ssidev_s *priv, uint32_t enable);
+
+#ifndef CONFIG_SSI_POLLWAIT
static void ssi_semtake(sem_t *sem);
#define ssi_semgive(s) sem_post(s);
+#endif
/* SSI data transfer */
@@ -446,6 +449,7 @@ static void ssi_enable(struct lm3s_ssidev_s *priv, uint32_t enable)
*
****************************************************************************/
+#ifndef CONFIG_SSI_POLLWAIT
static void ssi_semtake(sem_t *sem)
{
int ret;
@@ -456,6 +460,7 @@ static void ssi_semtake(sem_t *sem)
while (ret < 0 && errno == EINTR);
DEBUGASSERT(ret == 0);
}
+#endif
/****************************************************************************
* Name: ssi_txnull, ssi_txuint16, and ssi_txuint8
diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c
index cd52136b0..d320bc830 100644
--- a/nuttx/binfmt/binfmt_dumpmodule.c
+++ b/nuttx/binfmt/binfmt_dumpmodule.c
@@ -96,6 +96,9 @@ int dump_module(FAR const struct binary_s *bin)
bdbg(" ctors: %p nctors=%d\n", bin->ctors, bin->nctors);
bdbg(" dtors: %p ndtors=%d\n", bin->dtors, bin->ndtors);
#endif
+#ifdef CONFIG_ADDRENV
+ bdbg(" addrenv: %p\n", bin->addrenv);
+#endif
bdbg(" stacksize: %d\n", bin->stacksize);
}
return OK;
diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c
index 37f445966..400451c40 100644
--- a/nuttx/binfmt/binfmt_execmodule.c
+++ b/nuttx/binfmt/binfmt_execmodule.c
@@ -86,11 +86,26 @@
****************************************************************************/
#ifdef CONFIG_BINFMT_CONSTRUCTORS
-static inline void exec_ctors(FAR const struct binary_s *binp)
+static inline int exec_ctors(FAR const struct binary_s *binp)
{
binfmt_ctor_t *ctor = binp->ctors;
+#ifdef CONFIG_ADDRENV
+ hw_addrenv_t oldenv;
+ int ret;
+#endif
int i;
+ /* Instantiate the address enviroment containing the constructors */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_select(binp->addrenv, &oldenv);
+ if (ret < 0)
+ {
+ bdbg("up_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Execute each constructor */
for (i = 0; i < binp->nctors; i++)
@@ -100,6 +115,14 @@ static inline void exec_ctors(FAR const struct binary_s *binp)
(*ctor)();
ctor++;
}
+
+ /* Restore the address enviroment */
+
+#ifdef CONFIG_ADDRENV
+ return up_addrenv_restore(oldenv);
+#else
+ return OK;
+#endif
}
#endif
@@ -190,6 +213,18 @@ int exec_module(FAR const struct binary_s *binp, int priority)
up_initial_state(tcb);
#endif
+ /* Assign the address environment to the task */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_assign(binp->addrenv, tcb);
+ if (ret < 0)
+ {
+ err = -ret;
+ bdbg("up_addrenv_assign() failed: %d\n", ret);
+ goto errout_with_stack;
+ }
+#endif
+
/* Get the assigned pid before we start the task */
pid = tcb->pid;
@@ -197,7 +232,13 @@ int exec_module(FAR const struct binary_s *binp, int priority)
/* Execute all of the C++ static constructors */
#ifdef CONFIG_BINFMT_CONSTRUCTORS
- exec_ctors(binp);
+ ret = exec_ctors(binp);
+ if (ret < 0)
+ {
+ err = -ret;
+ bdbg("exec_ctors() failed: %d\n", ret);
+ goto errout_with_stack;
+ }
#endif
/* Then activate the task at the provided priority */
diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c
index 52243fcf7..a0050481c 100644
--- a/nuttx/binfmt/binfmt_unloadmodule.c
+++ b/nuttx/binfmt/binfmt_unloadmodule.c
@@ -86,8 +86,23 @@
static inline void exec_dtors(FAR const struct binary_s *binp)
{
binfmt_dtor_t *dtor = binp->dtors;
+#ifdef CONFIG_ADDRENV
+ hw_addrenv_t oldenv;
+ int ret;
+#endif
int i;
+ /* Instantiate the address enviroment containing the destructors */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_select(binp->addrenv, &oldenv);
+ if (ret < 0)
+ {
+ bdbg("up_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Execute each destructor */
for (i = 0; i < binp->ndtors; i++)
@@ -97,6 +112,14 @@ static inline void exec_dtors(FAR const struct binary_s *binp)
(*dtor)();
dtor++;
}
+
+ /* Restore the address enviroment */
+
+#ifdef CONFIG_ADDRENV
+ return up_addrenv_restore(oldenv);
+#else
+ return OK;
+#endif
}
#endif
@@ -125,15 +148,23 @@ static inline void exec_dtors(FAR const struct binary_s *binp)
int unload_module(FAR const struct binary_s *binp)
{
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ int ret;
+#endif
int i;
if (binp)
{
-
/* Execute C++ desctructors */
#ifdef CONFIG_BINFMT_CONSTRUCTORS
- exec_dtors(binp);
+ ret = exec_dtors(binp);
+ if (ret < 0)
+ {
+ bdbg("exec_ctors() failed: %d\n", ret);
+ set_errno(-ret);
+ return ERROR;
+ }
#endif
/* Unmap mapped address spaces */
@@ -155,6 +186,10 @@ int unload_module(FAR const struct binary_s *binp)
free(binp->alloc[i]);
}
}
+
+ /* Notice that the address environment is not destroyed. This should
+ * happen automatically when the task exits.
+ */
}
return OK;
diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c
index ea1e7b0ca..bcebf13ca 100644
--- a/nuttx/binfmt/elf.c
+++ b/nuttx/binfmt/elf.c
@@ -215,9 +215,22 @@ static int elf_loadbinary(struct binary_s *binp)
/* Return the load information */
binp->entrypt = (main_t)(loadinfo.elfalloc + loadinfo.ehdr.e_entry);
- binp->alloc[0] = (FAR void *)loadinfo.elfalloc;
binp->stacksize = CONFIG_ELF_STACKSIZE;
+ /* Add the ELF allocation to the alloc[] only if there is no address
+ * enironment. If there is an address environment, it will automatically
+ * be freed when the function exits
+ *
+ * REVISIT: If the module is loaded then unloaded, wouldn't this cause
+ * a memory leak?
+ */
+
+#ifdef CONFIG_ADDRENV
+# warning "REVISIT"
+#else
+ binp->alloc[0] = (FAR void *)loadinfo.elfalloc;
+#endif
+
#ifdef CONFIG_BINFMT_CONSTRUCTORS
/* Save information about constructors. NOTE: desctructors are not
* yet supported.
@@ -232,6 +245,14 @@ static int elf_loadbinary(struct binary_s *binp)
binp->ndtors = loadinfo.ndtors;
#endif
+#ifdef CONFIG_ADDRENV
+ /* Save the address environment. This will be needed when the module is
+ * executed for the up_addrenv_assign() call.
+ */
+
+ binp->addrenv = loadinfo.addrenv;
+#endif
+
elf_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,
MIN(loadinfo.allocsize - loadinfo.ehdr.e_entry, 512));
diff --git a/nuttx/binfmt/libelf/Make.defs b/nuttx/binfmt/libelf/Make.defs
index c8857c3f7..93d95a23c 100644
--- a/nuttx/binfmt/libelf/Make.defs
+++ b/nuttx/binfmt/libelf/Make.defs
@@ -41,9 +41,9 @@ BINFMT_CSRCS += elf.c
# ELF library
-BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_iobuffer.c libelf_load.c \
- libelf_read.c libelf_sections.c libelf_symbols.c libelf_uninit.c \
- libelf_unload.c libelf_verify.c
+BINFMT_CSRCS += libelf_bind.c libelf_init.c libelf_addrenv.c libelf_iobuffer.c
+BINFMT_CSRCS += libelf_load.c libelf_read.c libelf_sections.c libelf_symbols.c
+BINFMT_CSRCS += libelf_uninit.c libelf_unload.c libelf_verify.c
ifeq ($(CONFIG_BINFMT_CONSTRUCTORS),y)
BINFMT_CSRCS += libelf_ctors.c libelf_dtors.c
diff --git a/nuttx/binfmt/libelf/libelf.h b/nuttx/binfmt/libelf/libelf.h
index 5b0be9ab0..04c9144f6 100644
--- a/nuttx/binfmt/libelf/libelf.h
+++ b/nuttx/binfmt/libelf/libelf.h
@@ -45,6 +45,7 @@
#include <sys/types.h>
#include <elf32.h>
+#include <nuttx/arch.h>
#include <nuttx/binfmt/elf.h>
/****************************************************************************
@@ -74,7 +75,11 @@ int elf_verifyheader(FAR const Elf32_Ehdr *header);
* Name: elf_read
*
* Description:
- * Read 'readsize' bytes from the object file at 'offset'
+ * Read 'readsize' bytes from the object file at 'offset'. The data is
+ * read into 'buffer.' If 'buffer' is part of the ELF address environment,
+ * then the caller is responsibile for assuring that that address
+ * environment is in place before calling this function (i.e., that
+ * elf_addrenv_select() has been called if CONFIG_ADDRENV=y).
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
@@ -255,4 +260,82 @@ int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo);
int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo);
#endif
+/****************************************************************************
+ * Name: elf_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 elf_addrenv_alloc(FAR struct elf_loadinfo_s *loadinfo, size_t envsize);
+
+/****************************************************************************
+ * Name: elf_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 elf_addrenv_select(l) up_addrenv_select((l)->addrenv, &(l)->oldenv)
+#endif
+
+/****************************************************************************
+ * Name: elf_addrenv_restore
+ *
+ * Description:
+ * Restore the address environment before elf_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 elf_addrenv_restore(l) up_addrenv_restore((l)->oldenv)
+#endif
+
+/****************************************************************************
+ * Name: elf_addrenv_free
+ *
+ * Description:
+ * Release the address environment previously created by
+ * elf_addrenv_alloc(). 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 elf_addrenv_free(FAR struct elf_loadinfo_s *loadinfo);
+
#endif /* __BINFMT_LIBELF_LIBELF_H */
diff --git a/nuttx/binfmt/libelf/libelf_addrenv.c b/nuttx/binfmt/libelf/libelf_addrenv.c
new file mode 100644
index 000000000..28cc0e108
--- /dev/null
+++ b/nuttx/binfmt/libelf/libelf_addrenv.c
@@ -0,0 +1,176 @@
+/****************************************************************************
+ * binfmt/libelf/libelf_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 <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
+
+#include "libelf.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_addrenv_create
+ *
+ * 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 elf_addrenv_create(FAR struct elf_loadinfo_s *loadinfo, size_t envsize)
+{
+#ifdef CONFIG_ADDRENV
+ FAR void *vaddr;
+ int ret;
+
+ /* Create an address environment for the new ELF task */
+
+ ret = up_addrenv_create(envsize, &loadinfo->addrenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_create failed: %d\n", ret);
+ return ret;
+ }
+
+ /* 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 ELF image (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);
+ return ret;
+ }
+
+ loadinfo->elfalloc = (uintptr_t)vaddr;
+ return OK;
+#else
+ /* Allocate memory to hold the ELF image */
+
+ loadinfo->elfalloc = (uintptr_t)kzalloc(envsize);
+ if (!loadinfo->elfalloc)
+ {
+ return -ENOMEM;
+ }
+
+ return OK;
+#endif
+}
+
+/****************************************************************************
+ * Name: elf_addrenv_free
+ *
+ * Description:
+ * Release the address environment previously created by
+ * elf_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 elf_addrenv_free(FAR struct elf_loadinfo_s *loadinfo)
+{
+#ifdef CONFIG_ADDRENV
+ int ret;
+
+ /* Free the address environemnt */
+
+ ret = up_addrenv_destroy(loadinfo->addrenv);
+ if (ret < 0)
+ {
+ bdbg("ERROR: up_addrenv_destroy failed: %d\n", ret);
+ }
+
+ /* Clear out all indications of the allocated address environment */
+
+ loadinfo->elfalloc = 0;
+ loadinfo->elfsize = 0;
+ loadinfo->addrenv = 0;
+#else
+ /* If there is an allocation for the ELF image, free it */
+
+ if (loadinfo->elfalloc != 0)
+ {
+ kfree((FAR void *)loadinfo->elfalloc);
+ loadinfo->elfalloc = 0;
+ }
+
+ loadinfo->elfsize = 0;
+#endif
+}
diff --git a/nuttx/binfmt/libelf/libelf_bind.c b/nuttx/binfmt/libelf/libelf_bind.c
index e35087b1d..ccdb5108e 100644
--- a/nuttx/binfmt/libelf/libelf_bind.c
+++ b/nuttx/binfmt/libelf/libelf_bind.c
@@ -86,10 +86,10 @@
****************************************************************************/
/****************************************************************************
- * Name: elf_readsym
+ * Name: elf_readrel
*
* Description:
- * Read the ELFT symbol structure at the specfied index into memory.
+ * Read the ELF32_Rel structure into memory.
*
****************************************************************************/
@@ -184,7 +184,7 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx,
return ret;
}
- /* Calculate the relocation address */
+ /* Calculate the relocation address. */
if (rel.r_offset < 0 || rel.r_offset > dstsec->sh_size - sizeof(uint32_t))
{
@@ -195,14 +195,42 @@ static int elf_relocate(FAR struct elf_loadinfo_s *loadinfo, int relidx,
addr = dstsec->sh_addr + rel.r_offset;
+ /* If CONFIG_ADDRENV=y, then 'addr' lies in a virtual address space that
+ * may not be in place now. elf_addrenv_select() will temporarily
+ * instantiate that address space.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Now perform the architecture-specific relocation */
ret = arch_relocate(&rel, &sym, addr);
if (ret < 0)
{
- bdbg("Section %d reloc %d: Relocation failed: %d\n", ret);
+#ifdef CONFIG_ADDRENV
+ (void)elf_addrenv_restore(loadinfo);
+#endif
+ bdbg("ERROR: Section %d reloc %d: Relocation failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_restore() failed: %d\n", ret);
return ret;
}
+#endif
}
return OK;
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
index b1ac44e21..0e4ad9798 100644
--- a/nuttx/binfmt/libelf/libelf_load.c
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -49,7 +49,6 @@
#include <errno.h>
#include <debug.h>
-#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/elf.h>
#include "libelf.h"
@@ -135,11 +134,12 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
int i;
/* Allocate (and zero) memory for the ELF file. */
-
- loadinfo->elfalloc = (uintptr_t)kzalloc(loadinfo->elfsize);
- if (!loadinfo->elfalloc)
+
+ ret = elf_addrenv_alloc(loadinfo, loadinfo->elfsize);
+ if (ret < 0)
{
- return -ENOMEM;
+ bdbg("ERROR: elf_addrenv_alloc() failed: %d\n", ret);
+ return ret;
}
/* Read each section into memory that is marked SHF_ALLOC + SHT_NOBITS */
@@ -165,6 +165,20 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
if (shdr->sh_type != SHT_NOBITS)
{
+ /* If CONFIG_ADDRENV=y, then 'dest' lies in a virtual address space
+ * that may not be in place now. elf_addrenv_select() will
+ * temporarily instantiate that address space.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_select(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_select() failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Read the section data from sh_offset to dest */
ret = elf_read(loadinfo, dest, shdr->sh_size, shdr->sh_offset);
@@ -173,6 +187,17 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
bdbg("Failed to read section %d: %d\n", i, ret);
return ret;
}
+
+ /* Restore the original address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = elf_addrenv_restore(loadinfo);
+ if (ret < 0)
+ {
+ bdbg("ERROR: elf_addrenv_restore() failed: %d\n", ret);
+ return ret;
+ }
+#endif
}
/* Update sh_addr to point to copy in memory */
diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c
index da41212f2..f4b725183 100644
--- a/nuttx/binfmt/libelf/libelf_read.c
+++ b/nuttx/binfmt/libelf/libelf_read.c
@@ -98,7 +98,11 @@ static inline void elf_dumpreaddata(char *buffer, int buflen)
* Name: elf_read
*
* Description:
- * Read 'readsize' bytes from the object file at 'offset'
+ * Read 'readsize' bytes from the object file at 'offset'. The data is
+ * read into 'buffer.' If 'buffer' is part of the ELF address environment,
+ * then the caller is responsibile for assuring that that address
+ * environment is in place before calling this function (i.e., that
+ * elf_addrenv_select() has been called if CONFIG_ADDRENV=y).
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
diff --git a/nuttx/binfmt/libelf/libelf_unload.c b/nuttx/binfmt/libelf/libelf_unload.c
index 532fc606f..539e5faf7 100644
--- a/nuttx/binfmt/libelf/libelf_unload.c
+++ b/nuttx/binfmt/libelf/libelf_unload.c
@@ -67,8 +67,9 @@
* Name: elf_unload
*
* Description:
- * This function unloads the object from memory. This essentially
- * undoes the actions of elf_load.
+ * This function unloads the object from memory. This essentially undoes
+ * the actions of elf_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
@@ -84,13 +85,7 @@ int elf_unload(struct elf_loadinfo_s *loadinfo)
/* Release memory holding the relocated ELF image */
- if (loadinfo->elfalloc != 0)
- {
- kfree((FAR void *)loadinfo->elfalloc);
- loadinfo->elfalloc = 0;
- }
-
- loadinfo->elfsize = 0;
+ elf_addrenv_free(loadinfo);
/* Release memory used to hold static constructors and destructors */
diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs
index 4f522e52b..6a0bf1873 100644
--- a/nuttx/binfmt/libnxflat/Make.defs
+++ b/nuttx/binfmt/libnxflat/Make.defs
@@ -41,9 +41,9 @@ BINFMT_CSRCS += nxflat.c
# NXFLAT library
-BINFMT_CSRCS += libnxflat_init.c libnxflat_uninit.c libnxflat_load.c \
- libnxflat_unload.c libnxflat_verify.c libnxflat_read.c \
- libnxflat_bind.c
+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
diff --git a/nuttx/binfmt/libnxflat/libnxflat.h b/nuttx/binfmt/libnxflat/libnxflat.h
new file mode 100644
index 000000000..cb1cb7057
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat.h
@@ -0,0 +1,136 @@
+/****************************************************************************
+ * 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
new file mode 100644
index 000000000..c6b3fce34
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_addrenv.c
@@ -0,0 +1,234 @@
+/****************************************************************************
+ * 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 <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_create
+ *
+ * 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_create(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
index 2b9f64715..3a86d5355 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_bind.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_bind.c
@@ -47,9 +47,12 @@
#include <debug.h>
#include <arpa/inet.h>
+
#include <nuttx/binfmt/nxflat.h>
#include <nuttx/binfmt/symtab.h>
+#include "libnxflat.h"
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -229,8 +232,6 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
hdr = (FAR struct nxflat_hdr_s*)loadinfo->ispace;
- /* From this, we can get the list of relocation entries. */
-
/* From this, we can get the offset to the list of relocation entries */
offset = ntohl(hdr->h_relocstart);
@@ -252,6 +253,22 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
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 */
@@ -329,6 +346,16 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
}
#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;
}
@@ -346,16 +373,19 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
****************************************************************************/
static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
- FAR const struct symtab_s *exports,
- int nexports)
+ 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;
+ 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. */
@@ -370,6 +400,22 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
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)
@@ -421,6 +467,9 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
if (!symbol)
{
bdbg("Exported symbol \"%s\" not found\n", symname);
+#ifdef CONFIG_ADDRENV
+ (void)nxflat_addrenv_restore(loadinfo);
+#endif
return -ENOENT;
}
@@ -442,7 +491,73 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
}
#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
}
/****************************************************************************
@@ -484,8 +599,7 @@ int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
* space in the loaded file.
*/
- memset((void*)(loadinfo->dspace->region + loadinfo->datasize),
- 0, loadinfo->bsssize);
+ ret = nxflat_clearbss(loadinfo);
}
}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
index b6693ea36..5f13b577a 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_load.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_load.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <sys/mman.h>
+
#include <stdint.h>
#include <stdlib.h>
#include <nxflat.h>
@@ -48,8 +49,11 @@
#include <errno.h>
#include <arpa/inet.h>
+
#include <nuttx/binfmt/nxflat.h>
+#include "libnxflat.h"
+
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -143,7 +147,7 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
*/
loadinfo->ispace = (uint32_t)mmap(NULL, loadinfo->isize, PROT_READ,
- MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
+ MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
if (loadinfo->ispace == (uint32_t)MAP_FAILED)
{
bdbg("Failed to map NXFLAT ISpace: %d\n", errno);
@@ -152,23 +156,37 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
bvdbg("Mapped ISpace (%d bytes) at %08x\n", loadinfo->isize, loadinfo->ispace);
- /* The following call will give a pointer to the allocated but
- * uninitialized ISpace memory.
+ /* The following call allocate D-Space memory and will provide a pointer
+ * to the allocated (but still uninitialized) D-Space memory.
*/
- loadinfo->dspace = (struct dspace_s *)malloc(SIZEOF_DSPACE_S(loadinfo->dsize));
- if (loadinfo->dspace == 0)
+ ret = nxflat_addrenv_alloc(loadinfo, loadinfo->dsize);
+ if (ret < 0)
{
- bdbg("Failed to allocate DSpace\n");
- ret = -ENOMEM;
- goto errout;
+ bdbg("ERROR: nxflat_addrenv_alloc() failed: %d\n", ret);
+ return ret;
}
- loadinfo->dspace->crefs = 1;
- bvdbg("Allocated DSpace (%d bytes) at %p\n", loadinfo->dsize, loadinfo->dspace->region);
+ bvdbg("Allocated DSpace (%d bytes) at %p\n",
+ loadinfo->dsize, loadinfo->dspace->region);
- /* Now, read the data into allocated DSpace at doffset into the
- * allocated DSpace memory.
+ /* 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);
@@ -181,9 +199,23 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
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_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c
index 47c30bd55..71d0c8499 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_unload.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_unload.c
@@ -40,11 +40,15 @@
#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
****************************************************************************/
@@ -65,8 +69,9 @@
* Name: nxflat_unload
*
* Description:
- * This function unloads the object from memory. This essentially
- * undoes the actions of nxflat_load.
+ * 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
@@ -76,9 +81,8 @@
int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
{
- /* Reset the contents of the info structure. */
-
/* Release the memory segments */
+ /* Release the I-Space mmap'ed file */
if (loadinfo->ispace)
{
@@ -86,12 +90,9 @@ int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
loadinfo->ispace = 0;
}
- if (loadinfo->dspace)
- {
- free((void*)loadinfo->dspace);
- loadinfo->dspace = 0;
- }
+ /* Release the D-Space address environment */
+ nxflat_addrenv_free(loadinfo);
return OK;
}
diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c
index 5973a96a9..db29941ca 100644
--- a/nuttx/binfmt/nxflat.c
+++ b/nuttx/binfmt/nxflat.c
@@ -187,10 +187,31 @@ static int nxflat_loadbinary(struct binary_s *binp)
binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs);
binp->mapped = (void*)loadinfo.ispace;
- binp->alloc[0] = (void*)loadinfo.dspace;
binp->mapsize = loadinfo.isize;
binp->stacksize = loadinfo.stacksize;
+ /* Add the ELF allocation to the alloc[] only if there is no address
+ * enironment. If there is an address environment, it will automatically
+ * be freed when the function exits
+ *
+ * REVISIT: If the module is loaded then unloaded, wouldn't this cause
+ * a memory leak?
+ */
+
+#ifdef CONFIG_ADDRENV
+# warning "REVISIT"
+#else
+ binp->alloc[0] = (void*)loadinfo.dspace;
+#endif
+
+#ifdef CONFIG_ADDRENV
+ /* Save the address environment. This will be needed when the module is
+ * executed for the up_addrenv_assign() call.
+ */
+
+ binp->addrenv = loadinfo.addrenv;
+#endif
+
nxflat_dumpbuffer("Entry code", (FAR const uint8_t*)binp->entrypt,
MIN(loadinfo.isize - loadinfo.entryoffs, 512));
diff --git a/nuttx/configs/eagle100/httpd/setenv.sh b/nuttx/configs/eagle100/httpd/setenv.sh
index 9022695a4..d22bf6f91 100755
--- a/nuttx/configs/eagle100/httpd/setenv.sh
+++ b/nuttx/configs/eagle100/httpd/setenv.sh
@@ -32,15 +32,31 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
-
WD=`pwd`
-export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/eagle100/nettest/setenv.sh b/nuttx/configs/eagle100/nettest/setenv.sh
index f03beff85..37cc7735c 100755
--- a/nuttx/configs/eagle100/nettest/setenv.sh
+++ b/nuttx/configs/eagle100/nettest/setenv.sh
@@ -32,15 +32,31 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
-
WD=`pwd`
-export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/eagle100/nsh/setenv.sh b/nuttx/configs/eagle100/nsh/setenv.sh
index c64bfed54..cd8710503 100755
--- a/nuttx/configs/eagle100/nsh/setenv.sh
+++ b/nuttx/configs/eagle100/nsh/setenv.sh
@@ -32,15 +32,31 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
-
WD=`pwd`
-export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/eagle100/nxflat/setenv.sh b/nuttx/configs/eagle100/nxflat/setenv.sh
index 2335de190..771be4ec6 100755
--- a/nuttx/configs/eagle100/nxflat/setenv.sh
+++ b/nuttx/configs/eagle100/nxflat/setenv.sh
@@ -32,15 +32,31 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
-
WD=`pwd`
-export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h
index 2e2c6dda8..6df5190d2 100644
--- a/nuttx/include/nuttx/binfmt/binfmt.h
+++ b/nuttx/include/nuttx/binfmt/binfmt.h
@@ -41,8 +41,11 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <nxflat.h>
+
+#include <nuttx/arch.h>
#include <nuttx/sched.h>
/****************************************************************************
@@ -93,12 +96,26 @@ struct binary_s
main_t entrypt; /* Entry point into a program module */
FAR void *mapped; /* Memory-mapped, address space */
FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */
+
+ /* Constructors/destructors */
+
#ifdef CONFIG_BINFMT_CONSTRUCTORS
FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */
FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */
uint16_t nctors; /* Number of constructors in the list */
uint16_t ndtors; /* Number of destructors in the list */
#endif
+
+ /* Address environment.
+ *
+ * addrenv - This is the handle created by up_addrenv_create() that can be
+ * used to manage the tasks address space.
+ */
+
+#ifdef CONFIG_ADDRENV
+ task_addrenv_t addrenv; /* Task address environment */
+#endif
+
size_t mapsize; /* Size of the mapped address region (needed for munmap) */
size_t stacksize; /* Size of the stack in bytes (unallocated) */
};
diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h
index 432e57f0f..6b6851934 100644
--- a/nuttx/include/nuttx/binfmt/elf.h
+++ b/nuttx/include/nuttx/binfmt/elf.h
@@ -59,6 +59,18 @@
# define CONFIG_ELF_ALIGN_LOG2 2
#endif
+#ifndef CONFIG_ELF_STACKSIZE
+# define CONFIG_ELF_STACKSIZE 2048
+#endif
+
+#ifndef CONFIG_ELF_BUFFERSIZE
+# define CONFIG_ELF_BUFFERSIZE 128
+#endif
+
+#ifndef CONFIG_ELF_BUFFERINCR
+# define CONFIG_ELF_BUFFERINCR 32
+#endif
+
/* Allocation array size and indices */
#define LIBELF_ELF_ALLOC 0
@@ -80,8 +92,16 @@
struct elf_loadinfo_s
{
- /* The alloc[] array holds memory that persists after the ELF module has
- * been loaded.
+ /* elfalloc is the base address of the memory that is allocated to hold the
+ * ELF program image.
+ *
+ * If CONFIG_ADDRENV=n, elfalloc will be allocated using kmalloc() (or
+ * 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.
+ *
+ * The alloc[] array in struct binary_s will hold memory that persists after
+ * the ELF module has been loaded.
*/
uintptr_t elfalloc; /* Memory allocated when ELF file was loaded */
@@ -90,6 +110,9 @@ struct elf_loadinfo_s
Elf32_Ehdr ehdr; /* Buffered ELF file header */
FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */
uint8_t *iobuffer; /* File I/O buffer */
+
+ /* Constructors and destructors */
+
#ifdef CONFIG_BINFMT_CONSTRUCTORS
FAR void *ctoralloc; /* Memory allocated for ctors */
FAR void *dtoralloc; /* Memory allocated dtors */
@@ -98,6 +121,20 @@ struct elf_loadinfo_s
uint16_t nctors; /* Number of constructors */
uint16_t ndtors; /* Number of destructors */
#endif
+
+ /* Address environment.
+ *
+ * addrenv - This is the handle created by up_addrenv_create() that can be
+ * used to manage the tasks address space.
+ * oldenv - This is a value returned by up_addrenv_select() that must be
+ * used to restore the current hardware address environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ task_addrenv_t addrenv; /* Task address environment */
+ hw_addrenv_t oldenv; /* Saved hardware address environment */
+#endif
+
uint16_t symtabidx; /* Symbol table section index */
uint16_t strtabidx; /* String table section index */
uint16_t buflen; /* size of iobuffer[] */
@@ -187,8 +224,9 @@ EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
* Name: elf_unload
*
* Description:
- * This function unloads the object from memory. This essentially
- * undoes the actions of elf_load.
+ * This function unloads the object from memory. This essentially undoes
+ * the actions of elf_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
diff --git a/nuttx/include/nuttx/binfmt/nxflat.h b/nuttx/include/nuttx/binfmt/nxflat.h
index 89e28fbcc..db396771b 100644
--- a/nuttx/include/nuttx/binfmt/nxflat.h
+++ b/nuttx/include/nuttx/binfmt/nxflat.h
@@ -44,7 +44,9 @@
#include <stdint.h>
#include <nxflat.h>
+
#include <nuttx/sched.h>
+#include <nuttx/arch.h>
/****************************************************************************
* Pre-processor Definitions
@@ -61,17 +63,24 @@
struct nxflat_loadinfo_s
{
/* Instruction Space (ISpace): This region contains the nxflat file header
- * plus everything from the text section. Ideally, will have only one mmap'ed
- * text section instance in the system for each module.
+ * plus everything from the text section.
+ *
+ * The ISpace region is allocated using mmap() and, thus, can be shared by
+ * multiple tasks. Ideally, will have only one mmap'ed text section
+ * instance in the system for each module.
*/
- uint32_t ispace; /* Address where hdr/text is loaded */
+ uintptr_t ispace; /* Address where hdr/text is loaded */
uint32_t entryoffs; /* Offset from ispace to entry point */
uint32_t isize; /* Size of ispace. */
- /* Data Space (DSpace): This region contains all information that in referenced
- * as data (other than the stack which is separately allocated). There will be
- * a unique instance of DSpace (and stack) for each instance of a process.
+ /* Data Space (DSpace): This region contains all information that is
+ * referenced as data (other than the stack which is separately allocated).
+ *
+ * If CONFIG_ADDRENV=n, DSpace will be allocated using kmalloc() (or
+ * kzalloc()). If CONFIG_ADDRENV-y, then DSpace will be allocated using
+ * up_addrenv_create(). In either case, there will be a unique instance
+ * of DSpace (and stack) for each instance of a process.
*/
struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */
@@ -85,6 +94,19 @@ struct nxflat_loadinfo_s
uint32_t relocstart; /* Start of array of struct flat_reloc */
uint16_t reloccount; /* Number of elements in reloc array */
+ /* Address environment.
+ *
+ * addrenv - This is the handle created by up_addrenv_create() that can be
+ * used to manage the tasks address space.
+ * oldenv - This is a value returned by up_addrenv_select() that must be
+ * used to restore the current hardware address environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ task_addrenv_t addrenv; /* Task address environment */
+ hw_addrenv_t oldenv; /* Saved hardware address environment */
+#endif
+
/* File descriptors */
int filfd; /* Descriptor for the file being loaded */
@@ -212,8 +234,9 @@ EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
* Name: nxflat_unload
*
* Description:
- * This function unloads the object from memory. This essentially
- * undoes the actions of nxflat_load.
+ * 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
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 172f46901..6eaba6e9c 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -163,24 +163,40 @@ typedef struct environ_s environ_t;
# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1)
#endif
-/* This structure describes a reference counted D-Space region */
+/* This structure describes a reference counted D-Space region. This must be a
+ * separately allocated "break-away" structure that can be owned by a task and
+ * any pthreads created by the task.
+ */
+#ifdef CONFIG_PIC
struct dspace_s
{
- uint32_t crefs; /* This is the number of pthreads that shared the
- * the same D-Space */
- uint8_t region[1]; /* Beginning of the allocated region */
-};
+ /* The life of the structure allocation is determined by this reference
+ * count. This count is number of threads that shared the the same D-Space.
+ * This includes the parent task as well as any pthreads created by the
+ * parent task or any of its child threads.
+ */
+
+ uint16_t crefs;
-#define SIZEOF_DSPACE_S(n) (sizeof(struct dspace_s) - 1 + (n))
+ /* This is the allocated D-Space memory region. This may be a physical
+ * address allocated with kmalloc(), or it may be virtual address associated
+ * with an address environment (if CONFIG_ADDRENV=y).
+ */
-/* This is the task control block (TCB) */
+ FAR uint8_t *region;
+};
+#endif
+
+/* This is the task control block (TCB). Each task or thread is represented by
+ * a TCB. The TCB is the heart of the NuttX task-control logic.
+ */
struct _TCB
{
/* Fields used to support list management *************************************/
- FAR struct _TCB *flink; /* link in DQ of TCBs */
+ FAR struct _TCB *flink; /* Doubly linked list */
FAR struct _TCB *blink;
/* Task Management Fields *****************************************************/