summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/binfmt/Kconfig19
-rw-r--r--nuttx/binfmt/Makefile1
-rw-r--r--nuttx/binfmt/binfmt_schedunload.c2
-rw-r--r--nuttx/binfmt/builtin.c4
-rw-r--r--nuttx/binfmt/elf.c6
-rw-r--r--nuttx/binfmt/libelf/Kconfig2
-rw-r--r--nuttx/binfmt/libelf/libelf_load.c2
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c2
-rw-r--r--nuttx/binfmt/libpcode/Kconfig23
-rw-r--r--nuttx/binfmt/libpcode/Make.defs52
-rw-r--r--nuttx/binfmt/nxflat.c4
-rw-r--r--nuttx/binfmt/pcode.c246
-rw-r--r--nuttx/configs/sim/nsh/defconfig127
-rw-r--r--nuttx/include/nuttx/binfmt/builtin.h6
-rw-r--r--nuttx/include/nuttx/binfmt/elf.h35
-rw-r--r--nuttx/include/nuttx/binfmt/nxflat.h33
-rw-r--r--nuttx/include/nuttx/binfmt/pcode.h178
-rw-r--r--nuttx/include/nuttx/poff.h435
19 files changed, 1084 insertions, 97 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 376edcdcc..f6732216b 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -7300,3 +7300,7 @@
* arch/arm/src/armv7-a/arm_memcpy.S: This is the same optimized memcpy()
function that Mike Smith brought in for the ARMv7-M with minor tweaks
by David Sidrane to work with the ARMv7-A (2014-5-6).
+ * binfmt/libpcode, pcode.c, include/nuttx/poff.h, and binfmt/pcode.h:
+ Framework to support Pascal P-Code as a binary format. At present this
+ logic is incomplete and really nothing more than a thought experiment
+ to determine the feasibility of the P-code binary format (2014-5-7).
diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig
index 6e5f7c251..4c99b8b2c 100644
--- a/nuttx/binfmt/Kconfig
+++ b/nuttx/binfmt/Kconfig
@@ -63,6 +63,25 @@ if BUILTIN
source binfmt/libbuiltin/Kconfig
endif
+config PCODE
+ bool "Support P-Code Applications"
+ default n
+ depends on INTERPRETERS_PCODE
+ ---help---
+ Enable support for interpreted P-Code binaries. P-Code binaries are
+ generated by the NuttX Pascal compiler.
+
+ NOTE: You must first install and select the Pascal P-Code
+ interpreter before you can select this binary format. The P-Code
+ interpreter is in the pascal package and can also be fount in the
+ misc/pascal directory of the repository. Read the README.txt file
+ in the misc/pascal directory for more details. The correct
+ installation director is: apps/interpreters.
+
+if PCODE
+source binfmt/libpcode/Kconfig
+endif
+
endif
config PIC
diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
index 4e4ad931a..4e1f18ebc 100644
--- a/nuttx/binfmt/Makefile
+++ b/nuttx/binfmt/Makefile
@@ -70,6 +70,7 @@ DEPPATH = --dep-path .
include libnxflat$(DELIM)Make.defs
include libelf$(DELIM)Make.defs
include libbuiltin$(DELIM)Make.defs
+include libpcode$(DELIM)Make.defs
BINFMT_AOBJS = $(BINFMT_ASRCS:.S=$(OBJEXT))
BINFMT_COBJS = $(BINFMT_CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/binfmt/binfmt_schedunload.c b/nuttx/binfmt/binfmt_schedunload.c
index 7e7fa471f..15f8e3f7c 100644
--- a/nuttx/binfmt/binfmt_schedunload.c
+++ b/nuttx/binfmt/binfmt_schedunload.c
@@ -208,7 +208,7 @@ static void unload_callback(int signo, siginfo_t *info, void *ucontext)
if (!info || signo != SIGCHLD)
{
- blldbg("ERROR:Bad signal callback: signo=%d info=%p\n", signo, callback);
+ blldbg("ERROR:Bad signal callback: signo=%d info=%p\n", signo, info);
return;
}
diff --git a/nuttx/binfmt/builtin.c b/nuttx/binfmt/builtin.c
index eb838db92..c532d056f 100644
--- a/nuttx/binfmt/builtin.c
+++ b/nuttx/binfmt/builtin.c
@@ -150,9 +150,9 @@ static int builtin_loadbinary(struct binary_s *binp)
* Name: builtin_initialize
*
* Description:
- * Builtin support is built unconditionally. However, it order to
+ * Builtin support is built unconditionally. However, in order to
* use this binary format, this function must be called during system
- * format in order to register the builtin binary format.
+ * initialzie in order to register the builtin binary format.
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
diff --git a/nuttx/binfmt/elf.c b/nuttx/binfmt/elf.c
index 9dc59fbdd..6c84ca0e1 100644
--- a/nuttx/binfmt/elf.c
+++ b/nuttx/binfmt/elf.c
@@ -218,7 +218,7 @@ static int elf_loadbinary(struct binary_s *binp)
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
+ * environment. 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
@@ -275,9 +275,9 @@ errout:
* Name: elf_initialize
*
* Description:
- * ELF support is built unconditionally. However, it order to
+ * ELF support is built unconditionally. However, in order to
* use this binary format, this function must be called during system
- * format in order to register the ELF binary format.
+ * initialization in order to register the ELF binary format.
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
diff --git a/nuttx/binfmt/libelf/Kconfig b/nuttx/binfmt/libelf/Kconfig
index f6f579276..e63fd5382 100644
--- a/nuttx/binfmt/libelf/Kconfig
+++ b/nuttx/binfmt/libelf/Kconfig
@@ -13,7 +13,7 @@ config ELF_STACKSIZE
int "ELF Stack Size"
default 2048
---help---
- This is the default stack size that will will be used when starting ELF binaries.
+ This is the default stack size that will be used when starting ELF binaries.
config ELF_BUFFERSIZE
int "ELF I/O Buffer Size"
diff --git a/nuttx/binfmt/libelf/libelf_load.c b/nuttx/binfmt/libelf/libelf_load.c
index 0e4ad9798..f5df09eda 100644
--- a/nuttx/binfmt/libelf/libelf_load.c
+++ b/nuttx/binfmt/libelf/libelf_load.c
@@ -222,7 +222,7 @@ static inline int elf_loadfile(FAR struct elf_loadinfo_s *loadinfo)
*
* Description:
* Loads the binary into memory, allocating memory, performing relocations
- * and inializing the data and bss segments.
+ * and initializing the data and bss segments.
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
index 886c16147..b386628a6 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_load.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_load.c
@@ -80,7 +80,7 @@
* Description:
* Loads the binary specified by nxflat_init into memory, mapping
* the I-space executable regions, allocating the D-Space region,
- * and inializing the data segment (relocation information is
+ * and initializing the data segment (relocation information is
* temporarily loaded into the BSS region. BSS will be cleared
* by nxflat_bind() after the relocation data has been processed).
*
diff --git a/nuttx/binfmt/libpcode/Kconfig b/nuttx/binfmt/libpcode/Kconfig
new file mode 100644
index 000000000..4845eab31
--- /dev/null
+++ b/nuttx/binfmt/libpcode/Kconfig
@@ -0,0 +1,23 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config PCODE_STACKSIZE
+ int "P-code interpreter stack size"
+ default 2048
+ ---help---
+ This is the stack size that will be used when starting P-code interpreter.
+
+config PCODE_PRIORITY
+ int "P-code interpreter priority"
+ default 100
+ ---help---
+ This is the task_priority that will be used when starting P-code interpreter.
+
+config PCODE_DUMPBUFFER
+ bool "Dump P-code buffers"
+ default n
+ depends on DEBUG && DEBUG_VERBOSE
+ ---help---
+ Dump various P-code buffers for debug purposes
diff --git a/nuttx/binfmt/libpcode/Make.defs b/nuttx/binfmt/libpcode/Make.defs
new file mode 100644
index 000000000..a5d2fdc12
--- /dev/null
+++ b/nuttx/binfmt/libpcode/Make.defs
@@ -0,0 +1,52 @@
+############################################################################
+# binfmt/libpcode/Make.defs
+#
+# Copyright (C) 2014 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+ifeq ($(CONFIG_PCODE),y)
+
+# P-code application interfaces
+
+# BINFMT_CSRCS +=
+
+# P-code library interfaces
+
+# BINFMT_CSRCS +=
+
+# Hook the libbuiltin subdirectory into the build
+
+#VPATH += libbuiltin
+#SUBDIRS += libbuiltin
+#DEPPATH += --dep-path libbuiltin
+
+endif
diff --git a/nuttx/binfmt/nxflat.c b/nuttx/binfmt/nxflat.c
index db29941ca..2d06aa7d9 100644
--- a/nuttx/binfmt/nxflat.c
+++ b/nuttx/binfmt/nxflat.c
@@ -234,9 +234,9 @@ errout:
* Name: nxflat_initialize
*
* Description:
- * NXFLAT support is built unconditionally. However, it order to
+ * NXFLAT support is built unconditionally. However, in order to
* use this binary format, this function must be called during system
- * format in order to register the NXFLAT binary format.
+ * initialization in order to register the NXFLAT binary format.
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
diff --git a/nuttx/binfmt/pcode.c b/nuttx/binfmt/pcode.c
new file mode 100644
index 000000000..c5963b672
--- /dev/null
+++ b/nuttx/binfmt/pcode.c
@@ -0,0 +1,246 @@
+/****************************************************************************
+ * binfmt/pcode.c
+ *
+ * Copyright (C) 2014 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 <fcntl.h>
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/poff.h>
+#include <nuttx/binfmt/binfmt.h>
+#include <nuttx/binfmt/pcode.h>
+
+#ifdef CONFIG_PCODE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int pcode_loadbinary(FAR struct binary_s *binp);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct binfmt_s g_pcode_binfmt =
+{
+ NULL, /* next */
+ pcode_loadbinary, /* load */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pcode_proxy
+ *
+ * Description:
+ * This is the proxy program that runs and starts the P-Code interpreter.
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_NUTTX_KERNEL
+static int pcode_proxy(int argc, char **argv)
+{
+ /* REVISIT: There are issues here when CONFIG_NUTTX_KERNEL is selected. */
+
+ bdbg("ERROR: Not implemented");
+ return EXIT_FAILURE;
+}
+#else
+# error Missing logic for the case of CONFIG_NUTTX_KERNEL
+#endif
+
+/****************************************************************************
+ * Name: pcode_loadbinary
+ *
+ * Description:
+ * Verify that the file is an pcode binary.
+ *
+ ****************************************************************************/
+
+static int pcode_loadbinary(struct binary_s *binp)
+{
+ FAR struct poff_fileheader_s hdr;
+ FAR const struct pcode_s *b;
+ FAR uint8_t *ptr;
+ size_t remaining;
+ ssize_t nread;
+ int fd;
+ int ret;
+
+ bvdbg("Loading file: %s\n", binp->filename);
+
+ /* Open the binary file for reading (only) */
+
+ fd = open(binp->filename, O_RDONLY);
+ if (fd < 0)
+ {
+ int errval = errno;
+ bdbg("ERROR: Failed to open binary %s: %d\n", binp->filename, errval);
+ return -errval;
+ }
+
+ /* Read the POFF file header */
+
+ for (remaining = sizeof(struct poff_fileheader_s), ptr = (FAR uint8_t *)&hdr;
+ remaining > 0; )
+ {
+ /* Read the next GULP */
+
+ nread = read(fd, ptr, remaining);
+ if (nread < 0)
+ {
+ /* If errno is EINTR, then this is not an error; the read() was
+ * simply interrupted by a signal.
+ */
+
+ int errval = errno;
+ DEBUGASSERT(errval > 0);
+
+ if (errval != EINTR)
+ {
+ bdbg("ERROR: read failed: %d\n", errval);
+ ret = -errval;
+ goto errout_with_fd;
+ }
+
+ bdbg("Interrupted by a signal\n");
+ }
+ else
+ {
+ /* Set up for the next gulp */
+
+ DEBUASSERT(nread > 0 && nread <=remaining);
+ remaining -= nread;
+ ptr += nread;
+ }
+ }
+
+#ifdef CONFIG_PCODE_DUMPBUFFER
+ lib_dumpbuffer("POFF File Header", &hdr, sizeof(poff_fileheader_s));
+#endif
+
+ /* Verify that the file is a P-Code executable */
+
+ if (memcmp(&hdr.fh_ident, FHI_POFF_MAG, 4) != 0 || hdr.fh_type != FHT_EXEC)
+ {
+ dbg("ERROR: File is not a P-code executable: %d\n");
+ ret = -ENOEXEC;
+ goto errout_with_fd;
+ }
+
+ /* Return the load information.
+ * REVISIT: There are issues here when CONFIG_NUTTX_KERNEL is selected.
+ */
+
+ binp->entrypt = pcode_proxy;
+ binp->stacksize = CONFIG_PCODE_STACKSIZE;
+ binp->priority = CONFIG_PCODE_PRIORITY;
+
+ /* Successfully identified a p-code binary */
+
+ ret = OK;
+
+errout_with_fd:
+ close(fd);
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pcode_initialize
+ *
+ * Description:
+ * P-code support is built based on the configuration. However, in order
+ * to use this binary format, this function must be called during system
+ * initialization in order to register the P-Code 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.
+ *
+ ****************************************************************************/
+
+int pcode_initialize(void)
+{
+ int ret;
+
+ /* Register ourselves as a binfmt loader */
+
+ bvdbg("Registering P-Code Loader\n");
+
+ ret = register_binfmt(&g_pcode_binfmt);
+ if (ret != 0)
+ {
+ bdbg("Failed to register binfmt: %d\n", ret);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: pcode_uninitialize
+ *
+ * Description:
+ * Unregister the pcode binary loader
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void pcode_uninitialize(void)
+{
+ unregister_binfmt(&g_pcode_binfmt);
+}
+
+#endif /* CONFIG_PCODE */
+
diff --git a/nuttx/configs/sim/nsh/defconfig b/nuttx/configs/sim/nsh/defconfig
index 452cffeb5..396ec65f6 100644
--- a/nuttx/configs/sim/nsh/defconfig
+++ b/nuttx/configs/sim/nsh/defconfig
@@ -26,6 +26,7 @@ CONFIG_HOST_LINUX=y
# CONFIG_INTELHEX_BINARY is not set
# CONFIG_MOTOROLA_SREC is not set
# CONFIG_RAW_BINARY is not set
+# CONFIG_UBOOT_UIMAGE is not set
#
# Customize Header Files
@@ -81,6 +82,7 @@ CONFIG_ARCH="sim"
# CONFIG_ARCH_HAVE_VFORK is not set
# CONFIG_ARCH_HAVE_MMU is not set
# CONFIG_ARCH_NAND_HWECC is not set
+# CONFIG_ARCH_HAVE_EXTCLK is not set
# CONFIG_ARCH_STACKDUMP is not set
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_IDLE_CUSTOM is not set
@@ -134,38 +136,72 @@ CONFIG_NSH_MMCSDMINOR=0
#
# RTOS Features
#
-# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_DISABLE_OS_API=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+# CONFIG_DISABLE_ENVIRON is not set
+
+#
+# Clocks and Timers
+#
CONFIG_MSEC_PER_TICK=10
# CONFIG_SYSTEM_TIME64 is not set
-CONFIG_RR_INTERVAL=0
-# CONFIG_SCHED_CPULOAD is not set
-# CONFIG_SCHED_INSTRUMENTATION is not set
-CONFIG_TASK_NAME_SIZE=32
-CONFIG_SCHED_HAVE_PARENT=y
-# CONFIG_SCHED_CHILD_STATUS is not set
+# CONFIG_CLOCK_MONOTONIC is not set
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=2008
CONFIG_START_MONTH=6
CONFIG_START_DAY=1
-CONFIG_DEV_CONSOLE=y
+CONFIG_MAX_WDOGPARMS=4
+CONFIG_PREALLOC_WDOGS=32
+CONFIG_PREALLOC_TIMERS=8
+
+#
+# Tasks and Scheduling
+#
+CONFIG_USER_ENTRYPOINT="nsh_main"
+CONFIG_RR_INTERVAL=0
+CONFIG_TASK_NAME_SIZE=32
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_MAX_TASKS=64
+CONFIG_SCHED_HAVE_PARENT=y
+# CONFIG_SCHED_CHILD_STATUS is not set
+CONFIG_SCHED_WAITPID=y
+
+#
+# Pthread Options
+#
# CONFIG_MUTEX_TYPES is not set
-# CONFIG_PRIORITY_INHERITANCE is not set
+CONFIG_NPTHREAD_KEYS=4
+
+#
+# Performance Monitoring
+#
+# CONFIG_SCHED_CPULOAD is not set
+# CONFIG_SCHED_INSTRUMENTATION is not set
+
+#
+# Files and I/O
+#
+CONFIG_DEV_CONSOLE=y
# CONFIG_FDCLONE_DISABLE is not set
# CONFIG_FDCLONE_STDIO is not set
CONFIG_SDCLONE_DISABLE=y
-CONFIG_SCHED_WAITPID=y
+CONFIG_NFILE_DESCRIPTORS=32
+CONFIG_NFILE_STREAMS=16
+CONFIG_NAME_MAX=32
+# CONFIG_PRIORITY_INHERITANCE is not set
+
+#
+# RTOS hooks
+#
+# CONFIG_BOARD_INITIALIZE is not set
# CONFIG_SCHED_STARTHOOK is not set
# CONFIG_SCHED_ATEXIT is not set
CONFIG_SCHED_ONEXIT=y
CONFIG_SCHED_ONEXIT_MAX=1
-CONFIG_USER_ENTRYPOINT="nsh_main"
-CONFIG_DISABLE_OS_API=y
-# CONFIG_DISABLE_CLOCK is not set
-# CONFIG_DISABLE_POSIX_TIMERS is not set
-# CONFIG_DISABLE_PTHREAD is not set
-# CONFIG_DISABLE_SIGNALS is not set
-# CONFIG_DISABLE_MQUEUE is not set
-# CONFIG_DISABLE_ENVIRON is not set
#
# Signal Numbers
@@ -177,19 +213,10 @@ CONFIG_SIG_SIGCHLD=4
CONFIG_SIG_SIGCONDTIMEDOUT=16
#
-# Sizes of configurable things (0 disables)
+# POSIX Message Queue Options
#
-CONFIG_MAX_TASKS=64
-CONFIG_MAX_TASK_ARGS=4
-CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=32
-CONFIG_NFILE_STREAMS=16
-CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=32
CONFIG_MQ_MAXMSGSIZE=32
-CONFIG_MAX_WDOGPARMS=4
-CONFIG_PREALLOC_WDOGS=32
-CONFIG_PREALLOC_TIMERS=8
#
# Stack and heap information
@@ -216,6 +243,7 @@ CONFIG_DEV_NULL=y
# CONFIG_I2S is not set
# CONFIG_RTC is not set
# CONFIG_WATCHDOG is not set
+# CONFIG_TIMER is not set
# CONFIG_ANALOG is not set
# CONFIG_AUDIO_DEVICES is not set
# CONFIG_VIDEO_DEVICES is not set
@@ -339,6 +367,7 @@ CONFIG_PATH_INITIAL="/bin"
# CONFIG_NXFLAT is not set
# CONFIG_ELF is not set
CONFIG_BUILTIN=y
+# CONFIG_PCODE is not set
# CONFIG_PIC is not set
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
@@ -401,6 +430,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
# CONFIG_EXAMPLES_BUTTONS is not set
# CONFIG_EXAMPLES_CAN is not set
# CONFIG_EXAMPLES_CONFIGDATA is not set
+# CONFIG_EXAMPLES_CPUHOG is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
# CONFIG_EXAMPLES_FTPC is not set
@@ -411,7 +441,6 @@ CONFIG_EXAMPLES_HELLO=y
# CONFIG_EXAMPLES_HIDKBD is not set
# CONFIG_EXAMPLES_KEYPADTEST is not set
# CONFIG_EXAMPLES_IGMP is not set
-# CONFIG_EXAMPLES_LCDRW is not set
# CONFIG_EXAMPLES_MM is not set
# CONFIG_EXAMPLES_MODBUS is not set
# CONFIG_EXAMPLES_MOUNT is not set
@@ -434,6 +463,8 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_RGMP is not set
# CONFIG_EXAMPLES_ROMFS is not set
# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERIALBLASTER is not set
+# CONFIG_EXAMPLES_SERIALRX is not set
# CONFIG_EXAMPLES_SERLOOP is not set
# CONFIG_EXAMPLES_SLCD is not set
# CONFIG_EXAMPLES_SMART_TEST is not set
@@ -588,35 +619,32 @@ CONFIG_NSH_CONSOLE=y
#
#
-# USB CDC/ACM Device Commands
-#
-
-#
-# USB Composite Device Commands
+# Custom Free Memory Command
#
+# CONFIG_SYSTEM_FREE is not set
#
-# Custom Free Memory Command
+# EMACS-like Command Line Editor
#
-# CONFIG_SYSTEM_FREE is not set
+# CONFIG_SYSTEM_CLE is not set
#
-# I2C tool
+# FLASH Program Installation
#
+# CONFIG_SYSTEM_INSTALL is not set
#
-# INI File Parser
+# FLASH Erase-all Command
#
-# CONFIG_SYSTEM_INIFILE is not set
#
-# FLASH Program Installation
+# I2C tool
#
-# CONFIG_SYSTEM_INSTALL is not set
#
-# FLASH Erase-all Command
+# INI File Parser
#
+# CONFIG_SYSTEM_INIFILE is not set
#
# NxPlayer media player library / command Line
@@ -655,21 +683,20 @@ CONFIG_READLINE_ECHO=y
# CONFIG_SYSTEM_SYSINFO is not set
#
-# USB Monitor
+# VI Work-Alike Editor
#
+# CONFIG_SYSTEM_VI is not set
#
-# EMACS-like Command Line Editor
+# Stack Monitor
#
-# CONFIG_SYSTEM_CLE is not set
#
-# VI Work-Alike Editor
+# USB CDC/ACM Device Commands
#
-# CONFIG_SYSTEM_VI is not set
#
-# Stack Monitor
+# USB Composite Device Commands
#
#
@@ -677,6 +704,10 @@ CONFIG_READLINE_ECHO=y
#
#
+# USB Monitor
+#
+
+#
# Zmodem Commands
#
# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx/include/nuttx/binfmt/builtin.h b/nuttx/include/nuttx/binfmt/builtin.h
index 6ff565395..51f3ef55b 100644
--- a/nuttx/include/nuttx/binfmt/builtin.h
+++ b/nuttx/include/nuttx/binfmt/builtin.h
@@ -81,9 +81,9 @@ extern "C" {
* Name: builtin_initialize
*
* Description:
- * Builtin support is built unconditionally. However, it order to
+ * Builtin support is built unconditionally. However, in order to
* use this binary format, this function must be called during system
- * format in order to register the builtin binary format.
+ * initialzie in order to register the builtin binary format.
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
@@ -167,7 +167,7 @@ FAR const char *builtin_getname(int index);
*
****************************************************************************/
-EXTERN FAR const struct builtin_s *builtin_for_index(int index);
+FAR const struct builtin_s *builtin_for_index(int index);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h
index bb21bdad0..7bfe0d9a3 100644
--- a/nuttx/include/nuttx/binfmt/elf.h
+++ b/nuttx/include/nuttx/binfmt/elf.h
@@ -170,8 +170,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN int elf_init(FAR const char *filename,
- FAR struct elf_loadinfo_s *loadinfo);
+int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo);
/****************************************************************************
* Name: elf_uninit
@@ -186,14 +185,14 @@ EXTERN int elf_init(FAR const char *filename,
*
****************************************************************************/
-EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo);
+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.
+ * and initializing the data and bss segments.
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
@@ -201,7 +200,7 @@ EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo);
*
****************************************************************************/
-EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo);
+int elf_load(FAR struct elf_loadinfo_s *loadinfo);
/****************************************************************************
* Name: elf_bind
@@ -217,8 +216,8 @@ EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo);
****************************************************************************/
struct symtab_s;
-EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
- FAR const struct symtab_s *exports, int nexports);
+int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports, int nexports);
/****************************************************************************
* Name: elf_unload
@@ -234,7 +233,7 @@ EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
*
****************************************************************************/
-EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo);
+int elf_unload(struct elf_loadinfo_s *loadinfo);
/****************************************************************************
* These are APIs used outside of binfmt by NuttX:
@@ -243,9 +242,9 @@ EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo);
* Name: elf_initialize
*
* Description:
- * ELF support is built unconditionally. However, it order to
+ * ELF support is built unconditionally. However, in order to
* use this binary format, this function must be called during system
- * format in order to register the ELF binary format.
+ * initialization in order to register the ELF binary format.
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
@@ -254,7 +253,7 @@ EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo);
*
****************************************************************************/
-EXTERN int elf_initialize(void);
+int elf_initialize(void);
/****************************************************************************
* Name: elf_uninitialize
@@ -267,7 +266,7 @@ EXTERN int elf_initialize(void);
*
****************************************************************************/
-EXTERN void elf_uninitialize(void);
+void elf_uninitialize(void);
/****************************************************************************
* These are APIs must be provided by architecture-specific logic:
@@ -288,7 +287,7 @@ EXTERN void elf_uninitialize(void);
*
****************************************************************************/
-EXTERN bool arch_checkarch(FAR const Elf32_Ehdr *hdr);
+bool arch_checkarch(FAR const Elf32_Ehdr *hdr);
/****************************************************************************
* Name: arch_relocate and arch_relocateadd
@@ -308,10 +307,10 @@ EXTERN bool arch_checkarch(FAR const Elf32_Ehdr *hdr);
*
****************************************************************************/
-EXTERN int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym,
- uintptr_t addr);
-EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel,
- FAR const Elf32_Sym *sym, uintptr_t addr);
+int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym,
+ uintptr_t addr);
+int arch_relocateadd(FAR const Elf32_Rela *rel,
+ FAR const Elf32_Sym *sym, uintptr_t addr);
/****************************************************************************
* Name: arch_flushicache
@@ -329,7 +328,7 @@ EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel,
****************************************************************************/
#ifdef CONFIG_ELF_ICACHE
-EXTERN bool arch_flushicache(FAR void *addr, size_t len);
+bool arch_flushicache(FAR void *addr, size_t len);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/binfmt/nxflat.h b/nuttx/include/nuttx/binfmt/nxflat.h
index 71b36a36a..c87235c68 100644
--- a/nuttx/include/nuttx/binfmt/nxflat.h
+++ b/nuttx/include/nuttx/binfmt/nxflat.h
@@ -145,7 +145,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
+int nxflat_verifyheader(const struct nxflat_hdr_s *header);
/****************************************************************************
* Name: nxflat_init
@@ -160,8 +160,7 @@ EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
*
****************************************************************************/
-EXTERN int nxflat_init(const char *filename,
- struct nxflat_loadinfo_s *loadinfo);
+int nxflat_init(const char *filename, struct nxflat_loadinfo_s *loadinfo);
/****************************************************************************
* Name: nxflat_uninit
@@ -176,7 +175,7 @@ EXTERN int nxflat_init(const char *filename,
*
****************************************************************************/
-EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
+int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
/****************************************************************************
* Name: nxflat_load
@@ -184,7 +183,7 @@ EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
* Description:
* Loads the binary specified by nxflat_init into memory, mapping
* the I-space executable regions, allocating the D-Space region,
- * and inializing the data segment (relocation information is
+ * and initializing the data segment (relocation information is
* temporarily loaded into the BSS region. BSS will be cleared
* by nxflat_bind() after the relocation data has been processed).
*
@@ -194,7 +193,7 @@ EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
*
****************************************************************************/
-EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
+int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
/****************************************************************************
* Name: nxflat_read
@@ -208,8 +207,8 @@ EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
*
****************************************************************************/
-EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
- int readsize, int offset);
+int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
+ int readsize, int offset);
/****************************************************************************
* Name: nxflat_bind
@@ -227,8 +226,8 @@ EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
****************************************************************************/
struct symtab_s;
-EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
- FAR const struct symtab_s *exports, int nexports);
+int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports, int nexports);
/****************************************************************************
* Name: nxflat_unload
@@ -244,27 +243,27 @@ EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
*
****************************************************************************/
-EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo);
+int nxflat_unload(struct nxflat_loadinfo_s *loadinfo);
/****************************************************************************
* These are APIs used internally only by NuttX:
****************************************************************************/
-/****************************************************************************
+/***********************************************************************
* Name: nxflat_initialize
*
* Description:
- * NXFLAT support is built unconditionally. However, it order to
+ * NXFLAT support is built unconditionally. However, in order to
* use this binary format, this function must be called during system
- * format in order to register the NXFLAT binary format.
+ * initialization in order to register the NXFLAT 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 nxflat_initialize(void);
+int nxflat_initialize(void);
/****************************************************************************
* Name: nxflat_uninitialize
@@ -277,7 +276,7 @@ EXTERN int nxflat_initialize(void);
*
****************************************************************************/
-EXTERN void nxflat_uninitialize(void);
+void nxflat_uninitialize(void);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/binfmt/pcode.h b/nuttx/include/nuttx/binfmt/pcode.h
new file mode 100644
index 000000000..67136094d
--- /dev/null
+++ b/nuttx/include/nuttx/binfmt/pcode.h
@@ -0,0 +1,178 @@
+/****************************************************************************
+ * include/nuttx/binfmt/builtin.h
+ *
+ * Originally by:
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * With subsequent updates, modifications, and general maintenance by:
+ *
+ * Copyright (C) 2012-2013 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_BINFMT_BUILTIN_H
+#define __INCLUDE_NUTTX_BINFMT_BUILTIN_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+struct builtin_s
+{
+ const char *name; /* Invocation name and as seen under /sbin/ */
+ int priority; /* Use: SCHED_PRIORITY_DEFAULT */
+ int stacksize; /* Desired stack size */
+ main_t main; /* Entry point: main(int argc, char *argv[]) */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: builtin_initialize
+ *
+ * Description:
+ * Builtin support is built unconditionally. However, in order to
+ * use this binary format, this function must be called during system
+ * format in order to register the builtin 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.
+ *
+ ****************************************************************************/
+
+int builtin_initialize(void);
+
+/****************************************************************************
+ * Name: builtin_uninitialize
+ *
+ * Description:
+ * Unregister the builtin binary loader
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void builtin_uninitialize(void);
+
+/****************************************************************************
+ * Utility Functions Provided to Applications by binfmt/libbuiltin
+ ****************************************************************************/
+/****************************************************************************
+ * Name: builtin_isavail
+ *
+ * Description:
+ * Checks for availabiliy of application registerred during compile time.
+ *
+ * Input Parameter:
+ * filename - Name of the linked-in binary to be started.
+ *
+ * Returned Value:
+ * This is an end-user function, so it follows the normal convention:
+ * Returns index of builtin application. If it is not found then it
+ * returns -1 (ERROR) and sets errno appropriately.
+ *
+ ****************************************************************************/
+
+int builtin_isavail(FAR const char *appname);
+
+/****************************************************************************
+ * Name: builtin_getname
+ *
+ * Description:
+ * Returns pointer to a name of built-in application pointed by the
+ * index.
+ *
+ * Input Parameter:
+ * index, from 0 and on ...
+ *
+ * Returned Value:
+ * Returns valid pointer pointing to the app name if index is valid.
+ * Otherwise NULL is returned.
+ *
+ ****************************************************************************/
+
+FAR const char *builtin_getname(int index);
+
+/****************************************************************************
+ * Data Set Access Functions Provided to Applications by binfmt/libbuiltin
+ ****************************************************************************/
+/****************************************************************************
+ * Name: builtin_for_index
+ *
+ * Description:
+ * Returns the builtin_s structure for the selected builtin.
+ * If support for builtin functions is enabled in the NuttX configuration,
+ * then this function must be provided by the application code.
+ *
+ * Input Parameter:
+ * index, from 0 and on...
+ *
+ * Returned Value:
+ * Returns valid pointer pointing to the builtin_s structure if index is
+ * valid.
+ * Otherwise, NULL is returned.
+ *
+ ****************************************************************************/
+
+EXTERN FAR const struct builtin_s *builtin_for_index(int index);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_BINFMT_BUILTIN_H */
+
diff --git a/nuttx/include/nuttx/poff.h b/nuttx/include/nuttx/poff.h
new file mode 100644
index 000000000..b2b2c08c2
--- /dev/null
+++ b/nuttx/include/nuttx/poff.h
@@ -0,0 +1,435 @@
+/***************************************************************************
+ * include/nuttx/poff.h
+ * Definitions for the P-Code Object File Format (POFF)
+ *
+ * Copyright (C) 2014 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_NUXX_POFF_H
+#define __INCLUDE_NUXX_POFF_H
+
+/***************************************************************************
+ * Included Files
+ ***************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+/***************************************************************************
+ * Pre-processor Definitions
+ ***************************************************************************/
+
+/* Definitions for the fh_ident field of the poffHdr_t */
+
+#define FHI_MAG0 0 /* fh_ident[] indices */
+#define FHI_MAG1 1
+#define FHI_MAG2 2
+#define FHI_MAG3 3
+#define FHI_NIDENT 4
+
+#define FHI_POFF_MAG0 'P'
+#define FHI_POFF_MAG1 'O'
+#define FHI_POFF_MAG2 'F'
+#define FHI_POFF_MAG3 'F'
+#define FHI_POFF_MAG "POFF"
+
+/* Definitions for fh_version */
+
+#define FHV_NONE 0
+#define FHV_CURRENT 1
+
+/* Definitions for the fh_type */
+
+#define FHT_NONE 0 /* Shouldn't happen */
+#define FHT_EXEC 1 /* Pascal program executable */
+#define FHT_SHLIB 2 /* Pascal shared library */
+#define FHT_PROGRAM 3 /* Pascal program object */
+#define FHT_UNIT 4 /* Pascal unit object */
+#define FHT_NTYPES 5
+
+/* Definitions for fh_arch */
+
+#define FHAW_INSN16 0 /* Data width is 16 bits */
+#define FHAW_INSN32 1 /* Data width is 32 bits */
+
+#define FHAC_PCODE 0 /* Stack oriented P-Code machine class */
+#define FHAC_REGM 1 /* Generalized register machine class */
+
+#define MK_FH_ARCH(c,w) (((c)<<4)|(w))
+#define GET_FH_CLASS(fha) ((fha) >> 4)
+#define GET_FH_WIDTH(fha) ((fha) & 0x0f)
+
+#define FHA_PCODE_INSN16 MK_FH_ARCH(FHAC_PCODE,FHAW_INSN16)
+#define FHA_PCODE_INSN32 MK_FH_ARCH(FHAC_PCODE,FHAW_INSN32)
+#define FHA_REGM_INSN16 MK_FH_ARCH(FHAC_REGM,FHAW_INSN16)
+#define FHA_REGM_INSN32 MK_FH_ARCH(FHAC_REGM,FHAW_INSN32)
+
+#ifdef CONFIG_INSN16
+# define FHA_PCODE FHA_PCODE_INSN16
+# define FHA_REGM FHA_REGM_INSN16
+#endif
+#ifdef CONFIG_INSN32
+# define FHA_PCODE FHA_PCODE_INSN32
+# define FHA_REGM FHA_REGM_INSN16
+#endif
+
+/* Definitions for sh_type */
+
+#define SHT_NULL 0 /* Shouldn't happen */
+#define SHT_PROGDATA 1 /* Program data */
+#define SHT_SYMTAB 2 /* Symbol table */
+#define SHT_STRTAB 3 /* String table */
+#define SHT_REL 4 /* Relocation data */
+#define SHT_FILETAB 5 /* File table */
+#define SHT_LINENO 6 /* Line number data */
+#define SHT_DEBUG 7 /* Procedure/Function info */
+#define SHT_NTYPES 8
+
+/* Definitions for sh_flags */
+
+#define SHF_WRITE 0x01 /* Section is write-able */
+#define SHF_ALLOC 0x02 /* Memory must be allocated for setion */
+#define SHF_EXEC 0x04 /* Section contains program data */
+
+/* Values for st_type */
+
+#define STT_NONE 0 /* Should not occur */
+#define STT_DATA 1 /* Stack data section symbol */
+#define STT_RODATA 2 /* Read only data section symbol */
+#define STT_PROC 3 /* Procedure entry point */
+#define STT_FUNC 4 /* Function entry point */
+#define STT_NTYPES 5
+
+/* Values for st_align. Any power of two numeric value can be
+ * used, but the following are defined for convenience.
+ */
+
+#define STA_NONE 0 /* Should not occur */
+#define STA_8BIT 1 /* 8-bit byte alignment */
+#define STA_16BIT 2 /* 16-bit half word alignment */
+#define STA_32BIT 4 /* 32-bit word alignment */
+#define STA_64BIT 8 /* 32-bit double word alignment */
+
+/* Values for st_flags */
+
+#define STF_NONE 0x00
+#define STF_UNDEFINED 0x01 /* Symbol is undefined (imported) */
+
+/* P-Code relocation types (see RLI_type) */
+
+#define RLT_NONE 0 /* Should not occur */
+#define RLT_PCAL 1 /* PCAL to external proc/func */
+#define RLT_LDST 2 /* LA or LAX to external stack loc */
+#define RLT_NTYPES 3
+
+/* The following are used with relocation table rl_info field */
+
+#define RLI_SYM(x) ((x) >> 8) /* Symbol index */
+#define RLI_TYPE(x) ((x) & 0xff) /* Reloc type */
+#define RLI_MAKE(s,t) (((uint32_t)(s) << 8) | ((t) & 0xff))
+
+/***************************************************************************
+ * Public Types
+ ***************************************************************************/
+
+/* POFF file header */
+
+struct poff_fileheader_s
+{
+ /* fh_ident holds the four characters 'P', 'O', 'F', 'F'. See the FHI_
+ * definitions above.
+ */
+
+ uint8_t fh_ident[FHI_NIDENT];
+
+ /* fh_version holds the version of the POFF file format. This should
+ * always be FHV_CURRENT.
+ */
+
+ uint8_t fh_version;
+
+ /* fh_type holds the type of binary carry by the POFF file.
+ * See the FHT_ definitions above.
+ */
+
+ uint8_t fh_type;
+
+ /* fh_arch holds the architecture identifier. See the FHA_
+ * definitions above.
+ */
+
+ uint8_t fh_arch;
+
+ /* Pad so that the next field is aligned */
+
+ uint8_t fh_padding;
+
+ /* fh_shsize is the size a section header. This should be
+ * sizeof(poffSectionHeader_t)
+ */
+
+ uint16_t fh_shsize;
+
+ /* fh_num is the number of section headers in section header
+ * list. The total size of the section header block is then
+ * fh_shsize * fh_shnum.
+ */
+
+ uint16_t fh_shnum;
+
+ /* fh_name is an offset into the string table section data.
+ * It refers to a name associated with fh_type that determines
+ * the specific instances of the type.
+ */
+
+ uint32_t fh_name;
+
+ /* For fhi_type = {FHI_EXEC or FHI_PROGRAM}, fh_entry holds the
+ * entry point into the program. For FHI_PROGRAM, this entry point
+ * is a instruction space label. For FHI_EXEC, this entry point
+ * is an instruction space address offset (from address zero).
+ */
+
+ uint32_t fh_entry;
+
+ /* fh_shoff is the file offset to the beginning of the table of file
+ * headers. fh_shoff will most likely be sizeof(poffFileHeader_t).
+ */
+
+ uint32_t fh_shoff;
+};
+
+typedef struct poff_fileheader_s poff_fileheader_t;
+
+/* POFF section header */
+
+struct poff_sectionhdr_s
+{
+ /* sh_type is the type of section described by this header.
+ * See the SHT_ definitions above.
+ */
+
+ uint8_t sh_type;
+
+ /* These flags describe the characteristics of the section. See the
+ * SHF_ definitions above.
+ */
+
+ uint8_t sh_flags;
+
+ /* If the section holds a table of fixed sized entries, sh_entsize
+ * gives the size of one entry. The number of entries can then be
+ * obtained by dividing sh_size by sh_entsize.
+ */
+
+ uint16_t sh_entsize;
+
+ /* sh_name is an offset into the string table section data.
+ * It refers to a name associated with section.
+ */
+
+ uint32_t sh_name;
+
+ /* If the section is loaded into memory (SHF_ALLOC), then this
+ * address holds the address at which the data must be loaded
+ * (if applicable).
+ */
+
+ uint32_t sh_addr;
+
+ /* sh_offset is the offset from the beginning of the file to
+ * beginning of data associated with this section.
+ */
+
+ uint32_t sh_offset;
+
+ /* sh_size provides the total size of the section data in bytes.
+ * If the section holds a table of fixed sized entries, then
+ * sh_size be equal to sh_entsize times the number of entries.
+ */
+
+ uint32_t sh_size;
+};
+
+typedef struct poff_sectionhdr_s poff_sectionhdr_t;
+
+/* Structures which may appear as arrays in sections */
+
+/* Relocation data section array entry structure */
+
+struct poff_relocation_s
+ {
+ /* This value includes the symbol table index plus the
+ * relocation type. See the RLI_* macros above.
+ */
+
+ uint32_t rl_info;
+
+ /* This is the section data offset to the instruction/data
+ * to be relocated. The effected section is implicit in the
+ * relocation type.
+ */
+
+ uint32_t rl_offset; /* Offset to pcode */
+};
+
+typedef struct poff_relocation_s poff_relocation_t;
+
+/* Symbol section array entry structure */
+
+struct poff_symbol_s
+{
+ /* st_type is the type of symbol described by this entry.
+ * See the STT_ definitions above.
+ */
+
+ uint8_t st_type;
+
+ /* For data section symbols, the following provides the required
+ * data space alignment for the symbol memory representation. For
+ * procedures and functions, this value is ignored. See the STT_
+ * definitions above.
+ */
+
+ uint8_t st_align;
+
+ /* These flags describe the characteristics of the symbol. See the
+ * STF_ definitions above.
+ */
+
+ uint8_t st_flags;
+ uint8_t st_pad;
+
+ /* st_name is an offset into the string table section data.
+ * It refers to a name associated with symbol.
+ */
+
+ uint32_t st_name;
+
+ /* st_value is the value associated with symbol. For defined data
+ * section symbols, this is the offset into the initialized data
+ * section data; for defined procedures and functions, this the
+ * offset into program section data. For undefined symbols, this
+ * valid can be used as as addend.
+ */
+
+ uint32_t st_value;
+
+ /* For data section symbols, this is the size of the initialized
+ * data region associated with the symbol.
+ */
+
+ uint32_t st_size;
+};
+
+typedef struct poff_symbol_s poff_symbol_t;
+
+/* The file table section just consists of a list of offsets
+ * into the string table. The file table index is used elsewhere
+ * (such as in the line number array) to refer to a specific
+ * file.
+ */
+
+typedef uint32_t poffFileTab_t;
+
+/* Line number section array entry structure. Line numbers are
+ * associated with executable program data sections.
+ */
+
+struct poff_linenumber_s
+{
+ /* This is the source file line number */
+
+ uint16_t ln_lineno;
+
+ /* This is an index (not a byte offset) to an entry in the file
+ * section table. This can be used to identify the name of the
+ * file for which the line number applies.
+ */
+
+ uint16_t ln_fileno;
+
+ /* This is an offset to the beginning of the instruction in the
+ * program data section. At present, this is limited to a single
+ * program data section.
+ */
+
+ uint32_t ln_poffset;
+};
+
+typedef struct poff_linenumber_s poff_linenumber_t;
+
+/* The debug info section consists of a list of poffDebugFuncInfo_t
+ * entries, each following a sublist of poffDebugArgInfo_t entries.
+ */
+
+/* poffDebugFuncInfo_t provides description of function input
+ * parameters and return values.
+ */
+
+struct poff_debugfuncinfo_s
+{
+ /* This is the address or label of the function/procedure entry
+ * point.
+ */
+
+ uint32_t df_value;
+
+ /* This is the size of the value returned by the function in
+ * bytes (zero for procedures).
+ */
+
+ uint32_t df_size;
+
+ /* This is the number of parameters accepted by the function/
+ * procedure.
+ */
+
+ uint32_t df_nparms;
+};
+
+typedef struct poff_debugfuncinfo_s poff_debugfuncinfo_t;
+
+/* poffDebugArgInfo_t provides description of one function input
+ * parameter.
+ */
+
+struct poff_debugarginfo_s
+{
+ /* This is the size, in bytes, of one input paramter */
+
+ uint32_t da_size;
+};
+
+typedef struct poff_debugarginfo_s poff_debugarginfo_t;
+
+#endif /* __INCLUDE_NUXX_POFF_H */