summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/README.html2
-rw-r--r--nuttx/README.txt2
-rw-r--r--nuttx/arch/z80/src/common/up_doirq.c1
-rw-r--r--nuttx/arch/z80/src/common/up_initialize.c8
-rw-r--r--nuttx/arch/z80/src/common/up_internal.h6
-rw-r--r--nuttx/arch/z80/src/z180/Kconfig13
-rw-r--r--nuttx/arch/z80/src/z180/switch.h103
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.c71
-rw-r--r--nuttx/arch/z80/src/z180/z180_mmu.h6
-rw-r--r--nuttx/arch/z80/src/z180/z180_registerdump.c2
-rw-r--r--nuttx/configs/Kconfig28
-rw-r--r--nuttx/configs/README.txt27
-rw-r--r--nuttx/configs/p112/Kconfig4
-rw-r--r--nuttx/configs/p112/README.txt26
-rw-r--r--nuttx/configs/p112/include/board.h60
-rw-r--r--nuttx/configs/p112/ostest/Make.defs167
-rw-r--r--nuttx/configs/p112/ostest/defconfig530
-rw-r--r--nuttx/configs/p112/ostest/setenv.bat50
-rw-r--r--nuttx/configs/p112/scripts/setenv.bat50
-rwxr-xr-xnuttx/configs/p112/scripts/setenv.sh66
-rw-r--r--nuttx/configs/p112/src/Makefile77
-rw-r--r--nuttx/configs/z80sim/src/Makefile2
-rw-r--r--nuttx/include/nuttx/arch.h26
-rw-r--r--nuttx/sched/Kconfig8
-rw-r--r--nuttx/sched/env_internal.h2
-rw-r--r--nuttx/sched/pthread_create.c63
-rw-r--r--nuttx/sched/sched_releasetcb.c6
28 files changed, 1332 insertions, 76 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 7e3b2a43f..11e8b200b 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3780,4 +3780,6 @@
* include/nuttx/arch.h: Add address environment control interfaces (for use
with CPUs the provide MCUs and support process-like address environments).
* arch/z80/src/z180/z180_mmu.*: Add MMU support for z180 tasks.
+ * configs/p112: Add very basic board support and an examples/ostest
+ configuration for the venerable P112 board.
diff --git a/nuttx/Documentation/README.html b/nuttx/Documentation/README.html
index 7dd23ac3d..281b738b8 100644
--- a/nuttx/Documentation/README.html
+++ b/nuttx/Documentation/README.html
@@ -150,6 +150,8 @@
| | | |- <a href="http://svn.code.sf.net/p/nuttx/code/trunk/nuttx/configs/olimex-strp711/include/README.txt">include/README.txt</a>
| | | |- <a href="http://svn.code.sf.net/p/nuttx/code/trunk/nuttx/configs/olimex-strp711/src/README.txt">src/README.txt</a>
| | | `- <a href="http://svn.code.sf.net/p/nuttx/code/trunk/nuttx/configs/olimex-strp711/README.txt"><b><i>README.txt</i></b></a>
+ | | |- p112/
+ | | | `- <a href="http://svn.code.sf.net/p/nuttx/code/trunk/nuttx/configs/p112/README.txt"><b><i>README.txt</i></b></a>
| | |- pcblogic-pic32mx/
| | | `- <a href="http://svn.code.sf.net/p/nuttx/code/trunk/nuttx/configs/pcblogic-pic32mx/README.txt"><b><i>README.txt</i></b></a>
| | |- pic32-starterkit/
diff --git a/nuttx/README.txt b/nuttx/README.txt
index 55f42339c..9ad499d3f 100644
--- a/nuttx/README.txt
+++ b/nuttx/README.txt
@@ -849,6 +849,8 @@ nuttx
| | |- include/README.txt
| | |- src/README.txt
| | `- README.txt
+ | |- p112/
+ | | `- README.txt
| |- pcblogic-pic32mx/
| | `- README.txt
| |- pic32-starterkit/
diff --git a/nuttx/arch/z80/src/common/up_doirq.c b/nuttx/arch/z80/src/common/up_doirq.c
index a4bb830fd..4b57f8f7b 100644
--- a/nuttx/arch/z80/src/common/up_doirq.c
+++ b/nuttx/arch/z80/src/common/up_doirq.c
@@ -102,6 +102,7 @@ FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs)
IRQ_LEAVE(irq);
}
+
up_ledoff(LED_INIRQ);
return regs;
#endif
diff --git a/nuttx/arch/z80/src/common/up_initialize.c b/nuttx/arch/z80/src/common/up_initialize.c
index 1ae927831..e0b46f7ec 100644
--- a/nuttx/arch/z80/src/common/up_initialize.c
+++ b/nuttx/arch/z80/src/common/up_initialize.c
@@ -145,6 +145,14 @@ void up_initialize(void)
up_timerinit();
#endif
+ /* Initialize the CPU for those that use it (only for the Z180). This
+ * needs to be done before any tasks are created).
+ */
+
+#if CONFIG_ADDRENV
+ (void)up_mmuinit();
+#endif
+
/* Register devices */
#if CONFIG_NFILE_DESCRIPTORS > 0
diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h
index 1989f99d0..3adb02a39 100644
--- a/nuttx/arch/z80/src/common/up_internal.h
+++ b/nuttx/arch/z80/src/common/up_internal.h
@@ -117,6 +117,12 @@ EXTERN FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs);
EXTERN void up_sigdeliver(void);
+/* Defined in CPU-specific logic (only for Z180) */
+
+#if CONFIG_ADDRENV
+int up_mmuinit(void);
+#endif
+
/* Defined in up_allocateheap.c */
#if CONFIG_MM_REGIONS > 1
diff --git a/nuttx/arch/z80/src/z180/Kconfig b/nuttx/arch/z80/src/z180/Kconfig
index 58abbd6f2..3082e69cb 100644
--- a/nuttx/arch/z80/src/z180/Kconfig
+++ b/nuttx/arch/z80/src/z180/Kconfig
@@ -137,4 +137,17 @@ config ARCH_HAVEHEAD
Use a board-specific version of the "head" file in the
configs/<board-name>/src directory
+menu "Z180 Peripheral Support"
+
+config Z180_UART0
+ bool "UART0"
+ default n
+ select ARCH_HAVE_UART0
+
+config Z180_UART1
+ bool "UART1"
+ default n
+ select ARCH_HAVE_UART1
+
+endmenu
endif
diff --git a/nuttx/arch/z80/src/z180/switch.h b/nuttx/arch/z80/src/z180/switch.h
index 38054e4b8..aa33bd1e1 100644
--- a/nuttx/arch/z80/src/z180/switch.h
+++ b/nuttx/arch/z80/src/z180/switch.h
@@ -44,6 +44,7 @@
#include <nuttx/sched.h>
#include <nuttx/arch.h>
+#include "z180_iomap.h"
#include "up_internal.h"
/************************************************************************************
@@ -58,56 +59,116 @@
/* Initialize the IRQ state */
-#define INIT_IRQCONTEXT() current_regs = NULL
+#define INIT_IRQCONTEXT() \
+ current_regs = NULL
/* IN_INTERRUPT returns true if the system is currently operating in the interrupt
* context. IN_INTERRUPT is the inline equivalent of up_interrupt_context().
*/
-#define IN_INTERRUPT() (current_regs != NULL)
+#define IN_INTERRUPT() \
+ (current_regs != NULL)
-/* The following macro is used when the system enters interrupt handling logic */
+/* The following macro declares the variables need by IRQ_ENTER and IRQ_LEAVE.
+ * These variables are used to support nested interrupts.
+ *
+ * - savestate holds the previous value of current_state.
+ * - savecpr holds the previous value of current_cpr.
+ *
+ * TODO: I think this logic is bad... I do not thing that this will really
+ * handle nested interrupts correctly. What if we are nested and then a
+ * context switch occurs? current_regs will not be updated correctly!
+ */
#define DECL_SAVESTATE() \
- FAR chipreg_t *savestate
+ FAR chipreg_t *savestate; \
+ uint8_t savecbr;
-#define IRQ_ENTER(irq, regs) \
- do { \
- savestate = (FAR chipreg_t *)current_regs; \
- current_regs = (regs); \
- } while (0)
+/* The following macro is used when the system enters interrupt handling logic.
+ * The entry values of current_regs and current_cbr and stored in local variables.
+ * Then current_regs and current_cbr are set to the values of the interrupted
+ * task.
+ */
-/* The following macro is used when the system exits interrupt handling logic */
+#define IRQ_ENTER(irq, regs) \
+ do \
+ { \
+ savestate = (FAR chipreg_t *)current_regs; \
+ savecbr = current_cbr; \
+ current_regs = (regs); \
+ current_cbr = inp(Z180_MMU_CBR); \
+ } \
+ while (0)
+
+/* The following macro is used when the system exits interrupt handling logic.
+ * The value of current_regs is restored. If we are not processing a nested
+ * interrupt (meaning that we going to return to the user task), then also
+ * set the MMU's CBR register.
+ */
-#define IRQ_LEAVE(irq) current_regs = savestate
+#define IRQ_LEAVE(irq) \
+ do \
+ { \
+ current_regs = savestate; \
+ if (current_regs) \
+ { \
+ current_cbr = savecbr; \
+ } \
+ else \
+ { \
+ outp(Z180_MMU_CBR, savecbr); \
+ } \
+ }
/* The following macro is used to sample the interrupt state (as a opaque handle) */
-#define IRQ_STATE() (current_regs)
+#define IRQ_STATE() \
+ (current_regs)
/* Save the current IRQ context in the specified TCB */
-#define SAVE_IRQCONTEXT(tcb) z180_copystate((tcb)->xcp.regs, (FAR chipreg_t*)current_regs)
+#define SAVE_IRQCONTEXT(tcb) \
+ z180_copystate((tcb)->xcp.regs, (FAR chipreg_t*)current_regs)
/* Set the current IRQ context to the state specified in the TCB */
-#define SET_IRQCONTEXT(tcb) z180_copystate((FAR chipreg_t*)current_regs, (tcb)->xcp.regs)
+#define SET_IRQCONTEXT(tcb) \
+ do \
+ { \
+ if ((tcb)->xcp.cbr.cbr) \
+ { \
+ current_cbr = (tcb)->xcp.cbr->cbr); \
+ } \
+ z180_copystate((FAR chipreg_t*)current_regs, (tcb)->xcp.regs); \
+ } \
+ while (0)
/* Save the user context in the specified TCB. User context saves can be simpler
* because only those registers normally saved in a C called need be stored.
*/
-#define SAVE_USERCONTEXT(tcb) z180_saveusercontext((tcb)->xcp.regs)
+#define SAVE_USERCONTEXT(tcb) \
+ z180_saveusercontext((tcb)->xcp.regs)
/* Restore the full context -- either a simple user state save or the full,
* IRQ state save.
*/
-#define RESTORE_USERCONTEXT(tcb) z180_restoreusercontext((tcb)->xcp.regs)
+#define RESTORE_USERCONTEXT(tcb) \
+ do \
+ { \
+ if ((tcb)->xcp.cbr.cbr) \
+ { \
+ outp(Z180_MMU_CBR, (tcb)->xcp.cbr->cbr); \
+ } \
+ z180_restoreusercontext((tcb)->xcp.regs); \
+ } \
+ while (0)
/* Dump the current machine registers */
-#define _REGISTER_DUMP() z180_registerdump()
+#define _REGISTER_DUMP() \
+ z180_registerdump()
/************************************************************************************
* Public Types
@@ -123,6 +184,14 @@
*/
extern volatile chipreg_t *current_regs;
+
+/* This holds the value of the MMU's CBR register. This value is set to the
+ * interrupted tasks's CBR on interrupt entry, changed to the new task's CBR if
+ * an interrrupt level context switch occurs, and restored on interrupt exit. In
+ * this way, the CBR is always correct on interrupt exit.
+ */
+
+extern uint8_t current_cbr;
#endif
/************************************************************************************
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.c b/nuttx/arch/z80/src/z180/z180_mmu.c
index c71f59755..076d91bef 100644
--- a/nuttx/arch/z80/src/z180/z180_mmu.c
+++ b/nuttx/arch/z80/src/z180/z180_mmu.c
@@ -120,15 +120,21 @@ static FAR struct z180_cbr_s *z180_mmu_findcbr(void)
* called very early in the boot process to get the basic operating
* memory configuration correct. This function does *not* perform all
* necessray MMU initialization... only the basics needed at power-up.
- * z180_mmu_init() must be called later to complete the entire MMU
+ * up_mmuinit() must be called later to complete the entire MMU
* initialization.
*
****************************************************************************/
void z180_mmu_lowinit(void) __naked
{
+ /* Set the CBAR register to set up the virtual address of the Bank Area and
+ * Common Area 1. Set the BBR register to set up the physical mapping for
+ * the Bank Area (the physical mapping for Common Area 1 will not be done
+ * until the first task is started.
+ */
+
__asm
- ld c, #Z180_MMU_CBR ; port
+ ld c, #Z180_MMU_CBAR ; port
ld a, #Z180_CBAR_VALUE ; value
out (c), a
@@ -139,15 +145,15 @@ void z180_mmu_lowinit(void) __naked
}
/****************************************************************************
- * Name: z180_mmu_init
+ * Name: up_mmuinit
*
* Description:
- * Perform higher level initializatin of the MMU and physical memory
+ * Perform higher level initialization of the MMU and physical memory
* memory management logic.
*
****************************************************************************/
-int z180_mmu_init(void)
+int up_mmuinit(void)
{
/* Here we use the granule allocator as a page allocator. We lie and
* say that 1 page is 1 byte.
@@ -257,7 +263,7 @@ errout_with_irq:
}
/****************************************************************************
- * Name: up_addrenv_clone
+ * Name: up_addrenv_share
*
* Description:
* This function is called from the core scheduler logic when a thread
@@ -274,8 +280,7 @@ errout_with_irq:
*
****************************************************************************/
-#ifdef CONFIG_ADDRENV
-int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
+int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb)
{
irqstate_t flags;
@@ -299,7 +304,6 @@ int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
irqrestore(flags);
return OK;
}
-#endif
/****************************************************************************
* Name: up_addrenv_instantiate
@@ -316,35 +320,55 @@ int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb)
* be instantiated.
*
* Returned Value:
- * Zero (OK) on success; a negated errno value on failure.
+ * A handle that may be used with up_addrenv_restore() to restore the
+ * address environment before up_addrenv_instantiate() was called.
*
****************************************************************************/
-#ifdef CONFIG_ADDRENV
-int up_addrenv_instantiate(FAR _TCB *tcb)
+FAR void *up_addrenv_instantiate(FAR _TCB *tcb)
{
+ uint8_t oldcbr;
irqstate_t flags;
- /* Check if the task has an address environment. */
+ /* Get the current CBR value from the CBR register */
flags = irqsave();
+ cbr = inp(Z180_MMU_CBR);
+
+ /* Check if the task has an address environment. */
+
if (tcb->xcp.cbr)
{
- /* Yes... write the CBR value into CBR register */
+ /* Yes.. Write the new CBR value into CBR register */
outp(Z180_MMU_CBR, tcb->xcp.cbr.cbr);
- /* Clone the CBR by incrementing the reference counting and saving a
- * copy in the child thread's TCB.
- */
-
- ptcb->xcp.cbr.crefs++;
- ctcb->xcp.cbr = ptcb->xcp.cbr;
}
irqrestore(flags);
- return OK;
+ return (FAR void *)cbr;
+}
+
+/****************************************************************************
+ * Name: up_addrenv_restore
+ *
+ * Description:
+ * Restore an address environment using a handle previously returned by
+ * up_addrenv_instantiate().
+ *
+ * Input Parameters:
+ * handle - A handle previously returned by up_addrenv_instantiate.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int up_addrenv_restore(FAR void *handle)
+{
+ /* Restore the CBR value */
+
+ outp(Z180_MMU_CBR, (uint8_t)handle);
}
-#endif
/****************************************************************************
* Name: up_addrenv_release
@@ -364,7 +388,6 @@ int up_addrenv_instantiate(FAR _TCB *tcb)
*
****************************************************************************/
-#ifdef CONFIG_ADDRENV
int up_addrenv_release(FAR _TCB *tcb)
{
FAR struct z180_cbr_s *cbr;
@@ -401,5 +424,3 @@ int up_addrenv_release(FAR _TCB *tcb)
irqrestore(flags);
return OK;
}
-#endif
-
diff --git a/nuttx/arch/z80/src/z180/z180_mmu.h b/nuttx/arch/z80/src/z180/z180_mmu.h
index 1a4c03406..74463427a 100644
--- a/nuttx/arch/z80/src/z180/z180_mmu.h
+++ b/nuttx/arch/z80/src/z180/z180_mmu.h
@@ -128,7 +128,7 @@
* called very early in the boot process to get the basic operating
* memory configuration correct. This function does *not* perform all
* necessray MMU initialization... only the basics needed at power-up.
- * z180_mmu_init() must be called later to complete the entire MMU
+ * up_mmuinit() must be called later to complete the entire MMU
* initialization.
*
****************************************************************************/
@@ -136,7 +136,7 @@
void z180_mmu_lowinit(void) __naked;
/****************************************************************************
- * Name: z180_mmu_init
+ * Name: up_mmuinit
*
* Description:
* Perform higher level initializatin of the MMU and physical memory
@@ -144,6 +144,6 @@ void z180_mmu_lowinit(void) __naked;
*
****************************************************************************/
-void z180_mmu_init(void);
+void up_mmuinit(void);
#endif /* __ARCH_Z80_SRC_Z180_Z180_MMU_H */
diff --git a/nuttx/arch/z80/src/z180/z180_registerdump.c b/nuttx/arch/z80/src/z180/z180_registerdump.c
index 2ccfc2f99..65ae791db 100644
--- a/nuttx/arch/z80/src/z180/z180_registerdump.c
+++ b/nuttx/arch/z80/src/z180/z180_registerdump.c
@@ -86,6 +86,8 @@ static void z180_registerdump(void)
current_regs[XCPT_IX], current_regs[XCPT_IY]);
lldbg("SP: %04x PC: %04x\n"
current_regs[XCPT_SP], current_regs[XCPT_PC]);
+ lldbg("CBAR: %02x BBR: %02x CBR: %02x\n"
+ inp(Z180_MMU_CBAR), inp(Z180_MMU_BBR), inp(Z180_MMU_CBR));
}
}
#endif
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index 50e1cc600..bba1444c4 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -346,6 +346,33 @@ config ARCH_BOARD_OLIMEX_STM32P107
Linux or Cygwin. See the http://www.olimex.com for further information. This
board features the STMicro STM32F107VC MCU
+config ARCH_BOARD_P112
+ bool "P112 Z180-based platform"
+ depends on ARCH_CHIP_Z8018216FSG
+ ---help---
+ The P112 is notable because it was the first of the hobbyist single board
+ computers to reach the production stage. The P112 hobbyist computers
+ were relatively widespread and inspired other hobbyist centered home brew
+ computing projects such as N8VEM home brew computing project. The P112
+ project still maintains many devoted enthusiasts and has an online
+ repository of software and other information.
+
+ The P112 computer originated as a commercial product of "D-X Designs Pty
+ Ltd" of Australia. They describe the computer as "The P112 is a stand-alone
+ 8-bit CPU board. Typically running CP/M (tm) or a similar operating system,
+ it provides a Z80182 (Z-80 upgrade) CPU with up to 1MB of memory, serial,
+ parallel and diskette IO, and realtime clock, in a 3.5-inch drive form factor.
+ Powered solely from 5V, it draws 150mA (nominal: not including disk drives)
+ with a 16MHz CPU clock. Clock speeds up to 24.576MHz are possible."
+
+ The P112 board was last available new in 1996 by Dave Brooks. In late 2004
+ on the Usenet Newsgroup comp.os.cpm, talk about making another run of P112
+ boards was discussed. David Griffith decided to produce additional P112 kits
+ with Dave Brooks blessing and the assistance of others. In addition Terry
+ Gulczynski makes additional P112 derivative hobbyist home brew computers.
+ Hal Bower was very active in the mid 1990's on the P112 project and ported
+ the "Banked/Portable BIOS".
+
config ARCH_BOARD_PCBLOGICPIC32MX
bool "PIC32MX board from PCB Logic Design Co"
depends on ARCH_CHIP_PIC32MX460F512L
@@ -647,6 +674,7 @@ config ARCH_BOARD
default "olimex-lpc2378" if ARCH_BOARD_OLIMEXLPC2378
default "olimex-stm32-p107" if ARCH_BOARD_OLIMEX_STM32P107
default "olimex-strp711" if ARCH_BOARD_OLIMEX_STRP711
+ default "p112" if ARCH_BOARD_P112
default "pcblogic-pic32mx" if ARCH_BOARD_PCBLOGICPIC32MX
default "pic32-starterkit" if ARCH_BOARD_PIC32_STARTERKIT
default "pic32mx7mmb" if ARCH_BOARD_PIC32_PIC32MX7MMB
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 23f5e4380..e7f73f945 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -1780,14 +1780,36 @@ configs/pcblogic-pic32mx
STATUS: Code complete but testing has been stalled due to tool related problems
(PICkit 2 does not work with the PIC32).
-configs/pic32-starterkit
+configs/p112
+ The P112 is notable because it was the first of the hobbyist single board
+ computers to reach the production stage. The P112 hobbyist computers
+ were relatively widespread and inspired other hobbyist centered home brew
+ computing projects such as N8VEM home brew computing project. The P112
+ project still maintains many devoted enthusiasts and has an online
+ repository of software and other information.
+
+ The P112 computer originated as a commercial product of "D-X Designs Pty
+ Ltd" of Australia. They describe the computer as "The P112 is a stand-alone
+ 8-bit CPU board. Typically running CP/M (tm) or a similar operating system,
+ it provides a Z80182 (Z-80 upgrade) CPU with up to 1MB of memory, serial,
+ parallel and diskette IO, and realtime clock, in a 3.5-inch drive form factor.
+ Powered solely from 5V, it draws 150mA (nominal: not including disk drives)
+ with a 16MHz CPU clock. Clock speeds up to 24.576MHz are possible."
+
+ The P112 board was last available new in 1996 by Dave Brooks. In late 2004
+ on the Usenet Newsgroup comp.os.cpm, talk about making another run of P112
+ boards was discussed. David Griffith decided to produce additional P112 kits
+ with Dave Brooks blessing and the assistance of others. In addition Terry
+ Gulczynski makes additional P112 derivative hobbyist home brew computers.
+ Hal Bower was very active in the mid 1990's on the P112 project and ported
+ the "Banked/Portable BIOS".
+configs/pic32-starterkit
This directory contains the port of NuttX to the Microchip PIC32 Ethernet
Starter Kit (DM320004) with the Multimedia Expansion Board (MEB, DM320005).
See www.microchip.com for further information.
configs/pic32mx7mmb
-
This directory will (eventually) contain the port of NuttX to the
Mikroelektronika PIC32MX7 Multimedia Board (MMB). See
http://www.mikroe.com/ for further information.
@@ -1797,7 +1819,6 @@ configs/pjrc-8051
and the SDCC toolchain. This port is not quite ready for prime time.
configs/qemu-i486
-
Port of NuttX to QEMU in i486 mode. This port will also run on real i486
hardwared (Google the Bifferboard).
diff --git a/nuttx/configs/p112/Kconfig b/nuttx/configs/p112/Kconfig
new file mode 100644
index 000000000..ae2bf3130
--- /dev/null
+++ b/nuttx/configs/p112/Kconfig
@@ -0,0 +1,4 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
diff --git a/nuttx/configs/p112/README.txt b/nuttx/configs/p112/README.txt
new file mode 100644
index 000000000..6b6f5964d
--- /dev/null
+++ b/nuttx/configs/p112/README.txt
@@ -0,0 +1,26 @@
+P112 README
+^^^^^^^^^^^
+
+The P112 is notable because it was the first of the hobbyist single board
+computers to reach the production stage. The P112 hobbyist computers
+were relatively widespread and inspired other hobbyist centered home brew
+computing projects such as N8VEM home brew computing project. The P112
+project still maintains many devoted enthusiasts and has an online
+repository of software and other information.
+
+The P112 computer originated as a commercial product of "D-X Designs Pty
+Ltd" of Australia. They describe the computer as "The P112 is a stand-alone
+8-bit CPU board. Typically running CP/M (tm) or a similar operating system,
+it provides a Z80182 (Z-80 upgrade) CPU with up to 1MB of memory, serial,
+parallel and diskette IO, and realtime clock, in a 3.5-inch drive form factor.
+Powered solely from 5V, it draws 150mA (nominal: not including disk drives)
+with a 16MHz CPU clock. Clock speeds up to 24.576MHz are possible."
+
+The P112 board was last available new in 1996 by Dave Brooks. In late 2004
+on the Usenet Newsgroup comp.os.cpm, talk about making another run of P112
+boards was discussed. David Griffith decided to produce additional P112 kits
+with Dave Brooks blessing and the assistance of others. In addition Terry
+Gulczynski makes additional P112 derivative hobbyist home brew computers.
+Hal Bower was very active in the mid 1990's on the P112 project and ported
+the "Banked/Portable BIOS".
+
diff --git a/nuttx/configs/p112/include/board.h b/nuttx/configs/p112/include/board.h
new file mode 100644
index 000000000..55077709d
--- /dev/null
+++ b/nuttx/configs/p112/include/board.h
@@ -0,0 +1,60 @@
+/************************************************************
+ * configs/p112/include/board.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+#ifndef __CONFIGS_P112_INCLUDE_BOARD_H
+#define __CONFIGS_P112_INCLUDE_BOARD_H
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+#if defined(__cplusplus)
+extern "C"
+{
+#endif
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __CONFIGS_P112_INCLUDE_BOARD_H */
diff --git a/nuttx/configs/p112/ostest/Make.defs b/nuttx/configs/p112/ostest/Make.defs
new file mode 100644
index 000000000..e64c7b5dd
--- /dev/null
+++ b/nuttx/configs/p112/ostest/Make.defs
@@ -0,0 +1,167 @@
+############################################################################
+# configs/p112/ostest/Make.defs
+#
+# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+# These are the directories where the SDCC toolchain is installed. NOTE
+# that short 8.3 path names are used in order to avoid spaces. On my machine
+# I have:
+#
+# C:\PROGRA~1\ = C:\Profram Files\
+# C:\PROGRA~2\ = C:\Program Files (x86)\
+#
+# Your PC may be configured differently.
+
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ SDCC_INSTALLDIR = C:\PROGRA~2\SDCC
+ SDCC_BINDIR = $(SDCC_INSTALLDIR)\bin
+ SDCC_LIBDIR = $(SDCC_INSTALLDIR)\lib\z180
+else
+ SDCC_INSTALLDIR = /usr/local
+ SDCC_BINDIR = $(SDCC_INSTALLDIR)/bin
+ SDCC_LIBDIR = $(SDCC_INSTALLDIR)/share/sdcc/lib/z180
+endif
+
+CROSSDEV =
+CC = sdcc
+CPP = sdcpp
+LD = sdldz80
+AS = sdasz80
+AR = sdar -r
+ARCHCPUFLAGS = -mz180
+
+ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
+ ARCHOPTIMIZATION = --debug
+else
+ ARCHOPTIMIZATION =
+endif
+
+ARCHPICFLAGS =
+ARCHWARNINGS =
+ARCHDEFINES =
+ARCHINCLUDES = -I. -I$(TOPDIR)$(DELIM)include
+
+CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
+CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = -x -a -l -o -s -g
+
+SDCCLIB = z180.lib
+
+ASMEXT = .asm
+OBJEXT = .o
+LIBEXT = .lib
+EXEEXT = .hex
+
+# Custom ASSEMBLE definition. The most common toolchain, GCC, uses the
+# compiler to assemble files because this has the advantage of running the C
+# Pre-Processor against. This is not possible with other SDCC; we need to
+# define AS and over-ride the common definition in order to use the assembler
+# directly.
+
+define ASSEMBLE
+ @echo "AS: $1"
+ $(Q) $(AS) $(AFLAGS) $2 $1
+endef
+
+# Custom CLEAN definition
+
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+define CLEAN
+ $(Q) if exist *.o (del /f /q *.o)
+ $(Q) if exist *.asm (del /f /q *.asm)
+ $(Q) if exist *.rel (del /f /q *.rel)
+ $(Q) if exist *.lst (del /f /q *.lst)
+ $(Q) if exist *.rst (del /f /q *.rst)
+ $(Q) if exist *.sym (del /f /q *.sym)
+ $(Q) if exist *.adb (del /f /q *.adb)
+ $(Q) if exist *.lnk (del /f /q *.lnk)
+ $(Q) if exist *.map (del /f /q *.map)
+ $(Q) if exist *.mem (del /f /q *.mem)
+ $(Q) if exist *.hex (del /f /q *.hex)
+ $(Q) if exist *.cmd (del /f /q *.cmd)
+endef
+else
+define CLEAN
+ $(Q) rm -f *.o *.asm *.rel *.lst *.rst *.sym *.adb *.lnk *.map *.mem *.hex *.cmd
+endef
+endif
+
+# Windows native host tool definitions
+
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ HOSTCC = mingw32-gcc.exe
+ HOSTINCLUDES = -I.
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+ HOSTLDFLAGS =
+ HOSTEXEEXT = .exe
+
+ # Windows-native host tools
+
+ MKDEP = $(TOPDIR)\tools\mkdeps.exe --winnative
+
+ # Use NTFS links or directory copies
+
+ifeq ($(CONFIG_WINDOWS_MKLINK),y)
+ DIRLINK = $(TOPDIR)$(DELIM)tools$(DELIM)link.bat
+else
+ DIRLINK = $(TOPDIR)$(DELIM)tools$(DELIM)copydir.bat
+endif
+DIRUNLINK = $(TOPDIR)$(DELIM)tools$(DELIM)unlink.bat
+
+else
+
+# Linux/Cygwin host tool definitions
+
+ HOSTCC = gcc
+ HOSTINCLUDES = -I.
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+ HOSTLDFLAGS =
+
+ # This is the tool to use for dependencies (i.e., none)
+
+ MKDEP = $(TOPDIR)$(DELIM)tools$(DELIM)mknulldeps.sh
+
+ # SDCC for Linux, OSX, or Cygwin understands symbolic links. Windows SDCC
+ # running under Cygwin does not
+
+ifeq ($(WINTOOL),y)
+ DIRLINK = $(TOPDIR)$(DELIM)tools$(DELIM)copydir.sh
+else
+ DIRLINK = $(TOPDIR)$(DELIM)tools$(DELIM)link.sh
+endif
+DIRUNLINK = $(TOPDIR)$(DELIM)tools$(DELIM)unlink.sh
+
+endif
diff --git a/nuttx/configs/p112/ostest/defconfig b/nuttx/configs/p112/ostest/defconfig
new file mode 100644
index 000000000..2cdc13ba5
--- /dev/null
+++ b/nuttx/configs/p112/ostest/defconfig
@@ -0,0 +1,530 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+# CONFIG_HOST_LINUX is not set
+# CONFIG_HOST_OSX is not set
+CONFIG_HOST_WINDOWS=y
+# CONFIG_HOST_OTHER is not set
+CONFIG_WINDOWS_NATIVE=y
+# CONFIG_WINDOWS_CYGWIN is not set
+# CONFIG_WINDOWS_MSYS is not set
+# CONFIG_WINDOWS_OTHER is not set
+# CONFIG_WINDOWS_MKLINK is not set
+
+#
+# Build Configuration
+#
+# CONFIG_APPS_DIR="..\apps"
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+# CONFIG_RAW_BINARY is not set
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDBOOL_H is not set
+# CONFIG_ARCH_MATH_H is not set
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+# CONFIG_DEBUG is not set
+# CONFIG_DEBUG_SYMBOLS is not set
+
+#
+# System Type
+#
+# CONFIG_ARCH_8051 is not set
+# CONFIG_ARCH_ARM is not set
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+CONFIG_ARCH_Z80=y
+CONFIG_ARCH="z80"
+CONFIG_ARCH_CHIP="z180"
+CONFIG_BOARD_LOOPSPERMSEC=100
+# CONFIG_ARCH_CHIP_Z80 is not set
+# CONFIG_ARCH_CHIP_Z8018006VSG is not set
+# CONFIG_ARCH_CHIP_Z8018010VSG is not set
+# CONFIG_ARCH_CHIP_Z8018008VSG is not set
+# CONFIG_ARCH_CHIP_Z8018010FSG is not set
+# CONFIG_ARCH_CHIP_Z8018008VEG is not set
+# CONFIG_ARCH_CHIP_Z8018006VEG is not set
+# CONFIG_ARCH_CHIP_Z8018006PSG is not set
+# CONFIG_ARCH_CHIP_Z8018008FSG is not set
+# CONFIG_ARCH_CHIP_Z8018010PSG is not set
+# CONFIG_ARCH_CHIP_Z8018006PEG is not set
+# CONFIG_ARCH_CHIP_Z8018010VEG is not set
+# CONFIG_ARCH_CHIP_Z8018010PEG is not set
+# CONFIG_ARCH_CHIP_Z8018008PSG is not set
+# CONFIG_ARCH_CHIP_Z8018006FSG is not set
+# CONFIG_ARCH_CHIP_Z8018000XSO is not set
+# CONFIG_ARCH_CHIP_Z8018010FEG is not set
+# CONFIG_ARCH_CHIP_Z8018000WSO is not set
+# CONFIG_ARCH_CHIP_Z8018008PEG is not set
+# CONFIG_ARCH_CHIP_Z8018110FEG is not set
+# CONFIG_ARCH_CHIP_Z8018233FSG is not set
+# CONFIG_ARCH_CHIP_Z8018220AEG is not set
+CONFIG_ARCH_CHIP_Z8018216FSG=y
+# CONFIG_ARCH_CHIP_Z8018216ASG is not set
+# CONFIG_ARCH_CHIP_Z8018233ASG is not set
+# CONFIG_ARCH_CHIP_Z8019520FSG is not set
+# CONFIG_ARCH_CHIP_Z8019533FSG is not set
+# CONFIG_ARCH_CHIP_Z8L18020VSG is not set
+# CONFIG_ARCH_CHIP_Z8L18020FSG is not set
+# CONFIG_ARCH_CHIP_Z8L18020PSG is not set
+# CONFIG_ARCH_CHIP_Z8L18220ASG is not set
+# CONFIG_ARCH_CHIP_Z8L18220FSG is not set
+# CONFIG_ARCH_CHIP_Z8L18220AEG is not set
+# CONFIG_ARCH_CHIP_Z8S18020VSG is not set
+# CONFIG_ARCH_CHIP_Z8S18020VSG1960 is not set
+# CONFIG_ARCH_CHIP_Z8S18033VSG is not set
+# CONFIG_ARCH_CHIP_Z8S18010FSG is not set
+# CONFIG_ARCH_CHIP_Z8S18010VEG is not set
+# CONFIG_ARCH_CHIP_Z8S18020VEG is not set
+# CONFIG_ARCH_CHIP_Z8S18010VSG is not set
+# CONFIG_ARCH_CHIP_Z8S18020PSG is not set
+# CONFIG_ARCH_CHIP_Z8S18033FSG is not set
+# CONFIG_ARCH_CHIP_Z8S18033FEG is not set
+# CONFIG_ARCH_CHIP_Z8S18020FSG is not set
+# CONFIG_ARCH_CHIP_Z8S18033VEG is not set
+# CONFIG_ARCH_CHIP_Z8S18010PSG is not set
+# CONFIG_ARCH_CHIP_Z8S18020FEG is not set
+# CONFIG_ARCH_CHIP_Z8S18010PEG is not set
+# CONFIG_ARCH_CHIP_Z8S18010FEG is not set
+# CONFIG_ARCH_CHIP_Z8F6403 is not set
+# CONFIG_ARCH_CHIP_Z8F6423 is not set
+# CONFIG_ARCH_CHIP_EZ80F91 is not set
+# CONFIG_ARCH_CHIP_EZ80F92 is not set
+# CONFIG_ARCH_CHIP_EZ80F93 is not set
+CONFIG_ARCH_CHIP_Z180=y
+CONFIG_ARCH_CHIP_Z80182=y
+CONFIG_LINKER_HOME_AREA=0x0000
+CONFIG_LINKER_CODE_AREA=0x0200
+CONFIG_LINKER_DATA_AREA=0x8000
+# CONFIG_LINKER_ROM_AT_0000 is not set
+# CONFIG_ARCH_HAVEHEAD is not set
+# CONFIG_Z180_TOOLCHAIN_SDCCL is not set
+CONFIG_Z180_TOOLCHAIN_SDCCW=y
+CONFIG_Z180_BANKAREA_VIRTBASE=0x8000
+CONFIG_Z180_BANKAREA_PHYSBASE=0x08000
+CONFIG_Z180_COMMON1AREA_VIRTBASE=0xc000
+CONFIG_Z180_PHYSHEAP_START=0x0c000
+CONFIG_Z180_PHYSHEAP_END=0x100000
+
+#
+# Z180 Peripheral Support
+#
+CONFIG_Z180_UART0=y
+CONFIG_Z180_UART1=y
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_DMA is not set
+# CONFIG_ARCH_IRQPRIO is not set
+# CONFIG_CUSTOM_STACK is not set
+CONFIG_ADDRENV=y
+# CONFIG_ARCH_STACKDUMP is not set
+# CONFIG_ENDIAN_BIG is not set
+
+#
+# Board Settings
+#
+CONFIG_DRAM_START=0x0000
+CONFIG_DRAM_SIZE=65536
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_P112=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="p112"
+
+#
+# Common Board Options
+#
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+CONFIG_MSEC_PER_TICK=10
+CONFIG_RR_INTERVAL=0
+# CONFIG_SCHED_INSTRUMENTATION is not set
+CONFIG_TASK_NAME_SIZE=0
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2007
+CONFIG_START_MONTH=2
+CONFIG_START_DAY=21
+# CONFIG_DEV_CONSOLE is not set
+# CONFIG_MUTEX_TYPES is not set
+# CONFIG_PRIORITY_INHERITANCE is not set
+# CONFIG_FDCLONE_DISABLE is not set
+# CONFIG_FDCLONE_STDIO is not set
+CONFIG_SDCLONE_DISABLE=y
+# CONFIG_SCHED_WORKQUEUE is not set
+# CONFIG_SCHED_WAITPID is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="ostest_main"
+CONFIG_DISABLE_OS_API=y
+CONFIG_DISABLE_CLOCK=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=y
+CONFIG_DISABLE_POLL=y
+
+#
+# Sizes of configurable things (0 disables)
+#
+CONFIG_MAX_TASKS=8
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=0
+CONFIG_NFILE_DESCRIPTORS=0
+CONFIG_NFILE_STREAMS=0
+CONFIG_NAME_MAX=32
+CONFIG_PREALLOC_MQ_MSGS=0
+CONFIG_MQ_MAXMSGSIZE=0
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1024
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+
+#
+# Device Drivers
+#
+CONFIG_DEV_NULL=y
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+# CONFIG_I2C is not set
+# CONFIG_SPI is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+# CONFIG_SERCOMM_CONSOLE is not set
+CONFIG_SERIAL=y
+CONFIG_DEV_LOWCONSOLE=y
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_UART0=y
+CONFIG_ARCH_HAVE_UART1=y
+CONFIG_MCU_SERIAL=y
+CONFIG_UART0_SERIAL_CONSOLE=y
+# CONFIG_UART1_SERIAL_CONSOLE is not set
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# UART0 Configuration
+#
+CONFIG_UART0_RXBUFSIZE=64
+CONFIG_UART0_TXBUFSIZE=64
+CONFIG_UART0_BAUD=115200
+CONFIG_UART0_BITS=8
+CONFIG_UART0_PARITY=0
+CONFIG_UART0_2STOP=0
+
+#
+# UART1 Configuration
+#
+CONFIG_UART1_RXBUFSIZE=64
+CONFIG_UART1_TXBUFSIZE=64
+CONFIG_UART1_BAUD=115200
+CONFIG_UART1_BITS=8
+CONFIG_UART1_PARITY=0
+CONFIG_UART1_2STOP=0
+# CONFIG_USBDEV is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+
+#
+# Networking Support
+#
+# CONFIG_NET is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_FS_RAMMAP is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=1
+CONFIG_ARCH_HAVE_HEAP2=y
+CONFIG_HEAP2_BASE=0x00000000
+CONFIG_HEAP2_SIZE=0
+# CONFIG_GRAN is not set
+
+#
+# Binary Formats
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+# CONFIG_PIC is not set
+# CONFIG_SYMTAB_ORDEREDBYNAME is not set
+
+#
+# Library Routines
+#
+CONFIG_STDIO_BUFFER_SIZE=0
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=0
+# CONFIG_LIBM is not set
+CONFIG_NOPRINTF_FIELDWIDTH=y
+# CONFIG_LIBC_FLOATINGPOINT is not set
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_STRERROR is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_LIB_SENDFILE_BUFSIZE=512
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+# CONFIG_HAVE_CXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Named Applications
+#
+# CONFIG_NAMEDAPP is not set
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CDCACM is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_LCDRW is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_NETTEST is not set
+# CONFIG_EXAMPLES_NSH is not set
+# CONFIG_EXAMPLES_NULL is not set
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXCONSOLE is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+CONFIG_EXAMPLES_OSTEST=y
+# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set
+CONFIG_EXAMPLES_OSTEST_LOOPS=1
+CONFIG_EXAMPLES_OSTEST_STACKSIZE=1024
+CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=4
+CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000
+CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
+# CONFIG_EXAMPLES_PASHELLO is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POLL is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_UDP is not set
+# CONFIG_EXAMPLES_UIP is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBMSC is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+# CONFIG_EXAMPLES_WLAN is not set
+
+#
+# Interpreters
+#
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_DHCPC is not set
+# CONFIG_NETUTILS_DHCPD is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_FTPD is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_RESOLV is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TELNETD is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_UIPLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+
+#
+# ModBus
+#
+
+#
+# FreeModbus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+# CONFIG_NSH_LIBRARY is not set
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# readline()
+#
+# CONFIG_SYSTEM_READLINE is not set
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sysinfo
+#
+# CONFIG_SYSTEM_SYSINFO is not set
diff --git a/nuttx/configs/p112/ostest/setenv.bat b/nuttx/configs/p112/ostest/setenv.bat
new file mode 100644
index 000000000..19ca1ef57
--- /dev/null
+++ b/nuttx/configs/p112/ostest/setenv.bat
@@ -0,0 +1,50 @@
+@echo off
+
+rem configs/p112/ostest/setenv.bat
+rem
+rem Copyright (C) 2012 Gregory Nutt. All rights reserved.
+rem Author: Gregory Nutt <gnutt@nuttx.org>
+rem
+rem Redistribution and use in source and binary forms, with or without
+rem modification, are permitted provided that the following conditions
+rem are met:
+rem
+rem 1. Redistributions of source code must retain the above copyright
+rem notice, this list of conditions and the following disclaimer.
+rem 2. Redistributions in binary form must reproduce the above copyright
+rem notice, this list of conditions and the following disclaimer in
+rem the documentation and/or other materials provided with the
+rem distribution.
+rem 3. Neither the name NuttX nor the names of its contributors may be
+rem used to endorse or promote products derived from this software
+rem without specific prior written permission.
+rem
+rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+rem POSSIBILITY OF SUCH DAMAGE.
+
+rem This is the location where I installed in the MinGW compiler. With
+rem this configuration, it is recommended that you do NOT install the
+rem MSYS tools; they conflict with the GNUWin32 tools. See
+rem http://www.mingw.org/ for further info.
+
+set PATH=C:\MinGW\bin;%PATH%
+
+rem This is the location where I installed the SDCC toolchain for windows.
+
+set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
+
+rem This is the location where I installed the GNUWin32 tools. See
+rem http://gnuwin32.sourceforge.net/.
+
+set PATH=C:\gnuwin32\bin;%PATH%
+echo %PATH%
diff --git a/nuttx/configs/p112/scripts/setenv.bat b/nuttx/configs/p112/scripts/setenv.bat
new file mode 100644
index 000000000..dc214445f
--- /dev/null
+++ b/nuttx/configs/p112/scripts/setenv.bat
@@ -0,0 +1,50 @@
+@echo off
+
+rem configs/p112/scripts/setenv.bat
+rem
+rem Copyright (C) 2012 Gregory Nutt. All rights reserved.
+rem Author: Gregory Nutt <gnutt@nuttx.org>
+rem
+rem Redistribution and use in source and binary forms, with or without
+rem modification, are permitted provided that the following conditions
+rem are met:
+rem
+rem 1. Redistributions of source code must retain the above copyright
+rem notice, this list of conditions and the following disclaimer.
+rem 2. Redistributions in binary form must reproduce the above copyright
+rem notice, this list of conditions and the following disclaimer in
+rem the documentation and/or other materials provided with the
+rem distribution.
+rem 3. Neither the name NuttX nor the names of its contributors may be
+rem used to endorse or promote products derived from this software
+rem without specific prior written permission.
+rem
+rem THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+rem "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+rem LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+rem FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+rem COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+rem INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+rem BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+rem OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+rem AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+rem LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+rem ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+rem POSSIBILITY OF SUCH DAMAGE.
+
+rem This is the location where I installed in the MinGW compiler. With
+rem this configuration, it is recommended that you do NOT install the
+rem MSYS tools; they conflict with the GNUWin32 tools. See
+rem http://www.mingw.org/ for further info.
+
+set PATH=C:\MinGW\bin;%PATH%
+
+rem This is the location where I installed the SDCC toolchain for windows.
+
+set PATH=C:\Program Files (x86)\SDCC/bin;%PATH%
+
+rem This is the location where I installed the GNUWin32 tools. See
+rem http://gnuwin32.sourceforge.net/.
+
+set PATH=C:\gnuwin32\bin;%PATH%
+echo %PATH%
diff --git a/nuttx/configs/p112/scripts/setenv.sh b/nuttx/configs/p112/scripts/setenv.sh
new file mode 100755
index 000000000..c55027d62
--- /dev/null
+++ b/nuttx/configs/p112/scripts/setenv.sh
@@ -0,0 +1,66 @@
+#!/bin/bash
+# configs/p112/ostest/setenv.sh
+#
+# Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+#
+# This is the normal installation directory for SDCC under Linux, OSX
+# or Linux:
+#
+export TOOLCHAIN_BIN=/usr/local/bin
+
+#
+# This is the normal installation directory for SDCC under Windows
+#
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/SDCC/bin"
+
+#
+# Add the path to the toolchain to the PATH varialble
+#
+export PATH="${TOOLCHAIN_BIN}":/sbin:/usr/sbin:${PATH_ORIG}
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/p112/src/Makefile b/nuttx/configs/p112/src/Makefile
new file mode 100644
index 000000000..087e1ab2b
--- /dev/null
+++ b/nuttx/configs/p112/src/Makefile
@@ -0,0 +1,77 @@
+############################################################################
+# configs/p112/src/Makefile
+#
+# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)$(DELIM)sched
+CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)common
+CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)z180
+
+ASRCS =
+AOBJS = $(ASRCS:$(ASMEXT)=$(OBJEXT))
+CSRCS =
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+CFLAGS += -I $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %$(ASMEXT)
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx/configs/z80sim/src/Makefile b/nuttx/configs/z80sim/src/Makefile
index 99d557850..9ace92912 100644
--- a/nuttx/configs/z80sim/src/Makefile
+++ b/nuttx/configs/z80sim/src/Makefile
@@ -36,7 +36,7 @@
-include $(TOPDIR)/Make.defs
CFLAGS += -I$(TOPDIR)$(DELIM)sched
-CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)common -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)z80
+CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)common
CFLAGS += -I$(TOPDIR)$(DELIM)arch$(DELIM)z80$(DELIM)src$(DELIM)z80
ASRCS =
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index 54c234d8d..7c444602e 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -403,7 +403,7 @@ int up_addrenv_create(FAR _TCB *tcb, size_t envsize);
#endif
/****************************************************************************
- * Name: up_addrenv_clone
+ * Name: up_addrenv_share
*
* Description:
* This function is called from the core scheduler logic when a thread
@@ -421,7 +421,7 @@ int up_addrenv_create(FAR _TCB *tcb, size_t envsize);
****************************************************************************/
#ifdef CONFIG_ADDRENV
-int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb);
+int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb);
#endif
/****************************************************************************
@@ -439,12 +439,32 @@ int up_addrenv_clone(FAR const _TCB *ptcb, FAR _TCB *ctcb);
* be instantiated.
*
* Returned Value:
+ * A handle that may be used with up_addrenv_restore() to restore the
+ * address environment before up_addrenv_instantiate() was called.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+FAR void *up_addrenv_instantiate(FAR _TCB *tcb);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_restore
+ *
+ * Description:
+ * Restore an address environment using a handle previously returned by
+ * up_addrenv_instantiate().
+ *
+ * Input Parameters:
+ * handle - A handle previously returned by up_addrenv_instantiate.
+ *
+ * Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
#ifdef CONFIG_ADDRENV
-int up_addrenv_instantiate(FAR _TCB *tcb);
+int up_addrenv_restore(FAR void *handle);
#endif
/****************************************************************************
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index afb35c1c0..bfaec3b5d 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -22,7 +22,13 @@ config SCHED_INSTRUMENTATION
bool "Monitor system performance"
default n
---help---
- enables instrumentation in scheduler to monitor system performance.
+ Enables instrumentation in scheduler to monitor system performance.
+ If enabled, then the board-specific logic must provide the following
+ functions (see include/sched.h):
+
+ void sched_note_start(FAR _TCB *tcb);
+ void sched_note_stop(FAR _TCB *tcb);
+ void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
config TASK_NAME_SIZE
int "Maximum task name size"
diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h
index a6205d658..5370da059 100644
--- a/nuttx/sched/env_internal.h
+++ b/nuttx/sched/env_internal.h
@@ -80,7 +80,7 @@ EXTERN int env_dup(FAR _TCB *ptcb);
EXTERN int env_share(FAR _TCB *ptcb);
EXTERN int env_release(FAR _TCB *ptcb);
-/* functions used internally the environment handling logic */
+/* functions used internally by the environment handling logic */
EXTERN FAR char *env_findvar(environ_t *envp, const char *pname);
EXTERN int env_removevar(environ_t *envp, char *pvar);
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index 5fdf3b88d..dc2db2916 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -246,7 +246,7 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
{
FAR _TCB *ptcb;
FAR join_t *pjoin;
- int status;
+ int ret;
int priority;
#if CONFIG_RR_INTERVAL > 0
int policy;
@@ -268,13 +268,27 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
return ENOMEM;
}
+ /* Share the address environment of the parent task. NOTE: Only tasks
+ * created throught the nuttx/binfmt loaders may have an address
+ * environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_share((FAR const _TCB *)g_readytorun.head, ptcb);
+ if (ret < 0)
+ {
+ sched_releasetcb(ptcb);
+ return -ret;
+ }
+#endif
+
/* Associate file descriptors with the new task */
- status = sched_setuppthreadfiles(ptcb);
- if (status != OK)
+ ret = sched_setuppthreadfiles(ptcb);
+ if (ret != OK)
{
sched_releasetcb(ptcb);
- return status;
+ return ret;
}
/* Share the parent's envionment */
@@ -292,8 +306,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Allocate the stack for the TCB */
- status = up_create_stack(ptcb, attr->stacksize);
- if (status != OK)
+ ret = up_create_stack(ptcb, attr->stacksize);
+ if (ret != OK)
{
sched_releasetcb(ptcb);
sched_free(pjoin);
@@ -310,8 +324,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Get the priority for this thread. */
struct sched_param param;
- status = sched_getparam(0, &param);
- if (status == OK)
+ ret = sched_getparam(0, &param);
+ if (ret == OK)
{
priority = param.sched_priority;
}
@@ -348,11 +362,9 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Initialize the task control block */
- status = task_schedsetup(ptcb, priority, pthread_start,
- (main_t)start_routine);
- if (status != OK)
+ ret = task_schedsetup(ptcb, priority, pthread_start, (main_t)start_routine);
+ if (ret != OK)
{
-
sched_releasetcb(ptcb);
sched_free(pjoin);
return EBUSY;
@@ -390,21 +402,21 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Initialize the semaphores in the join structure to zero. */
- status = sem_init(&pjoin->data_sem, 0, 0);
- if (status == OK)
+ ret = sem_init(&pjoin->data_sem, 0, 0);
+ if (ret == OK)
{
- status = sem_init(&pjoin->exit_sem, 0, 0);
+ ret = sem_init(&pjoin->exit_sem, 0, 0);
}
/* Activate the task */
sched_lock();
- if (status == OK)
+ if (ret == OK)
{
- status = task_activate(ptcb);
+ ret = task_activate(ptcb);
}
- if (status == OK)
+ if (ret == OK)
{
/* Wait for the task to actually get running and to register
* its join_t
@@ -414,8 +426,15 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Return the thread information to the caller */
- if (thread) *thread = (pthread_t)pid;
- if (!pjoin->started) status = ERROR;
+ if (thread)
+ {
+ *thread = (pthread_t)pid;
+ }
+
+ if (!pjoin->started)
+ {
+ ret = EINVAL;
+ }
sched_unlock();
(void)sem_destroy(&pjoin->data_sem);
@@ -428,8 +447,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
(void)sem_destroy(&pjoin->exit_sem);
sched_releasetcb(ptcb);
sched_free(pjoin);
- return EIO;
+ ret = EIO;
}
- return OK;
+ return ret;
}
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 21837262d..0557c829b 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -171,6 +171,12 @@ int sched_releasetcb(FAR _TCB *tcb)
(void)env_release(tcb);
+ /* Release this thread's reference to the address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_release(tcb);
+#endif
+
/* And, finally, release the TCB itself */
sched_free(tcb);