From 4dce3ece605863986f69cad49477441805882ddd Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Mar 2007 22:44:29 +0000 Subject: 8051 is getting closer. Still have to setup timer and uart. git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@32 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/Documentation/NuttX.html | 4 +- nuttx/arch/README.txt | 34 ++++++++++ nuttx/arch/c5471/src/up_irq.c | 2 +- nuttx/arch/pjrc-8051/src/Makefile | 3 +- nuttx/arch/pjrc-8051/src/up_blocktask.c | 11 ++-- nuttx/arch/pjrc-8051/src/up_head.S | 34 +++++++--- nuttx/arch/pjrc-8051/src/up_initialize.c | 14 +++- nuttx/arch/pjrc-8051/src/up_internal.h | 14 +++- nuttx/arch/pjrc-8051/src/up_interruptcontext.c | 2 +- nuttx/arch/pjrc-8051/src/up_irq.c | 2 +- nuttx/arch/pjrc-8051/src/up_releasepending.c | 11 ++-- nuttx/arch/pjrc-8051/src/up_reprioritizertr.c | 12 ++-- nuttx/arch/pjrc-8051/src/up_restorecontext.c | 48 +++++++++++++- nuttx/arch/pjrc-8051/src/up_savecontext.c | 38 ++++++++++- nuttx/arch/pjrc-8051/src/up_timerisr.c | 91 ++++++++++++++++++++++++++ nuttx/arch/pjrc-8051/src/up_unblocktask.c | 13 ++-- nuttx/sched/sched_processtimer.c | 2 + 17 files changed, 282 insertions(+), 53 deletions(-) create mode 100644 nuttx/arch/pjrc-8051/src/up_timerisr.c diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index cb2fcdda8..13f2d7f5b 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -33,10 +33,10 @@
  • 8051 Microcontroller. This port uses the PJRC 87C52 development system and the SDCC toolchain. - This port will require a few more weeks before it is ready for time prime.
  • + This port will require a few more weeks before it is ready for prime time.
  • Motorola (Freescale) MC68HC908GP32 Microcontroller. Using the Axiom CMS8GP32 development board. - This is next in the queue.
  • Other ports. I also have partial ports for the TI TMS320DM270 and for MIPS. diff --git a/nuttx/arch/README.txt b/nuttx/arch/README.txt index 629431a45..c01215963 100644 --- a/nuttx/arch/README.txt +++ b/nuttx/arch/README.txt @@ -1,5 +1,15 @@ Architecture-Specific Code ^^^^^^^^^^^^^^^^^^^^^^^^^^ +Table of Contents +^^^^^^^^^^^^^^^^^ + + o Architecture-Specific Code + o Summary of Files + o Supported Architectures + o Configuring NuttX + +Architecture-Specific Code +^^^^^^^^^^^^^^^^^^^^^^^^^^ The file include/nuttx/arch.h identifies all of the APIs that must be provided by the architecture specific logic. (It also includes @@ -192,6 +202,30 @@ src/Makefile the final link with libup.a and other system archives to generate the final executable. +Supported Architectures +^^^^^^^^^^^^^^^^^^^^^^^ + +arch/c5471 + TI TMS320C5471 (also called TMS320DM180). + NuttX operates on the ARM7 of this dual core processor. This port + uses the Spectrum Digital evaluation board with a GNU arm-elf toolchain*. + This port is in progress and partially functional (However, my board + is dead at the moment so it will be awhile before I fix it). + +arch/pjrc-8051 + 8051 Microcontroller. This port uses the PJRC 87C52 development system + and the SDCC toolchain. This port is not quite ready for prime time. + +arch/axiom-mc68 + For the Motorola (Freescale) MC68HC908GP32 Microcontroller using the + Axiom CMS8GP32 development board. This has not yet been checked-in. + +arch/sim + x86 Linux Simulation. Fully functional. + +Other ports for the for the TI TMS320DM270 and for MIPS are in various states +of progress + Configuring NuttX ^^^^^^^^^^^^^^^^^ diff --git a/nuttx/arch/c5471/src/up_irq.c b/nuttx/arch/c5471/src/up_irq.c index 9c05bc91b..32c350d48 100644 --- a/nuttx/arch/c5471/src/up_irq.c +++ b/nuttx/arch/c5471/src/up_irq.c @@ -147,7 +147,7 @@ static inline void up_vectorinitialize(void) ************************************************************/ /************************************************************ - * Name: irq_initialize + * Name: up_irqinitialize ************************************************************/ void up_irqinitialize(void) diff --git a/nuttx/arch/pjrc-8051/src/Makefile b/nuttx/arch/pjrc-8051/src/Makefile index 5adb30284..1ba57af9c 100644 --- a/nuttx/arch/pjrc-8051/src/Makefile +++ b/nuttx/arch/pjrc-8051/src/Makefile @@ -47,7 +47,8 @@ CSRCS = up_initialize.c up_idle.c up_interruptcontext.c \ up_initialstate.c up_unblocktask.c up_blocktask.c \ up_releasepending.c up_reprioritizertr.c \ up_exit.c up_assert.c up_allocateheap.c \ - up_irq.c up_savecontext.c up_restorecontext.c up_putc.c + up_irq.c up_savecontext.c up_restorecontext.c \ + up_timerisr.c up_putc.c COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(SSRCS) $(CSRCS) OBJS = $(AOBJS) $(COBJS) diff --git a/nuttx/arch/pjrc-8051/src/up_blocktask.c b/nuttx/arch/pjrc-8051/src/up_blocktask.c index 4a15a817a..8a74d0ef0 100644 --- a/nuttx/arch/pjrc-8051/src/up_blocktask.c +++ b/nuttx/arch/pjrc-8051/src/up_blocktask.c @@ -125,27 +125,24 @@ void up_block_task(FAR _TCB *tcb, tstate_t task_state) { /* Are we in an interrupt handler? */ - if (g_ininterrupt) + if (g_irqtos) { -#if 0 -# warning REVISIT /* Yes, then we have to do things differently. * Just copy the current registers into the OLD rtcb. */ - up_copystate(&tcb->xcp, current_regs); + up_savestack(&tcb->xcp); /* Restore the exception context of the rtcb at the (new) head * of the g_readytorun task list. */ - rtcb = (_TCB*)g_readytorun.head; + rtcb = (FAR _TCB*)g_readytorun.head; dbg("New Active Task TCB=%p\n", rtcb); /* Then switch contexts */ - up_copystate(current_regs, &tcb->xcp); -#endif + up_restorestack(&tcb->xcp); } /* Copy the user C context into the TCB at the (old) head of the diff --git a/nuttx/arch/pjrc-8051/src/up_head.S b/nuttx/arch/pjrc-8051/src/up_head.S index ff2f3a5c9..4aecda48a 100644 --- a/nuttx/arch/pjrc-8051/src/up_head.S +++ b/nuttx/arch/pjrc-8051/src/up_head.S @@ -54,7 +54,7 @@ * Public Data ************************************************************/ - .globl _g_ininterrupt + .globl _g_irqtos /************************************************************ * Public Functions @@ -174,6 +174,11 @@ _up_interrupt: clr psw push _bp + /* Mark that we are in an interrupt */ + + mov dptr, #_g_irqtos + movx @dptr, a + /* Now call void irq_dispatch(int irq, FAR void *context) * * First, create the first argument as (int)irqno @@ -184,18 +189,31 @@ _up_interrupt: /* Create the second argument (void *context) on the stack */ - push sp - clr a - push acc + push sp + clr a + push acc - /* Then dispatch the IRQ */ + /* Then dispatch the IRQ. On return, the stack is off by + * by two because the above two pushes, but we fix that by + * reloading sp from g_irqtos below. + */ lcall _irq_dispatch - /* Clean up the stack */ + /* Get the stackpointer. This might be the stack pointer that + * we increment above or it might be the stack pointer of a + * new task if the a context switch happened during the + * interrupt handling. + */ + + mov dptr, #_g_irqtos + movx a, @dptr + mov sp, a + + /* Indicate that we are no longer in an interrupt */ - dec sp - dec sp + clr a + movx @dptr, a /* Then return from the interrupt */ diff --git a/nuttx/arch/pjrc-8051/src/up_initialize.c b/nuttx/arch/pjrc-8051/src/up_initialize.c index 20d2e8122..ae297d585 100644 --- a/nuttx/arch/pjrc-8051/src/up_initialize.c +++ b/nuttx/arch/pjrc-8051/src/up_initialize.c @@ -51,9 +51,13 @@ * Private Data ************************************************************/ -/* TRUE if processing an interrupt */ +/* This is the top of the stack containing the interrupt stack frame. It + * is set when processing an interrupt. It is also cleared when the + * interrupt returns so this can also be used like a boolean indication that + * we are in an interrupt. + */ -boolean g_ininterrupt; +ubyte g_irqtos; /************************************************************ * Private Functions @@ -87,12 +91,16 @@ void up_initialize(void) { /* Initialize global variables */ - g_ininterrupt = FALSE; + g_irqtos = 0; /* Initialize the interrupt subsystem */ + up_irqinitialize(); + /* Initialize the system timer interrupt */ + up_timerinit(); + /* Initialize the serial console support */ } diff --git a/nuttx/arch/pjrc-8051/src/up_internal.h b/nuttx/arch/pjrc-8051/src/up_internal.h index 27a83585f..f471c1b83 100644 --- a/nuttx/arch/pjrc-8051/src/up_internal.h +++ b/nuttx/arch/pjrc-8051/src/up_internal.h @@ -106,9 +106,13 @@ #ifndef __ASSEMBLY__ -/* TRUE if processing an interrupt */ +/* This is the top of the stack containing the interrupt stack frame. It + * is set when processing an interrupt. It is also cleared when the + * interrupt returns so this can also be used like a boolean indication that + * we are in an interrupt. + */ -extern boolean g_ininterrupt; +extern ubyte g_irqtos; #endif /* __ASSEMBLY */ @@ -118,8 +122,12 @@ extern boolean g_ininterrupt; #ifndef __ASSEMBLY__ -extern ubyte up_savecontext(FAR struct xcptcontext *context); +extern void up_irqinitialize(void); extern void up_restorecontext(FAR struct xcptcontext *context); +extern void up_restorestack(FAR struct xcptcontext *context); +extern ubyte up_savecontext(FAR struct xcptcontext *context); +extern void up_savestack(FAR struct xcptcontext *context); +extern void up_timerinit(void); #endif /* __ASSEMBLY */ #endif /* __ARCH_UP_INTERNAL_H */ diff --git a/nuttx/arch/pjrc-8051/src/up_interruptcontext.c b/nuttx/arch/pjrc-8051/src/up_interruptcontext.c index 2743ed7b0..26b5ad2ae 100644 --- a/nuttx/arch/pjrc-8051/src/up_interruptcontext.c +++ b/nuttx/arch/pjrc-8051/src/up_interruptcontext.c @@ -64,5 +64,5 @@ boolean up_interrupt_context(void) { - return g_ininterrupt; + return g_irqtos != 0; } diff --git a/nuttx/arch/pjrc-8051/src/up_irq.c b/nuttx/arch/pjrc-8051/src/up_irq.c index c524fe3e7..d3a5ffdd2 100644 --- a/nuttx/arch/pjrc-8051/src/up_irq.c +++ b/nuttx/arch/pjrc-8051/src/up_irq.c @@ -154,4 +154,4 @@ void up_enable_irq(int irq) { _up_enable_irq(~(1 << irq)); } -} +} \ No newline at end of file diff --git a/nuttx/arch/pjrc-8051/src/up_releasepending.c b/nuttx/arch/pjrc-8051/src/up_releasepending.c index 99c20ec23..64650bc89 100644 --- a/nuttx/arch/pjrc-8051/src/up_releasepending.c +++ b/nuttx/arch/pjrc-8051/src/up_releasepending.c @@ -88,27 +88,24 @@ void up_release_pending(void) * interrupt context: */ - if (g_ininterrupt) + if (g_irqtos) { -#if 0 -# warning REVISIT /* Yes, then we have to do things differently. * Just copy the current registers into the OLD rtcb. */ - up_copystate(&tcb->xcp, current_regs); + up_savestack(&rtcb->xcp); /* Restore the exception context of the rtcb at the (new) head * of the g_readytorun task list. */ - rtcb = (_TCB*)g_readytorun.head; + rtcb = (FAR _TCB*)g_readytorun.head; dbg("New Active Task TCB=%p\n", rtcb); /* Then switch contexts */ - up_copystate(current_regs, &tcb->xcp); -#endif + up_restorestack(&rtcb->xcp); } /* Copy the exception context into the TCB of the task that diff --git a/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c b/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c index dbb9db3c4..39c1cf508 100644 --- a/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c +++ b/nuttx/arch/pjrc-8051/src/up_reprioritizertr.c @@ -136,28 +136,26 @@ void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority) /* Are we in an interrupt handler? */ - if (g_ininterrupt) + if (g_irqtos) { -#if 0 -# warning REVISIT /* Yes, then we have to do things differently. * Just copy the current registers into the OLD rtcb. */ - up_copystate(&tcb->xcp, current_regs); + up_savestack(&tcb->xcp); /* Restore the exception context of the rtcb at the (new) head * of the g_readytorun task list. */ - rtcb = (_TCB*)g_readytorun.head; + rtcb = (FAR _TCB*)g_readytorun.head; dbg("New Active Task TCB=%p\n", rtcb); /* Then switch contexts */ - up_copystate(current_regs, &tcb->xcp); -#endif + up_restorestack(&tcb->xcp); } + /* Copy the exception context into the TCB at the (old) head of the * g_readytorun Task list. if up_savecontext returns a non-zero * value, then this is really the previously running task restarting! diff --git a/nuttx/arch/pjrc-8051/src/up_restorecontext.c b/nuttx/arch/pjrc-8051/src/up_restorecontext.c index d1d095d91..429b95445 100644 --- a/nuttx/arch/pjrc-8051/src/up_restorecontext.c +++ b/nuttx/arch/pjrc-8051/src/up_restorecontext.c @@ -134,8 +134,8 @@ static void up_popcontext(ubyte newsp) __naked void up_restorecontext(FAR struct xcptcontext *context) { - int nbytes = context->nbytes; - FAR ubyte *src = context->stack; + int nbytes = context->nbytes; + FAR ubyte *src = context->stack; FAR ubyte *dest = (FAR ubyte*)STACK_BASE; /* Interrupts should be disabled for the following. up_popcontext() will @@ -149,8 +149,50 @@ void up_restorecontext(FAR struct xcptcontext *context) *src++ = *dest++; } - /* Then return to the restored context */ + /* Then return to the restored context (probably restoring interrupts) */ up_popcontext(context->nbytes + (STACK_BASE-1)); } +/************************************************************************** + * Name: up_restorestack + * + * Description: + * Restore the entire interrupt stack contents in the provided context + * structure. + * + * Inputs: + * context - the context structure from which to restore the stack info + * + * Return: + * None + * + * Assumptions: + * - We are in an interrupt handler with g_irqtos set + * - Interrupts are disabled + * + **************************************************************************/ + +void up_restorestack(FAR struct xcptcontext *context) +{ + /* Now copy the current stack frame (including the saved execution + * context) from internal RAM to XRAM. + */ + + ubyte nbytes = context->nbytes; + FAR ubyte *src = context->stack; + FAR ubyte *dest = (FAR ubyte*)STACK_BASE; + + while (nbytes--) + { + *dest++ = *src++; + } + + /* We are still in the interrupt context, but the size of the interrupt + * stack has changed. + */ + + g_irqtos = context->nbytes + (STACK_BASE-1); +} + + diff --git a/nuttx/arch/pjrc-8051/src/up_savecontext.c b/nuttx/arch/pjrc-8051/src/up_savecontext.c index 1405fce4d..b8b796f07 100644 --- a/nuttx/arch/pjrc-8051/src/up_savecontext.c +++ b/nuttx/arch/pjrc-8051/src/up_savecontext.c @@ -126,7 +126,7 @@ static ubyte up_pushcontext(void) __naked * Inputs: * context - the context structure in which to save the stack info * - * Return + * Return: * 0 = Normal state save return * 1 = This is the matching return from up_restorecontext() * @@ -165,3 +165,39 @@ ubyte up_savecontext(FAR struct xcptcontext *context) irqrestore(flags); return 1; } + +/************************************************************************** + * Name: up_savestack + * + * Description: + * Save the entire interrupt stack contents in the provided context + * structure. + * + * Inputs: + * context - the context structure in which to save the stack info + * + * Return: + * None + * + * Assumptions: + * - We are in an interrupt handler with g_irqtos set + * - Interrupts are disabled + * + **************************************************************************/ + +void up_savestack(FAR struct xcptcontext *context) +{ + /* Now copy the current stack frame (including the saved execution + * context) from internal RAM to XRAM. + */ + + ubyte nbytes = g_irqtos - (STACK_BASE-1); + FAR ubyte *src = (FAR ubyte*)STACK_BASE; + FAR ubyte *dest = context->stack; + + context->nbytes = nbytes; + while (nbytes--) + { + *dest++ = *src++; + } +} diff --git a/nuttx/arch/pjrc-8051/src/up_timerisr.c b/nuttx/arch/pjrc-8051/src/up_timerisr.c new file mode 100644 index 000000000..a270da15c --- /dev/null +++ b/nuttx/arch/pjrc-8051/src/up_timerisr.c @@ -0,0 +1,91 @@ +/************************************************************ + * up_timerisr.c + * + * Copyright (C) 2007 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 Gregory Nutt 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 "clock_internal.h" +#include "up_internal.h" + +/************************************************************ + * Definitions + ************************************************************/ + +/************************************************************ + * Private Types + ************************************************************/ + +/************************************************************ + * Private Function Prototypes + ************************************************************/ + +/************************************************************ + * Global Functions + ************************************************************/ + +/************************************************************ + * Function: timer_isr + * + * Description: + * The timer ISR will perform a variety of services for + * various portions of the systems. + * + ************************************************************/ + +int up_timerisr(int irq, FAR ubyte *frame) +{ + /* Process timer interrupt */ + + sched_process_timer(); + return 0; +} + +void up_timerinit(void) +{ + up_disable_irq(TIMER2_IRQ); + +#warning "Missing TIMER2 setup logic here" + + /* Attach and enable the timer interrupt */ + + irq_attach(TIMER2_IRQ, (xcpt_t)up_timerisr); + up_enable_irq(TIMER2_IRQ); +} + diff --git a/nuttx/arch/pjrc-8051/src/up_unblocktask.c b/nuttx/arch/pjrc-8051/src/up_unblocktask.c index 1c9494f36..1db56f3b7 100644 --- a/nuttx/arch/pjrc-8051/src/up_unblocktask.c +++ b/nuttx/arch/pjrc-8051/src/up_unblocktask.c @@ -116,27 +116,24 @@ void up_unblock_task(FAR _TCB *tcb) * Are we in an interrupt handler? */ - if (g_ininterrupt) + if (g_irqtos) { -#if 0 -# warning REVISIT /* Yes, then we have to do things differently. - * Just copy the current registers into the OLD rtcb. + * Just copy the current stack into the OLD rtcb. */ - up_copystate(&tcb->xcp, current_regs); + up_savestack(&rtcb->xcp); /* Restore the exception context of the rtcb at the (new) head * of the g_readytorun task list. */ - rtcb = (_TCB*)g_readytorun.head; + rtcb = (FAR _TCB*)g_readytorun.head; dbg("New Active Task TCB=%p\n", rtcb); /* Then switch contexts */ - up_copystate(current_regs, &tcb->xcp); -#endif + up_restorestack(&rtcb->xcp); } /* We are not in an interrupt andler. Copy the user C context diff --git a/nuttx/sched/sched_processtimer.c b/nuttx/sched/sched_processtimer.c index eff439a5b..c6ee8fdb8 100644 --- a/nuttx/sched/sched_processtimer.c +++ b/nuttx/sched/sched_processtimer.c @@ -162,12 +162,14 @@ void sched_process_timer(void) { /* Increment the system time (if in the link) */ +#ifndef CONFIG_DISABLE_CLOCK #ifdef CONFIG_HAVE_WEAKFUNCTIONS if (clock_timer != NULL) #endif { clock_timer(); } +#endif /* Process watchdogs (if in the link) */ -- cgit v1.2.3