From bec5afdfb8ac3ef9abf83433f09bc711951479f1 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 11 Feb 2008 20:31:36 +0000 Subject: Fixes for z8 compilation git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@669 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/z80/src/Makefile.sdcc | 16 +++-- nuttx/arch/z80/src/Makefile.zdsii | 28 ++++++-- nuttx/arch/z80/src/common/up_allocateheap.c | 6 +- nuttx/arch/z80/src/common/up_arch.h | 2 +- nuttx/arch/z80/src/common/up_assert.c | 2 +- nuttx/arch/z80/src/common/up_exit.c | 2 +- nuttx/arch/z80/src/common/up_initialstate.c | 92 -------------------------- nuttx/arch/z80/src/common/up_internal.h | 6 +- nuttx/arch/z80/src/common/up_releasepending.c | 2 +- nuttx/arch/z80/src/common/up_reprioritizertr.c | 2 +- nuttx/arch/z80/src/common/up_unblocktask.c | 2 +- nuttx/arch/z80/src/z8/Make.defs | 6 +- nuttx/arch/z80/src/z80/Make.defs | 13 ++-- nuttx/arch/z80/src/z80/z80_initialstate.c | 92 ++++++++++++++++++++++++++ 14 files changed, 145 insertions(+), 126 deletions(-) delete mode 100644 nuttx/arch/z80/src/common/up_initialstate.c create mode 100644 nuttx/arch/z80/src/z80/z80_initialstate.c (limited to 'nuttx/arch/z80/src') diff --git a/nuttx/arch/z80/src/Makefile.sdcc b/nuttx/arch/z80/src/Makefile.sdcc index d45be7f93..13e56c4bf 100644 --- a/nuttx/arch/z80/src/Makefile.sdcc +++ b/nuttx/arch/z80/src/Makefile.sdcc @@ -104,15 +104,17 @@ $(SDCCLIBDIR)/myz80.lib: $(SDCCLIBDIR)/$(SDCCLIB) # Create a header file that contains addressing information needed by the code up_mem.h: - @echo "#ifndef __ARCH_MEM_H" >up_mem.h - @echo "#define __ARCH_MEM_H" >>up_mem.h + @echo "#ifndef __UP_MEM_H" >up_mem.h + @echo "#define __UP_MEM_H" >>up_mem.h @echo "" >>up_mem.h - @echo "#define UP_STACK_END $(CONFIG_DRAM_SIZE)" >> up_mem.h - @echo "#define UP_STACK_BASE (UP_STACK_END - $(CONFIG_PROC_STACK_SIZE))" >> up_mem.h - @echo "#define UP_HEAP1_END UP_STACK_BASE" >> up_mem.h - @echo "#define UP_HEAP1_BASE $(HEAP_BASE)" >> up_mem.h + @echo "#include @echo "" >>up_mem.h - @echo "#endif /* __ARCH_MEM_H */" >>up_mem.h + @echo "#define CONFIG_STACK_END $(CONFIG_DRAM_SIZE)" >> up_mem.h + @echo "#define CONFIG_STACK_BASE (CONFIG_STACK_END - $(CONFIG_PROC_STACK_SIZE))" >> up_mem.h + @echo "#define CONFIG_HEAP1_END CONFIG_STACK_BASE" >> up_mem.h + @echo "#define CONFIG_HEAP1_BASE $(HEAP_BASE)" >> up_mem.h + @echo "" >>up_mem.h + @echo "#endif /* __UP_MEM_H */" >>up_mem.h asm_mem.h: @echo " UP_COMPILER_OTHER == 0" > asm_mem.h diff --git a/nuttx/arch/z80/src/Makefile.zdsii b/nuttx/arch/z80/src/Makefile.zdsii index 199293ef3..c6dcf653c 100644 --- a/nuttx/arch/z80/src/Makefile.zdsii +++ b/nuttx/arch/z80/src/Makefile.zdsii @@ -77,12 +77,30 @@ $(AOBJS) $(HEAD_AOBJ): %$(OBJEXT): %$(ASMEXT) $(COBJS): %$(OBJEXT): %.c $(call COMPILE, `cygpath -w $<`, $@) -libarch$(LIBEXT): $(OBJS) +up_mem.h: + @echo "#ifndef __UP_MEM_H" >up_mem.h + @echo "#define __UP_MEM_H" >>up_mem.h + @echo "" >>up_mem.h + @echo "#include " >>up_mem.h + @echo "" >>up_mem.h + @echo "#ifndef CONFIG_HEAP1_BASE" >>up_mem.h + @echo " extern far unsigned long far_heapbot;" >>up_mem.h + @echo "# define CONFIG_HEAP1_BASE ((unsigned long)&far_heapbot)" >>up_mem.h + @echo "#endif" >>up_mem.h + @echo "" >>up_mem.h + @echo "#ifndef CONFIG_HEAP1_END" >>up_mem.h + @echo " extern far unsigned long far_heaptop;" >>up_mem.h + @echo "# define CONFIG_HEAP1_END ((unsigned long)&far_heaptop)" >>up_mem.h + @echo "#endif" >>up_mem.h + @echo "" >>up_mem.h + @echo "#endif /* __UP_MEM_H */" >>up_mem.h + +libarch$(LIBEXT): up_mem.h $(OBJS) @( for obj in $(OBJS) ; do \ $(call ARCHIVE, $@, $${obj}); \ done ; ) -board/libboard$(LIBEXT): +board/libboard$(LIBEXT): up_mem.h @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) nuttx.linkcmd: $(LINKCMDTEMPLATE) @@ -98,11 +116,11 @@ nuttx.linkcmd: $(LINKCMDTEMPLATE) @echo " \"${shell cygpath -w $(ZDSSTDLIBDIR)/csioLDD$(LIBEXT)}\", \\" >>nuttx.linkcmd @echo " \"${shell cygpath -w $(ZDSSTDLIBDIR)/zsldevinitdummy.lib$(LIBEXT)}\" \\" >>nuttx.linkcmd -nuttx$(EXEEXT): $(HEAD_AOBJ) board/libboard$(LIBEXT) nuttx.linkcmd +nuttx$(EXEEXT): up_mem.h $(HEAD_AOBJ) board/libboard$(LIBEXT) nuttx.linkcmd @echo "LD: nuttx.hex" @$(LD) $(LDFLAGS) -.depend: Makefile chip/Make.defs $(DEPSRCS) +.depend: Makefile up_mem.h chip/Make.defs $(DEPSRCS) @if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ fi @@ -116,7 +134,7 @@ clean: $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \ fi @rm -f libarch$(LIBEXT) *~ .*.swp - @rm -f nuttx.linkcmd *.asm *.tmp *.map + @rm -f nuttx.linkcmd up_mem.h *.asm *.tmp *.map $(call CLEAN) distclean: clean diff --git a/nuttx/arch/z80/src/common/up_allocateheap.c b/nuttx/arch/z80/src/common/up_allocateheap.c index 0c5f9fc30..4b21b575c 100644 --- a/nuttx/arch/z80/src/common/up_allocateheap.c +++ b/nuttx/arch/z80/src/common/up_allocateheap.c @@ -76,8 +76,8 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size) { - *heap_start = (FAR void*)UP_HEAP1_BASE; - *heap_size = UP_HEAP1_END - UP_HEAP1_BASE; + *heap_start = (FAR void*)CONFIG_HEAP1_BASE; + *heap_size = CONFIG_HEAP1_END - CONFIG_HEAP1_BASE; up_ledon(LED_HEAPALLOCATE); } @@ -93,6 +93,6 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size) #if CONFIG_MM_REGIONS > 1 void up_addregion(void) { - mm_addregion((FAR void*)UP_HEAP2_BASE, UP_HEAP2_END - UP_HEAP2_BASE); + mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE); } #endif diff --git a/nuttx/arch/z80/src/common/up_arch.h b/nuttx/arch/z80/src/common/up_arch.h index b0158325a..5ef0b932c 100644 --- a/nuttx/arch/z80/src/common/up_arch.h +++ b/nuttx/arch/z80/src/common/up_arch.h @@ -46,7 +46,7 @@ #endif #include -#include "chip.h" +#include "chip/chip.h" /************************************************************************************ * Definitions diff --git a/nuttx/arch/z80/src/common/up_assert.c b/nuttx/arch/z80/src/common/up_assert.c index f226c9431..c1e2e4a8c 100644 --- a/nuttx/arch/z80/src/common/up_assert.c +++ b/nuttx/arch/z80/src/common/up_assert.c @@ -46,8 +46,8 @@ #include #include -#include +#include "chip/chip.h" #include "up_arch.h" #include "os_internal.h" #include "up_internal.h" diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index d8c94fece..45409800e 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -44,8 +44,8 @@ #include #include -#include +#include "chip/chip.h" #include "os_internal.h" #include "up_internal.h" diff --git a/nuttx/arch/z80/src/common/up_initialstate.c b/nuttx/arch/z80/src/common/up_initialstate.c deleted file mode 100644 index 0e26af9a2..000000000 --- a/nuttx/arch/z80/src/common/up_initialstate.c +++ /dev/null @@ -1,92 +0,0 @@ -/**************************************************************************** - * common/up_initialstate.c - * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include - -#include "chip/chip.h" -#include "up_internal.h" -#include "up_arch.h" - -/**************************************************************************** - * Private Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_initial_state - * - * Description: - * A new thread is being started and a new TCB - * has been created. This function is called to initialize - * the processor specific portions of the new TCB. - * - * This function must setup the intial architecture registers - * and/or stack so that execution will begin at tcb->start - * on the next context switch. - * - ****************************************************************************/ - -void up_initial_state(_TCB *tcb) -{ - struct xcptcontext *xcp = &tcb->xcp; - - /* Initialize the initial exception register context structure */ - - memset(xcp, 0, sizeof(struct xcptcontext)); -#ifndef CONFIG_SUPPRESS_INTERRUPTS - xcp->regs[XCPT_I] = Z80_C_FLAG; /* Carry flag will enable interrupts */ -#endif - xcp->regs[XCPT_SP] = (uint16)tcb->adj_stack_ptr; - xcp->regs[XCPT_PC] = (uint16)tcb->start; -} diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h index d340a5631..e90bec766 100644 --- a/nuttx/arch/z80/src/common/up_internal.h +++ b/nuttx/arch/z80/src/common/up_internal.h @@ -41,7 +41,7 @@ ****************************************************************************/ #include -#include +#include "chip/chip.h" /**************************************************************************** * Definitions @@ -111,8 +111,8 @@ extern int up_restoreusercontext(chipreg_t *regs); extern FAR chipreg_t *up_decodeirq(uint8 rstno, FAR chipreg_t *regs); extern void up_irqinitialize(void); extern int up_timerisr(int irq, FAR chipreg_t *regs); -extern void up_lowputc(char ch) __naked; -extern char up_lowgetc(void) __naked; +extern void up_lowputc(char ch) naked_function; +extern char up_lowgetc(void) naked_function; /* Defined in up_doirq.c */ diff --git a/nuttx/arch/z80/src/common/up_releasepending.c b/nuttx/arch/z80/src/common/up_releasepending.c index 3b2b119a3..853cc7350 100644 --- a/nuttx/arch/z80/src/common/up_releasepending.c +++ b/nuttx/arch/z80/src/common/up_releasepending.c @@ -44,8 +44,8 @@ #include #include -#include +#include "chip/chip.h" #include "os_internal.h" #include "up_internal.h" diff --git a/nuttx/arch/z80/src/common/up_reprioritizertr.c b/nuttx/arch/z80/src/common/up_reprioritizertr.c index b5961d92d..3adf33735 100644 --- a/nuttx/arch/z80/src/common/up_reprioritizertr.c +++ b/nuttx/arch/z80/src/common/up_reprioritizertr.c @@ -44,8 +44,8 @@ #include #include -#include +#include "chip/chip.h" #include "os_internal.h" #include "up_internal.h" diff --git a/nuttx/arch/z80/src/common/up_unblocktask.c b/nuttx/arch/z80/src/common/up_unblocktask.c index 93bfdf472..1ce672a5d 100644 --- a/nuttx/arch/z80/src/common/up_unblocktask.c +++ b/nuttx/arch/z80/src/common/up_unblocktask.c @@ -44,8 +44,8 @@ #include #include -#include +#include "chip/chip.h" #include "os_internal.h" #include "clock_internal.h" #include "up_internal.h" diff --git a/nuttx/arch/z80/src/z8/Make.defs b/nuttx/arch/z80/src/z8/Make.defs index 8488efc96..3c48749d7 100644 --- a/nuttx/arch/z80/src/z8/Make.defs +++ b/nuttx/arch/z80/src/z8/Make.defs @@ -36,9 +36,9 @@ HEAD_ASRC = z8_head.asm CMN_ASRCS = -CMN_CSRCS = up_initialize.c up_allocateheap.c up_initialstate.c \ - up_createstack.c up_releasestack.c up_interruptcontext.c \ - up_blocktask.c up_unblocktask.c up_exit.c up_releasepending.c \ +CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \ + up_releasestack.c up_interruptcontext.c up_blocktask.c \ + up_unblocktask.c up_exit.c up_releasepending.c \ up_reprioritizertr.c up_copystate.c up_irq.c up_idle.c \ up_assert.c up_mdelay.c up_udelay.c \ up_schedulesigaction.c up_sigdeliver.c \ diff --git a/nuttx/arch/z80/src/z80/Make.defs b/nuttx/arch/z80/src/z80/Make.defs index 1d4d5c29e..ae5bdf56b 100644 --- a/nuttx/arch/z80/src/z80/Make.defs +++ b/nuttx/arch/z80/src/z80/Make.defs @@ -36,14 +36,13 @@ HEAD_ASRC = z80_head.asm CMN_ASRCS = -CMN_CSRCS = up_initialize.c up_allocateheap.c up_initialstate.c \ - up_createstack.c up_releasestack.c up_interruptcontext.c \ - up_blocktask.c up_unblocktask.c up_exit.c up_releasepending.c \ +CMN_CSRCS = up_initialize.c up_allocateheap.c up_createstack.c \ + up_releasestack.c up_interruptcontext.c up_blocktask.c \ + up_unblocktask.c up_exit.c up_releasepending.c \ up_reprioritizertr.c up_copystate.c up_irq.c up_idle.c \ - up_assert.c up_mdelay.c up_udelay.c \ - up_schedulesigaction.c up_sigdeliver.c \ - up_registerdump.c up_usestack.c + up_assert.c up_mdelay.c up_udelay.c up_schedulesigaction.c \ + up_sigdeliver.c up_registerdump.c up_usestack.c CHIP_ASRCS = z80_saveusercontext.asm z80_restoreusercontext.asm -CHIP_CSRCS = +CHIP_CSRCS = z80_initialstate.c diff --git a/nuttx/arch/z80/src/z80/z80_initialstate.c b/nuttx/arch/z80/src/z80/z80_initialstate.c new file mode 100644 index 000000000..767c7b605 --- /dev/null +++ b/nuttx/arch/z80/src/z80/z80_initialstate.c @@ -0,0 +1,92 @@ +/**************************************************************************** + * arch/z80/src/z80/up_initialstate.c + * + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include + +#include "chip/chip.h" +#include "up_internal.h" +#include "up_arch.h" + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_initial_state + * + * Description: + * A new thread is being started and a new TCB + * has been created. This function is called to initialize + * the processor specific portions of the new TCB. + * + * This function must setup the intial architecture registers + * and/or stack so that execution will begin at tcb->start + * on the next context switch. + * + ****************************************************************************/ + +void up_initial_state(_TCB *tcb) +{ + struct xcptcontext *xcp = &tcb->xcp; + + /* Initialize the initial exception register context structure */ + + memset(xcp, 0, sizeof(struct xcptcontext)); +#ifndef CONFIG_SUPPRESS_INTERRUPTS + xcp->regs[XCPT_I] = Z80_C_FLAG; /* Carry flag will enable interrupts */ +#endif + xcp->regs[XCPT_SP] = (uint16)tcb->adj_stack_ptr; + xcp->regs[XCPT_PC] = (uint16)tcb->start; +} -- cgit v1.2.3