summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/Makefile7
-rw-r--r--nuttx/binfmt/Makefile85
-rw-r--r--nuttx/binfmt/libnxflat/Make.defs37
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_load.c513
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_stack.c224
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_verify.c116
-rw-r--r--nuttx/examples/nxflat/nxflat.ld172
-rw-r--r--nuttx/examples/nxflat/tests/Make.defs45
-rw-r--r--nuttx/examples/nxflat/tests/Makefile55
-rw-r--r--nuttx/examples/nxflat/tests/errno/Makefile58
-rw-r--r--nuttx/examples/nxflat/tests/errno/errno.c83
-rw-r--r--nuttx/examples/nxflat/tests/errno/errno.obin0 -> 3708 bytes
-rw-r--r--nuttx/examples/nxflat/tests/hello++/Makefile114
-rw-r--r--nuttx/examples/nxflat/tests/hello++/hello++1.cpp60
-rw-r--r--nuttx/examples/nxflat/tests/hello++/hello++2.cpp123
-rw-r--r--nuttx/examples/nxflat/tests/hello++/hello++3.cpp132
-rw-r--r--nuttx/examples/nxflat/tests/hello++/hello++4.cpp150
-rw-r--r--nuttx/examples/nxflat/tests/hello/Makefile58
-rw-r--r--nuttx/examples/nxflat/tests/hello/hello.c89
-rw-r--r--nuttx/examples/nxflat/tests/hello/hello.obin0 -> 3456 bytes
-rw-r--r--nuttx/examples/nxflat/tests/longjmp/Makefile58
-rw-r--r--nuttx/examples/nxflat/tests/longjmp/longjmp.c128
-rw-r--r--nuttx/examples/nxflat/tests/mutex/Makefile58
-rw-r--r--nuttx/examples/nxflat/tests/mutex/mutex.c135
-rw-r--r--nuttx/examples/nxflat/tests/pthread/Makefile58
-rw-r--r--nuttx/examples/nxflat/tests/pthread/pthread.c136
-rw-r--r--nuttx/examples/nxflat/tests/signal/Makefile58
-rw-r--r--nuttx/examples/nxflat/tests/signal/signal.c296
-rw-r--r--nuttx/examples/nxflat/tests/task/Makefile59
-rw-r--r--nuttx/examples/nxflat/tests/task/task.c124
-rw-r--r--nuttx/include/nuttx/arch.h24
-rw-r--r--nuttx/include/nuttx/nxflat.h232
-rw-r--r--nuttx/sched/sched_releasetcb.c9
-rw-r--r--nuttx/sched/wd_internal.h3
-rw-r--r--nuttx/sched/wd_start.c12
35 files changed, 3502 insertions, 9 deletions
diff --git a/nuttx/Makefile b/nuttx/Makefile
index ae200d576..fe917e2bc 100644
--- a/nuttx/Makefile
+++ b/nuttx/Makefile
@@ -70,7 +70,7 @@ ADDON_DIRS := $(PCODE_DIR) $(NX_DIR)
# from the build if file descriptor support is disabled
NONFSDIRS = sched lib $(ARCH_SRC) mm examples/$(CONFIG_EXAMPLE) $(ADDON_DIRS)
-FSDIRS = fs drivers
+FSDIRS = fs drivers binfmt
ifeq ($(CONFIG_NET),y)
NONFSDIRS += net netutils
@@ -129,7 +129,7 @@ ifeq ($(CONFIG_NET),y)
LINKLIBS += drivers/libdrivers$(LIBEXT)
endif
else
-LINKLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT)
+LINKLIBS += fs/libfs$(LIBEXT) drivers/libdrivers$(LIBEXT) binfmt/libbinfmt$(LIBEXT)
endif
# Add libraries for Pascall P-Code
@@ -232,6 +232,9 @@ fs/libfs$(LIBEXT): context
drivers/libdrivers$(LIBEXT): context
@$(MAKE) -C drivers TOPDIR="$(TOPDIR)" libdrivers$(LIBEXT)
+binfmt/libbinfmt$(LIBEXT): context
+ @$(MAKE) -C binfmt TOPDIR="$(TOPDIR)" libbinfmt$(LIBEXT)
+
pcode/libpcode$(LIBEXT): context
@$(MAKE) -C pcode TOPDIR="$(TOPDIR)" libpcode$(LIBEXT)
diff --git a/nuttx/binfmt/Makefile b/nuttx/binfmt/Makefile
new file mode 100644
index 000000000..0e3d9720c
--- /dev/null
+++ b/nuttx/binfmt/Makefile
@@ -0,0 +1,85 @@
+############################################################################
+# nxflat/Makefile
+#
+# Copyright (C) 2007-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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+include libnxflat/Make.defs
+
+SUBDIRS = libnxflat
+
+ASRCS = $(LIBNXFLAT_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = $(LIBNXFLAT_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+BIN = libbinfmt$(LIBEXT)
+
+VPATH = libnxflat
+
+all: $(BIN)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+$(BIN): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) --dep-path . --dep-path libnxflat \
+ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f $(BIN) *~ .*.swp
+ $(call CLEAN)
+ @( for dir in $(SUBDIRS); do \
+ rm -f $${dir}/*~ $${dir}/.*.swp; \
+ done ; )
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/binfmt/libnxflat/Make.defs b/nuttx/binfmt/libnxflat/Make.defs
new file mode 100644
index 000000000..96cff471d
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/Make.defs
@@ -0,0 +1,37 @@
+############################################################################
+# nxflat/lib/Make.defs
+#
+# 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.
+#
+############################################################################
+
+LIBNXFLAT_ASRCS =
+LIBNXFLAT_CSRCS = libnxflat_load.c libnxflat_stack.c libnxflat_verify.c
diff --git a/nuttx/binfmt/libnxflat/libnxflat_load.c b/nuttx/binfmt/libnxflat/libnxflat_load.c
new file mode 100644
index 000000000..d456ae3a1
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_load.c
@@ -0,0 +1,513 @@
+/****************************************************************************
+ * libnxflat/lib/libnxflat_load.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 <nxflat.h>
+#include <debug.h>
+#include <errno.h>
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#define V_MAP (load_info->vtbl->map)
+#define V_UNMAP (load_info->vtbl->unmap)
+#define V_ALLOC (load_info->vtbl->alloc)
+#define V_FREE (load_info->vtbl->free)
+#define V_OPEN (load_info->vtbl->open)
+#define V_READ (load_info->vtbl->read)
+#define V_CLOSE (load_info->vtbl->close)
+
+#define NXFLAT_HDR_SIZE sizeof(struct nxflat_hdr_s)
+
+#ifndef MAX
+#define MAX(x,y) ((x) > (y) ? (x) : (y))
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+#ifdef CONFIG_NXFLAT_DEBUG
+static const char text_segment[] = "TEXT";
+static const char data_segment[] = "DATA";
+static const char bss_segment[] = "BSS";
+static const char unknown[] = "UNKNOWN";
+
+static const char *segment[] =
+{
+ text_segment,
+ data_segment,
+ bss_segment,
+ unknown
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_swap32
+ ****************************************************************************/
+
+#ifdef __BIG_ENDIAN
+static inline uint32 nxflat_swap32(uint32 little)
+{
+ uint32 big =
+ ((little >> 24) & 0xff) |
+ (((little >> 16) & 0xff) << 8) |
+ (((little >> 8) & 0xff) << 16) |
+ ((little & 0xff) << 24);
+ return big;
+}
+#endif
+
+/****************************************************************************
+ * Name: nxflat_reloc
+ ****************************************************************************/
+
+static void nxflat_reloc(struct nxflat_loadinfo_s *load_info, uint32 rl)
+{
+ union
+ {
+ uint32 l;
+ struct nxflat_reloc_s s;
+ } reloc;
+ uint32 *ptr;
+ uint32 datastart;
+
+ /* Force the long value into a union so that we can strip off some
+ * bit-encoded values.
+ */
+
+ reloc.l = rl;
+
+ /* We only support relocations in the data sections.
+ * Verify that the the relocation address lies in the data
+ * section of the file image.
+ */
+
+ if (reloc.s.r_offset > load_info->data_size)
+ {
+ dbg("ERROR: Relocation at 0x%08x invalid -- "
+ "does not lie in the data segment, size=0x%08x\n",
+ reloc.s.r_offset, load_info->data_size);
+ dbg(" Relocation not performed!\n");
+ }
+ else if ((reloc.s.r_offset & 0x00000003) != 0)
+ {
+ dbg("ERROR: Relocation at 0x%08x invalid -- "
+ "Improperly aligned\n",
+ reloc.s.r_offset);
+ }
+ else
+ {
+ /* Get a reference to the "real" start of data. It is
+ * offset slightly from the beginning of the allocated
+ * DSpace to hold information needed by ld.so at run time.
+ */
+
+ datastart = load_info->dspace + NXFLAT_DATA_OFFSET;
+
+ /* Get a pointer to the value that needs relocation in
+ * DSpace.
+ */
+
+ ptr = (uint32*)(datastart + reloc.s.r_offset);
+
+ vdbg("Relocation of variable at DATASEG+0x%08x "
+ "(address 0x%p, currently 0x%08x) into segment %s\n",
+ reloc.s.r_offset, ptr, *ptr, segment[reloc.s.r_type]);
+
+ switch (reloc.s.r_type)
+ {
+ /* TEXT is located at an offset of NXFLAT_HDR_SIZE from
+ * the allocated/mapped ISpace region.
+ */
+
+ case NXFLAT_RELOC_TYPE_TEXT:
+ *ptr += load_info->ispace + NXFLAT_HDR_SIZE;
+ 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.
+ * BSS is positioned after DATA, unrelocated references
+ * to BSS include the data offset.
+ *
+ * In other contexts, is it necessary to add the data_size
+ * to get the BSS offset like:
+ *
+ * *ptr += datastart + load_info->data_size;
+ */
+
+ case NXFLAT_RELOC_TYPE_DATA:
+ case NXFLAT_RELOC_TYPE_BSS:
+ *ptr += datastart;
+ break;
+
+ /* This case happens normally if the symbol is a weak
+ * undefined symbol. We permit these.
+ */
+
+ case NXFLAT_RELOC_TYPE_NONE:
+ dbg("NULL relocation!\n");
+ break;
+
+ default:
+ dbg("ERROR: Unknown relocation type=%d\n", reloc.s.r_type);
+ break;
+ }
+
+ vdbg("Relocation became 0x%08x\n", *ptr);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_init
+ ****************************************************************************/
+
+int nxflat_init(bin_handle_t bin_handle, file_handle_t file_handle,
+ const struct nxflat_hdr_s *header, const struct nxflat_vtbl_s *vtbl,
+ struct nxflat_loadinfo_s *load_info)
+{
+ uint32 datastart;
+ uint32 dataend;
+ uint32 bssstart;
+ uint32 bssend;
+
+ vdbg("bin_handle=0x%p header=0x%p load_info=0x%p\n",
+ bin_handle, header, load_info);
+
+ /* Clear the load info structure */
+
+ memset(load_info, 0, sizeof(struct nxflat_loadinfo_s));
+
+ /* Verify the xFLT header */
+
+ if (nxflat_verifyheader(header) != 0)
+ {
+ /* This is not an error because we will be called
+ * to attempt loading EVERY binary. Returning -ENOEXEC
+ * simply informs the system that the file is not
+ * an xFLT file. Besides, if there is something worth
+ * complaining about, nnxflat_verifyheader() has already
+ * done so.
+ */
+
+ dbg("Bad xFLT header\n");
+ return -ENOEXEC;
+ }
+
+ /* Save all of the input values in the load_info structure */
+
+ load_info->bin_handle = bin_handle;
+ load_info->file_handle = file_handle;
+ load_info->header = header;
+ load_info->vtbl = vtbl;
+
+ /* And extract some additional information from the xflat
+ * header. Note that the information in the xflat header is in
+ * network order.
+ */
+
+ datastart = ntohl(header->h_datastart);
+ dataend = ntohl(header->h_dataend);
+ bssstart = dataend;
+ bssend = ntohl(header->h_bssend);
+
+ /* And put this information into the load_info structure as well.
+ *
+ * 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.
+ */
+
+ load_info->entry_offset = ntohl(header->h_entry);
+ load_info->ispace_size = datastart;
+
+ load_info->data_size = dataend - datastart;
+ load_info->bss_size = bssend - dataend;
+ load_info->stack_size = 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.
+ */
+
+ load_info->dspace_size = /* Total DSpace Size is: */
+ (NXFLAT_DATA_OFFSET + /* Memory set aside for ldso */
+ bssend - datastart + /* Data and bss segment sizes */
+ load_info->stack_size); /* (Current) stack size */
+
+ /* Get the offset to the start of the relocations (we'll relocate
+ * this later).
+ */
+
+ load_info->reloc_start = ntohl(header->h_relocstart);
+ load_info->reloc_count = ntohl(header->h_reloccount);
+
+ return 0;
+}
+
+/****************************************************************************
+ * Name: nxflat_uninit
+ ****************************************************************************/
+
+int nxflat_uninit(struct nxflat_loadinfo_s *load_info)
+{
+ if (load_info->file_handle)
+ {
+ V_CLOSE(load_info->file_handle);
+ }
+ return 0;
+}
+
+/****************************************************************************
+ * Name: nxflat_load
+ ****************************************************************************/
+
+int nxflat_load(struct nxflat_loadinfo_s *load_info)
+{
+ uint32 dspace_read_size;
+ uint32 data_offset;
+ uint32 *reloc_tab;
+ uint32 result;
+ 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
+ */
+
+ {
+ uint32 extra_alloc;
+ uint32 reloc_size;
+
+ /* This is the amount of memory that we have to have to hold
+ * the relocations.
+ */
+
+ reloc_size = load_info->reloc_count * 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.
+ */
+
+ extra_alloc = MAX(load_info->bss_size + load_info->stack_size,
+ reloc_size);
+
+ /* Use this addtional amount to adjust the total size of the
+ * dspace region. */
+
+ load_info->dspace_size =
+ NXFLAT_DATA_OFFSET + /* Memory used by ldso */
+ load_info->data_size + /* Initialized data */
+ extra_alloc; /* bss+stack/relocs */
+
+ /* 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.
+ */
+
+ dspace_read_size = load_info->data_size + reloc_size;
+ }
+
+ /* We'll need this a few times as well. */
+
+ data_offset = load_info->ispace_size;
+
+ /* We will make two mmap calls create an address space for
+ * the executable. We will attempt to map the file to get
+ * the ISpace address space and to allocate RAM to get the
+ * DSpace address space. If the system does not support
+ * file mapping, the V_MAP() implementation should do the
+ * right thing.
+ */
+
+ /* The following call will give as a pointer to the mapped
+ * file ISpace. This may be in ROM, RAM, Flash, ...
+ * We don't really care where the memory resides as long
+ * as it is fully initialized and ready to execute.
+ * However, the memory should be share-able between processes;
+ * otherwise, we don't really have shared libraries.
+ */
+
+ load_info->ispace = (uint32)V_MAP(load_info->file_handle,
+ load_info->ispace_size);
+
+ if (load_info->ispace >= (uint32) -4096)
+ {
+ dbg("Failed to map xFLT ISpace, error=%d\n", -load_info->ispace);
+ return load_info->ispace;
+ }
+
+ vdbg("Mapped ISpace (%d bytes) at 0x%08x\n",
+ load_info->ispace_size, load_info->ispace);
+
+ /* The following call will give a pointer to the allocated
+ * but uninitialized ISpace memory.
+ */
+
+ load_info->dspace = (uint32)V_ALLOC(load_info->dspace_size);
+
+ if (load_info->dspace >= (uint32) -4096)
+ {
+ dbg("Failed to allocate DSpace, error=%d\n",
+ -load_info->ispace);
+ (void)nxflat_unload(load_info);
+ return load_info->ispace;
+ }
+
+ vdbg("Allocated DSpace (%d bytes) at 0x%08x\n",
+ load_info->dspace_size, load_info->dspace);
+
+ /* Now, read the data into allocated DSpace at an offset into
+ * the allocated DSpace memory. This offset provides a small
+ * amount of BSS for use by the loader.
+ */
+
+ result = V_READ(load_info->bin_handle,
+ load_info->file_handle,
+ (char*)(load_info->dspace + NXFLAT_DATA_OFFSET),
+ dspace_read_size,
+ data_offset);
+
+ if (result >= (uint32) -4096)
+ {
+ dbg("Unable to read DSpace, errno %d\n", -result);
+ (void)nxflat_unload(load_info);
+ return result;
+ }
+
+ /* Save information about the allocation. */
+
+ load_info->alloc_start = load_info->dspace;
+ load_info->alloc_size = load_info->dspace_size;
+
+ vdbg("TEXT=0x%x Entry point offset=0x%08x, datastart is 0x%08x\n",
+ load_info->ispace, load_info->entry_offset, data_offset);
+
+ /* 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.
+ * The following adjustment will convert it to an address in DSpace.
+ */
+
+ reloc_tab = (uint32*)
+ (load_info->reloc_start /* File offset to reloc records */
+ + load_info->dspace /* + Allocated DSpace memory */
+ + NXFLAT_DATA_OFFSET /* + Offset for ldso usage */
+ - load_info->ispace_size); /* - File offset to DSpace */
+
+ vdbg("Relocation table at 0x%p, reloc_count=%d\n",
+ reloc_tab, load_info->reloc_count);
+
+ /* Now run through the relocation entries. */
+
+ for (i=0; i < load_info->reloc_count; i++)
+ {
+#ifdef __BIG_ENDIAN
+ nxflat_reloc(load_info, nxflat_swap32(reloc_tab[i]));
+#else
+ nxflat_reloc(load_info, reloc_tab[i]);
+#endif
+ }
+
+ /* Zero the BSS, BRK and stack areas, trashing the relocations
+ * that lived in the corresponding space in the file. */
+
+ memset((void*)(load_info->dspace + NXFLAT_DATA_OFFSET + load_info->data_size),
+ 0,
+ (load_info->dspace_size - NXFLAT_DATA_OFFSET -
+ load_info->data_size));
+
+ return 0;
+}
+
+/****************************************************************************
+ * Name: nxflat_unload
+ *
+ * Description:
+ * This function unloads the object from memory. This essentially
+ * undoes the actions of nxflat_load.
+ *
+ ****************************************************************************/
+
+int nxflat_unload(struct nxflat_loadinfo_s *load_info)
+{
+ /* Reset the contents of the info structure. */
+
+ /* Nothing is allocated */
+
+ load_info->alloc_start = 0;
+ load_info->alloc_size = 0;
+
+ /* Release the memory segments */
+
+ if (load_info->ispace)
+ {
+ V_UNMAP((void*)load_info->ispace, load_info->ispace_size);
+ load_info->ispace = 0;
+ }
+
+ if (load_info->dspace)
+ {
+ V_FREE((void*)load_info->dspace, load_info->dspace_size);
+ load_info->dspace = 0;
+ }
+
+ return 0;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_stack.c b/nuttx/binfmt/libnxflat/libnxflat_stack.c
new file mode 100644
index 000000000..082a2e05e
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_stack.c
@@ -0,0 +1,224 @@
+/****************************************************************************
+ * libnxflat/lib/nxflat_stack.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 <debug.h>
+#include <errno.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_adjuststacksize
+ ****************************************************************************/
+
+void nxflat_adjuststacksize(struct nxflat_loadinfo_s *load_info,
+ int argc, int envc, int system_usage)
+{
+ uint32 total_usage = system_usage;
+
+ /* For argc, we will store the array (argc elements), the argc
+ * value itself, plus a null pointer.
+ */
+
+ total_usage += (argc + 2) * sizeof(uint32);
+
+ /* For envc, we will store the array (envc elements) plus a null
+ * pointer.
+ */
+
+ total_usage += (envc + 1) * sizeof(uint32);
+
+ /* And we will store six additional words described the memory
+ * layout.
+ */
+
+ total_usage += 6 * sizeof(uint32);
+
+ /* Add this to the previously determined stack size */
+
+ load_info->stack_size += total_usage;
+}
+
+/****************************************************************************
+ * Name: nxflat_initstack
+ *
+ * Description:
+ * When we enter the NXFLAT_ loader, it will expect to see a stack frame
+ * like the following. NOTE: This logic assumes a push down stack
+ * (i.e., we decrement the stack pointer to go from the "BOTTOM" to
+ * the "TOP").
+ *
+ *
+ * TOP->argc Argument count (integer)
+ * argv[0...(argc-1)] Program arguments (pointers)
+ * NULL Marks end of arguments
+ * env[0...N] Environment variables (pointers)
+ * NULL Marks end of environment variables
+ * loader ispace Address of loader ISpace (NXFLAT_ header)
+ * loader dspace Address of loader DSpace
+ * loader dspace size Size of the allocated loader DSpace
+ * program ispace Address of program ISpace (NXFLAT_ header)
+ * program dspace Address of program DSpace
+ * BOTTOM->program dspace size Size of the allocated program DSpace
+ *
+ ****************************************************************************/
+
+uint32 nxflat_initstack(struct nxflat_loadinfo_s *prog_load_info,
+ struct nxflat_loadinfo_s *lib_load_info,
+ int argc, int envc, char *p)
+{
+ uint32 *argv;
+ uint32 *envp;
+ uint32 *sp;
+ char dummy;
+
+ /* p points to the beginning of the array of arguments;
+ * sp points to the "bottom" of a push down stack.
+ */
+
+ sp = (uint32*)((-(uint32)sizeof(char*))&(uint32) p);
+
+ /* Place program information on the stack */
+
+ if (prog_load_info)
+ {
+ *sp-- = (uint32)prog_load_info->dspace_size;
+ *sp-- = (uint32)prog_load_info->dspace;
+ *sp-- = (uint32)prog_load_info->ispace;
+ }
+ else
+ {
+ dbg("No program load info provided\n");
+ return -EINVAL;
+ }
+
+ /* Place loader information on the stack */
+
+ if (lib_load_info)
+ {
+ *sp-- = (uint32)lib_load_info->dspace_size;
+ *sp-- = (uint32)lib_load_info->dspace;
+ *sp-- = (uint32)lib_load_info->ispace;
+ }
+ else
+ {
+ *sp-- = (uint32)0;
+ *sp-- = (uint32)0;
+ *sp-- = (uint32)0;
+ }
+
+ /* Allocate space on the stack for the envp array contents
+ * (including space for a null terminator).
+ */
+
+ sp -= envc+1;
+ envp = sp;
+
+ /* Allocate space on the stack for the argv array contents
+ * (including space for a null terminator).
+ */
+
+ sp -= argc+1;
+ argv = sp;
+
+ /* Put argc on the stack. sp now points to the "top" of the
+ * stack as it will be received by the new task.
+ */
+
+ *sp-- = (uint32)argc;
+
+ /* Copy argv pointers into the stack frame (terminated with
+ * a null pointer).
+ */
+
+ prog_load_info->arg_start = (uint32)p;
+ while (argc-->0)
+ {
+ /* Put the address of the beginning of the string */
+
+ *argv++ = (uint32)p;
+
+ /* Search for the end of the string */
+
+ do
+ {
+ dummy = *p++;
+ }
+ while (dummy);
+ }
+ *argv = (uint32)NULL,argv;
+
+ /* Copy envp pointers into the stack frame (terminated with
+ * a null pointer).
+ */
+
+ prog_load_info->env_start = (uint32)p;
+ while (envc-->0)
+ {
+ /* Put the address of the beginning of the string */
+
+ *envp++ = (uint32)p;
+
+ /* Search for the end of the string */
+
+ do
+ {
+ dummy = *p++;
+ }
+ while (dummy);
+ }
+ *envp = (uint32)NULL;
+
+ prog_load_info->env_end = (uint32)p;
+
+ return (uint32)sp;
+}
+
diff --git a/nuttx/binfmt/libnxflat/libnxflat_verify.c b/nuttx/binfmt/libnxflat/libnxflat_verify.c
new file mode 100644
index 000000000..b31994b8b
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/libnxflat_verify.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * nxflat/lib/nxflat_stack.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 <debug.h>
+#include <errno.h>
+#include <arpa/inet.h>
+#include <nuttx/nxflat.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define V_MAP (load_info->vtbl->map)
+#define V_UNMAP (load_info->vtbl->unmap)
+#define V_ALLOC (load_info->vtbl->alloc)
+#define V_FREE (load_info->vtbl->free)
+#define V_OPEN (load_info->vtbl->open)
+#define V_READ (load_info->vtbl->read)
+#define V_CLOSE (load_info->vtbl->close)
+
+#define XFLT_HDR_SIZE sizeof(struct nxflat_hdr_s)
+
+#ifndef MAX
+# define MAX(x,y) ((x) > (y) ? (x) : (y))
+#endif
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxflat_verifyheader
+ ****************************************************************************/
+
+int nxflat_verifyheader(const struct nxflat_hdr_s *header)
+{
+ uint16 revision;
+
+ if (!header)
+ {
+ dbg("NULL NXFLAT header!");
+ return -ENOEXEC;
+ }
+
+ /* Check the FLT header -- magic number and revision.
+ *
+ * If the the magic number does not match. Just return
+ * silently. This is not our binary.
+ */
+
+ if (strncmp(header->h_magic, "NXFLAT", 4) != 0)
+ {
+ dbg("Unrecognized magic=\"%c%c%c%c\"",
+ header->h_magic[0], header->h_magic[1],
+ 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)
+ {
+ dbg("Unsupported NXFLAT version=%d\n", revision);
+ return -ENOEXEC;
+ }
+ return 0;
+}
+
diff --git a/nuttx/examples/nxflat/nxflat.ld b/nuttx/examples/nxflat/nxflat.ld
new file mode 100644
index 000000000..9a59c0ec0
--- /dev/null
+++ b/nuttx/examples/nxflat/nxflat.ld
@@ -0,0 +1,172 @@
+/****************************************************************************
+ * examples/nxflat/nxflat.ld
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+ ISPACE : ORIGIN = 0x0, LENGTH = 2097152
+ DSPACE : ORIGIN = 0x0, LENGTH = 2097152
+}
+
+/****************************************************************************
+ * The XFLAT program image is divided into two segments:
+ *
+ * (1) ISpace (Instruction Space). This is the segment that contains
+ * code (.text). Everything in the segment should be fetch-able
+ * machine PC instructions (jump, branch, call, etc.).
+ * (2) DSpace (Data Space). This is the segment that contains both
+ * read-write data (.data, .bss) as well as read-only data (.rodata).
+ * Everything in this segment should be access-able with machine
+ * with machine load and store instructions.
+ ****************************************************************************/
+
+SECTIONS
+{
+ .text 0x00000000 :
+ {
+ /* ISpace is located at address 0. Every (unrelocated) ISpace
+ * address is an offset from the begining of this segment.
+ */
+
+ text_start = . ;
+
+ *(.text)
+ *(.text.*)
+ *(.gnu.warning)
+ *(.stub)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.jcr)
+
+ /* C++ support: The .init and .fini sections contain XFLAT-
+ * specific logic to manage static constructors and destructors.
+ */
+
+ *(.gnu.linkonce.t.*)
+ *(.init)
+ *(.fini)
+
+ /* This is special code area at the end of the normal
+ text section. It contains a small lookup table at
+ the start followed by the code pointed to by entries
+ in the lookup table. */
+
+ . = ALIGN (4) ;
+ PROVIDE(__ctbp = .);
+ *(.call_table_data)
+ *(.call_table_text)
+
+ _etext = . ;
+
+ } > ISPACE
+
+ /* DSpace is also located at address 0. Every (unrelocated) DSpace
+ * address is an offset from the begining of this segment.
+ */
+
+ .data 0x00000000 :
+ {
+ __data_start = . ;
+ *(.rodata)
+ *(.rodata1)
+ *(.rodata.*)
+ *(.gnu.linkonce.r*)
+ *(.data)
+ *(.data1)
+ *(.data.*)
+ *(.gnu.linkonce.d*)
+ *(.data1)
+ *(.eh_frame)
+ *(.gcc_except_table)
+
+ *(.gnu.linkonce.s.*)
+ *(__libc_atexit)
+ *(__libc_subinit)
+ *(__libc_subfreeres)
+ *(.note.ABI-tag)
+
+ /* C++ support. For each global and static local C++ object,
+ * GCC creates a small subroutine to construct the object. Pointers
+ * to these routines (not the routines themselves) are stored as
+ * simple, linear arrays in the .ctors section of the object file.
+ * Similarly, pointers to global/static destructor routines are
+ * stored in .dtors.
+ */
+
+ *(.gnu.linkonce.d.*)
+
+ _ctors_start = . ;
+ *(.ctors)
+ _ctors_end = . ;
+ _dtors_start = . ;
+ *(.dtors)
+ _dtors_end = . ;
+
+ _edata = . ;
+ edata = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .bss :
+ {
+ __bss_start = _edata ;
+ *(.dynsbss)
+ *(.sbss)
+ *(.sbss.*)
+ *(.scommon)
+ *(.dynbss)
+ *(.bss)
+ *(.bss.*)
+ *(.bss*)
+ *(.gnu.linkonce.b*)
+ *(COMMON)
+ end = ALIGN( 0x10 ) ;
+ _end = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .got 0 : { *(.got.plt) *(.got) }
+ .junk 0 : { *(.rel*) *(.rela*) }
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/examples/nxflat/tests/Make.defs b/nuttx/examples/nxflat/tests/Make.defs
new file mode 100644
index 000000000..c4ec82c52
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/Make.defs
@@ -0,0 +1,45 @@
+############################################################################
+# examples/nxflat/Make.defs
+#
+# 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.
+#
+############################################################################
+
+NXFLATCC = $(CC)
+NXFLATCFLAGS = $(CFLAGS)
+NXFLATCXX = $(CXX)
+NXFLATCXXFLAGS = $(CXXFLAGS)
+NXFLATCC = $(CC)
+NXFLATCFLAGS = $(CFLAGS)
+
+NXFLATLD = $(LD)
+NXFLATLDFLAGS =
+
diff --git a/nuttx/examples/nxflat/tests/Makefile b/nuttx/examples/nxflat/tests/Makefile
new file mode 100644
index 000000000..003c187f3
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/Makefile
@@ -0,0 +1,55 @@
+############################################################################
+# examples/nxflat/Makefile
+#
+# 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.
+#
+############################################################################
+
+TESTDIRS := errno hello hello++ longjmp mutex pthread signal task
+
+define TEST_template
+$(1)_$(2):
+ $(MAKE) -C $(1) $(3)
+endef
+
+$(foreach TEST, $(TESTDIRS), $(eval $(call TEST_template,$(TEST),build, all)))
+$(foreach TEST, $(TESTDIRS), $(eval $(call TEST_template,$(TEST),clean,clean)))
+$(foreach TEST, $(TESTDIRS), $(eval $(call TEST_template,$(TEST),install,install)))
+
+all: build
+.PHONY: all build clean user_install root_install
+
+build: $(foreach TEST, $(TESTDIRS), $(TEST)_build)
+
+clean: $(foreach TEST, $(TESTDIRS), $(TEST)_clean)
+
+install: $(foreach TEST, $(TESTDIRS), $(TEST)_install)
+
diff --git a/nuttx/examples/nxflat/tests/errno/Makefile b/nuttx/examples/nxflat/tests/errno/Makefile
new file mode 100644
index 000000000..4c1ce8180
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/errno/Makefile
@@ -0,0 +1,58 @@
+############################################################################
+# examples/nxflat/tests/hello/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = errno
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
diff --git a/nuttx/examples/nxflat/tests/errno/errno.c b/nuttx/examples/nxflat/tests/errno/errno.c
new file mode 100644
index 000000000..3c54de7be
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/errno/errno.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * examples/nxflat/tests/errno/errno.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 <stdio.h>
+#include <stdlib.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+static const char g_nonexistent[] = "aflav-sautga-ay";
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ FILE *test_stream;
+
+ /* Try using stdout and stderr explicitly. These are global variables
+ * exported from the base code.
+ */
+
+ fprintf(stdout, "Hello, World on stdout\n");
+ fprintf(stderr, "Hello, World on stderr\n");
+
+ /* Try opening a non-existent file using buffered IO. */
+
+ test_stream = fopen(g_nonexistent, "r");
+ if (test_stream)
+ {
+ fprintf(stderr, "Hmm... Delete \"%s\" and try this again\n",
+ g_nonexistent);
+ exit(1);
+ }
+
+ /* Now print the errno on stderr. Errno is also a global
+ * variable exported by the base code.
+ */
+
+ fprintf(stderr, "We failed to open \"%s!\" errno is %d\n",
+ g_nonexistent, errno);
+
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/errno/errno.o b/nuttx/examples/nxflat/tests/errno/errno.o
new file mode 100644
index 000000000..eada97cdb
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/errno/errno.o
Binary files differ
diff --git a/nuttx/examples/nxflat/tests/hello++/Makefile b/nuttx/examples/nxflat/tests/hello++/Makefile
new file mode 100644
index 000000000..dc2693219
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello++/Makefile
@@ -0,0 +1,114 @@
+############################################################################
+# examples/nxflat/tests/hello/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN1 = hello++1
+BIN2 = hello++2
+BIN3 = hello++3
+#BIN4 = hello++4
+
+SRCS1 = $(BIN1).c
+OBJS1 = $(SRCS1:.c=.o)
+
+SRCS2 = $(BIN2).c
+OBJS2 = $(SRCS2:.c=.o)
+
+SRCS3 = $(BIN3).c
+OBJS3 = $(SRCS3:.c=.o)
+
+#SRCS4 = $(BIN4).c
+#OBJS4 = $(SRCS4:.c=.o)
+
+CXXOBJS = $(OBJS1) $(OBJS2) $(OBJS3) # $(OBJS4)
+
+LIBSTDC_STUBS_DIR = $(TOPDIR)/libxx
+LIBSTDC_STUBS_LIB = $(LIBSTDC_STUBS_DIR)/liblibxx.a
+
+all: $(BIN1) $(BIN2) $(BIN3) # $(BIN4)
+
+$(CXXOBJS): %.o: %.cpp
+ $(NXFLATCXX) -c $(NXFLATCXXFLAGS) $< -o $@
+
+# This contains libstdc++ stubs to that you can build C++ code
+# without actually have libstdc++
+
+$(LIBSTDC_STUBS_LIB):
+ $(MAKE) -C $(LIBSTDC_STUBS_DIR)
+
+# BIN1 and BIN2 link just like C code because they contain no
+# static constructors. BIN1 is equivalent to a C hello world;
+# BIN2 contains a class that implements hello world, but it is
+# not statically initialized.
+
+$(BIN1): $(OBJS1)
+ $(XFLATLD) -o $@ $^
+
+$(BIN2): $(OBJS2) $(LIBSTDC_STUBS_LIB)
+ $(XFLATLD) -o $@ $^
+
+# BIN3 and BIN4 require that we include --cxx in the xflat-ld command.
+# This will instruct xflat-ld that we want it to put togethe the correct
+# startup files to handle the C++ static initializers.
+#
+# BIN3 is equivalent to BIN2 except that is uses static initializers
+
+$(BIN3): $(OBJS3) $(LIBSTDC_STUBS_LIB)
+ $(XFLATLD) --cxx -o $@ $^
+
+# BIN4 is similar to BIN3 except that it uses the streams code from libstdc++
+#
+# NOTE: libstdc++ is not available for XFLAT as of this writing
+#
+#$(BIN4): $(OBJS4) $(LIBSTDC_STUBS_LIB)
+# $(XFLATLD) --cxx -o $@ $^
+
+clean:
+ rm -f $(BIN1) $(BIN2) $(BIN3) $(BIN4) *.o *~ core
+
+user_install: $(BIN1) $(BIN2) $(BIN3) # $(BIN4)
+ install -D $(BIN1) $(ROMFS_DIR)/$(BIN1)
+ install -D $(BIN2) $(ROMFS_DIR)/$(BIN2)
+ install -D $(BIN3) $(ROMFS_DIR)/$(BIN3)
+# install -D $(BIN4) $(ROMFS_DIR)/$(BIN4)
+
+
+
+
+
+
+
diff --git a/nuttx/examples/nxflat/tests/hello++/hello++1.cpp b/nuttx/examples/nxflat/tests/hello++/hello++1.cpp
new file mode 100644
index 000000000..a8881422c
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello++/hello++1.cpp
@@ -0,0 +1,60 @@
+/////////////////////////////////////////////////////////////////////////////
+// examples/nxflat/tests/hello++/hello++1.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.
+//
+/////////////////////////////////////////////////////////////////////////////
+//
+// This is an trivial version of "Hello, World" program. It illustrates
+// that we can build C programs using the C++ compiler.
+//
+// - Building a C++ program to use the C library
+// - No class creation
+// - NO Streams
+// - NO Static constructor and destructors
+//
+/////////////////////////////////////////////////////////////////////////////
+
+/////////////////////////////////////////////////////////////////////////////
+// Included Files
+/////////////////////////////////////////////////////////////////////////////
+
+#include <cstdio>
+
+/////////////////////////////////////////////////////////////////////////////
+// Public Functions
+/////////////////////////////////////////////////////////////////////////////
+
+int main(int argc, char **argv, char **envp)
+{
+ printf("Hello, World!\n");
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/hello++/hello++2.cpp b/nuttx/examples/nxflat/tests/hello++/hello++2.cpp
new file mode 100644
index 000000000..4f189699e
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello++/hello++2.cpp
@@ -0,0 +1,123 @@
+/////////////////////////////////////////////////////////////////////////////
+// examples/nxflat/tests/hello++/hello++2.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.
+//
+/////////////////////////////////////////////////////////////////////////////
+//
+// This is an another trivial version of "Hello, World" design. It illustrates
+//
+// - Building a C++ program to use the C library
+// - Basic class creation
+// - NO Streams
+// - NO Static constructor and destructors
+//
+/////////////////////////////////////////////////////////////////////////////
+
+/////////////////////////////////////////////////////////////////////////////
+// Included Files
+/////////////////////////////////////////////////////////////////////////////
+
+#include <cstdio>
+
+/////////////////////////////////////////////////////////////////////////////
+// Classes
+/////////////////////////////////////////////////////////////////////////////
+
+class CThingSayer
+{
+ const char *szWhatToSay;
+public:
+ CThingSayer(void)
+ {
+ printf("CThingSayer::CThingSayer: I am!\n");
+ szWhatToSay = NULL;
+ }
+
+ ~CThingSayer(void)
+ {
+ printf("CThingSayer::~CThingSayer: I cease to be\n");
+ if (szWhatToSay)
+ {
+ printf("CThingSayer::~CThingSayer: I will never say '%s' again\n",
+ szWhatToSay);
+ }
+ szWhatToSay = NULL;
+ }
+
+ void Initialize(const char *czSayThis)
+ {
+ printf("CThingSayer::Initialize: When told, I will say '%s'\n",
+ czSayThis);
+ szWhatToSay = czSayThis;
+ }
+
+ void SayThing(void)
+ {
+ printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay);
+ }
+};
+
+/////////////////////////////////////////////////////////////////////////////
+// Public Functions
+/////////////////////////////////////////////////////////////////////////////
+
+int main(int argc, char **argv, char **envp)
+{
+ CThingSayer *MyThingSayer;
+
+ printf("main: Started. Creating MyThingSayer\n");
+
+ // Create an instance of the CThingSayer class
+ // We should see the message from constructor, CThingSayer::CThingSayer(),
+
+ MyThingSayer = new CThingSayer;
+ printf("main: Created MyThingSayer=0x%08lx\n", (long)MyThingSayer);
+
+ // Tell MyThingSayer that "Hello, World!" is the string to be said
+
+ printf("main: Calling MyThingSayer->Initialize\n");;
+ MyThingSayer->Initialize("Hello, World!");
+
+ // Tell MyThingSayer to say the thing we told it to say
+
+ printf("main: Calling MyThingSayer->SayThing\n");;
+ MyThingSayer->SayThing();
+
+ // We should see the message from the destructor,
+ // CThingSayer::~CThingSayer(), AFTER we see the following
+
+ printf("main: Destroying MyThingSayer\n");
+ delete MyThingSayer;
+
+ printf("main: Returning\n");;
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/hello++/hello++3.cpp b/nuttx/examples/nxflat/tests/hello++/hello++3.cpp
new file mode 100644
index 000000000..b41d09664
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello++/hello++3.cpp
@@ -0,0 +1,132 @@
+/////////////////////////////////////////////////////////////////////////////
+// examples/nxflat/tests/hello++/hello++3.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.
+//
+/////////////////////////////////////////////////////////////////////////////
+//
+// This is an another trivial version of "Hello, World" design. It illustrates
+//
+// - Building a C++ program to use the C library and stdio
+// - Basic class creation with virtual methods.
+// - Static constructor and destructors (in main program only)
+// - NO Streams
+//
+/////////////////////////////////////////////////////////////////////////////
+
+/////////////////////////////////////////////////////////////////////////////
+// Included Files
+/////////////////////////////////////////////////////////////////////////////
+
+#include <cstdio>
+
+/////////////////////////////////////////////////////////////////////////////
+// Classes
+/////////////////////////////////////////////////////////////////////////////
+
+class CThingSayer
+{
+ const char *szWhatToSay;
+public:
+ CThingSayer(void);
+ virtual ~CThingSayer(void);
+ virtual void Initialize(const char *czSayThis);
+ virtual void SayThing(void);
+};
+
+// A static instance of the CThingSayer class. This instance MUST
+// be constructed by the system BEFORE the program is started at
+// main() and must be destructed by the system AFTER the main()
+// returns to the system
+
+static CThingSayer MyThingSayer;
+
+// These are implementations of the methods of the CThingSayer class
+
+CThingSayer::CThingSayer(void)
+{
+ printf("CThingSayer::CThingSayer: I am!\n");
+ szWhatToSay = NULL;
+}
+
+CThingSayer::~CThingSayer(void)
+{
+ printf("CThingSayer::~CThingSayer: I cease to be\n");
+ if (szWhatToSay)
+ {
+ printf("CThingSayer::~CThingSayer: I will never say '%s' again\n",
+ szWhatToSay);
+ }
+ szWhatToSay = NULL;
+}
+
+void CThingSayer::Initialize(const char *czSayThis)
+{
+ printf("CThingSayer::Initialize: When told, I will say '%s'\n",
+ czSayThis);
+ szWhatToSay = czSayThis;
+}
+
+void CThingSayer::SayThing(void)
+{
+ printf("CThingSayer::SayThing: I am now saying '%s'\n", szWhatToSay);
+}
+
+/////////////////////////////////////////////////////////////////////////////
+// Public Functions
+/////////////////////////////////////////////////////////////////////////////
+
+int main(int argc, char **argv, char **envp)
+{
+ // We should see the message from constructor, CThingSayer::CThingSayer(),
+ // BEFORE we see the following messages. That is proof that the
+ // C++ static initializer is working
+
+ printf("main: Started. MyThingSayer should already exist\n");
+
+ // Tell MyThingSayer that "Hello, World!" is the string to be said
+
+ printf("main: Calling MyThingSayer.Initialize\n");;
+ MyThingSayer.Initialize("Hello, World!");
+
+ // Tell MyThingSayer to say the thing we told it to say
+
+ printf("main: Calling MyThingSayer.SayThing\n");;
+ MyThingSayer.SayThing();
+
+ // We are finished, return. We should see the message from the
+ // destructor, CThingSayer::~CThingSayer(), AFTER we see the following
+ // message. That is proof that the C++ static destructor logic
+ // is working
+
+ printf("main: Returning. MyThingSayer should be destroyed\n");;
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/hello++/hello++4.cpp b/nuttx/examples/nxflat/tests/hello++/hello++4.cpp
new file mode 100644
index 000000000..b6c0c488c
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello++/hello++4.cpp
@@ -0,0 +1,150 @@
+/////////////////////////////////////////////////////////////////////////////
+// examples/nxflat/tests/hello++/hello++4.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.
+//
+/////////////////////////////////////////////////////////////////////////////
+//
+// This is an excessively complex version of "Hello, World" design to
+// illustrate some basic properties of C++:
+//
+// - Building a C++ program
+// - Streams / statically linked libstdc++
+// - Static constructor and destructors (in main program only)
+//
+/////////////////////////////////////////////////////////////////////////////
+
+/////////////////////////////////////////////////////////////////////////////
+// Included Files
+/////////////////////////////////////////////////////////////////////////////
+
+#include <cstdio>
+#include <iostream>
+
+#ifndef NULL
+# define NULL ((void*)0L)
+#endif
+
+/////////////////////////////////////////////////////////////////////////////
+// Classes
+/////////////////////////////////////////////////////////////////////////////
+
+using namespace std;
+
+// A hello world sayer class
+
+class CThingSayer
+{
+ const char *szWhatToSay;
+public:
+ CThingSayer(void);
+ virtual ~CThingSayer(void);
+ virtual void Initialize(const char *czSayThis);
+ virtual void SayThing(void);
+};
+
+/////////////////////////////////////////////////////////////////////////////
+// Private Data
+/////////////////////////////////////////////////////////////////////////////
+
+// A static instance of the CThingSayer class. This instance MUST
+// be constructed by the system BEFORE the program is started at
+// main() and must be destructed by the system AFTER the main()
+// returns to the system
+
+static CThingSayer MyThingSayer;
+
+/////////////////////////////////////////////////////////////////////////////
+// Method Implementations
+/////////////////////////////////////////////////////////////////////////////
+
+// These are implementations of the methods of the CThingSayer class
+
+CThingSayer::CThingSayer(void)
+{
+ cout << "CThingSayer::CThingSayer: I am!" << endl;
+ szWhatToSay = (char*)NULL;
+}
+
+CThingSayer::~CThingSayer(void)
+{
+ cout << "CThingSayer::~CThingSayer: I cease to be" << endl;
+ if (szWhatToSay)
+ {
+ cout << "CThingSayer::~CThingSayer: I will never say '"
+ << szWhatToSay << "' again" << endl;
+ }
+ szWhatToSay = (char*)NULL;
+}
+
+void CThingSayer::Initialize(const char *czSayThis)
+{
+ cout << "CThingSayer::Initialize: When told, I will say '"
+ << czSayThis << "'" << endl;
+ szWhatToSay = czSayThis;
+}
+
+void CThingSayer::SayThing(void)
+{
+ cout << "CThingSayer::SayThing: I am now saying '"
+ << szWhatToSay << "'" << endl;
+}
+
+/////////////////////////////////////////////////////////////////////////////
+// Public Functions
+/////////////////////////////////////////////////////////////////////////////
+
+int main(int argc, char **argv, char **envp)
+{
+ // We should see the message from constructor, CThingSayer::CThingSayer(),
+ // BEFORE we see the following messages. That is proof that the
+ // C++ static initializer is working
+
+ cout << "main: Started" << endl;
+
+ // Tell MyThingSayer that "Hello, World!" is the string to be said
+
+ cout << "main: Calling MyThingSayer.Initialize" << endl;
+ MyThingSayer.Initialize("Hello, World!");
+
+ // Tell MyThingSayer to say the thing we told it to say
+
+ cout << "main: Calling MyThingSayer.SayThing" << endl;
+ MyThingSayer.SayThing();
+
+ // We are finished, return. We should see the message from the
+ // destructor, CThingSayer::~CThingSayer(), AFTER we see the following
+ // message. That is proof that the C++ static destructor logic
+ // is working
+
+ cout << "main: Returning" << endl;
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/hello/Makefile b/nuttx/examples/nxflat/tests/hello/Makefile
new file mode 100644
index 000000000..c8cbf6112
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello/Makefile
@@ -0,0 +1,58 @@
+############################################################################
+# examples/nxflat/tests/hello/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = hello
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
diff --git a/nuttx/examples/nxflat/tests/hello/hello.c b/nuttx/examples/nxflat/tests/hello/hello.c
new file mode 100644
index 000000000..d951d1565
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello/hello.c
@@ -0,0 +1,89 @@
+/****************************************************************************
+ * examples/nxflat/tests/hello/hello.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 <stdio.h>
+#include <stdlib.h>
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ int i;
+
+ /* Mandatory "Hello, world!" */
+
+ puts("Getting ready to say \"Hello, world\"\n");
+ printf("Hello, world!\n");
+ puts("It has been said.\n");
+
+ /* Print arguments */
+
+ printf("argc\t= %d\n", argc);
+ printf("argv\t= 0x%p\n", argv);
+
+ for (i = 0; i < argc; i++)
+ {
+ printf("argv[%d]\t= ", i);
+ if (argv[i])
+ {
+ printf("(0x%p) \"%s\"\n", argv[i], argv[i]);
+ }
+ else
+ {
+ printf("NULL?\n");
+ }
+ }
+
+ printf("argv[%d]\t= 0x%p\n", argc, argv[argc]);
+
+ /* Print environment variables */
+
+ printf("envp\t= 0x%p\n", envp);
+
+ for (i = 0; envp[i] != NULL; i++)
+ {
+ printf("envp[%d]\t= (0x%p) \"%s\"\n", i, envp[i], envp[i]);
+ }
+ printf("envp[%d]\t= 0x%p\n", i, envp[i]);
+
+ printf("Goodbye, world!\n");
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/hello/hello.o b/nuttx/examples/nxflat/tests/hello/hello.o
new file mode 100644
index 000000000..2ba7aa2ce
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/hello/hello.o
Binary files differ
diff --git a/nuttx/examples/nxflat/tests/longjmp/Makefile b/nuttx/examples/nxflat/tests/longjmp/Makefile
new file mode 100644
index 000000000..80b94d5f8
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/longjmp/Makefile
@@ -0,0 +1,58 @@
+############################################################################
+# examples/nxflat/tests/longjmp/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = longjmp
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
diff --git a/nuttx/examples/nxflat/tests/longjmp/longjmp.c b/nuttx/examples/nxflat/tests/longjmp/longjmp.c
new file mode 100644
index 000000000..a896fb13c
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/longjmp/longjmp.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ * examples/nxflat/tests/longjmp/longjmp.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 <stdio.h>
+#include <setjmp.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define MAIN_VAL 47
+#define FUNC_VAL 92
+#define LEAF_VAL 163
+
+#define FUNCTION_ARG MAIN_VAL
+#define LEAF_ARG (FUNCTION_ARG + FUNC_VAL)
+#define SETJMP_RETURN (LEAF_ARG + LEAF_VAL)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static jmp_buf env;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static int leaf(int *some_arg)
+{
+ int some_local_variable = *some_arg + LEAF_VAL;
+
+ printf("leaf: received %d\n", *some_arg);
+
+ if (*some_arg != LEAF_ARG)
+ printf("leaf: ERROR: expected %d\n", LEAF_ARG);
+
+ printf("leaf: Calling longjmp() with %d\n", some_local_variable);
+
+ longjmp(env, some_local_variable);
+}
+
+static int function(int some_arg)
+{
+ int some_local_variable = some_arg + FUNC_VAL;
+ int retval;
+
+ printf("function: received %d\n", some_arg);
+
+ if (some_arg != FUNCTION_ARG)
+ printf("function: ERROR: expected %d\n", FUNCTION_ARG);
+
+ printf("function: Calling leaf() with %d\n", some_local_variable);
+
+ retval = leaf(&some_local_variable);
+
+ printf("function: ERROR -- leaf returned!\n");
+ return retval;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ int value;
+
+ printf("main: Calling setjmp\n");
+ value = setjmp(env);
+ printf("main: setjmp returned %d\n", value);
+
+ if (value == 0)
+ {
+ printf("main: Normal setjmp return\n");
+ printf("main: Calling function with %d\n", MAIN_VAL);
+ function(MAIN_VAL);
+ printf("main: ERROR -- function returned!\n");
+ return 1;
+ }
+ else if (value != SETJMP_RETURN)
+ {
+ printf("main: ERROR: Expected %d\n", SETJMP_RETURN);
+ return 1;
+ }
+ else
+ {
+ printf("main: SUCCESS: setjmp return from longjmp call\n");
+ return 0;
+ }
+}
+
diff --git a/nuttx/examples/nxflat/tests/mutex/Makefile b/nuttx/examples/nxflat/tests/mutex/Makefile
new file mode 100644
index 000000000..6ba0b6736
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/mutex/Makefile
@@ -0,0 +1,58 @@
+############################################################################
+# examples/nxflat/tests/mutex/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = mutex
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
diff --git a/nuttx/examples/nxflat/tests/mutex/mutex.c b/nuttx/examples/nxflat/tests/mutex/mutex.c
new file mode 100644
index 000000000..5fdbdac5d
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/mutex/mutex.c
@@ -0,0 +1,135 @@
+/****************************************************************************
+ * examples/nxflat/tests/mutex/mutex.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 <stdio.h>
+#include <pthread.h>
+#include <signal.h>
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static pthread_mutex_t mut;
+static volatile int my_mutex = 0;
+static unsigned long nloops[2] = {0, 0};
+static unsigned long nerrors[2] = {0, 0};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static void thread_func(void *parameter)
+{
+ int my_id = (int)parameter;
+ int my_ndx = my_id - 1;
+ volatile int i;
+
+ for (;;)
+ {
+ if ((pthread_mutex_lock(&mut)) != 0)
+ {
+ printf("ERROR thread %d: pthread_mutex_lock failed\n", my_id);
+ }
+
+ if (my_mutex == 1)
+ {
+ printf("ERROR thread=%d: "
+ "my_mutex should be zero, instead my_mutex=%d\n",
+ my_id, my_mutex);
+ nerrors[my_ndx]++;
+ }
+
+ my_mutex = 1;
+ for (i = 0; i < 1000; i++);
+ my_mutex = 0;
+
+ if ((pthread_mutex_unlock(&mut)) != 0)
+ {
+ printf("ERROR thread %d: pthread_mutex_unlock failed\n", my_id);
+ }
+
+ nloops[my_ndx]++;
+ }
+}
+
+static void signal_handler(int signo)
+{
+ printf("\tThread1\tThread2\n");
+ printf("Loops\t%ld\t%ld\n", nloops[0], nloops[1]);
+ printf("Errors\t%ld\t%ld\n", nerrors[0], nerrors[1]);
+ exit(0);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ pthread_t thread1, thread2;
+
+ printf("Starting threads\n");
+
+ /* Set up to catch control-C interrupt */
+
+ (void)signal(SIGINT, signal_handler);
+
+ /* Initialize the mutex */
+
+ pthread_mutex_init(&mut, NULL);
+
+ /* Start two thread instances */
+
+ if ((pthread_create(&thread1, NULL, (void*)&thread_func, (void*)1)) != 0)
+ {
+ fprintf(stderr, "Error in thread#1 creation\n");
+ }
+
+ if ((pthread_create(&thread2, NULL, (void*)&thread_func, (void*)2)) != 0)
+ {
+ fprintf(stderr, "Error in thread#2 creation\n");
+ }
+
+ printf("Press control-C to terminate the example\n");
+
+ pthread_join(thread1, NULL);
+ pthread_join(thread2, NULL);
+ return 0;
+}
+
diff --git a/nuttx/examples/nxflat/tests/pthread/Makefile b/nuttx/examples/nxflat/tests/pthread/Makefile
new file mode 100644
index 000000000..eadba85ab
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/pthread/Makefile
@@ -0,0 +1,58 @@
+############################################################################
+# examples/nxflat/tests/pthread/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = pthread
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
diff --git a/nuttx/examples/nxflat/tests/pthread/pthread.c b/nuttx/examples/nxflat/tests/pthread/pthread.c
new file mode 100644
index 000000000..89b489302
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/pthread/pthread.c
@@ -0,0 +1,136 @@
+/****************************************************************************
+ * examples/nxflat/tests/pthread/pthread.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 <stdlib.h>
+#include <pthread.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define CHILD_ARG ((void*)0x12345678)
+#define CHILD_RET ((void*)0x87654321)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+enum exit_values_e
+{
+ TESTRESULT_SUCCESS = 0,
+ TESTRESULT_PTHREAD_ATTR_INIT_FAIL,
+ TESTRESULT_PTHREAD_CREATE_FAIL,
+ TESTRESULT_PTHREAD_JOIN_FAIL,
+ TESTRESULT_CHILD_ARG_FAIL,
+ TESTRESULT_CHILD_RETVAL_FAIL,
+};
+
+/****************************************************************************
+ * External Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static void *child_start_routine(void *arg)
+{
+ printf("CHILD: started with arg=%d\n", (int)arg);
+
+ if (arg != CHILD_ARG)
+ {
+ printf("CHILD: expected arg=%d\n", (int)CHILD_ARG);
+ return (void*)TESTRESULT_CHILD_ARG_FAIL;
+ }
+ sleep(2);
+
+ printf("CHILD: returning %d\n", (int)CHILD_RET);
+ pthread_exit(CHILD_RET);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ pthread_attr_t attr;
+ pthread_t thread;
+ void *retval;
+ int status;
+
+ puts("PARENT: started\n");
+
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("PARENT: pthread_attr_init() returned %d\n", status);
+ exit(TESTRESULT_PTHREAD_ATTR_INIT_FAIL);
+ }
+
+ printf("PARENT: calling pthread_start with arg=%d\n", (int)CHILD_ARG);
+ status = pthread_create(&thread, &attr, child_start_routine, CHILD_ARG);
+ if (status != 0)
+ {
+ printf("PARENT: pthread_create() returned %d\n", status);
+ exit(TESTRESULT_PTHREAD_CREATE_FAIL);
+ }
+
+ status = pthread_join(thread, &retval);
+ if (status != 0)
+ {
+ printf("PARENT pthread_join() returned %d\n", status);
+
+ exit(TESTRESULT_PTHREAD_JOIN_FAIL);
+ }
+
+ printf("PARENT child exitted with %d\n", (int)retval);
+ if (retval != CHILD_RET)
+ {
+ printf("PARENT child thread did not exit with %d\n", (int)CHILD_RET);
+ exit(TESTRESULT_CHILD_RETVAL_FAIL);
+ }
+
+ puts("PARENT returning success\n");
+ return TESTRESULT_SUCCESS;
+}
diff --git a/nuttx/examples/nxflat/tests/signal/Makefile b/nuttx/examples/nxflat/tests/signal/Makefile
new file mode 100644
index 000000000..e1632aa8f
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/signal/Makefile
@@ -0,0 +1,58 @@
+############################################################################
+# examples/nxflat/tests/signal/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = signal
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
diff --git a/nuttx/examples/nxflat/tests/signal/signal.c b/nuttx/examples/nxflat/tests/signal/signal.c
new file mode 100644
index 000000000..68d96702e
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/signal/signal.c
@@ -0,0 +1,296 @@
+/****************************************************************************
+ * examples/nxflat/tests/signal/signal.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 <stdio.h> /* For printf(), fprintf(), etc. */
+#include <signal.h> /* For signal(), sigaction(), etc. */
+#include <unistd.h> /* For usleep() */
+#include <errno.h> /* For errno */
+#include <sys/types.h> /* (needed by getpid()) */
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define USEC_PER_MSEC 1000
+#define MSEC_PER_SEC 1000
+#define USEC_PER_SEC (USEC_PER_MSEC * MSEC_PER_SEC)
+#define SHORT_DELAY (USEC_PER_SEC / 3)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int sigusr1_rcvd = 0;
+static int sigusr2_rcvd = 0;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigusr1_sighandler
+ ****************************************************************************/
+
+static void sigusr1_sighandler(int signo)
+{
+ printf("sigusr1_sighandler: Received SIGUSR1, signo=%d\n", signo);
+ sigusr1_rcvd = 1;
+}
+
+/****************************************************************************
+ * Name: sigusr2_sigaction
+ ***************************************************************************/
+
+#ifdef __USE_POSIX199309
+static void sigusr2_sigaction(int signo, siginfo_t *siginfo, void *arg)
+{
+ printf("sigusr2_sigaction: Received SIGUSR2, signo=%d siginfo=%p arg=%p\n",
+ signo, siginfo, arg);
+
+#ifdef HAVE_SIGQUEUE
+ if (siginfo)
+ {
+ printf(" si_signo = %d\n", siginfo->si_signo);
+ printf(" si_errno = %d\n", siginfo->si_errno);
+ printf(" si_code = %d\n", siginfo->si_code);
+ printf(" si_pid = %d\n", siginfo->si_pid);
+ printf(" si_uid = %d\n", siginfo->si_uid);
+ printf(" si_status = %d\n", siginfo->si_status);
+ printf(" si_utime = %ld\n", (long)siginfo->si_utime);
+ printf(" si_stime = %ld\n", (long)siginfo->si_stime);
+ printf(" si_value = %d\n", siginfo->si_value.sival_int);
+ printf(" si_int = %d\n", siginfo->si_int);
+ printf(" si_ptr = %p\n", siginfo->si_ptr);
+ printf(" si_addr = %p\n", siginfo->si_addr);
+ printf(" si_band = %ld\n", siginfo->si_band);
+ printf(" si_fd = %d\n", siginfo->si_fd);
+ }
+#endif
+ sigusr2_rcvd = 1;
+}
+#else
+static void sigusr2_sigaction(int signo)
+{
+ printf("sigusr2_sigaction: Received SIGUSR2, signo=%d\n", signo);
+ sigusr2_rcvd = 1;
+}
+
+#endif
+
+/****************************************************************************
+ * Name: sigusr2_sighandler
+ ****************************************************************************/
+
+static void sigusr2_sighandler(int signo)
+{
+ printf("sigusr2_sighandler: Received SIGUSR2, signo=%d\n", signo);
+ sigusr2_rcvd = 1;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: main
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ struct sigaction act;
+ struct sigaction oact;
+ void (*old_sigusr1_sighandler)(int signo);
+ void (*old_sigusr2_sighandler)(int signo);
+ pid_t mypid = getpid();
+#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE)
+ sigval_t sigval;
+#endif
+ int status;
+
+ printf("Setting up signal handlers from pid=%d\n", mypid);
+
+ /* Set up so that sigusr1_sighandler will respond to SIGUSR1 */
+
+ old_sigusr1_sighandler = signal(SIGUSR1, sigusr1_sighandler);
+ if (old_sigusr1_sighandler == SIG_ERR)
+ {
+ fprintf(stderr, "Failed to install SIGUSR1 handler, errno=%d\n",
+ errno);
+ exit(1);
+ }
+
+ printf("Old SIGUSR1 sighandler at %p\n", old_sigusr1_sighandler);
+ printf("New SIGUSR1 sighandler at %p\n", sigusr1_sighandler);
+
+ /* Set up so that sigusr2_sigaction will respond to SIGUSR2 */
+
+ memset(&act, 0, sizeof(struct sigaction));
+ act.sa_sigaction = sigusr2_sigaction;
+ act.sa_flags = SA_SIGINFO;
+
+ (void)sigemptyset(&act.sa_mask);
+
+ status = sigaction(SIGUSR2, &act, &oact);
+ if (status != 0)
+ {
+ fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n",
+ errno);
+ exit(2);
+ }
+
+ printf("Old SIGUSR2 sighandler at %p\n", oact.sa_handler);
+ printf("New SIGUSR2 sighandler at %p\n", sigusr2_sigaction);
+ printf("Raising SIGUSR1 from pid=%d\n", mypid);
+
+ fflush(stdout); usleep(SHORT_DELAY);
+
+ /* Send SIGUSR1 to ourselves via raise() */
+
+ status = raise(SIGUSR1);
+ if (status != 0)
+ {
+ fprintf(stderr, "Failed to raise SIGUSR1, errno=%d\n", errno);
+ exit(3);
+ }
+
+ usleep(SHORT_DELAY);
+ printf("SIGUSR1 raised from pid=%d\n", mypid);
+
+ /* Verify that we received SIGUSR1 */
+
+ if (sigusr1_rcvd == 0)
+ {
+ fprintf(stderr, "SIGUSR1 not received\n");
+ exit(4);
+ }
+ sigusr1_rcvd = 0;
+
+ /* Send SIGUSR2 to ourselves */
+
+ printf("Killing SIGUSR2 from pid=%d\n", mypid);
+ fflush(stdout); usleep(SHORT_DELAY);
+
+#if defined(__USE_POSIX199309) && defined(HAVE_SIGQUEUE)
+ /* Send SIGUSR2 to ourselves via sigqueue() */
+
+ sigval.sival_int = 87;
+ status = sigqueue(mypid, SIGUSR2, sigval);
+ if (status != 0)
+ {
+ fprintf(stderr, "Failed to queue SIGUSR2, errno=%d\n", errno);
+ exit(5);
+ }
+
+ usleep(SHORT_DELAY);
+ printf("SIGUSR2 queued from pid=%d, sigval=97\n", mypid);
+#else
+ /* Send SIGUSR2 to ourselves via kill() */
+
+ status = kill(mypid, SIGUSR2);
+ if (status != 0)
+ {
+ fprintf(stderr, "Failed to kill SIGUSR2, errno=%d\n", errno);
+ exit(5);
+ }
+
+ usleep(SHORT_DELAY);
+ printf("SIGUSR2 killed from pid=%d\n", mypid);
+#endif
+ /* Verify that SIGUSR2 was received */
+
+ if (sigusr2_rcvd == 0)
+ {
+ fprintf(stderr, "SIGUSR2 not received\n");
+ exit(6);
+ }
+ sigusr2_rcvd = 0;
+
+ /* Remove the sigusr2_sigaction handler and replace the SIGUSR2
+ * handler with sigusr2_sighandler.
+ */
+
+ printf("Resetting SIGUSR2 signal handler from pid=%d\n", mypid);
+
+ old_sigusr2_sighandler = signal(SIGUSR2, sigusr2_sighandler);
+ if (old_sigusr2_sighandler == SIG_ERR)
+ {
+ fprintf(stderr, "Failed to install SIGUSR2 handler, errno=%d\n",
+ errno);
+ exit(7);
+ }
+
+ printf("Old SIGUSR2 sighandler at %p\n", old_sigusr2_sighandler);
+ printf("New SIGUSR2 sighandler at %p\n", sigusr2_sighandler);
+
+ /* Verify that the handler that was removed was sigusr2_sigaction */
+
+ if ((void*)old_sigusr2_sighandler != (void*)sigusr2_sigaction)
+ {
+ fprintf(stderr,
+ "Old SIGUSR2 signhanlder (%p) is not sigusr2_sigation (%p)\n",
+ old_sigusr2_sighandler, sigusr2_sigaction);
+ exit(8);
+ }
+
+ /* Send SIGUSR2 to ourselves via kill() */
+
+ printf("Killing SIGUSR2 from pid=%d\n", mypid);
+ fflush(stdout); usleep(SHORT_DELAY);
+
+ status = kill(mypid, SIGUSR2);
+ if (status != 0)
+ {
+ fprintf(stderr, "Failed to kill SIGUSR2, errno=%d\n", errno);
+ exit(9);
+ }
+
+ usleep(SHORT_DELAY);
+ printf("SIGUSR2 killed from pid=%d\n", mypid);
+
+ /* Verify that SIGUSR2 was received */
+
+ if (sigusr2_rcvd == 0)
+ {
+ fprintf(stderr, "SIGUSR2 not received\n");
+ exit(10);
+ }
+ sigusr2_rcvd = 0;
+
+ return 0;
+}
diff --git a/nuttx/examples/nxflat/tests/task/Makefile b/nuttx/examples/nxflat/tests/task/Makefile
new file mode 100644
index 000000000..b71d135e5
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/task/Makefile
@@ -0,0 +1,59 @@
+############################################################################
+# examples/nxflat/tests/task/Makefile
+#
+# 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config # Current configuration
+-include $(TOPDIR)/Make.defs # Basic make info
+include ../Make.defs # NXFLAT make info
+
+BIN = task
+
+SRCS = $(BIN).c
+OBJS = $(SRCS:.c=.o)
+
+all: $(BIN)
+
+$(OBJS): %.o: %.c
+ $(NXFLATCC) -c $(NXFLATCFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ $(NXFLATLD) $(NXFLATLDFLAGS) -o $@ $(OBJS)
+
+clean:
+ rm -f $(BIN) *.o core
+
+install:
+ install -D $(BIN) $(ROMFS_DIR)/$(BIN)
+
+
diff --git a/nuttx/examples/nxflat/tests/task/task.c b/nuttx/examples/nxflat/tests/task/task.c
new file mode 100644
index 000000000..28ec88d5f
--- /dev/null
+++ b/nuttx/examples/nxflat/tests/task/task.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ * examples/nxflat/tests/task/parent.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 <sys/types.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <sched.h>
+#include <semaphore.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static char child_arg[] = "Hello from your parent!";
+static sem_t g_sem;
+
+/****************************************************************************
+ * Privite Functions
+ ****************************************************************************/
+
+int child_task(int argc, char **argv, char **envp)
+{
+ printf("Child: execv was successful!\n");
+ printf("Child: argc=%d\n", argc);
+
+ if (argc != 2)
+ {
+ printf("Child: expected argc to be 2\n");
+ printf("Child: Exit-ting with status=2\n");
+ exit(2);
+ }
+
+ printf("Child: argv[0]=\"%s\"\n", argv[0]);
+
+ if (strcmp(argv[0], my_path) != 0)
+ {
+ printf("Child: expected argv[0] to be \"%s\"\n", my_path);
+ printf("Child: Exit-ting with status=3\n");
+ exit(3);
+ }
+
+ printf("Child: argv[1]=\"%s\"\n", argv[1]);
+
+ if (strcmp(argv[1], child_arg) != 0)
+ {
+ printf("Child: expected argv[1] to be \"%s\"\n", parent_arg);
+ printf("Child: Exit-ting with status=4\n");
+ exit(4);
+ }
+
+ printf("Child: Exit-ting with status=0\n");
+ sem_post(&g_sem);
+ return 0;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int main(int argc, char **argv, char **envp)
+{
+ pid_t parent_pid = getpid();
+ char *child_argv[2];
+ int ret;
+
+ printf("Parent: Started, pid=%d\n", parent_pid);
+
+ sem_init(&g_sem, 0, 0);
+
+ printf("Parent: Calling task_create()\n");
+
+ child_argv[0] = child_arg;
+ child_argv[1] = 0;
+ ret = task_create("child", 50, 512, child_task, &child_arg);
+ if (ret != 0)
+ {
+ printf("Parent: task_create failed: %d\n", errno);
+ }
+
+ printf("Parent: Waiting for child\n");
+ sem_wait(&g_sem);
+ printf("Parent: Exiting\n");
+ sem_destroy(&g_sem);
+ return 0;
+}
+
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index b4e17f658..a51227680 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -1,7 +1,7 @@
/****************************************************************************
* nuttx/arch.h
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -353,10 +353,9 @@ EXTERN void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver);
* Name: up_allocate_heap
*
* Description:
- * The heap may be statically allocated by
- * defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
- * are not defined, then this function will be called to
- * dynamically set aside the heap region.
+ * The heap may be statically allocated by defining CONFIG_HEAP_BASE and
+ * CONFIG_HEAP_SIZE. If these are not defined, then this function will be
+ * called to dynamically set aside the heap region.
*
****************************************************************************/
@@ -365,6 +364,21 @@ EXTERN void up_allocate_heap(FAR void **heap_start, size_t *heap_size);
#endif
/****************************************************************************
+ * Name: up_setpicbase, up_getpicbase
+ *
+ * Description:
+ * It NXFLAT external modules are supported, then these macros must
+ * defined to (1) get or get the PIC base register value. These must
+ * be done with in-line assembly.
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_NXFLAT
+# define up_setpicbase(picbase)
+# define up_getpicbase()
+#endif
+
+/****************************************************************************
* Name: up_interrupt_context
*
* Description:
diff --git a/nuttx/include/nuttx/nxflat.h b/nuttx/include/nuttx/nxflat.h
new file mode 100644
index 000000000..e3d19e1de
--- /dev/null
+++ b/nuttx/include/nuttx/nxflat.h
@@ -0,0 +1,232 @@
+/****************************************************************************
+ * include/nuttx/nxflat.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 __INCLUDE_NUTTX_NXFLAT_H
+#define __INCLUDE_NUTTX_NXFLAT_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nxflat.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* When DSpace is allocated, space is reserved at the beginning to
+ * hold ldso-specific information. The following structure defines
+ * that information. This structure can be referenced at run-time
+ * using a negative offset from the PID base address.
+ */
+
+struct nxflat_ldso_info
+{
+ uint32 dspace; /* The beginning of ldso DSpace */
+};
+#define NXFLAT_DATA_OFFSET sizeof(struct nxflat_ldso_info)
+
+/* An "opaque" handle that describes the xflat binary to be loaded. */
+
+typedef void *bin_handle_t;
+
+/* An "opaque" handle that describes an open file */
+
+typedef void *file_handle_t;
+
+/* This is a call table that is used by the xflat library to call
+ * obtain system information. The use of this call table allows the
+ * library to be designed in a platform independent way.
+ */
+
+struct nxflat_vtbl_s
+{
+ /* Allocators. These imports keep the xflat library independent of
+ * the memory mapping and memory management facilities of the host
+ * system.
+ *
+ * map/unmap will map/unmap a program file onto an address;
+ * alloc/free will allocate/deallocate program memory.
+ */
+
+ void *(*map)(file_handle_t file_handle, uint32 nbytes);
+ void (*unmap)(void *address, uint32 nbytes);
+ void *(*alloc)(uint32 nbytes);
+ void (*free)(void *address, uint32 nbytes);
+
+ /* File access utilities. These imports keep the xflat libary independent
+ * of the host system's file system.
+ */
+
+ file_handle_t (*open)(bin_handle_t bin_handle, const char *filename);
+ int (*read)(bin_handle_t bin_handle, file_handle_t file_handle,
+ char *dest, uint32 nbytes,
+ uint32 fpos);
+ void (*close)(file_handle_t file_handle);
+};
+
+/* This struct provides a desciption of the currently loaded
+ * instantiation of an xflat binary.
+ */
+
+struct nxflat_loadinfo_s
+{
+ /* Instruction Space (ISpace): This region contains the flat
+ * file header plus everything from the text section. Ideally,
+ * will have only one text section instance in the system.
+ */
+
+ uint32 ispace; /* Address where hdr/text is loaded */
+ /* 1st: struct nxflat_hdr_s */
+ /* 2nd: text section */
+ uint32 entry_offset; /* Offset from ispace to entry point */
+ uint32 ispace_size; /* Size of ispace. */
+
+ /* Data Space (DSpace): This region contains all information that
+ * in referenced as data. There will be a unique instance of
+ * DSpace for each instance of a process.
+ */
+
+ uint32 dspace; /* Address where data/bss/stack/etc. is loaded */
+ /* 1st: Memory set aside for ldso */
+ uint32 data_size; /* 2nd: Size of data segment in dspace */
+ uint32 bss_size; /* 3rd: Size of bss segment in dspace */
+ /* 4th: Potential padding from relocs/mm/etc. */
+ uint32 stack_size; /* 5th: Size of stack in dspace */
+ uint32 dspace_size; /* Size of dspace (may be large than parts) */
+
+ /* Program arguments (addresses in dspace) */
+
+ uint32 arg_start; /* Beginning of program arguments */
+ uint32 env_start; /* End of argments, beginning of env */
+ uint32 env_end; /* End(+4) of env */
+
+ /* This is temporary memory where relocation records will be loaded. */
+
+ uint32 reloc_start; /* Start of array of struct flat_reloc */
+ uint32 reloc_count; /* Number of elements in reloc array */
+
+ /* These are hooks stored by nxflat_init for subsequent use.
+ * These constitute all points of contact between the flat
+ * library and the rest of the world. These allows the flat
+ * library to opperate in a variey of contexts without change.
+ */
+
+ bin_handle_t bin_handle; /* Like a "this" pointer. Retains
+ * calling context information in callbacks */
+ file_handle_t file_handle; /* Describes an open file */
+
+ const struct nxflat_hdr_s *header; /* A reference to the flat file header */
+ const struct nxflat_vtbl_s *vtbl; /* Systam callback vtbl */
+
+ /* At most one memory allocation will be made. These describe that
+ * allocation.
+ */
+
+ uint32 alloc_start; /* Start of the allocation */
+ uint32 alloc_size; /* Size of the allocation */
+};
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Given the header from a possible xFLT executable, verify that it
+ * is an NXFLAT executable.
+ */
+
+EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
+
+/* This function is called to configure xflatlib to process an xFLT
+ * program binary. Upon return, the controlling logic has the opportunity
+ * to adjust the contents of the load_info structure.
+ */
+
+EXTERN int nxflat_init(bin_handle_t bin_handle, file_handle_t file_handle,
+ const struct nxflat_hdr_s *header,
+ const struct nxflat_vtbl_s *vtbl,
+ struct nxflat_loadinfo_s *load_info);
+
+/* This function unloads the object from memory. This essentially
+ * undoes the actions of nxflat_load.
+ */
+
+EXTERN int nxflat_unload(struct nxflat_loadinfo_s *load_info);
+
+/* Releases any resources committed by nxflat_init(). This essentially
+ * undoes the actions of nxflat_init or nxflat_init_interpreter. */
+
+EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *load_info);
+
+/* Loads the binary specified by nxflat_init into memory,
+ * Completes all relocations, and clears BSS.
+ */
+
+EXTERN int nxflat_load(struct nxflat_loadinfo_s *load_info);
+
+/* Adjust stack size to include argc, envc, xFLT internal usage and
+ * system internal usage. */
+
+EXTERN void nxflat_adjuststacksize(struct nxflat_loadinfo_s *load_info,
+ int argc, int envc, int system_usage);
+
+/* Initialize stack frame for execution */
+
+EXTERN uint32 nxflat_initstack(struct nxflat_loadinfo_s *prog_load_info,
+ struct nxflat_loadinfo_s *lib_load_info,
+ int argc, int envc, char *p);
+
+/* Releases any resources committed by nxflat_init(). */
+
+EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *load_info);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_NXFLAT_H */
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 95f533c20..35821b597 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -135,6 +135,15 @@ int sched_releasetcb(FAR _TCB *tcb)
}
#endif
+ /* Delete the tasks's allocated DSpace region (external modules only) */
+
+#ifdef CONFIG_NXFLAT
+ if (tcb->picbase)
+ {
+ sched_free(tcb->picbase);
+ }
+#endif
+
/* Release command line arguments that were allocated
* for task start/re-start.
*/
diff --git a/nuttx/sched/wd_internal.h b/nuttx/sched/wd_internal.h
index d603e2973..581f0c5da 100644
--- a/nuttx/sched/wd_internal.h
+++ b/nuttx/sched/wd_internal.h
@@ -65,6 +65,9 @@ struct wdog_s
{
FAR struct wdog_s *next; /* Support for singly linked lists. */
wdentry_t func; /* Function to execute when delay expires */
+#ifdef CONFIG_NXFLAT
+ FAR void *picbase; /* PIC base address */
+#endif
int lag; /* Timer associated with the delay */
boolean active; /* TRUE if the watchdog is actively timing */
ubyte argc; /* The number of parameters to pass */
diff --git a/nuttx/sched/wd_start.c b/nuttx/sched/wd_start.c
index ec50b94cd..d27f066f5 100644
--- a/nuttx/sched/wd_start.c
+++ b/nuttx/sched/wd_start.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/wd_start.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -38,11 +38,15 @@
****************************************************************************/
#include <sys/types.h>
+
#include <stdarg.h>
#include <wdog.h>
#include <unistd.h>
#include <sched.h>
#include <errno.h>
+
+#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "wd_internal.h"
@@ -154,6 +158,9 @@ STATUS wd_start(WDOG_ID wdog, int delay, wdentry_t wdentry, int argc, ...)
/* Save the data in the watchdog structure */
wdog->func = wdentry; /* Function to execute when delay expires */
+#ifdef CONFIG_NXFLAT
+ wdog->picbase = up_getpicbase();
+#endif
wdog->argc = argc;
va_start(ap, argc);
@@ -322,7 +329,7 @@ void wd_timer(void)
((FAR wdog_t*)g_wdactivelist.head)->lag += wdog->lag;
}
- /* Indicate that the watchdog is no longer activer. */
+ /* Indicate that the watchdog is no longer active. */
wdog->active = FALSE;
@@ -334,6 +341,7 @@ void wd_timer(void)
/* Execute the watchdog function */
+ up_setpicbase(wdog->picbase);
switch (wdog->argc)
{
default: