summaryrefslogtreecommitdiff
path: root/nuttx/binfmt
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-06-17 18:45:48 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-06-17 18:45:48 +0000
commit7a34357c62dd8c1910f444d37f80ed18425b7fad (patch)
tree95f253c9e6737c9f270b4997c6f94b9a16a81159 /nuttx/binfmt
parent0587988c3752c97d158b84afa34fb836b9642b62 (diff)
downloadpx4-nuttx-7a34357c62dd8c1910f444d37f80ed18425b7fad.tar.gz
px4-nuttx-7a34357c62dd8c1910f444d37f80ed18425b7fad.tar.bz2
px4-nuttx-7a34357c62dd8c1910f444d37f80ed18425b7fad.zip
Add basic module management logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1894 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/binfmt')
-rw-r--r--nuttx/binfmt/Makefile11
-rw-r--r--nuttx/binfmt/binfmt_dumpmodule.c97
-rw-r--r--nuttx/binfmt/binfmt_globals.c67
-rw-r--r--nuttx/binfmt/binfmt_internal.h89
-rw-r--r--nuttx/binfmt/binfmt_loadmodule.c127
-rw-r--r--nuttx/binfmt/binfmt_register.c97
-rw-r--r--nuttx/binfmt/binfmt_unloadmodule.c100
-rw-r--r--nuttx/binfmt/binfmt_unregister.c130
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_init.c30
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c84
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_unload.c7
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_verify.c13
-rw-r--r--nuttx/binfmt/nxflat.c45
13 files changed, 782 insertions, 115 deletions
diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
index deb6879a9..4b3905e06 100644
--- a/nuttx/binfmt/Makefile
+++ b/nuttx/binfmt/Makefile
@@ -35,14 +35,21 @@
-include $(TOPDIR)/Make.defs
+ifeq ($(CONFIG_NXFLAT),y)
include libnxflat/Make.defs
+LIBNXFLAT_CSRCS += nxflat.c
+endif
+
+BINFMT_ASRCS =
+BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \
+ binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_dumpmodule.c
SUBDIRS = libnxflat
-ASRCS = $(LIBNXFLAT_ASRCS)
+ASRCS = $(BINFMT_ASRCS) $(LIBNXFLAT_ASRCS)
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = nxflat.c $(LIBNXFLAT_CSRCS)
+CSRCS = $(BINFMT_CSRCS) $(LIBNXFLAT_CSRCS)
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/binfmt/binfmt_dumpmodule.c b/nuttx/binfmt/binfmt_dumpmodule.c
new file mode 100644
index 000000000..5b7bd1fe9
--- /dev/null
+++ b/nuttx/binfmt/binfmt_dumpmodule.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ * binfmt/binfmt_dumpmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: load_module
+ *
+ * Description:
+ * Load a module into memory and prep it for execution.
+ *
+ ***********************************************************************/
+
+int dump_module(FAR const struct binary_s *bin)
+{
+ if (bin)
+ {
+ bdbg("Module:\n");
+ bdbg(" filename: %s\n", bin->filename);
+ bdbg(" argv: %p\n", bin->argv);
+ bdbg(" entrypt: %p\n", bin->entrypt);
+ bdbg(" ispace: %p size=%d\n", bin->ispace, bin->isize);
+ bdbg(" dspace: %p\n", bin->dspace);
+ bdbg(" stacksize: %d\n", bin->stacksize);
+ }
+ return OK;
+}
+#endif
+
+
diff --git a/nuttx/binfmt/binfmt_globals.c b/nuttx/binfmt/binfmt_globals.c
new file mode 100644
index 000000000..535160cff
--- /dev/null
+++ b/nuttx/binfmt/binfmt_globals.c
@@ -0,0 +1,67 @@
+/****************************************************************************
+ * binfmt/binfmt_globals.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/binfmt.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* This is a list of registered handlers for different binary formats. This
+ * list should only be accessed by normal user programs. It should be sufficient
+ * protection to simply disable pre-emption when accessing this list.
+ */
+
+FAR struct binfmt_s *g_binfmts;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h
new file mode 100644
index 000000000..c5232f3d3
--- /dev/null
+++ b/nuttx/binfmt/binfmt_internal.h
@@ -0,0 +1,89 @@
+/****************************************************************************
+ * binfmt/binfmt_internal.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_BINFMT_INTERNAL_H
+#define __BINFMT_BINFMT_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include <nuttx/binfmt.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* This is a list of registered handlers for different binary formats. This
+ * list should only be accessed by normal user programs. It should be sufficient
+ * protection to simply disable pre-emption when accessing this list.
+ */
+
+EXTERN FAR struct binfmt_s *g_binfmts;
+
+/***********************************************************************
+ * Public Function Prototypes
+ ***********************************************************************/
+
+/* Dump the contents of strtuc binary_s */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
+EXTERN int dump_module(FAR const struct binary_s *bin);
+#else
+# define dump_module(bin)
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __BINFMT_BINFMT_INTERNAL_H */
+
diff --git a/nuttx/binfmt/binfmt_loadmodule.c b/nuttx/binfmt/binfmt_loadmodule.c
new file mode 100644
index 000000000..37910ae7c
--- /dev/null
+++ b/nuttx/binfmt/binfmt_loadmodule.c
@@ -0,0 +1,127 @@
+/****************************************************************************
+ * binfmt/binfmt_loadmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: load_module
+ *
+ * Description:
+ * Load a module into memory and prep it for execution.
+ *
+ ***********************************************************************/
+
+int load_module(const char *filename, FAR struct binary_s *bin)
+{
+ FAR struct binfmt_s *binfmt;
+ int ret;
+
+#ifdef CONFIG_DEBUG
+ if (!filename || !bin)
+ {
+ ret = -EINVAL;
+ }
+ else
+ {
+#endif
+ bdbg("Loading %s\n", filename);
+
+ /* Disabling pre-emption should be sufficient protection while
+ * accessing the list of registered binary format handlers.
+ */
+
+ sched_lock();
+
+ /* Traverse the list of registered binary format handlers. Stop
+ * when either (1) a handler recognized and loads the format, or
+ * (2) no handler recognizes the format.
+ */
+
+ for (binfmt = g_binfmts; binfmt; binfmt = binfmt->next)
+ {
+ /* Use this handler to try to load the format */
+
+ ret = binfmt->load(bin);
+ if (ret == OK)
+ {
+
+ /* Successfully loaded -- break out with ret == 0 */
+
+ dump_module(bin);
+ break;
+ }
+ }
+
+ sched_unlock();
+ }
+
+ if (ret < 0) bdbg("Returning %d\n", ret);
+ return ret;
+}
+
+
diff --git a/nuttx/binfmt/binfmt_register.c b/nuttx/binfmt/binfmt_register.c
new file mode 100644
index 000000000..309c081e6
--- /dev/null
+++ b/nuttx/binfmt/binfmt_register.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ * binfmt/binfmt_register.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <string.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: register_binfmt
+ *
+ * Description:
+ * Register a loader for a binary format
+ *
+ ***********************************************************************/
+
+int register_binfmt(FAR struct binfmt_s *binfmt)
+{
+ if (binfmt)
+ {
+ /* Add the new binary format handler to the head of the list of
+ * handlers
+ */
+
+ sched_lock();
+ binfmt->next = g_binfmts;
+ g_binfmts = binfmt;
+ sched_unlock();
+ return OK;
+ }
+ return -EINVAL;
+}
+
+
diff --git a/nuttx/binfmt/binfmt_unloadmodule.c b/nuttx/binfmt/binfmt_unloadmodule.c
new file mode 100644
index 000000000..f5d7ec92c
--- /dev/null
+++ b/nuttx/binfmt/binfmt_unloadmodule.c
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * binfmt/binfmt_loadmodule.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <stdlib.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: unload_module
+ *
+ * Description:
+ * Unload a (non-executing) module from memory. If the module has
+ * been started (via exec_module), calling this will be fatal.
+ *
+ ***********************************************************************/
+
+int unload_module(FAR const struct binary_s *bin)
+{
+ if (bin)
+ {
+ if (bin->ispace)
+ {
+ bvdbg("Unmapping ISpace: %p\n", bin->ispace);
+ munmap(bin->ispace, bin->isize);
+ }
+
+ if (bin->dspace)
+ {
+ bvdbg("Freeing DSpace: %p\n", bin->dspace);
+ free(bin->dspace);
+ }
+ }
+ return OK;
+}
+
diff --git a/nuttx/binfmt/binfmt_unregister.c b/nuttx/binfmt/binfmt_unregister.c
new file mode 100644
index 000000000..1eedffcfc
--- /dev/null
+++ b/nuttx/binfmt/binfmt_unregister.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ * binfmt/binfmt_unregister.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <string.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/binfmt.h>
+
+#include "binfmt_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+/***********************************************************************
+ * Name: unregister_binfmt
+ *
+ * Description:
+ * Register a loader for a binary format
+ *
+ ***********************************************************************/
+
+int unregister_binfmt(FAR struct binfmt_s *binfmt)
+{
+ FAR struct binfmt_s *curr;
+ FAR struct binfmt_s *prev;
+ int ret = -EINVAL;
+
+ if (binfmt)
+ {
+ /* Disabling pre-emption should be sufficient protection while
+ * accessing the list of registered binary format handlers.
+ */
+
+ sched_lock();
+
+ /* Search the list of registered binary format handlers for the
+ * one to be unregistered.
+ */
+
+ for (prev = NULL, curr = g_binfmts;
+ curr && curr != binfmt;
+ prev = curr, curr = curr->next);
+
+ /* Was it in the list? */
+
+ if (curr)
+ {
+ /* Yes.. was it at the head of the list? */
+
+ if (!prev)
+ {
+ /* Yes.. remove it from the head of the list */
+
+ g_binfmts = binfmt->next;
+ }
+ else
+ {
+ /* No.. remove it from the middle/end of the list */
+
+ prev->next = binfmt->next;
+ }
+
+ binfmt->next = NULL;
+ ret = OK;
+ }
+
+ sched_unlock();
+ }
+ return ret;
+}
+
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_init.c b/nuttx/binfmt/libnxflat/libnxflat_init.c
index 4696d491a..f60eac1d7 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_init.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_init.c
@@ -136,34 +136,30 @@ int nxflat_init(const char *filename, struct nxflat_hdr_s *header,
*
* Note that:
*
- * ispace_size = the address range from 0 up to datastart.
- * data_size = the address range from datastart up to dataend
- * bss_size = the address range from dataend up to bssend.
+ * 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->entry_offset = ntohl(header->h_entry);
- loadinfo->ispace_size = datastart;
+ loadinfo->entryoffs = ntohl(header->h_entry);
+ loadinfo->isize = datastart;
- loadinfo->data_size = dataend - datastart;
- loadinfo->bss_size = bssend - dataend;
- loadinfo->stack_size = ntohl(header->h_stacksize);
+ loadinfo->datasize = dataend - datastart;
+ loadinfo->bsssize = bssend - dataend;
+ loadinfo->stacksize = ntohl(header->h_stacksize);
- /* This is the initial dspace size. We'll recaculate this later
- * after the memory has been allocated. So that the caller can feel
- * free to modify dspace_size values from now until then.
+ /* This is the initial dspace size. We'll re-calculate this later
+ * after the memory has been allocated.
*/
- loadinfo->dspace_size = /* Total DSpace Size is: */
- (NXFLAT_DATA_OFFSET + /* Memory set aside for ldso */
- bssend - datastart + /* Data and bss segment sizes */
- loadinfo->stack_size); /* (Current) stack size */
+ loadinfo->dsize = bssend - datastart;
/* Get the offset to the start of the relocations (we'll relocate
* this later).
*/
- loadinfo->reloc_start = ntohl(header->h_relocstart);
- loadinfo->reloc_count = ntohl(header->h_reloccount);
+ loadinfo->relocstart = ntohl(header->h_relocstart);
+ loadinfo->reloccount = ntohl(header->h_reloccount);
return 0;
}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
index 0b143dad4..8f9da18cb 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_load.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_load.c
@@ -106,11 +106,11 @@ static void nxflat_reloc(struct nxflat_loadinfo_s *loadinfo, uint32 rl)
* section of the file image.
*/
- if (reloc.s.r_offset > loadinfo->data_size)
+ if (reloc.s.r_offset > loadinfo->datasize)
{
bdbg("ERROR: Relocation at 0x%08x invalid -- "
"does not lie in the data segment, size=0x%08x\n",
- reloc.s.r_offset, loadinfo->data_size);
+ reloc.s.r_offset, loadinfo->datasize);
bdbg(" Relocation not performed!\n");
}
else if ((reloc.s.r_offset & 0x00000003) != 0)
@@ -126,7 +126,7 @@ static void nxflat_reloc(struct nxflat_loadinfo_s *loadinfo, uint32 rl)
* DSpace to hold information needed by ld.so at run time.
*/
- datastart = loadinfo->dspace + NXFLAT_DATA_OFFSET;
+ datastart = loadinfo->dspace;
/* Get a pointer to the value that needs relocation in
* DSpace.
@@ -149,15 +149,14 @@ static void nxflat_reloc(struct nxflat_loadinfo_s *loadinfo, uint32 rl)
break;
/* DATA and BSS are always contiguous regions. DATA
- * begins at an offset of NXFLAT_DATA_OFFSET from
- * the beginning of the allocated data segment.
+ * begins at the beginning of the allocated data segment.
* BSS is positioned after DATA, unrelocated references
* to BSS include the data offset.
*
- * In other contexts, is it necessary to add the data_size
+ * In other contexts, is it necessary to add the datasize
* to get the BSS offset like:
*
- * *ptr += datastart + loadinfo->data_size;
+ * *ptr += datastart + loadinfo->datasize;
*/
case NXFLAT_RELOC_TYPE_DATA:
@@ -198,11 +197,11 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
uint32 ret;
int i;
- /* Calculate the extra space we need to map in. This region will be the
- * BSS segment and the stack. It will also be used temporarily to hold
- * relocation information. So the size of this region will either be the
- * size of the BSS section and the stack OR, it the size of the relocation
- * entries, whichever is larger
+ /* 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
*/
{
@@ -213,35 +212,32 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
* relocations.
*/
- relocsize = loadinfo->reloc_count * sizeof(uint32);
+ relocsize = loadinfo->reloccount * sizeof(uint32);
/* 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 + the stack size, or (2) the size of the relocation records,
- * whicher is larger.
+ * BSS size, or (2) the size of the relocation records, whicher is
+ * larger.
*/
- extrasize = MAX(loadinfo->bss_size + loadinfo->stack_size, relocsize);
+ extrasize = MAX(loadinfo->bsssize, relocsize);
/* Use this addtional amount to adjust the total size of the dspace
* region.
*/
- loadinfo->dspace_size =
- NXFLAT_DATA_OFFSET + /* Memory used by ldso */
- loadinfo->data_size + /* Initialized data */
- extrasize; /* bss+stack/relocs */
+ 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->data_size + relocsize;
+ dreadsize = loadinfo->datasize + relocsize;
}
/* We'll need this a few times as well. */
- doffset = loadinfo->ispace_size;
+ 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
@@ -255,7 +251,7 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
* resides as long as it is fully initialized and ready to execute.
*/
- loadinfo->ispace = (uint32)mmap(NULL, loadinfo->ispace_size, PROT_READ,
+ loadinfo->ispace = (uint32)mmap(NULL, loadinfo->isize, PROT_READ,
MAP_SHARED|MAP_FILE, loadinfo->filfd, 0);
if (loadinfo->ispace == (uint32)MAP_FAILED)
{
@@ -263,14 +259,13 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
return -errno;
}
- bvdbg("Mapped ISpace (%d bytes) at 0x%08x\n",
- loadinfo->ispace_size, loadinfo->ispace);
+ bvdbg("Mapped ISpace (%d bytes) at 0x%08x\n", loadinfo->isize, loadinfo->ispace);
/* The following call will give a pointer to the allocated but
* uninitialized ISpace memory.
*/
- loadinfo->dspace = (uint32)malloc(loadinfo->dspace_size);
+ loadinfo->dspace = (uint32)malloc(loadinfo->dsize);
if (loadinfo->dspace == 0)
{
bdbg("Failed to allocate DSpace\n");
@@ -279,57 +274,46 @@ int nxflat_load(struct nxflat_loadinfo_s *loadinfo)
}
bvdbg("Allocated DSpace (%d bytes) at %08x\n",
- loadinfo->dspace_size, loadinfo->dspace);
+ loadinfo->dsize, loadinfo->dspace);
/* Now, read the data into allocated DSpace at doffset into the
* allocated DSpace memory.
*/
- ret = nxflat_read(loadinfo, (char*)(loadinfo->dspace + NXFLAT_DATA_OFFSET), dreadsize, doffset);
+ ret = nxflat_read(loadinfo, (char*)loadinfo->dspace, dreadsize, doffset);
if (ret < 0)
{
bdbg("Failed to read .data section: %d\n", ret);
goto errout;
}
- /* Save information about the allocation. */
-
- loadinfo->alloc_start = loadinfo->dspace;
- loadinfo->alloc_size = loadinfo->dspace_size;
-
bvdbg("TEXT=0x%x Entry point offset=0x%08x, datastart is 0x%08x\n",
- loadinfo->ispace, loadinfo->entry_offset, doffset);
+ loadinfo->ispace, loadinfo->entryoffs, doffset);
/* Resolve the address of the relocation table. In the file, the
* relocations should lie at the same offset as BSS. The current
- * value of reloc_start is the offset from the beginning of the file.
+ * value of relocstart is the offset from the beginning of the file.
* The following adjustment will convert it to an address in DSpace.
*/
- reloctab = (uint32*)
- (loadinfo->reloc_start /* File offset to reloc records */
- + loadinfo->dspace /* + Allocated DSpace memory */
- + NXFLAT_DATA_OFFSET /* + Offset for ldso usage */
- - loadinfo->ispace_size); /* - File offset to DSpace */
+ reloctab = (uint32*)(loadinfo->relocstart + loadinfo->dspace - loadinfo->isize);
- bvdbg("Relocation table at 0x%p, reloc_count=%d\n",
- reloctab, loadinfo->reloc_count);
+ bvdbg("Relocation table at 0x%p, reloccount=%d\n",
+ reloctab, loadinfo->reloccount);
/* Now run through the relocation entries. */
- for (i=0; i < loadinfo->reloc_count; i++)
+ for (i=0; i < loadinfo->reloccount; i++)
{
nxflat_reloc(loadinfo, htonl(reloctab[i]));
}
- /* Zero the BSS, BRK and stack areas, trashing the relocations
- * that lived in the corresponding space in the file. */
-
- memset((void*)(loadinfo->dspace + NXFLAT_DATA_OFFSET + loadinfo->data_size),
- 0,
- (loadinfo->dspace_size - NXFLAT_DATA_OFFSET -
- loadinfo->data_size));
+ /* Zero the BSS area, trashing the relocations that lived in space
+ * in the file.
+ */
+ memset((void*)(loadinfo->dspace + loadinfo->datasize),
+ 0, loadinfo->bsssize);
return OK;
errout:
diff --git a/nuttx/binfmt/libnxflat/libnxflat_unload.c b/nuttx/binfmt/libnxflat/libnxflat_unload.c
index d648c0ebd..e095315a2 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_unload.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_unload.c
@@ -75,16 +75,11 @@ int nxflat_unload(struct nxflat_loadinfo_s *loadinfo)
{
/* Reset the contents of the info structure. */
- /* Nothing is allocated */
-
- loadinfo->alloc_start = 0;
- loadinfo->alloc_size = 0;
-
/* Release the memory segments */
if (loadinfo->ispace)
{
- munmap((void*)loadinfo->ispace, loadinfo->ispace_size);
+ munmap((void*)loadinfo->ispace, loadinfo->isize);
loadinfo->ispace = 0;
}
diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c
index db1069e9f..b1ca85330 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_verify.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c
@@ -67,8 +67,6 @@
int nxflat_verifyheader(const struct nxflat_hdr_s *header)
{
- uint16 revision;
-
if (!header)
{
bdbg("NULL NXFLAT header!");
@@ -88,15 +86,6 @@ int nxflat_verifyheader(const struct nxflat_hdr_s *header)
header->h_magic[2], header->h_magic[3]);
return -ENOEXEC;
}
-
- /* Complain a little more if the version does not match. */
-
- revision = ntohs(header->h_rev);
- if (revision != NXFLAT_VERSION_CURRENT)
- {
- bdbg("Unsupported NXFLAT version=%d\n", revision);
- return -ENOEXEC;
- }
- return 0;
+ return OK;
}
diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c
index d0456bebd..711be9353 100644
--- a/nuttx/binfmt/nxflat.c
+++ b/nuttx/binfmt/nxflat.c
@@ -64,7 +64,7 @@ static void nxflat_dumploadinfo(struct nxflat_loadinfo_s *loadinfo);
#endif
/****************************************************************************
- * Private Constant Data
+ * Private Data
****************************************************************************/
static struct binfmt_s g_nxflatbinfmt =
@@ -103,45 +103,31 @@ static void nxflat_dumpmemory(void *addr, int nbytes)
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
static void nxflat_dumploadinfo(struct nxflat_loadinfo_s *loadinfo)
{
- unsigned long dspace_size =
- NXFLAT_DATA_OFFSET +
- loadinfo->data_size +
- loadinfo->bss_size +
- loadinfo->stack_size;
+ unsigned long dsize = loadinfo->datasize + loadinfo->bsssize;
bdbg("LOAD_INFO:\n");
bdbg(" ISPACE:\n");
bdbg(" ispace: %08lx\n", loadinfo->ispace);
- bdbg(" entry_offset: %08lx\n", loadinfo->entry_offset);
- bdbg(" ispace_size: %08lx\n", loadinfo->ispace_size);
+ bdbg(" entryoffs: %08lx\n", loadinfo->entryoffs);
+ bdbg(" isize: %08lx\n", loadinfo->isize);
bdbg(" DSPACE:\n");
bdbg(" dspace: %08lx\n", loadinfo->dspace);
- bdbg(" (ldso): %08x\n", NXFLAT_DATA_OFFSET);
- bdbg(" data_size: %08lx\n", loadinfo->data_size);
- bdbg(" bss_size: %08lx\n", loadinfo->bss_size);
- bdbg(" (pad): %08lx\n", loadinfo->dspace_size - dspace_size);
- bdbg(" stack_size: %08lx\n", loadinfo->stack_size);
- bdbg(" dspace_size: %08lx\n", loadinfo->dspace_size);
-
- bdbg(" ARGUMENTS:\n");
- bdbg(" arg_start: %08lx\n", loadinfo->arg_start);
- bdbg(" env_start: %08lx\n", loadinfo->env_start);
- bdbg(" env_end: %08lx\n", loadinfo->env_end);
+ bdbg(" datasize: %08lx\n", loadinfo->datasize);
+ bdbg(" bsssize: %08lx\n", loadinfo->bsssize);
+ bdbg(" (pad): %08lx\n", loadinfo->dsize - dsize);
+ bdbg(" stacksize: %08lx\n", loadinfo->stacksize);
+ bdbg(" dsize: %08lx\n", loadinfo->dsize);
bdbg(" RELOCS:\n");
- bdbg(" reloc_start: %08lx\n", loadinfo->reloc_start);
- bdbg(" reloc_count: %08lx\n", loadinfo->reloc_count);
+ bdbg(" relocstart: %08lx\n", loadinfo->relocstart);
+ bdbg(" reloccount: %08lx\n", loadinfo->reloccount);
bdbg(" HANDLES:\n");
bdbg(" filfd: %d\n", loadinfo->filfd);
bdbg(" NXFLT HEADER:");
bdbg(" header: %p\n", loadinfo->header);
-
- bdbg(" ALLOCATIONS:\n");
- bdbg(" alloc_start: %08lx\n", loadinfo->alloc_start);
- bdbg(" alloc_size: %08lx\n", loadinfo->alloc_size);
}
#else /* CONFIG_XFLAT_DEBUG */
# define nxflat_dumploadinfo(i)
@@ -187,11 +173,14 @@ static int nxflat_loadbinary(struct binary_s *binp)
/* Return the load information */
- binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entry_offset);
- binp->picbase = (void*)loadinfo.dspace;
+ binp->entrypt = (main_t)(loadinfo.ispace + loadinfo.entryoffs);
+ binp->ispace = (void*)loadinfo.ispace;
+ binp->dspace = (void*)loadinfo.dspace;
+ binp->isize = loadinfo.isize;
+ binp->stacksize = loadinfo.stacksize;
bvdbg("ENTRY CODE:\n");
- nxflat_dumpmemory(binp->entrypt, 16*sizeof(unsigned long));
+ nxflat_dumpmemory(binp->entrypt, 16*sizeof(uint32));
nxflat_uninit(&loadinfo);
return OK;
}