summaryrefslogtreecommitdiff
path: root/nuttx/arch/pjrc-8051
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-14 18:58:21 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-14 18:58:21 +0000
commit78cbcfd2a16c0cf3763173ce0a14d656bede0135 (patch)
tree5fd6d76721ba77adb12c7fc265befb5cf264329f /nuttx/arch/pjrc-8051
parent9daf318dc8fbefa6d41c739fa53baa155b31887f (diff)
downloadpx4-nuttx-78cbcfd2a16c0cf3763173ce0a14d656bede0135.tar.gz
px4-nuttx-78cbcfd2a16c0cf3763173ce0a14d656bede0135.tar.bz2
px4-nuttx-78cbcfd2a16c0cf3763173ce0a14d656bede0135.zip
Add 8052 IRQ test; Fix places where IDLE task could try to wait on semaphoresnuttx-1.1
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@61 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/pjrc-8051')
-rw-r--r--nuttx/arch/pjrc-8051/defconfig4
-rw-r--r--nuttx/arch/pjrc-8051/include/irq.h6
-rw-r--r--nuttx/arch/pjrc-8051/src/Makefile16
-rw-r--r--nuttx/arch/pjrc-8051/src/up_irqtest.c269
-rw-r--r--nuttx/arch/pjrc-8051/src/up_savecontext.c2
-rw-r--r--nuttx/arch/pjrc-8051/src/up_timerisr.c1
6 files changed, 292 insertions, 6 deletions
diff --git a/nuttx/arch/pjrc-8051/defconfig b/nuttx/arch/pjrc-8051/defconfig
index 8e122c065..789bd79c9 100644
--- a/nuttx/arch/pjrc-8051/defconfig
+++ b/nuttx/arch/pjrc-8051/defconfig
@@ -68,10 +68,10 @@ CONFIG_ARCH_LEDS=y
CONFIG_8052_TIMER2=y
CONFIG_ARCH_BRINGUP=y
-CONFIG_FRAME_DUMP=y
+CONFIG_FRAME_DUMP=n
CONFIG_FRAME_DUMP_SHORT=n
CONFIG_SUPPRESS_INTERRUPTS=y
-CONFIG_SWITCH_FRAME_DUMP=y
+CONFIG_SWITCH_FRAME_DUMP=n
CONFIG_INTERRUPT_FRAME_DUMP=n
CONFIG_LED_DEBUG=n
diff --git a/nuttx/arch/pjrc-8051/include/irq.h b/nuttx/arch/pjrc-8051/include/irq.h
index 45891986a..e41ba9687 100644
--- a/nuttx/arch/pjrc-8051/include/irq.h
+++ b/nuttx/arch/pjrc-8051/include/irq.h
@@ -65,7 +65,11 @@
*/
#define IRAM_BASE 0x0000
-#define IRAM_SIZE 0x0100
+#ifdef CONFIG_ARCH_8052
+# define IRAM_SIZE 0x0100
+#else
+# define IRAM_SIZE 0x0080
+#endif
#define STACK_BASE 0x0024
#define STACK_SIZE (IRAM_SIZE - STACK_BASE)
diff --git a/nuttx/arch/pjrc-8051/src/Makefile b/nuttx/arch/pjrc-8051/src/Makefile
index 628d239a2..51eaf269b 100644
--- a/nuttx/arch/pjrc-8051/src/Makefile
+++ b/nuttx/arch/pjrc-8051/src/Makefile
@@ -65,6 +65,11 @@ LINKLIBS =
LDPATHES = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
LDLIBS = $(addprefix -l,$(notdir $(LINKLIBS)))
+TESTSRCS = up_irqtest.c
+TESTOBJS = $(TESTSRCS:.c=$(OBJEXT))
+TESTLINKOBJS = up_head$(OBJEXT)
+TESTEXTRAOBJS = up_savecontext$(OBJEXT) up_restorecontext$(OBJEXT)
+
IRAM_SIZE = 0x100
DEF_STACK_BASE = 0x24
LDFLAGS = --model-large --nostdlib \
@@ -108,7 +113,7 @@ $(ASRCS) $(LINKASRCS): %$(ASMEXT): %.S
$(AOBJS) $(LINKOBJS): $(ASRCS) $(LINKASRCS)
$(AS) $(ASFLAGS) $<
-$(COBJS): %$(OBJEXT): %.c
+$(COBJS) $(TESTOBJS): %$(OBJEXT): %.c
$(CC) -c $(CFLAGS) $< -o $@
# Create a header file that contains addressing information needed by the code
@@ -174,6 +179,15 @@ nuttx$(EXEEXT): pass1.ihx nuttx.ihx
packihx nuttx.ihx > $(TOPDIR)/nuttx$(EXEEXT)
@cp -f nuttx.map $(TOPDIR)/.
+# This target builds a test program to verify interrupt context switching. irqtest is
+# a PHONY target that just sets upt the up_irqtest build correctly
+
+up_irqtest.ihx: $(TESTOBJS)
+ $(CC) $(LDFLAGS) -L. $(SDCCPATH) $(TESTLINKOBJS) $(TESTOBJS) $(TESTEXTRAOBJS) $(SDCCLIBS) -o $@
+
+irqtest:
+ $(MAKE) TOPDIR=../../.. up_irqtest.ihx
+
# Build dependencies
.depend: Makefile up_mem.h $(DEPSRCS)
diff --git a/nuttx/arch/pjrc-8051/src/up_irqtest.c b/nuttx/arch/pjrc-8051/src/up_irqtest.c
new file mode 100644
index 000000000..944e70594
--- /dev/null
+++ b/nuttx/arch/pjrc-8051/src/up_irqtest.c
@@ -0,0 +1,269 @@
+/************************************************************
+ * up_putc.c
+ *
+ * Copyright (C) 2007 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 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 <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/arch.h>
+#include <8052.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+#define up_extint0 ((vector_t)PM2_VECTOR_EXTINT0)
+#define up_timer0 ((vector_t)PM2_VECTOR_TIMER0)
+#define up_extint1 ((vector_t)PM2_VECTOR_EXTINT1)
+#define up_timer1 ((vector_t)PM2_VECTOR_TIMER1)
+#define up_uart ((vector_t)PM2_VECTOR_UART)
+#define up_timer2 ((vector_t)PM2_VECTOR_TIMER2)
+
+/************************************************************
+ * Private Types
+ ************************************************************/
+
+typedef void (*vector_t)(void);
+
+/************************************************************
+ * Public Variables
+ ************************************************************/
+
+boolean g_irqtest;
+ubyte g_irqtos;
+ubyte g_irqregs[REGS_SIZE];
+int g_nirqs;
+FAR struct xcptcontext *g_irqcontext;
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: utility functions
+ ************************************************************/
+
+static void _up_putc(ubyte ch) __naked
+{
+ ch; /* To avoid unreferenced argument warning */
+ _asm
+ mov a, dpl
+ ljmp PM2_ENTRY_COUT
+ _endasm;
+}
+
+void _up_puthex(ubyte hex) __naked
+{
+ hex; /* To avoid unreferenced argument warning */
+ _asm
+ mov a, dpl
+ ljmp PM2_ENTRY_PHEX
+ _endasm;
+}
+
+void _up_puthex16(int hex) __naked
+{
+ hex; /* To avoid unreferenced argument warning */
+ _asm
+ ljmp PM2_ENTRY_PHEX16
+ _endasm;
+}
+
+void _up_putnl(void) __naked
+{
+ _asm
+ ljmp PM2_ENTRY_NEWLINE
+ _endasm;
+}
+
+void _up_puts(__code char *ptr)
+{
+ for (; *ptr; ptr++)
+ {
+ _up_putc(*ptr);
+ }
+}
+
+void _up_delay(ubyte milliseconds) __naked
+{
+ _asm
+ mov r0, dpl
+00001$: mov r1, #230
+00002$: nop
+ nop
+ nop
+ nop
+ nop
+ nop
+ djnz r1, 00002$
+ djnz r0, 00001$
+ ret
+ _endasm;
+}
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: os_start
+ *
+ * Description:
+ * "Fake" OS entry point.
+ *
+ ************************************************************/
+
+void os_start(void)
+{
+ int i;
+
+ /* Disable all interrupts */
+
+ IE = 0;
+
+ /* Then verify all of the interrupt */
+
+ g_irqtest = FALSE;
+
+ up_extint0();
+ up_timer0();
+#ifndef CONFIG_8052_TIMER2
+ up_timer0();
+#endif
+ up_extint1();
+ up_timer1();
+ up_uart();
+ up_timer2();
+
+ /* Now a real interrupt ... */
+
+ /* Configure timer 0 */
+
+ TR0 = 0; /* Make sure timer 0 is stopped */
+ TF0 = 0; /* Clear the overflow flag */
+ TMOD &= 0xF0; /* Set to mode 0 (without changing timer1) */
+ TL0 = 0; /* Clear timer 0 value */
+ TH0 = 0;
+ TR0 = 1; /* Start the timer */
+
+ /* Start timer interrupts */
+
+ g_irqtest = TRUE;
+ g_nirqs = 0;
+ IE = 0x82; /* Enable interrupts */
+
+ /* Wait a about 500 MS */
+
+ _up_delay(500);
+
+ /* Disable the timer */
+
+ TR0 = 0; /* Stop timer 0 */
+ IE = 0; /* Disable interrupts */
+
+ _up_puts("IRQs in 500 MS=");
+ _up_puthex16(g_nirqs);
+ _up_putnl();
+
+ /* end of test */
+
+ _up_puts("Test complete");
+ _up_putnl();
+ for(;;);
+}
+
+/************************************************************
+ * Name: irq_dispatch
+ *
+ * Description:
+ * "Fake" IRQ dispatcher
+ *
+ ***********************************************************/
+
+void irq_dispatch(int irq, FAR void *context)
+{
+ context;
+ if (g_irqtest)
+ {
+ g_nirqs++;
+ }
+ else
+ {
+ _up_puts("Dispatch IRQ=");
+ _up_puthex(irq);
+ _up_putnl();
+ }
+}
+
+/************************************************************
+ * Name: up_dumpstack / up_dumpframe
+ *
+ * Description:
+ * "Fake" debug routines if needed.
+ *
+ ************************************************************/
+
+void up_dumpstack(void)
+{
+}
+
+void up_dumpframe(FAR struct xcptcontext *context)
+{
+}
+
+/************************************************************
+ * Name: up_ledinit, up_ledon, up_ledoff
+ *
+ * Description:
+ * "Fake" LED routines if needed
+ *
+ ************************************************************/
+
+void up_ledinit(void)
+{
+}
+
+void up_ledon(ubyte led)
+{
+ led;
+}
+
+void up_ledoff(ubyte led)
+{
+ led;
+}
diff --git a/nuttx/arch/pjrc-8051/src/up_savecontext.c b/nuttx/arch/pjrc-8051/src/up_savecontext.c
index 83310534c..1c4b26898 100644
--- a/nuttx/arch/pjrc-8051/src/up_savecontext.c
+++ b/nuttx/arch/pjrc-8051/src/up_savecontext.c
@@ -274,7 +274,7 @@ ubyte up_savecontext(FAR struct xcptcontext *context) _naked
/* Push the top of frame stack pointer. We need to
* decrement the current SP value by three to account
- * for dpst+IE on the stack above the end of the frame.
+ * for dptr+IE on the stack above the end of the frame.
*/
mov a, sp
diff --git a/nuttx/arch/pjrc-8051/src/up_timerisr.c b/nuttx/arch/pjrc-8051/src/up_timerisr.c
index 8f139d89a..c4575273b 100644
--- a/nuttx/arch/pjrc-8051/src/up_timerisr.c
+++ b/nuttx/arch/pjrc-8051/src/up_timerisr.c
@@ -139,7 +139,6 @@ void up_timerinit(void)
TR0 = 1; /* Start the timer */
up_enable_irq(TIMER0_IRQ);
-# warning "No support for timer 0 as the system timer"
#endif
}