summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-24 16:46:12 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-10-24 16:46:12 +0000
commit31d66d5fb2961c4c2df0d9f415f91ee5405f8d19 (patch)
tree199c1ac47d5ce30532f7b23121bc7df2c580a8c6 /nuttx/include
parente2cd590a6f7e1a4132d2eda16e1f29c760b804bb (diff)
downloadpx4-nuttx-31d66d5fb2961c4c2df0d9f415f91ee5405f8d19.tar.gz
px4-nuttx-31d66d5fb2961c4c2df0d9f415f91ee5405f8d19.tar.bz2
px4-nuttx-31d66d5fb2961c4c2df0d9f415f91ee5405f8d19.zip
Add framework to support loadable ELF modules (not much logic in place yet)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5250 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/elf.h53
-rw-r--r--nuttx/include/nuttx/elf.h259
-rw-r--r--nuttx/include/nuttx/nxflat.h38
3 files changed, 331 insertions, 19 deletions
diff --git a/nuttx/include/elf.h b/nuttx/include/elf.h
new file mode 100644
index 000000000..8d6539c36
--- /dev/null
+++ b/nuttx/include/elf.h
@@ -0,0 +1,53 @@
+/****************************************************************************
+ * include/elf.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 __INCLUDE_ELF_H
+#define __INCLUDE_ELF_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#endif /* __INCLUDE_ELF_H */
diff --git a/nuttx/include/nuttx/elf.h b/nuttx/include/nuttx/elf.h
new file mode 100644
index 000000000..4be2c23a0
--- /dev/null
+++ b/nuttx/include/nuttx/elf.h
@@ -0,0 +1,259 @@
+/****************************************************************************
+ * include/nuttx/elf.h
+ *
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_ELF_H
+#define __INCLUDE_NUTTX_ELF_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <elf.h>
+#include <nuttx/sched.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* This struct provides a desciption of the currently loaded instantiation
+ * of an ELF binary.
+ */
+
+struct elf_loadinfo_s
+{
+ /* Instruction Space (ISpace): This region contains the ELF file header
+ * plus everything from the text section. 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 */
+ 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.
+ */
+
+ FAR struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */
+ uint32_t datasize; /* Size of data segment in dspace */
+ uint32_t bsssize; /* Size of bss segment in dspace */
+ uint32_t stacksize; /* Size of stack (not allocated) */
+ uint32_t dsize; /* Size of dspace (may be large than parts) */
+
+ /* This is temporary memory where relocation records will be loaded. */
+
+ uint32_t relocstart; /* Start of array of struct flat_reloc */
+ uint16_t reloccount; /* Number of elements in reloc array */
+
+ /* File descriptors */
+
+ int filfd; /* Descriptor for the file being loaded */
+
+ /* This is a copy of the ELF header (still in network order) */
+
+ FAR struct elf_hdr_s header;
+};
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * These are APIs exported by libelf (and may be used outside of NuttX):
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_verifyheader
+ *
+ * Description:
+ * Given the header from a possible ELF executable, verify that it is
+ * an ELF executable.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_verifyheader(FAR const struct elf_hdr_s *header);
+
+/****************************************************************************
+ * Name: elf_init
+ *
+ * Description:
+ * This function is called to configure the library to process an ELF
+ * program binary.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_init(FAR const char *filename,
+ FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_uninit
+ *
+ * Description:
+ * Releases any resources committed by elf_init(). This essentially
+ * undoes the actions of elf_init.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_load
+ *
+ * Description:
+ * Loads the binary into memory, allocating memory, performing relocations
+ * and inializing the data and bss segments.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_read
+ *
+ * Description:
+ * Read 'readsize' bytes from the object file at 'offset'
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_read(FAR struct elf_loadinfo_s *loadinfo, FAR char *buffer,
+ FAR int readsize, int offset);
+
+/****************************************************************************
+ * Name: elf_bind
+ *
+ * Description:
+ * Bind the imported symbol names in the loaded module described by
+ * 'loadinfo' using the exported symbol values provided by 'symtab'.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+struct symtab_s;
+EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports, int nexports);
+
+/****************************************************************************
+ * Name: elf_unload
+ *
+ * Description:
+ * This function unloads the object from memory. This essentially
+ * undoes the actions of elf_load.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * These are APIs used internally only by NuttX:
+ ****************************************************************************/
+/****************************************************************************
+ * Name: elf_initialize
+ *
+ * Description:
+ * ELF support is built unconditionally. However, it order to
+ * use this binary format, this function must be called during system
+ * format in order to register the ELF binary format.
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_initialize(void);
+
+/****************************************************************************
+ * Name: elf_uninitialize
+ *
+ * Description:
+ * Unregister the ELF binary loader
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+EXTERN void elf_uninitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_ELF_H */
diff --git a/nuttx/include/nuttx/nxflat.h b/nuttx/include/nuttx/nxflat.h
index b6501522e..59dcea854 100644
--- a/nuttx/include/nuttx/nxflat.h
+++ b/nuttx/include/nuttx/nxflat.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/nxflat.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -110,22 +110,22 @@ extern "C" {
* These are APIs exported by libnxflat (and may be used outside of NuttX):
****************************************************************************/
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_verifyheader
*
* Description:
- * Given the header from a possible NXFLAT executable, verify that it
- * is an NXFLAT executable.
+ * Given the header from a possible NXFLAT executable, verify that it is
+ * an NXFLAT executable.
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_init
*
* Description:
@@ -136,12 +136,12 @@ EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_init(const char *filename,
struct nxflat_loadinfo_s *loadinfo);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_uninit
*
* Description:
@@ -152,11 +152,11 @@ EXTERN int nxflat_init(const char *filename,
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_load
*
* Description:
@@ -170,11 +170,11 @@ EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_read
*
* Description:
@@ -184,12 +184,12 @@ EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
int readsize, int offset);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_bind
*
* Description:
@@ -202,13 +202,13 @@ EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
struct symtab_s;
EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
FAR const struct symtab_s *exports, int nexports);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_unload
*
* Description:
@@ -219,14 +219,14 @@ EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo);
/****************************************************************************
* These are APIs used internally only by NuttX:
****************************************************************************/
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_initialize
*
* Description:
@@ -239,7 +239,7 @@ EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_initialize(void);