summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/z16/src/common/up_allocateheap.c8
-rw-r--r--nuttx/arch/z16/src/common/up_initialize.c2
-rw-r--r--nuttx/arch/z16/src/common/up_initialstate.c2
-rw-r--r--nuttx/arch/z16/src/common/up_internal.h2
-rw-r--r--nuttx/arch/z16/src/common/up_sigdeliver.c2
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_head.S38
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_restoreusercontext.S210
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_sysexec.c6
-rw-r--r--nuttx/configs/z16f2800100zcog/ostest/README.txt12
-rw-r--r--nuttx/configs/z16f2800100zcog/ostest/ostest.zfpproj237
10 files changed, 396 insertions, 123 deletions
diff --git a/nuttx/arch/z16/src/common/up_allocateheap.c b/nuttx/arch/z16/src/common/up_allocateheap.c
index 015b6c978..62d96e0b3 100644
--- a/nuttx/arch/z16/src/common/up_allocateheap.c
+++ b/nuttx/arch/z16/src/common/up_allocateheap.c
@@ -57,13 +57,13 @@
*/
#ifndef CONFIG_HEAP1_BASE
- extern _Far unsigned long far_heaptop;
- #define CONFIG_HEAP1_BASE ((unsigned long)&far_heaptop)
+ extern _Far unsigned long far_heapbot;
+ #define CONFIG_HEAP1_BASE ((unsigned long)&far_heapbot)
#endif
#ifndef CONFIG_HEAP1_END
- extern _Far unsigned long far_heapbot;
- #define CONFIG_HEAP1_END ((unsigned long)&far_heapbot)
+ extern _Far unsigned long far_heaptop;
+ #define CONFIG_HEAP1_END ((unsigned long)&far_heaptop)
#endif
/****************************************************************************
diff --git a/nuttx/arch/z16/src/common/up_initialize.c b/nuttx/arch/z16/src/common/up_initialize.c
index 0f54beb4f..8a30d33ad 100644
--- a/nuttx/arch/z16/src/common/up_initialize.c
+++ b/nuttx/arch/z16/src/common/up_initialize.c
@@ -66,7 +66,7 @@
* interrupt processing.
*/
-chipreg_t *current_regs;
+FAR chipreg_t *current_regs;
/****************************************************************************
* Private Types
diff --git a/nuttx/arch/z16/src/common/up_initialstate.c b/nuttx/arch/z16/src/common/up_initialstate.c
index acb5c31f1..d41e303bd 100644
--- a/nuttx/arch/z16/src/common/up_initialstate.c
+++ b/nuttx/arch/z16/src/common/up_initialstate.c
@@ -84,7 +84,7 @@ void up_initial_state(_TCB *tcb)
memset(&tcb->xcp, 0, sizeof(struct xcptcontext));
#ifndef CONFIG_SUPPRESS_INTERRUPTS
- tcb->xcp.regs[REG_FLAGS] = (uint16)(Z16F_CNTRL_FLAGS_IRQE << 8); /* IRQE flag will enable interrupts */
+ tcb->xcp.regs[REG_FLAGS] = (uint16)Z16F_CNTRL_FLAGS_IRQE; /* IRQE flag will enable interrupts */
#endif
reg32[REG_SP/2] = (uint32)tcb->adj_stack_ptr;
reg32[REG_PC/2] = (uint32)tcb->start;
diff --git a/nuttx/arch/z16/src/common/up_internal.h b/nuttx/arch/z16/src/common/up_internal.h
index 206fdc98a..f6acb97a6 100644
--- a/nuttx/arch/z16/src/common/up_internal.h
+++ b/nuttx/arch/z16/src/common/up_internal.h
@@ -85,7 +85,7 @@ typedef void (*up_vector_t)(void);
* interrupt processing.
*/
-extern chipreg_t *current_regs;
+extern FAR chipreg_t *current_regs;
#endif
/****************************************************************************
diff --git a/nuttx/arch/z16/src/common/up_sigdeliver.c b/nuttx/arch/z16/src/common/up_sigdeliver.c
index 8360b032a..59b40715d 100644
--- a/nuttx/arch/z16/src/common/up_sigdeliver.c
+++ b/nuttx/arch/z16/src/common/up_sigdeliver.c
@@ -118,7 +118,7 @@ void up_sigdeliver(void)
/* Then restore the task interrupt state. */
- if ((reg[REG_FLAGS] & (Z16F_CNTRL_FLAGS_IRQE << 8)) != 0)
+ if ((reg[REG_FLAGS] & Z16F_CNTRL_FLAGS_IRQE) != 0)
{
EI();
}
diff --git a/nuttx/arch/z16/src/z16f/z16f_head.S b/nuttx/arch/z16/src/z16f/z16f_head.S
index 85bfc04ef..2a1871aae 100755
--- a/nuttx/arch/z16/src/z16f/z16f_head.S
+++ b/nuttx/arch/z16/src/z16f/z16f_head.S
@@ -270,12 +270,12 @@ _halt2: /* _z16f_sysexec() should not return */
_timer2_isr:
pushmlo <r0-r7> /* Save r0-r7 on the stack */
- ld r1, #Z16F_IRQ_TIMER0 /* r1 = Timer 2 IRQ number */
+ ld r1, #Z16F_IRQ_TIMER2 /* r1 = Timer 2 IRQ number */
jp _common_isr /* Join common interrupt handling logic */
_timer1_isr:
pushmlo <r0-r7> /* Save r0-r7 on the stack */
- ld r1, #Z16F_IRQ_TIMER0 /* r1 = Timer 1 IRQ number */
+ ld r1, #Z16F_IRQ_TIMER1 /* r1 = Timer 1 IRQ number */
jp _common_isr /* Join common interrupt handling logic */
_timer0_isr:
@@ -397,7 +397,7 @@ _c0_isr:
*
* On entry:
*
- * r0 = IRQ number
+ * r1 = IRQ number
*
* And the stack contains the following:
*
@@ -409,8 +409,8 @@ _c0_isr:
* TOS[20-23] = r5
* TOS[24-27] = r6
* TOS[28-31] = r7
- * TOS[32-33] = return PC
- * TOS[34-35] = flags (with padding)
+ * TOS[32-35] = return PC
+ * TOS[36-37] = flags (with padding)
*
**************************************************************************/
@@ -419,9 +419,9 @@ _common_isr:
* push that as the saved value of r15=sp
*/
- ld r1, #-36 /* See stack accounting above */
- add r1, sp /* r1 = Value of the SP before the interrupt */
- push r1 /* Push r1 in the spot for the saved SP */
+ ld r2, #(9*4+2) /* See stack accounting above */
+ add r2, sp /* r1 = Value of the SP before the interrupt */
+ push r2 /* Push r1 in the spot for the saved SP */
/* Save all of the remaining registers */
@@ -439,16 +439,34 @@ _common_isr:
* to use to return from the interrupt in r0. This may or may not be the
* same value as sp.
*/
+
+ cp r0, sp /* Check if we are performing a context switch */
+ jp nz, _common_switch /* Jump if yes, else use faster return */
+ popmhi <r8-r14> /* Restore r8-r14 */
+ add sp, #4 /* Skip over restore of r15=sp */
+ popmlo <r0-r7> /* Restore r0-r7 */
+ iret
+ /* We are not returning to the same thread that was interrupted. In this case,
+ * r0 is not in the stack but, instead, refers to a storage structure in the TCB
+ */
+
+_common_switch:
ld sp, 2*REG_SP(r0) /* sp=Value of SP on return from interrupt */
ld.w r1, 2*REG_FLAGS(r0) /* r1=padded flags value */
push.w r1 /* Push padded flags value onto the stack */
ld r1, 2*REG_PC(r0) /* r1=return address */
push r1 /* Push the return address onto the stack */
+ ld r7, 2*REG_R7(r0) /* Recover saved r7 */
+ push r7 /* And save on the stack so that we can use r7 */
+ ld r7, sp /* r7=saved sp */
- ld sp, r0 /* sp=Value of SP at call to _up_doirq */
+ ld sp, r0 /* sp=Pointer to register save structure */
popmhi <r8-r14> /* Restore r8-r14 */
- popmlo <r0-r7> /* Restore r0-r7 */
+ add sp, #4 /* Skip over restore of r15=sp */
+ popmlo <r0-r6> /* Restore r0-r6 */
+ ld sp, r7 /* Switch back to the correct stack */
+ pop r7 /* Recover r7 from the stack */
iret /* Return from interrupt */
end
diff --git a/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S b/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S
index 447ba1124..f983499ba 100755
--- a/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S
+++ b/nuttx/arch/z16/src/z16f/z16f_restoreusercontext.S
@@ -1,105 +1,105 @@
-/*************************************************************************
- * arch/z16/src/z16f/z16f_restoreusercontext.asm
- *
- * Copyright (C) 2008 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 <arch/irq.h>
-#include "chip/chip.h"
-
-/*************************************************************************
- * External References / External Definitions
- *************************************************************************/
-
- xdef _up_restoreusercontext
-
-/*************************************************************************
- * Data Allocation
- *************************************************************************/
-
- define CODESEG, SPACE=EROM
- segment CODESEG
-
-/*************************************************************************
- * Code
- *************************************************************************/
-
-/*************************************************************************
- * Name: up_restoreusercontext
- *
- * Description:
- * Restore the current user context.
- *
- * Parameters:
- * r1: pointer to the register save array in the XCPT structure
- *
- *************************************************************************/
-
-_up_restoreusercontext:
- /* Disable interrupts throughout the following */
-
- di
-
- /* Set up the stack for return */
-
- ld sp, 2*REG_SP(r1) /* sp=Value of SP on return */
- ld r2, 2*REG_PC(r1) /* r2=return address */
- push r1 /* Push the return address onto the stack */
-
- /* Retore r8-r18 */
-
- ld sp, r1 /* sp=Value of SP at call to _up_doirq */
- popmhi <r8-r14> /* Restore r8-r14 */
-
- /* Test if interrupts should be enabled upon return */
-
- ld.w r2, 2*REG_FLAGS(r1) /* r2=padded flags value */
- tm r2, #(Z16F_CNTRL_FLAGS_IRQE << 8) /* Test (shifted) IRQE bit */
- jp z, _up_returndisabled /* Jump if interrupts should remain disabled */
-
- /* Return with interrupts enabled */
-
- popmlo <r0-r7> /* Restore r0-r7 */
- ei /* Enable interrupts and return */
- ret
-
- /* Return with interrupts disabled */
-
-_up_returndisabled:
- popmlo <r0-r7> /* Restore r0-r7 */
- ret
- end
+/*************************************************************************
+ * arch/z16/src/z16f/z16f_restoreusercontext.asm
+ *
+ * Copyright (C) 2008 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 <arch/irq.h>
+#include "chip/chip.h"
+
+/*************************************************************************
+ * External References / External Definitions
+ *************************************************************************/
+
+ xdef _up_restoreusercontext
+
+/*************************************************************************
+ * Data Allocation
+ *************************************************************************/
+
+ define CODESEG, SPACE=EROM
+ segment CODESEG
+
+/*************************************************************************
+ * Code
+ *************************************************************************/
+
+/*************************************************************************
+ * Name: up_restoreusercontext
+ *
+ * Description:
+ * Restore the current user context.
+ *
+ * Parameters:
+ * r1: pointer to the register save array in the XCPT structure
+ *
+ *************************************************************************/
+
+_up_restoreusercontext:
+ /* Disable interrupts throughout the following */
+
+ di
+
+ /* Set up the stack for return */
+
+ ld sp, 2*REG_SP(r1) /* sp=Value of SP on return */
+ ld r2, 2*REG_PC(r1) /* r2=return address */
+ push r1 /* Push the return address onto the stack */
+
+ /* Retore r8-r18 */
+
+ ld sp, r1 /* sp=Value of SP at call to _up_doirq */
+ popmhi <r8-r14> /* Restore r8-r14 */
+
+ /* Test if interrupts should be enabled upon return */
+
+ ld.w r2, 2*REG_FLAGS(r1) /* r2=padded flags value */
+ tm r2, #Z16F_CNTRL_FLAGS_IRQE /* Test IRQE bit */
+ jp z, _up_returndisabled /* Jump if interrupts should remain disabled */
+
+ /* Return with interrupts enabled */
+
+ popmlo <r0-r7> /* Restore r0-r7 */
+ ei /* Enable interrupts and return */
+ ret
+
+ /* Return with interrupts disabled */
+
+_up_returndisabled:
+ popmlo <r0-r7> /* Restore r0-r7 */
+ ret
+ end
diff --git a/nuttx/arch/z16/src/z16f/z16f_sysexec.c b/nuttx/arch/z16/src/z16f/z16f_sysexec.c
index 8ee91764c..e492bab6e 100644
--- a/nuttx/arch/z16/src/z16f/z16f_sysexec.c
+++ b/nuttx/arch/z16/src/z16f/z16f_sysexec.c
@@ -82,6 +82,12 @@ void z16f_sysexec(FAR chipreg_t *regs)
{
int errcode = OSERR_ERREXCEPTION;
uint16 excp;
+
+ /* Save that register reference so that it can be used for built-in
+ * diagnostics.
+ */
+
+ current_regs = regs;
/* The cause of the the system exception is indicated in the SYSEXCPH&L
* registers
diff --git a/nuttx/configs/z16f2800100zcog/ostest/README.txt b/nuttx/configs/z16f2800100zcog/ostest/README.txt
new file mode 100644
index 000000000..214c3a9f1
--- /dev/null
+++ b/nuttx/configs/z16f2800100zcog/ostest/README.txt
@@ -0,0 +1,12 @@
+README.txt
+^^^^^^^^^^
+
+ostest.zfpproj is a simple ZDS-II project that will allow you
+ to use the ZDS-II debugger. Before using, copy the following
+ files from the toplevel directory:
+
+ nuttx.hex, nuttx.map, nuttx.lod
+
+ to this directory as:
+
+ ostest.hex, ostest.map, ostest.lod
diff --git a/nuttx/configs/z16f2800100zcog/ostest/ostest.zfpproj b/nuttx/configs/z16f2800100zcog/ostest/ostest.zfpproj
new file mode 100644
index 000000000..f0dfc3319
--- /dev/null
+++ b/nuttx/configs/z16f2800100zcog/ostest/ostest.zfpproj
@@ -0,0 +1,237 @@
+<project type="Standard" project-type="Standard" configuration="Debug" created-by="{{build_number}}" modified-by="c:4.11:07031901">
+<cpu>Z16F2811AL</cpu>
+
+<!-- file information -->
+<files>
+<file filter-key="flash">..\..\..\nuttx.hex</file>
+</files>
+
+<!-- configuration information -->
+<configurations>
+<configuration name="Debug" >
+<tools>
+<tool name="Assembler">
+<options>
+<option name="define" type="string" change-action="assemble">_Z16F2811AL=1,_Z16F_SERIES=1</option>
+<option name="include" type="string" change-action="assemble"></option>
+<option name="list" type="boolean" change-action="none">true</option>
+<option name="listmac" type="boolean" change-action="none">false</option>
+<option name="name" type="boolean" change-action="none">true</option>
+<option name="pagelen" type="integer" change-action="none">56</option>
+<option name="pagewidth" type="integer" change-action="none">80</option>
+<option name="quiet" type="boolean" change-action="none">true</option>
+</options>
+</tool>
+<tool name="Compiler">
+<options>
+<option name="chartype" type="string" change-action="compile">U</option>
+<option name="define" type="string" change-action="compile">_Z16F2811AL,_Z16F_SERIES</option>
+<option name="genprintf" type="boolean" change-action="compile">true</option>
+<option name="keepasm" type="boolean" change-action="none">false</option>
+<option name="keeplst" type="boolean" change-action="none">false</option>
+<option name="list" type="boolean" change-action="none">false</option>
+<option name="listinc" type="boolean" change-action="none">false</option>
+<option name="model" type="string" change-action="compile">S</option>
+<option name="modsect" type="boolean" change-action="compile">false</option>
+<option name="stdinc" type="string" change-action="compile"></option>
+<option name="usrinc" type="string" change-action="compile"></option>
+<option name="regvar" type="boolean" change-action="compile">true</option>
+<option name="regvarcache" type="boolean" change-action="none">false</option>
+<option name="reduceopt" type="boolean" change-action="compile">false</option>
+<option name="watch" type="boolean" change-action="none">false</option>
+</options>
+</tool>
+<tool name="Debugger">
+<options>
+<option name="target" type="string" change-action="rebuild">Z16F2800100ZCOG</option>
+<option name="debugtool" type="string" change-action="none">USBSmartCable</option>
+<option name="usepageerase" type="boolean" change-action="none">true</option>
+</options>
+</tool>
+<tool name="FlashProgrammer">
+<options>
+<option name="erasebeforeburn" type="boolean" change-action="none">false</option>
+<option name="eraseinfopage" type="boolean" change-action="none">false</option>
+<option name="enableinfopage" type="boolean" change-action="none">false</option>
+<option name="includeserial" type="boolean" change-action="none">false</option>
+<option name="offset" type="integer" change-action="none">0</option>
+<option name="snenable" type="boolean" change-action="none">true</option>
+<option name="sn" type="string" change-action="none">000000000000000000000000</option>
+<option name="snsize" type="integer" change-action="none">1</option>
+<option name="snstep" type="integer" change-action="none">000000000000000000000001</option>
+<option name="snstepformat" type="integer" change-action="none">0</option>
+<option name="snaddress" type="string" change-action="none">0</option>
+<option name="snformat" type="integer" change-action="none">0</option>
+<option name="snbigendian" type="boolean" change-action="none">true</option>
+<option name="singleval" type="string" change-action="none">0</option>
+<option name="singlevalformat" type="integer" change-action="none">0</option>
+<option name="usepageerase" type="boolean" change-action="none">false</option>
+<option name="autoselect" type="boolean" change-action="none">true</option>
+</options>
+</tool>
+<tool name="General">
+<options>
+<option name="warn" type="boolean" change-action="none">true</option>
+<option name="debug" type="boolean" change-action="assemble">true</option>
+<option name="debugcache" type="boolean" change-action="none">true</option>
+<option name="igcase" type="boolean" change-action="assemble">false</option>
+<option name="outputdir" type="string" change-action="compile">.</option>
+</options>
+</tool>
+<tool name="Librarian">
+<options>
+<option name="outfile" type="string" change-action="build"></option>
+<option name="warn" type="boolean" change-action="none">false</option>
+</options>
+</tool>
+<tool name="Linker">
+<options>
+<option name="directives" type="string" change-action="build"></option>
+<option name="createnew" type="boolean" change-action="build">false</option>
+<option name="eram" type="string" change-action="build">0-0</option>
+<option name="erom" type="string" change-action="build">0-0</option>
+<option name="exeform" type="string" change-action="build">OMF695,INTEL32</option>
+<option name="fplib" type="string" change-action="build">Dummy</option>
+<option name="iodata" type="string" change-action="build">0-0</option>
+<option name="linkctlfile" type="string" change-action="build"></option>
+<option name="map" type="boolean" change-action="none">true</option>
+<option name="maxhexlen" type="integer" change-action="build">64</option>
+<option name="objlibmods" type="string" change-action="build"></option>
+<option name="of" type="string" change-action="build">.\ostest</option>
+<option name="padhex" type="boolean" change-action="build">false</option>
+<option name="quiet" type="boolean" change-action="none">false</option>
+<option name="ram" type="string" change-action="build">FFB000-FFBFFF</option>
+<option name="relist" type="boolean" change-action="build">false</option>
+<option name="rom" type="string" change-action="build">000000-007FFF</option>
+<option name="sort" type="string" change-action="none">name</option>
+<option name="startuplnkcmds" type="boolean" change-action="build">true</option>
+<option name="startuptype" type="string" change-action="build">1</option>
+<option name="undefisfatal" type="boolean" change-action="none">true</option>
+<option name="useadddirectives" type="boolean" change-action="build">false</option>
+<option name="usecrun" type="boolean" change-action="build">true</option>
+<option name="warnoverlap" type="boolean" change-action="none">false</option>
+<option name="warnisfatal" type="boolean" change-action="none">false</option>
+<option name="xref" type="boolean" change-action="none">false</option>
+</options>
+</tool>
+</tools>
+</configuration>
+<configuration name="Release" >
+<tools>
+<tool name="Assembler">
+<options>
+<option name="define" type="string" change-action="assemble">_Z16F2811AL=1,_Z16F_SERIES=1</option>
+<option name="include" type="string" change-action="assemble"></option>
+<option name="list" type="boolean" change-action="none">true</option>
+<option name="listmac" type="boolean" change-action="none">false</option>
+<option name="name" type="boolean" change-action="none">true</option>
+<option name="pagelen" type="integer" change-action="none">56</option>
+<option name="pagewidth" type="integer" change-action="none">80</option>
+<option name="quiet" type="boolean" change-action="none">true</option>
+</options>
+</tool>
+<tool name="Compiler">
+<options>
+<option name="chartype" type="string" change-action="compile">U</option>
+<option name="define" type="string" change-action="compile">_Z16F2811AL,_Z16F_SERIES</option>
+<option name="genprintf" type="boolean" change-action="compile">true</option>
+<option name="keepasm" type="boolean" change-action="none">false</option>
+<option name="keeplst" type="boolean" change-action="none">false</option>
+<option name="list" type="boolean" change-action="none">false</option>
+<option name="listinc" type="boolean" change-action="none">false</option>
+<option name="model" type="string" change-action="compile">S</option>
+<option name="modsect" type="boolean" change-action="compile">false</option>
+<option name="stdinc" type="string" change-action="compile"></option>
+<option name="usrinc" type="string" change-action="compile"></option>
+<option name="regvar" type="boolean" change-action="compile">true</option>
+<option name="regvarcache" type="boolean" change-action="none">false</option>
+<option name="reduceopt" type="boolean" change-action="compile">false</option>
+<option name="watch" type="boolean" change-action="none">false</option>
+</options>
+</tool>
+<tool name="Debugger">
+<options>
+<option name="target" type="string" change-action="rebuild"></option>
+<option name="debugtool" type="string" change-action="none">ZPAKII</option>
+<option name="usepageerase" type="boolean" change-action="none">true</option>
+</options>
+</tool>
+<tool name="FlashProgrammer">
+<options>
+<option name="erasebeforeburn" type="boolean" change-action="none">false</option>
+<option name="eraseinfopage" type="boolean" change-action="none">false</option>
+<option name="enableinfopage" type="boolean" change-action="none">false</option>
+<option name="includeserial" type="boolean" change-action="none">false</option>
+<option name="offset" type="integer" change-action="none">0</option>
+<option name="snenable" type="boolean" change-action="none">false</option>
+<option name="sn" type="string" change-action="none">0</option>
+<option name="snsize" type="integer" change-action="none">0</option>
+<option name="snstep" type="integer" change-action="none">1</option>
+<option name="snstepformat" type="integer" change-action="none">0</option>
+<option name="snaddress" type="string" change-action="none">0</option>
+<option name="snformat" type="integer" change-action="none">0</option>
+<option name="snbigendian" type="boolean" change-action="none">true</option>
+<option name="singleval" type="string" change-action="none">0</option>
+<option name="singlevalformat" type="integer" change-action="none">0</option>
+<option name="usepageerase" type="boolean" change-action="none">false</option>
+<option name="autoselect" type="boolean" change-action="none">true</option>
+</options>
+</tool>
+<tool name="General">
+<options>
+<option name="warn" type="boolean" change-action="none">true</option>
+<option name="debug" type="boolean" change-action="assemble">false</option>
+<option name="debugcache" type="boolean" change-action="none">true</option>
+<option name="igcase" type="boolean" change-action="assemble">false</option>
+<option name="outputdir" type="string" change-action="compile">.</option>
+</options>
+</tool>
+<tool name="Librarian">
+<options>
+<option name="outfile" type="string" change-action="build"></option>
+<option name="warn" type="boolean" change-action="none">false</option>
+</options>
+</tool>
+<tool name="Linker">
+<options>
+<option name="directives" type="string" change-action="build"></option>
+<option name="createnew" type="boolean" change-action="build">false</option>
+<option name="eram" type="string" change-action="build">0-0</option>
+<option name="erom" type="string" change-action="build">0-0</option>
+<option name="exeform" type="string" change-action="build">OMF695,INTEL32</option>
+<option name="fplib" type="string" change-action="build">Dummy</option>
+<option name="iodata" type="string" change-action="build">0-0</option>
+<option name="linkctlfile" type="string" change-action="build"></option>
+<option name="map" type="boolean" change-action="none">true</option>
+<option name="maxhexlen" type="integer" change-action="build">64</option>
+<option name="objlibmods" type="string" change-action="build"></option>
+<option name="of" type="string" change-action="build">.\ostest</option>
+<option name="padhex" type="boolean" change-action="build">false</option>
+<option name="quiet" type="boolean" change-action="none">false</option>
+<option name="ram" type="string" change-action="build">FFB000-FFBFFF</option>
+<option name="relist" type="boolean" change-action="build">false</option>
+<option name="rom" type="string" change-action="build">000000-007FFF</option>
+<option name="sort" type="string" change-action="none">name</option>
+<option name="startuplnkcmds" type="boolean" change-action="build">true</option>
+<option name="startuptype" type="string" change-action="build">1</option>
+<option name="undefisfatal" type="boolean" change-action="none">true</option>
+<option name="useadddirectives" type="boolean" change-action="build">false</option>
+<option name="usecrun" type="boolean" change-action="build">true</option>
+<option name="warnoverlap" type="boolean" change-action="none">false</option>
+<option name="warnisfatal" type="boolean" change-action="none">false</option>
+<option name="xref" type="boolean" change-action="none">false</option>
+</options>
+</tool>
+</tools>
+</configuration>
+</configurations>
+
+<!-- watch information -->
+<watch-elements>
+</watch-elements>
+
+<!-- breakpoint information -->
+<breakpoints>
+</breakpoints>
+
+</project> \ No newline at end of file