From f0233026fc2379ba8630a35f3a2525eac1e0bf66 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 19 May 2009 17:16:17 +0000 Subject: Move ARM and Cortex files to separate directories git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1795 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/Makefile | 16 +- nuttx/arch/arm/src/arm/arm.h | 250 +++++++++++ nuttx/arch/arm/src/arm/up_assert.c | 310 +++++++++++++ nuttx/arch/arm/src/arm/up_cache.S | 74 ++++ nuttx/arch/arm/src/arm/up_copystate.c | 82 ++++ nuttx/arch/arm/src/arm/up_dataabort.c | 81 ++++ nuttx/arch/arm/src/arm/up_doirq.c | 104 +++++ nuttx/arch/arm/src/arm/up_fullcontextrestore.S | 117 +++++ nuttx/arch/arm/src/arm/up_head.S | 369 ++++++++++++++++ nuttx/arch/arm/src/arm/up_initialstate.c | 103 +++++ nuttx/arch/arm/src/arm/up_nommuhead.S | 165 +++++++ nuttx/arch/arm/src/arm/up_prefetchabort.c | 81 ++++ nuttx/arch/arm/src/arm/up_saveusercontext.S | 119 +++++ nuttx/arch/arm/src/arm/up_schedulesigaction.c | 203 +++++++++ nuttx/arch/arm/src/arm/up_sigdeliver.c | 143 ++++++ nuttx/arch/arm/src/arm/up_syscall.c | 94 ++++ nuttx/arch/arm/src/arm/up_undefinedinsn.c | 81 ++++ nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S | 83 ++++ nuttx/arch/arm/src/arm/up_vectors.S | 440 ++++++++++++++++++ nuttx/arch/arm/src/arm/up_vectortab.S | 103 +++++ nuttx/arch/arm/src/common/arm.h | 250 ----------- nuttx/arch/arm/src/common/cortexm3_nvic.h | 489 --------------------- nuttx/arch/arm/src/common/cortexm3_psr.h | 91 ---- nuttx/arch/arm/src/common/up_arch.h | 1 - nuttx/arch/arm/src/common/up_assert.c | 327 -------------- nuttx/arch/arm/src/common/up_cache.S | 74 ---- nuttx/arch/arm/src/common/up_copystate.c | 90 ---- nuttx/arch/arm/src/common/up_dataabort.c | 81 ---- nuttx/arch/arm/src/common/up_doirq.c | 119 ----- nuttx/arch/arm/src/common/up_fullcontextrestore.S | 117 ----- nuttx/arch/arm/src/common/up_head.S | 369 ---------------- nuttx/arch/arm/src/common/up_initialstate.c | 122 ----- nuttx/arch/arm/src/common/up_internal.h | 4 +- nuttx/arch/arm/src/common/up_nommuhead.S | 165 ------- nuttx/arch/arm/src/common/up_prefetchabort.c | 81 ---- nuttx/arch/arm/src/common/up_saveusercontext.S | 119 ----- nuttx/arch/arm/src/common/up_schedulesigaction.c | 223 ---------- nuttx/arch/arm/src/common/up_sigdeliver.c | 154 ------- nuttx/arch/arm/src/common/up_syscall.c | 94 ---- nuttx/arch/arm/src/common/up_undefinedinsn.c | 81 ---- nuttx/arch/arm/src/common/up_vectoraddrexcptn.S | 83 ---- nuttx/arch/arm/src/common/up_vectors.S | 440 ------------------ nuttx/arch/arm/src/common/up_vectortab.S | 103 ----- nuttx/arch/arm/src/cortexm3/nvic.h | 489 +++++++++++++++++++++ nuttx/arch/arm/src/cortexm3/psr.h | 91 ++++ nuttx/arch/arm/src/cortexm3/up_assert.c | 311 +++++++++++++ nuttx/arch/arm/src/cortexm3/up_copystate.c | 86 ++++ nuttx/arch/arm/src/cortexm3/up_doirq.c | 113 +++++ nuttx/arch/arm/src/cortexm3/up_initialstate.c | 106 +++++ nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c | 208 +++++++++ nuttx/arch/arm/src/cortexm3/up_sigdeliver.c | 144 ++++++ nuttx/arch/arm/src/lm3s/Make.defs | 9 +- nuttx/arch/arm/src/lm3s/chip.h | 1 - nuttx/arch/arm/src/lm3s/lm3s_context.S | 2 +- nuttx/arch/arm/src/lm3s/lm3s_hardfault.c | 2 +- nuttx/arch/arm/src/lm3s/lm3s_irq.c | 1 + nuttx/arch/arm/src/lm3s/lm3s_timerisr.c | 1 + 57 files changed, 4572 insertions(+), 3687 deletions(-) create mode 100644 nuttx/arch/arm/src/arm/arm.h create mode 100644 nuttx/arch/arm/src/arm/up_assert.c create mode 100644 nuttx/arch/arm/src/arm/up_cache.S create mode 100644 nuttx/arch/arm/src/arm/up_copystate.c create mode 100644 nuttx/arch/arm/src/arm/up_dataabort.c create mode 100644 nuttx/arch/arm/src/arm/up_doirq.c create mode 100644 nuttx/arch/arm/src/arm/up_fullcontextrestore.S create mode 100644 nuttx/arch/arm/src/arm/up_head.S create mode 100644 nuttx/arch/arm/src/arm/up_initialstate.c create mode 100644 nuttx/arch/arm/src/arm/up_nommuhead.S create mode 100644 nuttx/arch/arm/src/arm/up_prefetchabort.c create mode 100644 nuttx/arch/arm/src/arm/up_saveusercontext.S create mode 100644 nuttx/arch/arm/src/arm/up_schedulesigaction.c create mode 100644 nuttx/arch/arm/src/arm/up_sigdeliver.c create mode 100644 nuttx/arch/arm/src/arm/up_syscall.c create mode 100644 nuttx/arch/arm/src/arm/up_undefinedinsn.c create mode 100644 nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S create mode 100644 nuttx/arch/arm/src/arm/up_vectors.S create mode 100644 nuttx/arch/arm/src/arm/up_vectortab.S delete mode 100644 nuttx/arch/arm/src/common/arm.h delete mode 100644 nuttx/arch/arm/src/common/cortexm3_nvic.h delete mode 100644 nuttx/arch/arm/src/common/cortexm3_psr.h delete mode 100644 nuttx/arch/arm/src/common/up_assert.c delete mode 100644 nuttx/arch/arm/src/common/up_cache.S delete mode 100644 nuttx/arch/arm/src/common/up_copystate.c delete mode 100644 nuttx/arch/arm/src/common/up_dataabort.c delete mode 100644 nuttx/arch/arm/src/common/up_doirq.c delete mode 100644 nuttx/arch/arm/src/common/up_fullcontextrestore.S delete mode 100644 nuttx/arch/arm/src/common/up_head.S delete mode 100644 nuttx/arch/arm/src/common/up_initialstate.c delete mode 100644 nuttx/arch/arm/src/common/up_nommuhead.S delete mode 100644 nuttx/arch/arm/src/common/up_prefetchabort.c delete mode 100644 nuttx/arch/arm/src/common/up_saveusercontext.S delete mode 100644 nuttx/arch/arm/src/common/up_schedulesigaction.c delete mode 100644 nuttx/arch/arm/src/common/up_sigdeliver.c delete mode 100644 nuttx/arch/arm/src/common/up_syscall.c delete mode 100644 nuttx/arch/arm/src/common/up_undefinedinsn.c delete mode 100644 nuttx/arch/arm/src/common/up_vectoraddrexcptn.S delete mode 100644 nuttx/arch/arm/src/common/up_vectors.S delete mode 100644 nuttx/arch/arm/src/common/up_vectortab.S create mode 100644 nuttx/arch/arm/src/cortexm3/nvic.h create mode 100644 nuttx/arch/arm/src/cortexm3/psr.h create mode 100644 nuttx/arch/arm/src/cortexm3/up_assert.c create mode 100644 nuttx/arch/arm/src/cortexm3/up_copystate.c create mode 100644 nuttx/arch/arm/src/cortexm3/up_doirq.c create mode 100644 nuttx/arch/arm/src/cortexm3/up_initialstate.c create mode 100644 nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c create mode 100644 nuttx/arch/arm/src/cortexm3/up_sigdeliver.c (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile index 29e64f299..cf85c741b 100644 --- a/nuttx/arch/arm/src/Makefile +++ b/nuttx/arch/arm/src/Makefile @@ -1,7 +1,7 @@ ############################################################################ # arch/arm/src/Makefile # -# Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -37,7 +37,14 @@ -include chip/Make.defs ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src -CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(TOPDIR)/sched +ifeq ($(CONFIG_ARCH_CORTEXM3),y) +ARCH_SUBDIR = cortexm3 +else +ARCH_SUBDIR = arm +endif + +CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \ + -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched HEAD_AOBJ = $(HEAD_ASRC:.S=$(OBJEXT)) @@ -61,7 +68,7 @@ BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board LIBGCC = ${shell $(CC) -print-libgcc-file-name} -VPATH = chip:common +VPATH = chip:common:$(ARCH_SUBDIR) all: $(HEAD_OBJ) libarch$(LIBEXT) @@ -101,7 +108,8 @@ endif @if [ -e board/Makefile ]; then \ $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \ fi - @$(MKDEP) --dep-path chip --dep-path common $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \ + $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ depend: .depend diff --git a/nuttx/arch/arm/src/arm/arm.h b/nuttx/arch/arm/src/arm/arm.h new file mode 100644 index 000000000..aa737ff96 --- /dev/null +++ b/nuttx/arch/arm/src/arm/arm.h @@ -0,0 +1,250 @@ +/************************************************************************************ + * arch/arm/src/arm/arm.h + * + * Copyright (C) 2007-2009 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_COMMON_ARM_H +#define __ARCH_ARM_SRC_COMMON_ARM_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +# include +#endif + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +#undef CONFIG_ALIGNMENT_TRAP +#undef CONFIG_DCACHE_WRITETHROUGH +#undef CONFIG_CACHE_ROUND_ROBIN +#undef CONFIG_DCACHE_DISABLE +#undef CONFIG_ICACHE_DISABLE + +/* ARM9EJS **************************************************************************/ + +/* PSR bits */ + +#define MODE_MASK 0x0000001f +#define USR26_MODE 0x00000000 +#define FIQ26_MODE 0x00000001 +#define IRQ26_MODE 0x00000002 +#define SVC26_MODE 0x00000003 +#define USR_MODE 0x00000010 +#define FIQ_MODE 0x00000011 +#define IRQ_MODE 0x00000012 +#define SVC_MODE 0x00000013 +#define ABT_MODE 0x00000017 +#define UND_MODE 0x0000001b +#define MODE32_BIT 0x00000010 +#define SYSTEM_MODE 0x0000001f +#define PSR_T_BIT 0x00000020 +#define PSR_F_BIT 0x00000040 +#define PSR_I_BIT 0x00000080 +#define PSR_J_BIT 0x01000000 +#define PSR_Q_BIT 0x08000000 +#define PSR_V_BIT 0x10000000 +#define PSR_C_BIT 0x20000000 +#define PSR_Z_BIT 0x40000000 +#define PSR_N_BIT 0x80000000 + +/* CR1 bits (CP#15 CR1) */ + +#define CR_M 0x00000001 /* MMU enable */ +#define CR_A 0x00000002 /* Alignment abort enable */ +#define CR_C 0x00000004 /* Dcache enable */ +#define CR_W 0x00000008 /* Write buffer enable */ +#define CR_P 0x00000010 /* 32-bit exception handler */ +#define CR_D 0x00000020 /* 32-bit data address range */ +#define CR_L 0x00000040 /* Implementation defined */ +#define CR_B 0x00000080 /* Big endian */ +#define CR_S 0x00000100 /* System MMU protection */ +#define CR_R 0x00000200 /* ROM MMU protection */ +#define CR_F 0x00000400 /* Implementation defined */ +#define CR_Z 0x00000800 /* Implementation defined */ +#define CR_I 0x00001000 /* Icache enable */ +#define CR_V 0x00002000 /* Vectors relocated to 0xffff0000 */ +#define CR_RR 0x00004000 /* Round Robin cache replacement */ +#define CR_L4 0x00008000 /* LDR pc can set T bit */ +#define CR_DT 0x00010000 +#define CR_IT 0x00040000 +#define CR_ST 0x00080000 +#define CR_FI 0x00200000 /* Fast interrupt (lower latency mode) */ +#define CR_U 0x00400000 /* Unaligned access operation */ +#define CR_XP 0x00800000 /* Extended page tables */ +#define CR_VE 0x01000000 /* Vectored interrupts */ + +/* Hardware page table definitions. + * + * Level 1 Descriptor (PMD) + * + * Common definitions. + */ + +#define PMD_TYPE_MASK 0x00000003 /* Bits 1:0: Type of descriptor */ +#define PMD_TYPE_FAULT 0x00000000 +#define PMD_TYPE_COARSE 0x00000001 +#define PMD_TYPE_SECT 0x00000002 +#define PMD_TYPE_FINE 0x00000003 + /* Bits 3:2: Depends on descriptor */ +#define PMD_BIT4 0x00000010 /* Bit 4: Must be one */ +#define PMD_DOMAIN_MASK 0x000001e0 /* Bits 8:5: Domain control bits */ +#define PMD_DOMAIN(x) ((x) << 5) +#define PMD_PROTECTION 0x00000200 /* Bit 9: v5 only */ + /* Bits 31:10: Depend on descriptor */ + +/* Level 1 Section Descriptor. Section descriptors allow fast, single + * level mapping between 1Mb address regions. + */ + /* Bits 1:0: Type of mapping */ +#define PMD_SECT_BUFFERABLE 0x00000004 /* Bit 2: 1=bufferable */ +#define PMD_SECT_CACHEABLE 0x00000008 /* Bit 3: 1=cacheable */ + /* Bit 4: Common, must be one */ + /* Bits 8:5: Common domain control */ + /* Bit 9: Common protection */ +#define PMD_SECT_AP_MASK 0x00000c00 /* Bits 11:10: Access permission */ +#define PMD_SECT_AP_WRITE 0x00000400 +#define PMD_SECT_AP_READ 0x00000800 + /* Bits 19:20: Should be zero */ +#define PMD_SECT_TEX_MASK 0xfff00000 /* Bits 31:20: v5, Physical page */ +#define PMD_SECT_APX 0x00008000 /* Bit 15: v6 only */ +#define PMD_SECT_S 0x00010000 /* Bit 16: v6 only */ +#define PMD_SECT_nG 0x00020000 /* Bit 17: v6 only */ + +#define PMD_SECT_UNCACHED (0) +#define PMD_SECT_BUFFERED (PMD_SECT_BUFFERABLE) +#define PMD_SECT_WT (PMD_SECT_CACHEABLE) +#define PMD_SECT_WB (PMD_SECT_CACHEABLE|PMD_SECT_BUFFERABLE) +#define PMD_SECT_MINICACHE (PMD_SECT_TEX(1)|PMD_SECT_CACHEABLE) +#define PMD_SECT_WBWA (PMD_SECT_TEX(1)|PMD_SECT_CACHEABLE|PMD_SECT_BUFFERABLE) + +/* Level 1 Coarse Table Descriptor. Coarse Table Descriptors support + * two level mapping between 16Kb memory regions. + */ + /* Bits 1:0: Type of mapping */ + /* Bits 3:2: Should be zero */ + /* Bit 4: Common, must be one */ + /* Bits 8:5: Common domain control */ + /* Bits 9: Should be zero */ +#define PMD_COARSE_TEX_MASK 0xfffffc00 /* Bits 31:10: v5, Physical page */ + +/* Level 1 Fine Table Descriptor. Coarse Table Descriptors support + * two level mapping between 4Kb memory regions. + */ + + /* Bits 1:0: Type of mapping */ + /* Bits 3:2: Should be zero */ + /* Bit 4: Common, must be one */ + /* Bits 8:5: Common domain control */ + /* Bits 11:9: Should be zero */ +#define PMD_FINE_TEX_MASK 0xfffff000 /* Bits 31:12: v5, Physical page */ + +/* Level 2 Table Descriptor (PTE). -- All tables */ + +#define PTE_TYPE_MASK (3 << 0) /* Bits: 1:0: Type of mapping */ +#define PTE_TYPE_FAULT (0 << 0) /* None */ +#define PTE_TYPE_LARGE (1 << 0) /* 64Kb of memory */ +#define PTE_TYPE_SMALL (2 << 0) /* 4Kb of memory */ +#define PTE_TYPE_TINY (3 << 0) /* 1Kb of memory (v5)*/ +#define PTE_BUFFERABLE (1 << 2) /* Bit 2: 1=bufferable */ +#define PTE_CACHEABLE (1 << 3) /* Bit 3: 1=cacheable */ + /* Bits 31:4: Depend on type */ + +/* Large page -- 64Kb */ + /* Bits: 1:0: Type of mapping */ + /* Bits: 3:2: Bufferable/cacheable */ +#define PTE_LARGE_AP_MASK (0xff << 4) /* Bits 11:4 Access permissions */ +#define PTE_LARGE_AP_UNO_SRO (0x00 << 4) +#define PTE_LARGE_AP_UNO_SRW (0x55 << 4) +#define PTE_LARGE_AP_URO_SRW (0xaa << 4) +#define PTE_LARGE_AP_URW_SRW (0xff << 4) + /* Bits 15:12: Should be zero */ +#define PTE_LARGE_TEX_MASK 0xffff0000 /* Bits 31:16: v5, Physical page */ + +/* Small page -- 4Kb */ + + /* Bits: 1:0: Type of mapping */ + /* Bits: 3:2: Bufferable/cacheable */ +#define PTE_SMALL_AP_MASK (0xff << 4) /* Bits: 11:4: Access permissions */ +#define PTE_SMALL_AP_UNO_SRO (0x00 << 4) +#define PTE_SMALL_AP_UNO_SRW (0x55 << 4) +#define PTE_SMALL_AP_URO_SRW (0xaa << 4) +#define PTE_SMALL_AP_URW_SRW (0xff << 4) +#define PTE_SMALL_TEX_MASK 0xfffff000 /* Bits: 31:12: Physical page */ + +/* Tiny page -- 1Kb */ + + /* Bits: 1:0: Type of mapping */ + /* Bits: 3:2: Bufferable/cacheable */ +#define PTE_EXT_AP_MASK (3 << 4) /* Bits: 5:4: Access persions */ +#define PTE_EXT_AP_UNO_SRO (0 << 4) +#define PTE_EXT_AP_UNO_SRW (1 << 4) +#define PTE_EXT_AP_URO_SRW (2 << 4) +#define PTE_EXT_AP_URW_SRW (3 << 4) + /* Bits: 9:6: Should be zero */ +#define PTE_TINY_TEX_MASK 0xfffffc00 /* Bits: 31:10: Physical page */ + +/* Default MMU flags for memory and IO */ + +#define MMU_MEMFLAGS \ + (PMD_TYPE_SECT|PMD_SECT_WB|PMD_BIT4|PMD_SECT_AP_WRITE|PMD_SECT_AP_READ) + +#define MMU_IOFLAGS \ + (PMD_TYPE_SECT|PMD_BIT4|PMD_SECT_AP_WRITE|PMD_SECT_AP_READ) + +#define MMU_L1_VECTORFLAGS (PMD_TYPE_COARSE|PMD_BIT4) +#define MMU_L2_VECTORFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW) + +/* Mapped section size */ + +#define SECTION_SIZE (1 << 20) /* 1Mb */ + +/* We place the page tables 16K below the beginning of .text. The + * following value is assume to be the (virtual) start address of + * .text. + */ + +#define PGTABLE_SIZE 0x00004000 + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#endif /* __ASSEMBLY__ */ + +#endif /* __ARCH_ARM_SRC_COMMON_ARM_H */ diff --git a/nuttx/arch/arm/src/arm/up_assert.c b/nuttx/arch/arm/src/arm/up_assert.c new file mode 100644 index 000000000..0c38781d4 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_assert.c @@ -0,0 +1,310 @@ +/**************************************************************************** + * arch/arm/src/arm/up_assert.c + * + * Copyright (C) 2007-2009 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 + +#include +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Output debug info if stack dump is selected -- even if + * debug is not selected. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_getsp + ****************************************************************************/ + +/* I don't know if the builtin to get SP is enabled */ + +static inline uint32 up_getsp(void) +{ + uint32 sp; + __asm__ + ( + "\tmov %0, sp\n\t" + : "=r"(sp) + ); + return sp; +} + +/**************************************************************************** + * Name: up_stackdump + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static void up_stackdump(uint32 sp, uint32 stack_base) +{ + uint32 stack ; + + for (stack = sp & ~0x1f; stack < stack_base; stack += 32) + { + uint32 *ptr = (uint32*)stack; + lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n", + stack, ptr[0], ptr[1], ptr[2], ptr[3], + ptr[4], ptr[5], ptr[6], ptr[7]); + } +} +#else +# define up_stackdump() +#endif + +/**************************************************************************** + * Name: up_registerdump + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static inline void up_registerdump(void) +{ + /* Are user registers available from interrupt processing? */ + + if (current_regs) + { + int regs; + + /* Yes.. dump the interrupt registers */ + + for (regs = REG_R0; regs <= REG_R15; regs += 8) + { + uint32 *ptr = (uint32*)¤t_regs[regs]; + lldbg("R%d: %08x %08x %08x %08x %08x %08x %08x %08x\n", + regs, ptr[0], ptr[1], ptr[2], ptr[3], + ptr[4], ptr[5], ptr[6], ptr[7]); + } + + lldbg("CPSR: %08x\n", current_regs[REG_CPSR]); + } +} +#else +# define up_registerdump() +#endif + +/**************************************************************************** + * Name: up_dumpstate + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static void up_dumpstate(void) +{ + _TCB *rtcb = (_TCB*)g_readytorun.head; + uint32 sp = up_getsp(); + uint32 ustackbase; + uint32 ustacksize; +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + uint32 istackbase; + uint32 istacksize; +#endif + + /* Get the limits on the user stack memory */ + + if (rtcb->pid == 0) + { + ustackbase = g_heapbase - 4; + ustacksize = CONFIG_IDLETHREAD_STACKSIZE; + } + else + { + ustackbase = (uint32)rtcb->adj_stack_ptr; + ustacksize = (uint32)rtcb->adj_stack_size; + } + + /* Get the limits on the interrupt stack memory */ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + istackbase = (uint32)&g_userstack; + istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4; + + /* Show interrupt stack info */ + + lldbg("sp: %08x\n", sp); + lldbg("IRQ stack:\n"); + lldbg(" base: %08x\n", istackbase); + lldbg(" size: %08x\n", istacksize); + + /* Does the current stack pointer lie within the interrupt + * stack? + */ + + if (sp <= istackbase && sp > istackbase - istacksize) + { + /* Yes.. dump the interrupt stack */ + + up_stackdump(sp, istackbase); + + /* Extract the user stack pointer which should lie + * at the base of the interrupt stack. + */ + + sp = g_userstack; + lldbg("sp: %08x\n", sp); + } + + /* Show user stack info */ + + lldbg("User stack:\n"); + lldbg(" base: %08x\n", ustackbase); + lldbg(" size: %08x\n", ustacksize); +#else + lldbg("sp: %08x\n", sp); + lldbg("stack base: %08x\n", ustackbase); + lldbg("stack size: %08x\n", ustacksize); +#endif + + /* Dump the user stack if the stack pointer lies within the allocated user + * stack memory. + */ + + if (sp > ustackbase || sp <= ustackbase - ustacksize) + { +#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4 + lldbg("ERROR: Stack pointer is not within allocated stack\n"); +#endif + } + else + { + up_stackdump(sp, ustackbase); + } + + /* Then dump the registers (if available) */ + + up_registerdump(); +} +#else +# define up_dumpstate() +#endif + +/**************************************************************************** + * Name: _up_assert + ****************************************************************************/ + +static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */ +{ + /* Are we in an interrupt handler or the idle task? */ + + if (current_regs || ((_TCB*)g_readytorun.head)->pid == 0) + { + (void)irqsave(); + for(;;) + { +#ifdef CONFIG_ARCH_LEDS + up_ledon(LED_PANIC); + up_mdelay(250); + up_ledoff(LED_PANIC); + up_mdelay(250); +#endif + } + } + else + { + exit(errorcode); + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_assert + ****************************************************************************/ + +void up_assert(const ubyte *filename, int lineno) +{ +#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG) + _TCB *rtcb = (_TCB*)g_readytorun.head; +#endif + + up_ledon(LED_ASSERTION); +#if CONFIG_TASK_NAME_SIZE > 0 + lldbg("Assertion failed at file:%s line: %d task: %s\n", + filename, lineno, rtcb->name); +#else + lldbg("Assertion failed at file:%s line: %d\n", + filename, lineno); +#endif + up_dumpstate(); + _up_assert(EXIT_FAILURE); +} + +/**************************************************************************** + * Name: up_assert_code + ****************************************************************************/ + +void up_assert_code(const ubyte *filename, int lineno, int errorcode) +{ +#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG) + _TCB *rtcb = (_TCB*)g_readytorun.head; +#endif + + up_ledon(LED_ASSERTION); +#if CONFIG_TASK_NAME_SIZE > 0 + lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n", + filename, lineno, rtcb->name, errorcode); +#else + lldbg("Assertion failed at file:%s line: %d error code: %d\n", + filename, lineno, errorcode); +#endif + up_dumpstate(); + _up_assert(errorcode); +} diff --git a/nuttx/arch/arm/src/arm/up_cache.S b/nuttx/arch/arm/src/arm/up_cache.S new file mode 100644 index 000000000..05926fbb4 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_cache.S @@ -0,0 +1,74 @@ +/**************************************************************************** + * arch/arm/src/arm/up_cache.S + * + * Copyright (C) 2007, 2009 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 "up_internal.h" +#include "up_arch.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define CACHE_DLINESIZE 32 + +/**************************************************************************** + * Assembly Macros + ****************************************************************************/ + +/**************************************************************************** + * Name: up_flushicache + ****************************************************************************/ + +/* Esure coherency between the Icache and the Dcache in the region described + * by r0=start and r1=end. + */ + .globl up_flushicache + .type up_flushicache,%function +up_flushicache: + bic r0, r0, #CACHE_DLINESIZE - 1 +1: mcr p15, 0, r0, c7, c10, 1 /* Clean D entry */ + mcr p15, 0, r0, c7, c5, 1 /* Invalidate I entry */ + add r0, r0, #CACHE_DLINESIZE + cmp r0, r1 + blo 1b + mcr p15, 0, r0, c7, c10, 4 /* Drain WB */ + mov pc, lr + .size up_flushicache, .-up_flushicache + .end + diff --git a/nuttx/arch/arm/src/arm/up_copystate.c b/nuttx/arch/arm/src/arm/up_copystate.c new file mode 100644 index 000000000..80b34aed7 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_copystate.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * arch/arm/src/arm/up_copystate.c + * + * Copyright (C) 2007-2009 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 "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_undefinedinsn + ****************************************************************************/ + +/* A little faster than most memcpy's */ + +void up_copystate(uint32 *dest, uint32 *src) +{ + int i; + + /* In the current ARM model, the state is always copied to and from the + * stack and TCB. + */ + + for (i = 0; i < XCPTCONTEXT_REGS; i++) + { + *dest++ = *src++; + } +} + diff --git a/nuttx/arch/arm/src/arm/up_dataabort.c b/nuttx/arch/arm/src/arm/up_dataabort.c new file mode 100644 index 000000000..df51f2343 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_dataabort.c @@ -0,0 +1,81 @@ +/**************************************************************************** + * arch/arm/src/arm/up_dataabort.c + * + * Copyright (C) 2007-2009 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 "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Output debug info if stack dump is selected -- even if + * debug is not selected. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_dataabort + ****************************************************************************/ + +void up_dataabort(uint32 *regs) +{ + lldbg("Data abort at 0x%x\n", regs[REG_PC]); + current_regs = regs; + PANIC(OSERR_ERREXCEPTION); +} diff --git a/nuttx/arch/arm/src/arm/up_doirq.c b/nuttx/arch/arm/src/arm/up_doirq.c new file mode 100644 index 000000000..948550904 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_doirq.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * arch/arm/src/arm/up_doirq.c + * + * Copyright (C) 2007-2009 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 +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +void up_doirq(int irq, uint32 *regs) +{ + up_ledon(LED_INIRQ); +#ifdef CONFIG_SUPPRESS_INTERRUPTS + PANIC(OSERR_ERREXCEPTION); +#else + if ((unsigned)irq < NR_IRQS) + { + /* Current regs non-zero indicates that we are processing + * an interrupt; current_regs is also used to manage + * interrupt level context switches. + */ + + current_regs = regs; + + /* Mask and acknowledge the interrupt */ + + up_maskack_irq(irq); + + /* Deliver the IRQ */ + + irq_dispatch(irq, regs); + + /* Indicate that we are no long in an interrupt handler */ + + current_regs = NULL; + + /* Unmask the last interrupt (global interrupts are still + * disabled. + */ + + up_enable_irq(irq); + } + up_ledoff(LED_INIRQ); +#endif +} diff --git a/nuttx/arch/arm/src/arm/up_fullcontextrestore.S b/nuttx/arch/arm/src/arm/up_fullcontextrestore.S new file mode 100644 index 000000000..c99337636 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_fullcontextrestore.S @@ -0,0 +1,117 @@ +/************************************************************************** + * arch/arm/src/arm/up_fullcontextrestore.S + * + * Copyright (C) 2007, 2009 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 "up_internal.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_fullcontextrestore + **************************************************************************/ + + .globl up_fullcontextrestore + .type up_fullcontextrestore, function +up_fullcontextrestore: + + /* On entry, a1 (r0) holds address of the register save area */ + + /* Recover all registers except for r0, r1, R15, and CPSR */ + + add r1, r0, #(4*REG_R2) /* Offset to REG_R2 storage */ + ldmia r1, {r2-r14} /* Recover registers */ + + /* Create a stack frame to hold the PC */ + + sub sp, sp, #(3*4) /* Frame for three registers */ + ldr r1, [r0, #(4*REG_R0)] /* Fetch the stored r0 value */ + str r1, [sp] /* Save it at the top of the stack */ + ldr r1, [r0, #(4*REG_R1)] /* Fetch the stored r1 value */ + str r1, [sp, #4] /* Save it in the stack */ + ldr r1, [r0, #(4*REG_PC)] /* Fetch the stored pc value */ + str r1, [sp, #8] /* Save it at the bottom of the frame */ + + /* Now we can restore the CPSR. We wait until we are completely + * finished with the context save data to do this. Restore the CPSR + * may re-enable and interrupts and we couldt be in a context + * where save structure is only protected by interrupts being disabled. + */ + + ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the stored CPSR value */ + msr cpsr, r1 /* Set the CPSR */ + + /* Now recover r0 and r1 */ + + ldr r0, [sp] + ldr r1, [sp, #4] + add sp, sp, #(2*4) + + /* Then return to the address at the stop of the stack, + * destroying the stack frame + */ + + ldr pc, [sp], #4 + .size up_fullcontextrestore, . - up_fullcontextrestore + diff --git a/nuttx/arch/arm/src/arm/up_head.S b/nuttx/arch/arm/src/arm/up_head.S new file mode 100644 index 000000000..dda8566d3 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_head.S @@ -0,0 +1,369 @@ +/**************************************************************************** + * arch/arm/src/arm/up_head.S + * + * Copyright (C) 2007, 2009 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 "up_internal.h" +#include "up_arch.h" + +/********************************************************************************** + * Conditional Compilation + **********************************************************************************/ + +#undef ALIGNMENT_TRAP +#undef CPU_DCACHE_WRITETHROUGH +#undef CPU_CACHE_ROUND_ROBIN +#undef CPU_DCACHE_DISABLE +#undef CPU_ICACHE_DISABLE + +/* There are three operational memory configurations: + * + * 1. We execute in place in FLASH (CONFIG_BOOT_RUNFROMFLASH=y). In this case + * the boot logic must: + * + * - Configure SDRAM and, + * - Initialize the .data section in RAM. + */ + +#ifdef CONFIG_BOOT_RUNFROMFLASH +# define CONFIGURE_SDRAM + +/* 2. We boot in FLASH but copy ourselves to DRAM from better performance. + * (CONFIG_BOOT_RUNFROMFLASH=n && CONFIG_BOOT_COPYTORAM=y). In this case + * the boot logic must: + * + * - Configure SDRAM and, + * - Copy ourself to DRAM (after mapping it) + */ + +#elif defined(CONFIG_BOOT_COPYTORAM) +# define CONFIG_SDRAM + +/* 3. There is bootloader that copies us to DRAM (but probably not to the beginning) + * (CONFIG_BOOT_RUNFROMFLASH=n && CONFIG_BOOT_COPYTORAM=n). In this case the + * boot logic must: + * + * - Nothing special. + */ + +#endif + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* The physical address of the beginning of SDRAM is provided by + * CONFIG_DRAM_START. The size of installed SDRAM is provided by + * CONFIG_DRAM_SIZE. The virtual address of SDRAM is provided by + * CONFIG_DRAM_VSTART. + */ + +#define NSDRAM_SECTIONS (CONFIG_DRAM_SIZE >> 20) + +/**************************************************************************** + * Assembly Macros + ****************************************************************************/ + +/* Since the page table is closely related to the NuttX base + * address, we can convert the page table base address to the + * base address of the section containing both. + */ + + .macro mksection, section, pgtable + bic \section, \pgtable, #0x000ff000 + .endm + +/* This macro will modify r0, r1, r2 and r14 */ + +#ifdef CONFIG_DEBUG + .macro showprogress, code + mov r0, #\code + bl up_lowputc + .endm +#else + .macro showprogress, code + .endm +#endif + +/**************************************************************************** + * Name: __start + ****************************************************************************/ + +/* We assume the bootloader has already initialized most of the h/w for + * us and that only leaves us having to do some os specific things + * below. + */ + .text + .global __start + .type __start, #function +__start: + /* Make sure that we are in SVC mode with all IRQs disabled */ + + mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT) + msr cpsr_c, r0 + + /* Initialize DRAM using a macro provided by board-specific logic */ + +#ifdef CONFIG_SDRAM + config_sdram +#endif + /* Clear the 16K level 1 page table */ + + ldr r4, .LCppgtable /* r4=phys. page table */ + mov r0, r4 + mov r1, #0 + add r2, r0, #PGTABLE_SIZE +.Lpgtableclear: + str r1, [r0], #4 + str r1, [r0], #4 + str r1, [r0], #4 + str r1, [r0], #4 + teq r0, r2 + bne .Lpgtableclear + + /* Create identity mapping for first MB section to support + * this startup logic executing out of the physical address + * space. This identity mapping will be removed by .Lvstart + * (see below). + */ + + mksection r0, r4 /* r0=phys. base section */ + ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */ + add r3, r1, r0 /* r3=flags + base */ + str r3, [r4, r0, lsr #18] /* identity mapping */ + + /* Create a "normal" single section mapping for the first + * MB of memory. Now, we have the first 1MB mapping to + * both phyical and virtual addresses. The reset of the + * SDRAM mapping will be completed in .Lvstart once we have + * moved the physical mapping out of the way. + */ + + ldr r2, .LCvpgtable /* r2=virt. page table */ + mksection r0, r2 /* r0=virt. base section */ + str r3, [r4, r0, lsr #18] /* identity mapping */ + + /* The following logic will set up the ARM920/ARM926 for normal operation */ + + mov r0, #0 + mcr p15, 0, r0, c7, c7 /* Invalidate I,D caches */ + mcr p15, 0, r0, c7, c10, 4 /* Drain write buffer */ + mcr p15, 0, r0, c8, c7 /* Invalidate I,D TLBs */ + mcr p15, 0, r4, c2, c0 /* Load page table pointer */ + +#ifdef CPU_DCACHE_WRITETHROUGH + mov r0, #4 /* Disable write-back on caches explicitly */ + mcr p15, 7, r0, c15, c0, 0 +#endif + + /* Enable the MMU and caches + * lr = Resume at .Lvstart with the MMU enabled + */ + + ldr lr, .LCvstart /* Abs. virtual address */ + + mov r0, #0x1f /* Domains 0, 1 = client */ + mcr p15, 0, r0, c3, c0 /* Load domain access register */ + mrc p15, 0, r0, c1, c0 /* Get control register */ + + /* Clear bits (see arm.h) */ + + bic r0, r0, #(CR_R|CR_F|CR_Z) + bic r0, r0, #(CR_A|CR_C|CR_W) + bic r0, r0, #(CR_I) + + /* Set bits (see arm.h) */ + + orr r0, r0, #(CR_M|CR_P|CR_D) + + /* In most architectures, vectors are reloated to 0xffff0000. + * -- but not all + */ + +#ifndef CONFIG_ARCH_LOWVECTORS + orr r0, r0, #(CR_S) +#else + orr r0, r0, #(CR_S|CR_V) +#endif +#ifdef CPU_CACHE_ROUND_ROBIN + orr r0, r0, #(CR_RR) +#endif +#ifndef CPU_DCACHE_DISABLE + orr r0, r0, #(CR_C) +#endif +#ifndef CPU_ICACHE_DISABLE + orr r0, r0, #(CR_I) +#endif +#ifdef ALIGNMENT_TRAP + orr r0, r0, #(CR_A) +#endif + mcr p15, 0, r0, c1, c0, 0 /* write control reg */ + + /* Get TMP=2 Processor ID register */ + + mrc p15, 0, r1, c0, c0, 0 /* read id reg */ + mov r1, r1 + mov r1, r1 + + mov pc, lr + +/********************************************************************************** + * PC_Relative Data + **********************************************************************************/ + + /* These addresses are all virtual address */ + + .type .LCvstart, %object +.LCvstart: + .long .Lvstart + .type .LCmmuflags, %object +.LCmmuflags: + .long MMU_MEMFLAGS + .type .LCppagetable, %object +.LCppgtable: + .long CONFIG_DRAM_START /* Physical start of DRAM */ + .type .LCvpagetable, %object +.LCvpgtable: + .long CONFIG_DRAM_VSTART /* Virtual start of DRAM */ + .size _start, .-_start + +/********************************************************************************** + * Name: .Lvstart + **********************************************************************************/ + +/* The following is executed after the MMU has been enabled. This uses + * absolute addresses; this is not position independent. + */ + .align 5 + .local .Lvstart + .type .Lvstart, %function +.Lvstart: + + /* Remove the temporary null mapping */ + + ldr r4, .LCvpgtable /* r4=virtual page table */ + ldr r1, .LCppgtable /* r1=phys. page table */ + mksection r3, r1 /* r2=phys. base addr */ + mov r0, #0 /* flags + base = 0 */ + str r0, [r4, r3, lsr #18] /* Undo identity mapping */ + + /* Now setup the pagetables for our normal SDRAM mappings + * mapped region. We round NUTTX_START_VADDR down to the + * nearest megabyte boundary. + */ + + ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */ + add r3, r3, r1 /* r3=flags + base */ + + add r0, r4, #(NUTTX_START_VADDR & 0xff000000) >> 18 + bic r2, r3, #0x00f00000 + str r2, [r0] + + add r0, r0, #(NUTTX_START_VADDR & 0x00f00000) >> 18 + str r3, [r0], #4 + + /* Now map the remaining NSDRAM_SECTIONS-1 SDRAM sections */ + + .rept NSDRAM_SECTIONS-1 + add r3, r3, #SECTION_SIZE + str r3, [r0], #4 + .endr + + /* Zero BSS and set up the stack pointer */ + + adr r0, .Linitparms + ldmia r0, {r0, r1, sp} + + /* Clear the frame pointer and .bss */ + + mov fp, #0 + +.Lbssinit: + cmp r0, r1 /* Clear up to _bss_end_ */ + strcc fp, [r0],#4 + bcc .Lbssinit + + /* Perform early C-level initialization */ + + bl up_boot + + /* Set up the LEDs */ + +#ifdef CONFIG_ARCH_LEDS + bl up_ledinit +#endif + /* Perform early serial initialization */ + +#ifdef CONFIG_USE_EARLYSERIALINIT + bl up_earlyserialinit +#endif + + /* Finally branch to the OS entry point */ + + mov lr, #0 + b os_start + + /* Variables: + * _sbss is the start of the BSS region (see ld.script) + * _ebss is the end of the BSS regsion (see ld.script) + * The idle task stack starts at the end of BSS and is + * of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues + * from there until the end of memory. See g_heapbase + * below. + */ + +.Linitparms: + .long _sbss + .long _ebss + .long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4 + .size .Lvstart, .-.Lvstart + + /* This global variable is unsigned long g_heapbase and is + * exported from here only because of its coupling to .Linitparms + * above. + */ + + .data + .align 4 + .globl g_heapbase + .type g_heapbase, object +g_heapbase: + .long _ebss+CONFIG_IDLETHREAD_STACKSIZE + .size g_heapbase, .-g_heapbase + .end + diff --git a/nuttx/arch/arm/src/arm/up_initialstate.c b/nuttx/arch/arm/src/arm/up_initialstate.c new file mode 100644 index 000000000..deed07209 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_initialstate.c @@ -0,0 +1,103 @@ +/**************************************************************************** + * arch/arm/src/arm/up_initialstate.c + * + * Copyright (C) 2007-2009 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 "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)); + + /* Save the initial stack pointer */ + + xcp->regs[REG_SP] = (uint32)tcb->adj_stack_ptr; + + /* Save the task entry point */ + + xcp->regs[REG_PC] = (uint32)tcb->start; + + /* Enable or disable interrupts, based on user configuration */ + +# ifdef CONFIG_SUPPRESS_INTERRUPTS + xcp->regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT; +# else + xcp->regs[REG_CPSR] = SVC_MODE | PSR_F_BIT; +# endif +} + diff --git a/nuttx/arch/arm/src/arm/up_nommuhead.S b/nuttx/arch/arm/src/arm/up_nommuhead.S new file mode 100644 index 000000000..05c5cf9e6 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_nommuhead.S @@ -0,0 +1,165 @@ +/**************************************************************************** + * arch/arm/src/arm/up_nommuhead.S + * + * Copyright (C) 2007, 2009 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 "up_internal.h" +#include "up_arch.h" + +/**************************************************************************** + * Macros + ****************************************************************************/ + + /* This macro will modify r0, r1, r2 and r14 */ + +#ifdef CONFIG_DEBUG + .macro showprogress, code + mov r0, #\code + bl up_lowputc + .endm +#else + .macro showprogress, code + .endm +#endif + +/**************************************************************************** + * OS Entry Point + ****************************************************************************/ + +/* We assume the bootloader has already initialized most of the h/w for + * us and that only leaves us having to do some os specific things + * below. + */ + .text + .global __start + .type __start, #function +__start: + + /* First, setup initial processor mode */ + + mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT ) + msr cpsr, r0 + + showprogress 'A' + + /* Setup system stack (and get the BSS range) */ + + adr r0, LC0 + ldmia r0, {r4, r5, sp} + + /* Clear system BSS section */ + + mov r0, #0 +1: cmp r4, r5 + strcc r0, [r4], #4 + bcc 1b + + showprogress 'B' + + /* Copy system .data sections to new home in RAM. */ + +#ifdef CONFIG_BOOT_RUNFROMFLASH + + adr r3, LC2 + ldmia r3, {r0, r1, r2} + +1: ldmia r0!, {r3 - r10} + stmia r1!, {r3 - r10} + cmp r1, r2 + blt 1b + +#endif + + /* Perform early serial initialization */ + + mov fp, #0 +#ifdef CONFIG_USE_EARLYSERIALINIT + bl up_earlyserialinit +#endif + +#ifdef CONFIG_DEBUG + mov r0, #'C' + bl up_putc + mov r0, #'\n' + bl up_putc +#endif + /* Initialize onboard LEDs */ + +#ifdef CONFIG_ARCH_LEDS + bl up_ledinit +#endif + + /* Then jump to OS entry */ + + b os_start + + /* Variables: + * _sbss is the start of the BSS region (see ld.script) + * _ebss is the end of the BSS regsion (see ld.script) + * The idle task stack starts at the end of BSS and is + * of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues + * from there until the end of memory. See g_heapbase + * below. + */ + +LC0: .long _sbss + .long _ebss + .long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4 + +#ifdef CONFIG_BOOT_RUNFROMFLASH +LC2: .long _eronly /* Where .data defaults are stored in FLASH */ + .long _sdata /* Where .data needs to reside in SDRAM */ + .long _edata +#endif + .size __start, .-__start + + /* This global variable is unsigned long g_heapbase and is + * exported from here only because of its coupling to LCO + * above. + */ + + .data + .align 4 + .globl g_heapbase + .type g_heapbase, object +g_heapbase: + .long _ebss+CONFIG_IDLETHREAD_STACKSIZE + .size g_heapbase, .-g_heapbase + + .end + diff --git a/nuttx/arch/arm/src/arm/up_prefetchabort.c b/nuttx/arch/arm/src/arm/up_prefetchabort.c new file mode 100644 index 000000000..3f6a1c914 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_prefetchabort.c @@ -0,0 +1,81 @@ +/**************************************************************************** + * arch/arm/src/src/up_prefetchabort.c + * + * Copyright (C) 2007-2009 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 "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Output debug info if stack dump is selected -- even if + * debug is not selected. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_prefetchabort + ****************************************************************************/ + +void up_prefetchabort(uint32 *regs) +{ + lldbg("Prefetch abort at 0x%x\n", regs[REG_PC]); + current_regs = regs; + PANIC(OSERR_ERREXCEPTION); +} diff --git a/nuttx/arch/arm/src/arm/up_saveusercontext.S b/nuttx/arch/arm/src/arm/up_saveusercontext.S new file mode 100644 index 000000000..8d154d187 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_saveusercontext.S @@ -0,0 +1,119 @@ +/************************************************************************** + * arch/arm/src/arm/up_saveusercontext.S + * + * Copyright (C) 2007, 2009 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 "up_internal.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_saveusercontext + **************************************************************************/ + + .text + .globl up_saveusercontext + .type up_saveusercontext, function +up_saveusercontext: + /* On entry, a1 (r0) holds address of struct xcptcontext. + * Offset to the user region. + */ + + /* Make sure that the return value will be non-zero (the + * value of the other volatile registers don't matter -- + * r1-r3, ip). This function is called throught the + * noraml C calling conventions and the values of these + * registers cannot be assumed at the point of setjmp + * return. + */ + + mov ip, #1 + str ip, [r0, #(4*REG_R0)] + + /* Save the volatile registers (plus r12 which really + * doesn't need to be saved) + */ + + add r1, r0, #(4*REG_R4) + stmia r1, {r4-r14} + + /* Save the current cpsr */ + + mrs r2, cpsr /* R3 = CPSR value */ + add r1, r0, #(4*REG_CPSR) + str r2, [r1] + + /* Finally save the return address as the PC so that we + * return to the exit from this function. + */ + + add r1, r0, #(4*REG_PC) + str lr, [r1] + + /* Return 0 */ + + mov r0, #0 /* Return value == 0 */ + mov pc, lr /* Return */ + .size up_saveusercontext, . - up_saveusercontext + diff --git a/nuttx/arch/arm/src/arm/up_schedulesigaction.c b/nuttx/arch/arm/src/arm/up_schedulesigaction.c new file mode 100644 index 000000000..af536bd07 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_schedulesigaction.c @@ -0,0 +1,203 @@ +/**************************************************************************** + * arch/arm/src/arm/up_schedulesigaction.c + * + * Copyright (C) 2007-2009 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 + +#include "os_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#ifndef CONFIG_DISABLE_SIGNALS + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_schedule_sigaction + * + * Description: + * This function is called by the OS when one or more + * signal handling actions have been queued for execution. + * The architecture specific code must configure things so + * that the 'igdeliver' callback is executed on the thread + * specified by 'tcb' as soon as possible. + * + * This function may be called from interrupt handling logic. + * + * This operation should not cause the task to be unblocked + * nor should it cause any immediate execution of sigdeliver. + * Typically, a few cases need to be considered: + * + * (1) This function may be called from an interrupt handler + * During interrupt processing, all xcptcontext structures + * should be valid for all tasks. That structure should + * be modified to invoke sigdeliver() either on return + * from (this) interrupt or on some subsequent context + * switch to the recipient task. + * (2) If not in an interrupt handler and the tcb is NOT + * the currently executing task, then again just modify + * the saved xcptcontext structure for the recipient + * task so it will invoke sigdeliver when that task is + * later resumed. + * (3) If not in an interrupt handler and the tcb IS the + * currently executing task -- just call the signal + * handler now. + * + ****************************************************************************/ + +void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver) +{ + /* Refuse to handle nested signal actions */ + + sdbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver); + + if (!tcb->xcp.sigdeliver) + { + irqstate_t flags; + + /* Make sure that interrupts are disabled */ + + flags = irqsave(); + + /* First, handle some special cases when the signal is + * being delivered to the currently executing task. + */ + + sdbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs); + + if (tcb == (_TCB*)g_readytorun.head) + { + /* CASE 1: We are not in an interrupt handler and + * a task is signalling itself for some reason. + */ + + if (!current_regs) + { + /* In this case just deliver the signal now. */ + + sigdeliver(tcb); + } + + /* CASE 2: We are in an interrupt handler AND the + * interrupted task is the same as the one that + * must receive the signal, then we will have to modify + * the return state as well as the state in the TCB. + * + * Hmmm... there looks like a latent bug here: The following + * logic would fail in the strange case where we are in an + * interrupt handler, the thread is signalling itself, but + * a context switch to another task has occurred so that + * current_regs does not refer to the thread at g_readytorun.head! + */ + + else + { + /* Save the return lr and cpsr and one scratch register + * These will be restored by the signal trampoline after + * the signals have been delivered. + */ + + tcb->xcp.sigdeliver = sigdeliver; + tcb->xcp.saved_pc = current_regs[REG_PC]; + tcb->xcp.saved_cpsr = current_regs[REG_CPSR]; + + /* Then set up to vector to the trampoline with interrupts + * disabled + */ + + current_regs[REG_PC] = (uint32)up_sigdeliver; + current_regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT; + + /* And make sure that the saved context in the TCB + * is the same as the interrupt return context. + */ + + up_savestate(tcb->xcp.regs); + } + } + + /* Otherwise, we are (1) signaling a task is not running + * from an interrupt handler or (2) we are not in an + * interrupt handler and the running task is signalling + * some non-running task. + */ + + else + { + /* Save the return lr and cpsr and one scratch register + * These will be restored by the signal trampoline after + * the signals have been delivered. + */ + + tcb->xcp.sigdeliver = sigdeliver; + tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC]; + tcb->xcp.saved_cpsr = tcb->xcp.regs[REG_CPSR]; + + /* Then set up to vector to the trampoline with interrupts + * disabled + */ + + tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver; + tcb->xcp.regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT; + } + + irqrestore(flags); + } +} + +#endif /* !CONFIG_DISABLE_SIGNALS */ diff --git a/nuttx/arch/arm/src/arm/up_sigdeliver.c b/nuttx/arch/arm/src/arm/up_sigdeliver.c new file mode 100644 index 000000000..8b12a88cc --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_sigdeliver.c @@ -0,0 +1,143 @@ +/**************************************************************************** + * arch/arm/src/arm/up_sigdeliver.c + * + * Copyright (C) 2007-2009 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 +#include + +#include "os_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#ifndef CONFIG_DISABLE_SIGNALS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_sigdeliver + * + * Description: + * This is the a signal handling trampoline. When a + * signal action was posted. The task context was mucked + * with and forced to branch to this location with interrupts + * disabled. + * + ****************************************************************************/ + +void up_sigdeliver(void) +{ + _TCB *rtcb = (_TCB*)g_readytorun.head; + uint32 regs[XCPTCONTEXT_REGS]; + sig_deliver_t sigdeliver; + + /* Save the errno. This must be preserved throughout the + * signal handling so that the the user code final gets + * the correct errno value (probably EINTR). + */ + + int saved_errno = rtcb->pterrno; + + up_ledon(LED_SIGNAL); + + sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n", + rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head); + ASSERT(rtcb->xcp.sigdeliver != NULL); + + /* Save the real return state on the stack. */ + + up_copystate(regs, rtcb->xcp.regs); + regs[REG_PC] = rtcb->xcp.saved_pc; + regs[REG_CPSR] = rtcb->xcp.saved_cpsr; + + /* Get a local copy of the sigdeliver function pointer. + * we do this so that we can nullify the sigdeliver + * function point in the TCB and accept more signal + * deliveries while processing the current pending + * signals. + */ + + sigdeliver = rtcb->xcp.sigdeliver; + rtcb->xcp.sigdeliver = NULL; + + /* Then restore the task interrupt statat. */ + + irqrestore(regs[REG_CPSR]); + + /* Deliver the signals */ + + sigdeliver(rtcb); + + /* Output any debug messaged BEFORE restoreing errno + * (becuase they may alter errno), then restore the + * original errno that is needed by the user logic + * (it is probably EINTR). + */ + + sdbg("Resuming\n"); + rtcb->pterrno = saved_errno; + + /* Then restore the correct state for this thread of + * execution. + */ + + up_ledoff(LED_SIGNAL); + up_fullcontextrestore(regs); +\} + +#endif /* !CONFIG_DISABLE_SIGNALS */ + diff --git a/nuttx/arch/arm/src/arm/up_syscall.c b/nuttx/arch/arm/src/arm/up_syscall.c new file mode 100644 index 000000000..ec38b3500 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_syscall.c @@ -0,0 +1,94 @@ +/**************************************************************************** + * arch/arm/src/arm/up_syscall.c + * + * Copyright (C) 2007-2009 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 "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Output debug info if stack dump is selected -- even if + * debug is not selected. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * vectors + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_syscall + * + * Description: + * SWI interrupts will vection here with insn=the SWI + * instruction and xcp=the interrupt context + * + * The handler may get the SWI number be de-referencing + * the return address saved in the xcp and decoding + * the SWI instruction + * + ****************************************************************************/ + +void up_syscall(uint32 *regs) +{ + lldbg("Syscall from 0x%x\n", regs[REG_PC]); + current_regs = regs; + PANIC(OSERR_ERREXCEPTION); +} diff --git a/nuttx/arch/arm/src/arm/up_undefinedinsn.c b/nuttx/arch/arm/src/arm/up_undefinedinsn.c new file mode 100644 index 000000000..e15457960 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_undefinedinsn.c @@ -0,0 +1,81 @@ +/**************************************************************************** + * arch/arm/src/arm/up_undefinedinsn.c + * + * Copyright (C) 2007-2009 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 "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Output debug info if stack dump is selected -- even if + * debug is not selected. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_undefinedinsn + ****************************************************************************/ + +void up_undefinedinsn(uint32 *regs) +{ + lldbg("Undefined instruction at 0x%x\n", regs[REG_PC]); + current_regs = regs; + PANIC(OSERR_UNDEFINEDINSN); +} diff --git a/nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S b/nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S new file mode 100644 index 000000000..28df31481 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_vectoraddrexcptn.S @@ -0,0 +1,83 @@ +/************************************************************************************ + * arch/arm/src/src/up_vectoraddrexceptn.S + * + * Copyright (C) 2008-2009 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 "up_arch.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Global Data + ************************************************************************************/ + +/************************************************************************************ + * Assembly Macros + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + + .text + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + + .text + +/************************************************************************************ + * Name: up_vectoraddrexcption + * + * Description: + * Shouldn't happen. This exception handler is in a separate file from other + * vector handlers because some processors (e.g., lpc2148) do not support the + * the Address Exception vector. + * + ************************************************************************************/ + + .globl up_vectoraddrexcptn + .type up_vectoraddrexcptn, %function +up_vectoraddrexcptn: + b up_vectoraddrexcptn + .size up_vectoaddrexcptn, . - up_vectoraddrexcptn + .end diff --git a/nuttx/arch/arm/src/arm/up_vectors.S b/nuttx/arch/arm/src/arm/up_vectors.S new file mode 100644 index 000000000..a084b8594 --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_vectors.S @@ -0,0 +1,440 @@ +/************************************************************************************ + * arch/arm/src/arm/up_vectors.S + * + * Copyright (C) 2007-2009 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 "up_arch.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Global Data + ************************************************************************************/ + + .data +g_irqtmp: + .word 0 /* Saved lr */ + .word 0 /* Saved spsr */ +g_undeftmp: + .word 0 /* Saved lr */ + .word 0 /* Saved spsr */ +g_aborttmp: + .word 0 /* Saved lr */ + .word 0 /* Saved spsr */ + +/************************************************************************************ + * Assembly Macros + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + + .text + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + + .text + +/************************************************************************************ + * Name: up_vectorirq + * + * Description: + * Interrupt excetpion. Entered in IRQ mode with spsr = SVC + * CPSR, lr = SVC PC + ************************************************************************************/ + + .globl up_vectorirq + .type up_vectorirq, %function +up_vectorirq: + /* On entry, we are in IRQ mode. We are free to use + * the IRQ mode r13 and r14. + * + */ + + ldr r13, .Lirqtmp + sub lr, lr, #4 + str lr, [r13] @ save lr_IRQ + mrs lr, spsr + str lr, [r13, #4] @ save spsr_IRQ + + /* Then switch back to SVC mode */ + + bic lr, lr, #MODE_MASK /* Keep F and T bits */ + orr lr, lr, #(SVC_MODE | PSR_I_BIT) + msr cpsr_c, lr /* Switch to SVC mode */ + + /* Create a context structure. First set aside a stack frame + * and store r0-r12 into the frame. + */ + + sub sp, sp, #XCPTCONTEXT_SIZE + stmia sp, {r0-r12} /* Save the SVC mode regs */ + + /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ + + add r1, sp, #XCPTCONTEXT_SIZE + mov r2, r14 + + /* Get the values for r15(pc) and CPSR in r3 and r4 */ + + ldr r0, .Lirqtmp /* Points to temp storage */ + ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ + + add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ + stmia r0, {r1-r4} + + /* Then call the IRQ handler with interrupts disabled. */ + + mov fp, #0 /* Init frame pointer */ + mov r0, sp /* Get r0=xcp */ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + ldr sp, .Lirqstackbase /* SP = interrupt stack base */ + str r0, [sp] /* Save the user stack pointer */ + bl up_decodeirq /* Call the handler */ + ldr sp, [sp] /* Restore the user stack pointer */ +#else + bl up_decodeirq /* Call the handler */ +#endif + + /* Restore the CPSR, SVC modr registers and return */ +.Lnoirqset: + ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ + msr spsr, r0 + ldmia sp, {r0-r15}^ /* Return */ + +.Lirqtmp: + .word g_irqtmp +#if CONFIG_ARCH_INTERRUPTSTACK > 3 +.Lirqstackbase: + .word up_stackbase +#endif + .size up_vectorirq, . - up_vectorirq + .align 5 + +/************************************************************************************ + * Function: up_vectorswi + * + * Description: + * SWI interrupt. We enter the SWI in SVC mode + ************************************************************************************/ + + .globl up_vectorswi + .type up_vectorswi, %function +up_vectorswi: + + /* Create a context structure. First set aside a stack frame + * and store r0-r12 into the frame. + */ + + sub sp, sp, #XCPTCONTEXT_SIZE + stmia sp, {r0-r12} /* Save the SVC mode regs */ + + /* Get the correct values of r13(sp), r14(lr), r15(pc) + * and CPSR in r1-r4 */ + + add r1, sp, #XCPTCONTEXT_SIZE + mov r2, r14 /* R14 is altered on return from SWI */ + mov r3, r14 /* Save r14 as the PC as well */ + mrs r4, spsr /* Get the saved CPSR */ + + add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ + stmia r0, {r1-r4} + + /* Then call the SWI handler with interrupts disabled. + * void up_syscall(struct xcptcontext *xcp) + */ + + mov fp, #0 /* Init frame pointer */ + mov r0, sp /* Get r0=xcp */ + bl up_syscall /* Call the handler */ + + /* Restore the CPSR, SVC modr registers and return */ + + ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ + msr spsr, r0 + ldmia sp, {r0-r15}^ /* Return */ + .size up_vectorswi, . - up_vectorswi + + .align 5 + +/************************************************************************************ + * Name: up_vectordata + * + * Description: + * Data abort Exception dispatcher. Give control to data + * abort handler. This function is entered in ABORT mode + * with spsr = SVC CPSR, lr = SVC PC + * + ************************************************************************************/ + + .globl up_vectordata + .type up_vectordata, %function +up_vectordata: + /* On entry we are free to use the ABORT mode registers + * r13 and r14 + */ + + ldr r13, .Ldaborttmp /* Points to temp storage */ + sub lr, lr, #8 /* Fixup return */ + str lr, [r13] /* Save in temp storage */ + mrs lr, spsr /* Get SPSR */ + str lr, [r13, #4] /* Save in temp storage */ + + /* Then switch back to SVC mode */ + + bic lr, lr, #MODE_MASK /* Keep F and T bits */ + orr lr, lr, #(SVC_MODE | PSR_I_BIT) + msr cpsr_c, lr /* Switch to SVC mode */ + + /* Create a context structure. First set aside a stack frame + * and store r0-r12 into the frame. + */ + + sub sp, sp, #XCPTCONTEXT_SIZE + stmia sp, {r0-r12} /* Save the SVC mode regs */ + + /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ + + add r1, sp, #XCPTCONTEXT_SIZE + mov r2, r14 + + /* Get the values for r15(pc) and CPSR in r3 and r4 */ + + ldr r0, .Ldaborttmp /* Points to temp storage */ + ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ + + add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ + stmia r0, {r1-r4} + + /* Then call the data abort handler with interrupts disabled. + * void up_dataabort(struct xcptcontext *xcp) + */ + + mov fp, #0 /* Init frame pointer */ + mov r0, sp /* Get r0=xcp */ + bl up_dataabort /* Call the handler */ + + /* Restore the CPSR, SVC modr registers and return */ + + ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ + msr spsr_cxsf, r0 + ldmia sp, {r0-r15}^ /* Return */ + +.Ldaborttmp: + .word g_aborttmp + .size up_vectordata, . - up_vectordata + + .align 5 + +/************************************************************************************ + * Name: up_vectorprefetch + * + * Description: + * Prefetch abort exception. Entered in ABT mode with + * spsr = SVC CPSR, lr = SVC PC + ************************************************************************************/ + + .globl up_vectorprefetch + .type up_vectorprefetch, %function +up_vectorprefetch: + /* On entry we are free to use the ABORT mode registers + * r13 and r14 + */ + + ldr r13, .Lpaborttmp /* Points to temp storage */ + sub lr, lr, #4 /* Fixup return */ + str lr, [r13] /* Save in temp storage */ + mrs lr, spsr /* Get SPSR */ + str lr, [r13, #4] /* Save in temp storage */ + + /* Then switch back to SVC mode */ + + bic lr, lr, #MODE_MASK /* Keep F and T bits */ + orr lr, lr, #(SVC_MODE | PSR_I_BIT) + msr cpsr_c, lr /* Switch to SVC mode */ + + /* Create a context structure. First set aside a stack frame + * and store r0-r12 into the frame. + */ + + sub sp, sp, #XCPTCONTEXT_SIZE + stmia sp, {r0-r12} /* Save the SVC mode regs */ + + /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ + + add r1, sp, #XCPTCONTEXT_SIZE + mov r2, r14 + + /* Get the values for r15(pc) and CPSR in r3 and r4 */ + + ldr r0, .Lpaborttmp /* Points to temp storage */ + ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ + + add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ + stmia r0, {r1-r4} + + /* Then call the prefetch abort handler with interrupts disabled. + * void up_prefetchabort(struct xcptcontext *xcp) + */ + + mov fp, #0 /* Init frame pointer */ + mov r0, sp /* Get r0=xcp */ + bl up_prefetchabort /* Call the handler */ + + /* Restore the CPSR, SVC modr registers and return */ + + ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ + msr spsr_cxsf, r0 + ldmia sp, {r0-r15}^ /* Return */ + +.Lpaborttmp: + .word g_aborttmp + .size up_vectorprefetch, . - up_vectorprefetch + + .align 5 + +/************************************************************************************ + * Name: up_vectorundefinsn + * + * Description: + * Undefined instruction entry exception. Entered in + * UND mode, spsr = SVC CPSR, lr = SVC PC + * + ************************************************************************************/ + + .globl up_vectorundefinsn + .type up_vectorundefinsn, %function +up_vectorundefinsn: + /* On entry we are free to use the UND mode registers + * r13 and r14 + */ + + ldr r13, .Lundeftmp /* Points to temp storage */ + str lr, [r13] /* Save in temp storage */ + mrs lr, spsr /* Get SPSR */ + str lr, [r13, #4] /* Save in temp storage */ + + /* Then switch back to SVC mode */ + + bic lr, lr, #MODE_MASK /* Keep F and T bits */ + orr lr, lr, #(SVC_MODE | PSR_I_BIT) + msr cpsr_c, lr /* Switch to SVC mode */ + + /* Create a context structure. First set aside a stack frame + * and store r0-r12 into the frame. + */ + + sub sp, sp, #XCPTCONTEXT_SIZE + stmia sp, {r0-r12} /* Save the SVC mode regs */ + + /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ + + add r1, sp, #XCPTCONTEXT_SIZE + mov r2, r14 + + /* Get the values for r15(pc) and CPSR in r3 and r4 */ + + ldr r0, .Lundeftmp /* Points to temp storage */ + ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ + + add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ + stmia r0, {r1-r4} + + /* Then call the undef insn handler with interrupts disabled. + * void up_undefinedinsn(struct xcptcontext *xcp) + */ + + mov fp, #0 /* Init frame pointer */ + mov r0, sp /* Get r0=xcp */ + bl up_undefinedinsn /* Call the handler */ + + /* Restore the CPSR, SVC modr registers and return */ + + ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ + msr spsr_cxsf, r0 + ldmia sp, {r0-r15}^ /* Return */ + +.Lundeftmp: + .word g_undeftmp + .size up_vectorundefinsn, . - up_vectorundefinsn + + .align 5 + +/************************************************************************************ + * Name: up_vectorfiq + * + * Description: + * Shouldn't happen + ************************************************************************************/ + + .globl up_vectorfiq + .type up_vectorfiq, %function +up_vectorfiq: + subs pc, lr, #4 + .size up_vectofiq, . - up_vectorfiq + +/************************************************************************************ + * Name: up_interruptstack/g_userstack + * + * Description: + * Shouldn't happen + * + ************************************************************************************/ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + .bss + .align 4 + .globl g_userstack + .type g_userstack, object +up_interruptstack: + .skip ((CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4) +g_userstack: +up_stackbase: + .skip 4 + .size g_userstack, 4 + .size up_interruptstack, (CONFIG_ARCH_INTERRUPTSTACK & ~3) +#endif + .end diff --git a/nuttx/arch/arm/src/arm/up_vectortab.S b/nuttx/arch/arm/src/arm/up_vectortab.S new file mode 100644 index 000000000..b1efcce3f --- /dev/null +++ b/nuttx/arch/arm/src/arm/up_vectortab.S @@ -0,0 +1,103 @@ +/**************************************************************************** + * arch/arm/src/arm/up_vectortab.S + * + * Copyright (C) 2007, 2009 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 + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Data + ****************************************************************************/ + +/**************************************************************************** + * Assembly Macros + ****************************************************************************/ + +/**************************************************************************** + * Name: _vector_start + * + * Description: + * Vector initialization block + ****************************************************************************/ + + .globl _vector_start + +/* These will be relocated to VECTOR_BASE. */ + +_vector_start: + ldr pc, .Lresethandler /* 0x00: Reset */ + ldr pc, .Lundefinedhandler /* 0x04: Undefined instruction */ + ldr pc, .Lswihandler /* 0x08: Software interrupt */ + ldr pc, .Lprefetchaborthandler /* 0x0c: Prefetch abort */ + ldr pc, .Ldataaborthandler /* 0x10: Data abort */ + ldr pc, .Laddrexcptnhandler /* 0x14: Address exception */ + ldr pc, .Lirqhandler /* 0x18: IRQ */ + ldr pc, .Lfiqhandler /* 0x1c: FIQ */ + + .globl __start + .globl up_vectorundefinsn + .globl up_vectorswi + .globl up_vectorprefetch + .globl up_vectordata + .globl up_vectoraddrexcptn + .globl up_vectorirq + .globl up_vectorfiq + +.Lresethandler: + .long __start +.Lundefinedhandler: + .long up_vectorundefinsn +.Lswihandler: + .long up_vectorswi +.Lprefetchaborthandler: + .long up_vectorprefetch +.Ldataaborthandler: + .long up_vectordata +.Laddrexcptnhandler: + .long up_vectoraddrexcptn +.Lirqhandler: + .long up_vectorirq +.Lfiqhandler: + .long up_vectorfiq + + .globl _vector_end +_vector_end: + .end diff --git a/nuttx/arch/arm/src/common/arm.h b/nuttx/arch/arm/src/common/arm.h deleted file mode 100644 index 07b21de64..000000000 --- a/nuttx/arch/arm/src/common/arm.h +++ /dev/null @@ -1,250 +0,0 @@ -/************************************************************************************ - * arch/arm/src/common/arm.h - * - * Copyright (C) 2007-2009 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. - * - ************************************************************************************/ - -#ifndef __ARCH_ARM_SRC_COMMON_ARM_H -#define __ARCH_ARM_SRC_COMMON_ARM_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#ifndef __ASSEMBLY__ -# include -#endif - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -#undef CONFIG_ALIGNMENT_TRAP -#undef CONFIG_DCACHE_WRITETHROUGH -#undef CONFIG_CACHE_ROUND_ROBIN -#undef CONFIG_DCACHE_DISABLE -#undef CONFIG_ICACHE_DISABLE - -/* ARM9EJS **************************************************************************/ - -/* PSR bits */ - -#define MODE_MASK 0x0000001f -#define USR26_MODE 0x00000000 -#define FIQ26_MODE 0x00000001 -#define IRQ26_MODE 0x00000002 -#define SVC26_MODE 0x00000003 -#define USR_MODE 0x00000010 -#define FIQ_MODE 0x00000011 -#define IRQ_MODE 0x00000012 -#define SVC_MODE 0x00000013 -#define ABT_MODE 0x00000017 -#define UND_MODE 0x0000001b -#define MODE32_BIT 0x00000010 -#define SYSTEM_MODE 0x0000001f -#define PSR_T_BIT 0x00000020 -#define PSR_F_BIT 0x00000040 -#define PSR_I_BIT 0x00000080 -#define PSR_J_BIT 0x01000000 -#define PSR_Q_BIT 0x08000000 -#define PSR_V_BIT 0x10000000 -#define PSR_C_BIT 0x20000000 -#define PSR_Z_BIT 0x40000000 -#define PSR_N_BIT 0x80000000 - -/* CR1 bits (CP#15 CR1) */ - -#define CR_M 0x00000001 /* MMU enable */ -#define CR_A 0x00000002 /* Alignment abort enable */ -#define CR_C 0x00000004 /* Dcache enable */ -#define CR_W 0x00000008 /* Write buffer enable */ -#define CR_P 0x00000010 /* 32-bit exception handler */ -#define CR_D 0x00000020 /* 32-bit data address range */ -#define CR_L 0x00000040 /* Implementation defined */ -#define CR_B 0x00000080 /* Big endian */ -#define CR_S 0x00000100 /* System MMU protection */ -#define CR_R 0x00000200 /* ROM MMU protection */ -#define CR_F 0x00000400 /* Implementation defined */ -#define CR_Z 0x00000800 /* Implementation defined */ -#define CR_I 0x00001000 /* Icache enable */ -#define CR_V 0x00002000 /* Vectors relocated to 0xffff0000 */ -#define CR_RR 0x00004000 /* Round Robin cache replacement */ -#define CR_L4 0x00008000 /* LDR pc can set T bit */ -#define CR_DT 0x00010000 -#define CR_IT 0x00040000 -#define CR_ST 0x00080000 -#define CR_FI 0x00200000 /* Fast interrupt (lower latency mode) */ -#define CR_U 0x00400000 /* Unaligned access operation */ -#define CR_XP 0x00800000 /* Extended page tables */ -#define CR_VE 0x01000000 /* Vectored interrupts */ - -/* Hardware page table definitions. - * - * Level 1 Descriptor (PMD) - * - * Common definitions. - */ - -#define PMD_TYPE_MASK 0x00000003 /* Bits 1:0: Type of descriptor */ -#define PMD_TYPE_FAULT 0x00000000 -#define PMD_TYPE_COARSE 0x00000001 -#define PMD_TYPE_SECT 0x00000002 -#define PMD_TYPE_FINE 0x00000003 - /* Bits 3:2: Depends on descriptor */ -#define PMD_BIT4 0x00000010 /* Bit 4: Must be one */ -#define PMD_DOMAIN_MASK 0x000001e0 /* Bits 8:5: Domain control bits */ -#define PMD_DOMAIN(x) ((x) << 5) -#define PMD_PROTECTION 0x00000200 /* Bit 9: v5 only */ - /* Bits 31:10: Depend on descriptor */ - -/* Level 1 Section Descriptor. Section descriptors allow fast, single - * level mapping between 1Mb address regions. - */ - /* Bits 1:0: Type of mapping */ -#define PMD_SECT_BUFFERABLE 0x00000004 /* Bit 2: 1=bufferable */ -#define PMD_SECT_CACHEABLE 0x00000008 /* Bit 3: 1=cacheable */ - /* Bit 4: Common, must be one */ - /* Bits 8:5: Common domain control */ - /* Bit 9: Common protection */ -#define PMD_SECT_AP_MASK 0x00000c00 /* Bits 11:10: Access permission */ -#define PMD_SECT_AP_WRITE 0x00000400 -#define PMD_SECT_AP_READ 0x00000800 - /* Bits 19:20: Should be zero */ -#define PMD_SECT_TEX_MASK 0xfff00000 /* Bits 31:20: v5, Physical page */ -#define PMD_SECT_APX 0x00008000 /* Bit 15: v6 only */ -#define PMD_SECT_S 0x00010000 /* Bit 16: v6 only */ -#define PMD_SECT_nG 0x00020000 /* Bit 17: v6 only */ - -#define PMD_SECT_UNCACHED (0) -#define PMD_SECT_BUFFERED (PMD_SECT_BUFFERABLE) -#define PMD_SECT_WT (PMD_SECT_CACHEABLE) -#define PMD_SECT_WB (PMD_SECT_CACHEABLE|PMD_SECT_BUFFERABLE) -#define PMD_SECT_MINICACHE (PMD_SECT_TEX(1)|PMD_SECT_CACHEABLE) -#define PMD_SECT_WBWA (PMD_SECT_TEX(1)|PMD_SECT_CACHEABLE|PMD_SECT_BUFFERABLE) - -/* Level 1 Coarse Table Descriptor. Coarse Table Descriptors support - * two level mapping between 16Kb memory regions. - */ - /* Bits 1:0: Type of mapping */ - /* Bits 3:2: Should be zero */ - /* Bit 4: Common, must be one */ - /* Bits 8:5: Common domain control */ - /* Bits 9: Should be zero */ -#define PMD_COARSE_TEX_MASK 0xfffffc00 /* Bits 31:10: v5, Physical page */ - -/* Level 1 Fine Table Descriptor. Coarse Table Descriptors support - * two level mapping between 4Kb memory regions. - */ - - /* Bits 1:0: Type of mapping */ - /* Bits 3:2: Should be zero */ - /* Bit 4: Common, must be one */ - /* Bits 8:5: Common domain control */ - /* Bits 11:9: Should be zero */ -#define PMD_FINE_TEX_MASK 0xfffff000 /* Bits 31:12: v5, Physical page */ - -/* Level 2 Table Descriptor (PTE). -- All tables */ - -#define PTE_TYPE_MASK (3 << 0) /* Bits: 1:0: Type of mapping */ -#define PTE_TYPE_FAULT (0 << 0) /* None */ -#define PTE_TYPE_LARGE (1 << 0) /* 64Kb of memory */ -#define PTE_TYPE_SMALL (2 << 0) /* 4Kb of memory */ -#define PTE_TYPE_TINY (3 << 0) /* 1Kb of memory (v5)*/ -#define PTE_BUFFERABLE (1 << 2) /* Bit 2: 1=bufferable */ -#define PTE_CACHEABLE (1 << 3) /* Bit 3: 1=cacheable */ - /* Bits 31:4: Depend on type */ - -/* Large page -- 64Kb */ - /* Bits: 1:0: Type of mapping */ - /* Bits: 3:2: Bufferable/cacheable */ -#define PTE_LARGE_AP_MASK (0xff << 4) /* Bits 11:4 Access permissions */ -#define PTE_LARGE_AP_UNO_SRO (0x00 << 4) -#define PTE_LARGE_AP_UNO_SRW (0x55 << 4) -#define PTE_LARGE_AP_URO_SRW (0xaa << 4) -#define PTE_LARGE_AP_URW_SRW (0xff << 4) - /* Bits 15:12: Should be zero */ -#define PTE_LARGE_TEX_MASK 0xffff0000 /* Bits 31:16: v5, Physical page */ - -/* Small page -- 4Kb */ - - /* Bits: 1:0: Type of mapping */ - /* Bits: 3:2: Bufferable/cacheable */ -#define PTE_SMALL_AP_MASK (0xff << 4) /* Bits: 11:4: Access permissions */ -#define PTE_SMALL_AP_UNO_SRO (0x00 << 4) -#define PTE_SMALL_AP_UNO_SRW (0x55 << 4) -#define PTE_SMALL_AP_URO_SRW (0xaa << 4) -#define PTE_SMALL_AP_URW_SRW (0xff << 4) -#define PTE_SMALL_TEX_MASK 0xfffff000 /* Bits: 31:12: Physical page */ - -/* Tiny page -- 1Kb */ - - /* Bits: 1:0: Type of mapping */ - /* Bits: 3:2: Bufferable/cacheable */ -#define PTE_EXT_AP_MASK (3 << 4) /* Bits: 5:4: Access persions */ -#define PTE_EXT_AP_UNO_SRO (0 << 4) -#define PTE_EXT_AP_UNO_SRW (1 << 4) -#define PTE_EXT_AP_URO_SRW (2 << 4) -#define PTE_EXT_AP_URW_SRW (3 << 4) - /* Bits: 9:6: Should be zero */ -#define PTE_TINY_TEX_MASK 0xfffffc00 /* Bits: 31:10: Physical page */ - -/* Default MMU flags for memory and IO */ - -#define MMU_MEMFLAGS \ - (PMD_TYPE_SECT|PMD_SECT_WB|PMD_BIT4|PMD_SECT_AP_WRITE|PMD_SECT_AP_READ) - -#define MMU_IOFLAGS \ - (PMD_TYPE_SECT|PMD_BIT4|PMD_SECT_AP_WRITE|PMD_SECT_AP_READ) - -#define MMU_L1_VECTORFLAGS (PMD_TYPE_COARSE|PMD_BIT4) -#define MMU_L2_VECTORFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW) - -/* Mapped section size */ - -#define SECTION_SIZE (1 << 20) /* 1Mb */ - -/* We place the page tables 16K below the beginning of .text. The - * following value is assume to be the (virtual) start address of - * .text. - */ - -#define PGTABLE_SIZE 0x00004000 - -/************************************************************************************ - * Inline Functions - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -#endif /* __ASSEMBLY__ */ - -#endif /* __ARCH_ARM_SRC_COMMON_ARM_H */ diff --git a/nuttx/arch/arm/src/common/cortexm3_nvic.h b/nuttx/arch/arm/src/common/cortexm3_nvic.h deleted file mode 100644 index d627a4dab..000000000 --- a/nuttx/arch/arm/src/common/cortexm3_nvic.h +++ /dev/null @@ -1,489 +0,0 @@ -/************************************************************************************ - * arch/arm/src/common/cortexm3_nvic.h - * - * Copyright (C) 2009 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. - * - ************************************************************************************/ - -#ifndef __ARCH_ARM_SRC_COMMON_CORTEXM3_NVIC_H -#define __ARCH_ARM_SRC_COMMON_CORTEXM3_NVIC_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* NVIC base address ****************************************************************/ - -#define CORTEXM3_NVIC_BASE 0xe000e000 - -/* NVIC register offsets ************************************************************/ - -#define NVIC_INTCTRL_TYPE_OFFSET 0x0004 /* Interrupt controller type */ -#define NVIC_SYSTICK_CTRL_OFFSET 0x0010 /* SysTick control and status register */ -#define NVIC_SYSTICK_RELOAD_OFFSET 0x0014 /* SysTick reload value register */ -#define NVIC_SYSTICK_CURRENT_OFFSET 0x0018 /* SysTick current value register */ -#define NVIC_SYSTICK_CALIB_OFFSET 0x001c /* SysTick calibration value register */ - -#define NVIC_IRQ_ENABLE_OFFSET(n) (0x0100 + 4*((n) >> 5)) -#define NVIC_IRQ0_31_ENABLE_OFFSET 0x0100 /* IRQ 0-31 set enable register */ -#define NVIC_IRQ32_63_ENABLE_OFFSET 0x0104 /* IRQ 32-63 set enable register */ -#define NVIC_IRQ64_95_ENABLE_OFFSET 0x0108 /* IRQ 64-95 set enable register */ -#define NVIC_IRQ96_127_ENABLE_OFFSET 0x010c /* IRQ 96-127 set enable register */ -#define NVIC_IRQ128_159_ENABLE_OFFSET 0x0110 /* IRQ 128-159 set enable register */ -#define NVIC_IRQ160_191_ENABLE_OFFSET 0x0114 /* IRQ 160-191 set enable register */ -#define NVIC_IRQ192_223_ENABLE_OFFSET 0x0118 /* IRQ 192-223 set enable register */ -#define NVIC_IRQ224_239_ENABLE_OFFSET 0x011c /* IRQ 224-239 set enable register */ - -#define NVIC_IRQ_CLEAR_OFFSET(n) (0x0180 + 4*((n) >> 5)) -#define NVIC_IRQ0_31_CLEAR_OFFSET 0x0180 /* IRQ 0-31 clear enable register */ -#define NVIC_IRQ32_63_CLEAR_OFFSET 0x0184 /* IRQ 32-63 clear enable register */ -#define NVIC_IRQ64_95_CLEAR_OFFSET 0x0188 /* IRQ 64-95 clear enable register */ -#define NVIC_IRQ96_127_CLEAR_OFFSET 0x018c /* IRQ 96-127 clear enable register */ -#define NVIC_IRQ128_159_CLEAR_OFFSET 0x0190 /* IRQ 128-159 clear enable register */ -#define NVIC_IRQ160_191_CLEAR_OFFSET 0x0194 /* IRQ 160-191 clear enable register */ -#define NVIC_IRQ192_223_CLEAR_OFFSET 0x0198 /* IRQ 192-223 clear enable register */ -#define NVIC_IRQ224_239_CLEAR_OFFSET 0x019c /* IRQ 224-2391 clear enable register */ - -#define NVIC_IRQ_PEND_OFFSET(n) (0x0200 + 4*((n) >> 5)) -#define NVIC_IRQ0_31_PEND_OFFSET 0x0200 /* IRQ 0-31 set pending register */ -#define NVIC_IRQ32_63_PEND_OFFSET 0x0204 /* IRQ 32-63 set pending register */ -#define NVIC_IRQ64_95_PEND_OFFSET 0x0208 /* IRQ 64-95 set pending register */ -#define NVIC_IRQ96_127_PEND_OFFSET 0x020c /* IRQ 96-127 set pending register */ -#define NVIC_IRQ128_159_PEND_OFFSET 0x0210 /* IRQ 128-159 set pending register */ -#define NVIC_IRQ160_191_PEND_OFFSET 0x0214 /* IRQ 160-191 set pending register */ -#define NVIC_IRQ192_223_PEND_OFFSET 0x0218 /* IRQ 192-2231 set pending register */ -#define NVIC_IRQ224_239_PEND_OFFSET 0x021c /* IRQ 224-2391 set pending register */ - -#define NVIC_IRQ_CLRPEND_OFFSET(n) (0x0280 + 4*((n) >> 5)) -#define NVIC_IRQ0_31_CLRPEND_OFFSET 0x0280 /* IRQ 0-31 clear pending register */ -#define NVIC_IRQ32_63_CLRPEND_OFFSET 0x0284 /* IRQ 32-63 clear pending register */ -#define NVIC_IRQ64_95_CLRPEND_OFFSET 0x0288 /* IRQ 64-95 clear pending register */ -#define NVIC_IRQ96_127_CLRPEND_OFFSET 0x028c /* IRQ 96-127 clear pending register */ -#define NVIC_IRQ128_159_CLRPEND_OFFSET 0x0290 /* IRQ 128-159 clear pending register */ -#define NVIC_IRQ160_191_CLRPEND_OFFSET 0x0294 /* IRQ 160-191 clear pending register */ -#define NVIC_IRQ192_223_CLRPEND_OFFSET 0x0298 /* IRQ 192-223 clear pending register */ -#define NVIC_IRQ224_239_CLRPEND_OFFSET 0x029c /* IRQ 224-239 clear pending register */ - -#define NVIC_IRQ_ACTIVE_OFFSET(n) (0x0300 + 4*((n) >> 5)) -#define NVIC_IRQ0_31_ACTIVE_OFFSET 0x0300 /* IRQ 0-31 active bit register */ -#define NVIC_IRQ32_63_ACTIVE_OFFSET 0x0304 /* IRQ 32-63 active bit register */ -#define NVIC_IRQ64_95_ACTIVE_OFFSET 0x0308 /* IRQ 64-95 active bit register */ -#define NVIC_IRQ96_127_ACTIVE_OFFSET 0x030c /* IRQ 96-127 active bit register */ -#define NVIC_IRQ128_159_ACTIVE_OFFSET 0x0310 /* IRQ 128-159 active bit register */ -#define NVIC_IRQ160_191_ACTIVE_OFFSET 0x0314 /* IRQ 160-191 active bit register */ -#define NVIC_IRQ192_223_ACTIVE_OFFSET 0x0318 /* IRQ 192-223 active bit register */ -#define NVIC_IRQ224_239_ACTIVE_OFFSET 0x031c /* IRQ 224-239 active bit register */ - -#define NVIC_IRQ_PRIORITY_OFFSET(n) (0x0400 + 4*((n) >> 2)) -#define NVIC_IRQ0_3_PRIORITY_OFFSET 0x0400 /* IRQ 0-3 priority register */ -#define NVIC_IRQ4_7_PRIORITY_OFFSET 0x0404 /* IRQ 4-7 priority register */ -#define NVIC_IRQ8_11_PRIORITY_OFFSET 0x0408 /* IRQ 8-11 priority register */ -#define NVIC_IRQ12_15_PRIORITY_OFFSET 0x040c /* IRQ 12-15 priority register */ -#define NVIC_IRQ16_19_PRIORITY_OFFSET 0x0410 /* IRQ 16-19 priority register */ -#define NVIC_IRQ20_23_PRIORITY_OFFSET 0x0414 /* IRQ 20-23 priority register */ -#define NVIC_IRQ24_27_PRIORITY_OFFSET 0x0418 /* IRQ 24-29 priority register */ -#define NVIC_IRQ28_31_PRIORITY_OFFSET 0x041c /* IRQ 28-31 priority register */ -#define NVIC_IRQ32_35_PRIORITY_OFFSET 0x0420 /* IRQ 32-35 priority register */ -#define NVIC_IRQ36_39_PRIORITY_OFFSET 0x0424 /* IRQ 36-39 priority register */ -#define NVIC_IRQ40_43_PRIORITY_OFFSET 0x0428 /* IRQ 40-43 priority register */ -#define NVIC_IRQ44_47_PRIORITY_OFFSET 0x042c /* IRQ 44-47 priority register */ -#define NVIC_IRQ48_51_PRIORITY_OFFSET 0x0430 /* IRQ 48-51 priority register */ -#define NVIC_IRQ52_55_PRIORITY_OFFSET 0x0434 /* IRQ 52-55 priority register */ -#define NVIC_IRQ56_59_PRIORITY_OFFSET 0x0438 /* IRQ 56-59 priority register */ -#define NVIC_IRQ60_63_PRIORITY_OFFSET 0x043c /* IRQ 60-63 priority register */ -#define NVIC_IRQ64_67_PRIORITY_OFFSET 0x0440 /* IRQ 64-67 priority register */ -#define NVIC_IRQ68_71_PRIORITY_OFFSET 0x0444 /* IRQ 68-71 priority register */ -#define NVIC_IRQ72_75_PRIORITY_OFFSET 0x0448 /* IRQ 72-75 priority register */ -#define NVIC_IRQ76_79_PRIORITY_OFFSET 0x044c /* IRQ 76-79 priority register */ -#define NVIC_IRQ80_83_PRIORITY_OFFSET 0x0450 /* IRQ 80-83 priority register */ -#define NVIC_IRQ84_87_PRIORITY_OFFSET 0x0454 /* IRQ 84-87 priority register */ -#define NVIC_IRQ88_91_PRIORITY_OFFSET 0x0458 /* IRQ 88-91 priority register */ -#define NVIC_IRQ92_95_PRIORITY_OFFSET 0x045c /* IRQ 92-95 priority register */ -#define NVIC_IRQ96_99_PRIORITY_OFFSET 0x0460 /* IRQ 96-99 priority register */ -#define NVIC_IRQ100_103_PRIORITY_OFFSET 0x0464 /* IRQ 100-103 priority register */ -#define NVIC_IRQ104_107_PRIORITY_OFFSET 0x0468 /* IRQ 104-107 priority register */ -#define NVIC_IRQ108_111_PRIORITY_OFFSET 0x046c /* IRQ 108-111 priority register */ -#define NVIC_IRQ112_115_PRIORITY_OFFSET 0x0470 /* IRQ 112-115 priority register */ -#define NVIC_IRQ116_119_PRIORITY_OFFSET 0x0474 /* IRQ 116-119 priority register */ -#define NVIC_IRQ120_123_PRIORITY_OFFSET 0x0478 /* IRQ 120-123 priority register */ -#define NVIC_IRQ124_127_PRIORITY_OFFSET 0x047c /* IRQ 124-127 priority register */ -#define NVIC_IRQ128_131_PRIORITY_OFFSET 0x0480 /* IRQ 128-131 priority register */ -#define NVIC_IRQ132_135_PRIORITY_OFFSET 0x0484 /* IRQ 132-135 priority register */ -#define NVIC_IRQ136_139_PRIORITY_OFFSET 0x0488 /* IRQ 136-139 priority register */ -#define NVIC_IRQ140_143_PRIORITY_OFFSET 0x048c /* IRQ 140-143 priority register */ -#define NVIC_IRQ144_147_PRIORITY_OFFSET 0x0490 /* IRQ 144-147 priority register */ -#define NVIC_IRQ148_151_PRIORITY_OFFSET 0x0494 /* IRQ 148-151 priority register */ -#define NVIC_IRQ152_155_PRIORITY_OFFSET 0x0498 /* IRQ 152-155 priority register */ -#define NVIC_IRQ156_159_PRIORITY_OFFSET 0x049c /* IRQ 156-159 priority register */ -#define NVIC_IRQ160_163_PRIORITY_OFFSET 0x04a0 /* IRQ 160-163 priority register */ -#define NVIC_IRQ164_167_PRIORITY_OFFSET 0x04a4 /* IRQ 164-167 priority register */ -#define NVIC_IRQ168_171_PRIORITY_OFFSET 0x04a8 /* IRQ 168-171 priority register */ -#define NVIC_IRQ172_175_PRIORITY_OFFSET 0x04ac /* IRQ 172-175 priority register */ -#define NVIC_IRQ176_179_PRIORITY_OFFSET 0x04b0 /* IRQ 176-179 priority register */ -#define NVIC_IRQ180_183_PRIORITY_OFFSET 0x04b4 /* IRQ 180-183 priority register */ -#define NVIC_IRQ184_187_PRIORITY_OFFSET 0x04b8 /* IRQ 184-187 priority register */ -#define NVIC_IRQ188_191_PRIORITY_OFFSET 0x04bc /* IRQ 188-191 priority register */ -#define NVIC_IRQ192_195_PRIORITY_OFFSET 0x04c0 /* IRQ 192-195 priority register */ -#define NVIC_IRQ196_199_PRIORITY_OFFSET 0x04c4 /* IRQ 196-199 priority register */ -#define NVIC_IRQ200_203_PRIORITY_OFFSET 0x04c8 /* IRQ 200-203 priority register */ -#define NVIC_IRQ204_207_PRIORITY_OFFSET 0x04cc /* IRQ 204-207 priority register */ -#define NVIC_IRQ208_211_PRIORITY_OFFSET 0x04d0 /* IRQ 208-211 priority register */ -#define NVIC_IRQ212_215_PRIORITY_OFFSET 0x04d4 /* IRQ 212-215 priority register */ -#define NVIC_IRQ216_219_PRIORITY_OFFSET 0x04d8 /* IRQ 216-219 priority register */ -#define NVIC_IRQ220_223_PRIORITY_OFFSET 0x04dc /* IRQ 220-223 priority register */ -#define NVIC_IRQ224_227_PRIORITY_OFFSET 0x04e0 /* IRQ 224-227 priority register */ -#define NVIC_IRQ228_231_PRIORITY_OFFSET 0x04e4 /* IRQ 228-231 priority register */ -#define NVIC_IRQ232_235_PRIORITY_OFFSET 0x04e8 /* IRQ 232-235 priority register */ -#define NVIC_IRQ236_239_PRIORITY_OFFSET 0x04ec /* IRQ 236-239 priority register */ - -#define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */ -#define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */ -#define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */ -#define NVIC_AIRC_OFFSET 0x0d0c /* Application interrupt/reset contol registr */ -#define NVIC_SYSCON_OFFSET 0x0d10 /* System control register */ -#define NVIC_CFGCON_OFFSET 0x0d14 /* Configuration control register */ -#define NVIC_SYSH_PRIORITY_OFFSET(n) (0x0d14 + 4*((n) >> 2)) -#define NVIC_SYSH4_7_PRIORITY_OFFSET 0x0d18 /* System handlers 4-7 priority register */ -#define NVIC_SYSH8_11_PRIORITY_OFFSET 0x0d1c /* System handler 8-11 priority register */ -#define NVIC_SYSH12_15_PRIORITY_OFFSET 0x0d20 /* System handler 12-15 priority register */ -#define NVIC_SYSHCON_OFFSET 0x0d24 /* System handler control and state register */ -#define NVIC_CFAULTS_OFFSET 0x0d28 /* Configurable fault status register */ -#define NVIC_HFAULTS_OFFSET 0x0d2c /* Hard fault status register */ -#define NVIC_DFAULTS_OFFSET 0x0d30 /* Debug fault status register */ -#define NVIC_MEMMANAGE_ADDR_OFFSET 0x0d34 /* Mem manage address register */ -#define NVIC_BFAULT_ADDR_OFFSET 0x0d38 /* Bus fault address register */ -#define NVIC_AFAULTS_OFFSET 0x0d3c /* Auxiliary fault status register */ -#define NVIC_PFR0_OFFSET 0x0d40 /* Processor feature register 0 */ -#define NVIC_PFR1_OFFSET 0x0d44 /* Processor feature register 1 */ -#define NVIC_DFR0_OFFSET 0x0d48 /* Debug feature register 0 */ -#define NVIC_AFR0_OFFSET 0x0d4c /* Auxiliary feature register 0 */ -#define NVIC_MMFR0_OFFSET 0x0d50 /* Memory model feature register 0 */ -#define NVIC_MMFR1_OFFSET 0x0d54 /* Memory model feature register 1 */ -#define NVIC_MMFR2_OFFSET 0x0d58 /* Memory model feature register 2 */ -#define NVIC_MMFR3_OFFSET 0x0d5c /* Memory model feature register 3 */ -#define NVIC_ISAR0_OFFSET 0x0d60 /* ISA feature register 0 */ -#define NVIC_ISAR1_OFFSET 0x0d64 /* ISA feature register 1 */ -#define NVIC_ISAR2_OFFSET 0x0d68 /* ISA feature register 2 */ -#define NVIC_ISAR3_OFFSET 0x0d6c /* ISA feature register 3 */ -#define NVIC_ISAR4_OFFSET 0x0d70 /* ISA feature register 4 */ -#define NVIC_STIR_OFFSET 0x0f00 /* Software trigger interrupt register */ -#define NVIC_PID4_OFFSET 0x0fd0 /* Peripheral identification register (PID4) */ -#define NVIC_PID5_OFFSET 0x0fd4 /* Peripheral identification register (PID5) */ -#define NVIC_PID6_OFFSET 0x0fd8 /* Peripheral identification register (PID6) */ -#define NVIC_PID7_OFFSET 0x0fdc /* Peripheral identification register (PID7) */ -#define NVIC_PID0_OFFSET 0x0fe0 /* Peripheral identification register bits 7:0 (PID0) */ -#define NVIC_PID1_OFFSET 0x0fe4 /* Peripheral identification register bits 15:8 (PID1) */ -#define NVIC_PID2_OFFSET 0x0fe8 /* Peripheral identification register bits 23:16 (PID2) */ -#define NVIC_PID3_OFFSET 0x0fec /* Peripheral identification register bits 23:16 (PID3) */ -#define NVIC_CID0_OFFSET 0x0ff0 /* Component identification register bits 7:0 (CID0) */ -#define NVIC_CID1_OFFSET 0x0ff4 /* Component identification register bits 15:8 (CID0) */ -#define NVIC_CID2_OFFSET 0x0ff8 /* Component identification register bits 23:16 (CID0) */ -#define NVIC_CID3_OFFSET 0x0ffc /* Component identification register bits 23:16 (CID0) */ - -/* NVIC register addresses **********************************************************/ - -#define NVIC_INTCTRL_TYPE (CORTEXM3_NVIC_BASE + NVIC_INTCTRL_TYPE_OFFSET) -#define NVIC_SYSTICK_CTRL (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_CTRL_OFFSET) -#define NVIC_SYSTICK_RELOAD (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_RELOAD_OFFSET) -#define NVIC_SYSTICK_CURRENT (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_CURRENT_OFFSET) -#define NVIC_SYSTICK_CALIB (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_CALIB_OFFSET) - -#define NVIC_IRQ_ENABLE(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_ENABLE_OFFSET(n)) -#define NVIC_IRQ0_31_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_ENABLE_OFFSET) -#define NVIC_IRQ32_63_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_ENABLE_OFFSET) -#define NVIC_IRQ64_95_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_ENABLE_OFFSET) -#define NVIC_IRQ96_127_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_ENABLE_OFFSET) -#define NVIC_IRQ128_159_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_ENABLE_OFFSET) -#define NVIC_IRQ160_191_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_ENABLE_OFFSET) -#define NVIC_IRQ192_223_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_ENABLE_OFFSET) -#define NVIC_IRQ224_239_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_ENABLE_OFFSET) - -#define NVIC_IRQ_CLEAR(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_CLEAR_OFFSET(n)) -#define NVIC_IRQ0_31_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_CLEAR_OFFSET) -#define NVIC_IRQ32_63_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_CLEAR_OFFSET) -#define NVIC_IRQ64_95_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_CLEAR_OFFSET) -#define NVIC_IRQ96_127_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_CLEAR_OFFSET) -#define NVIC_IRQ128_159_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_CLEAR_OFFSET) -#define NVIC_IRQ160_191_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_CLEAR_OFFSET) -#define NVIC_IRQ192_223_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_CLEAR_OFFSET) -#define NVIC_IRQ224_239_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_CLEAR_OFFSET) - -#define NVIC_IRQ_PEND(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_PEND_OFFSET(n)) -#define NVIC_IRQ0_31_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_PEND_OFFSET) -#define NVIC_IRQ32_63_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_PEND_OFFSET) -#define NVIC_IRQ64_95_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_PEND_OFFSET) -#define NVIC_IRQ96_127_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_PEND_OFFSET) -#define NVIC_IRQ128_159_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_PEND_OFFSET) -#define NVIC_IRQ160_191_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_PEND_OFFSET) -#define NVIC_IRQ192_223_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_PEND_OFFSET) -#define NVIC_IRQ224_239_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_PEND_OFFSET) - -#define NVIC_IRQ_CLRPEND(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_CLRPEND_OFFSET(n)) -#define NVIC_IRQ0_31_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_CLRPEND_OFFSET) -#define NVIC_IRQ32_63_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_CLRPEND_OFFSET) -#define NVIC_IRQ64_95_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_CLRPEND_OFFSET) -#define NVIC_IRQ96_127_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_CLRPEND_OFFSET) -#define NVIC_IRQ128_159_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_CLRPEND_OFFSET) -#define NVIC_IRQ160_191_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_CLRPEND_OFFSET) -#define NVIC_IRQ192_223_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_CLRPEND_OFFSET) -#define NVIC_IRQ224_239_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_CLRPEND_OFFSET) - -#define NVIC_IRQ_ACTIVE(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_ACTIVE_OFFSET(n)) -#define NVIC_IRQ0_31_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_ACTIVE_OFFSET) -#define NVIC_IRQ32_63_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_ACTIVE_OFFSET) -#define NVIC_IRQ64_95_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_ACTIVE_OFFSET) -#define NVIC_IRQ96_127_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_ACTIVE_OFFSET) -#define NVIC_IRQ128_159_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_ACTIVE_OFFSET) -#define NVIC_IRQ160_191_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_ACTIVE_OFFSET) -#define NVIC_IRQ192_223_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_ACTIVE_OFFSET) -#define NVIC_IRQ224_239_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_ACTIVE_OFFSET) - -#define NVIC_IRQ_PRIORITY(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_PRIORITY_OFFSET(n)) -#define NVIC_IRQ0_3_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ0_3_PRIORITY_OFFSET) -#define NVIC_IRQ4_7_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ4_7_PRIORITY_OFFSET) -#define NVIC_IRQ8_11_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ8_11_PRIORITY_OFFSET) -#define NVIC_IRQ12_15_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ12_15_PRIORITY_OFFSET) -#define NVIC_IRQ16_19_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ16_19_PRIORITY_OFFSET) -#define NVIC_IRQ20_23_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ20_23_PRIORITY_OFFSET) -#define NVIC_IRQ24_27_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ24_27_PRIORITY_OFFSET) -#define NVIC_IRQ28_31_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ28_31_PRIORITY_OFFSET) -#define NVIC_IRQ32_35_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ32_35_PRIORITY_OFFSET) -#define NVIC_IRQ36_39_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ36_39_PRIORITY_OFFSET) -#define NVIC_IRQ40_43_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ40_43_PRIORITY_OFFSET) -#define NVIC_IRQ44_47_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ44_47_PRIORITY_OFFSET) -#define NVIC_IRQ48_51_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ48_51_PRIORITY_OFFSET) -#define NVIC_IRQ52_55_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ52_55_PRIORITY_OFFSET) -#define NVIC_IRQ56_59_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ56_59_PRIORITY_OFFSET) -#define NVIC_IRQ60_63_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ60_63_PRIORITY_OFFSET) -#define NVIC_IRQ64_67_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ64_67_PRIORITY_OFFSET) -#define NVIC_IRQ68_71_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ68_71_PRIORITY_OFFSET) -#define NVIC_IRQ72_75_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ72_75_PRIORITY_OFFSET) -#define NVIC_IRQ76_79_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ76_79_PRIORITY_OFFSET) -#define NVIC_IRQ80_83_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ80_83_PRIORITY_OFFSET) -#define NVIC_IRQ84_87_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ84_87_PRIORITY_OFFSET) -#define NVIC_IRQ88_91_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ88_91_PRIORITY_OFFSET) -#define NVIC_IRQ92_95_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ92_95_PRIORITY_OFFSET) -#define NVIC_IRQ96_99_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ96_99_PRIORITY_OFFSET) -#define NVIC_IRQ100_103_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ100_103_PRIORITY_OFFSET) -#define NVIC_IRQ104_107_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ104_107_PRIORITY_OFFSET) -#define NVIC_IRQ108_111_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ108_111_PRIORITY_OFFSET) -#define NVIC_IRQ112_115_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ112_115_PRIORITY_OFFSET) -#define NVIC_IRQ116_119_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ116_119_PRIORITY_OFFSET) -#define NVIC_IRQ120_123_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ120_123_PRIORITY_OFFSET) -#define NVIC_IRQ124_127_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ124_127_PRIORITY_OFFSET) -#define NVIC_IRQ128_131_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ128_131_PRIORITY_OFFSET) -#define NVIC_IRQ132_135_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ132_135_PRIORITY_OFFSET) -#define NVIC_IRQ136_139_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ136_139_PRIORITY_OFFSET) -#define NVIC_IRQ140_143_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ140_143_PRIORITY_OFFSET) -#define NVIC_IRQ144_147_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ144_147_PRIORITY_OFFSET) -#define NVIC_IRQ148_151_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ148_151_PRIORITY_OFFSET) -#define NVIC_IRQ152_155_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ152_155_PRIORITY_OFFSET) -#define NVIC_IRQ156_159_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ156_159_PRIORITY_OFFSET) -#define NVIC_IRQ160_163_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ160_163_PRIORITY_OFFSET) -#define NVIC_IRQ164_167_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ164_167_PRIORITY_OFFSET) -#define NVIC_IRQ168_171_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ168_171_PRIORITY_OFFSET) -#define NVIC_IRQ172_175_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ172_175_PRIORITY_OFFSET) -#define NVIC_IRQ176_179_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ176_179_PRIORITY_OFFSET) -#define NVIC_IRQ180_183_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ180_183_PRIORITY_OFFSET) -#define NVIC_IRQ184_187_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ184_187_PRIORITY_OFFSET) -#define NVIC_IRQ188_191_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ188_191_PRIORITY_OFFSET) -#define NVIC_IRQ192_195_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ192_195_PRIORITY_OFFSET) -#define NVIC_IRQ196_199_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ196_199_PRIORITY_OFFSET) -#define NVIC_IRQ200_203_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ200_203_PRIORITY_OFFSET) -#define NVIC_IRQ204_207_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ204_207_PRIORITY_OFFSET) -#define NVIC_IRQ208_211_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ208_211_PRIORITY_OFFSET) -#define NVIC_IRQ212_215_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ212_215_PRIORITY_OFFSET) -#define NVIC_IRQ216_219_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ216_219_PRIORITY_OFFSET) -#define NVIC_IRQ220_223_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ220_223_PRIORITY_OFFSET) -#define NVIC_IRQ224_227_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ224_227_PRIORITY_OFFSET) -#define NVIC_IRQ228_231_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ228_231_PRIORITY_OFFSET) -#define NVIC_IRQ232_235_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ232_235_PRIORITY_OFFSET) - -#define NVIC_CPUID_BASE (CORTEXM3_NVIC_BASE + NVIC_CPUID_BASE_OFFSET) -#define NVIC_INTCTRL (CORTEXM3_NVIC_BASE + NVIC_INTCTRL_OFFSET) -#define NVIC_VECTAB (CORTEXM3_NVIC_BASE + NVIC_VECTAB_OFFSET) -#define NVIC_AIRC (CORTEXM3_NVIC_BASE + NVIC_AIRC_OFFSET) -#define NVIC_SYSCON (CORTEXM3_NVIC_BASE + NVIC_SYSCON_OFFSET) -#define NVIC_CFGCON (CORTEXM3_NVIC_BASE + NVIC_CFGCON_OFFSET) -#define NVIC_SYSH_PRIORITY(n) (CORTEXM3_NVIC_BASE + NVIC_SYSH_PRIORITY_OFFSET(n)) -#define NVIC_SYSH4_7_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_SYSH4_7_PRIORITY_OFFSET) -#define NVIC_SYSH8_11_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_SYSH8_11_PRIORITY_OFFSET) -#define NVIC_SYSH12_15_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_SYSH12_15_PRIORITY_OFFSET) -#define NVIC_SYSHCON (CORTEXM3_NVIC_BASE + NVIC_SYSHCON_OFFSET) -#define NVIC_CFAULTS (CORTEXM3_NVIC_BASE + NVIC_CFAULTS_OFFSET) -#define NVIC_HFAULTS (CORTEXM3_NVIC_BASE + NVIC_HFAULTS_OFFSET) -#define NVIC_DFAULTS (CORTEXM3_NVIC_BASE + NVIC_DFAULTS_OFFSET) -#define NVIC_MEMMANAGE_ADDR (CORTEXM3_NVIC_BASE + NVIC_MEMMANAGE_ADDR_OFFSET) -#define NVIC_BFAULT_ADDR (CORTEXM3_NVIC_BASE + NVIC_BFAULT_ADDR_OFFSET) -#define NVIC_AFAULTS (CORTEXM3_NVIC_BASE + NVIC_AFAULTS_OFFSET) -#define NVIC_PFR0 (CORTEXM3_NVIC_BASE + NVIC_PFR0_OFFSET) -#define NVIC_PFR1 (CORTEXM3_NVIC_BASE + NVIC_PFR1_OFFSET) -#define NVIC_DFR0 (CORTEXM3_NVIC_BASE + NVIC_DFR0_OFFSET) -#define NVIC_AFR0 (CORTEXM3_NVIC_BASE + NVIC_AFR0_OFFSET) -#define NVIC_MMFR0 (CORTEXM3_NVIC_BASE + NVIC_MMFR0_OFFSET) -#define NVIC_MMFR1 (CORTEXM3_NVIC_BASE + NVIC_MMFR1_OFFSET) -#define NVIC_MMFR2 (CORTEXM3_NVIC_BASE + NVIC_MMFR2_OFFSET) -#define NVIC_MMFR3 (CORTEXM3_NVIC_BASE + NVIC_MMFR3_OFFSET) -#define NVIC_ISAR0 (CORTEXM3_NVIC_BASE + NVIC_ISAR0_OFFSET) -#define NVIC_ISAR1 (CORTEXM3_NVIC_BASE + NVIC_ISAR1_OFFSET) -#define NVIC_ISAR2 (CORTEXM3_NVIC_BASE + NVIC_ISAR2_OFFSET) -#define NVIC_ISAR3 (CORTEXM3_NVIC_BASE + NVIC_ISAR3_OFFSET) -#define NVIC_ISAR4 (CORTEXM3_NVIC_BASE + NVIC_ISAR4_OFFSET) -#define NVIC_STIR (CORTEXM3_NVIC_BASE + NVIC_STIR_OFFSET) -#define NVIC_PID4 (CORTEXM3_NVIC_BASE + NVIC_PID4_OFFSET) -#define NVIC_PID5 (CORTEXM3_NVIC_BASE + NVIC_PID5_OFFSET) -#define NVIC_PID6 (CORTEXM3_NVIC_BASE + NVIC_PID6_OFFSET) -#define NVIC_PID7 (CORTEXM3_NVIC_BASE + NVIC_PID7_OFFSET) -#define NVIC_PID0 (CORTEXM3_NVIC_BASE + NVIC_PID0_OFFSET) -#define NVIC_PID1 (CORTEXM3_NVIC_BASE + NVIC_PID1_OFFSET) -#define NVIC_PID2 (CORTEXM3_NVIC_BASE + NVIC_PID2_OFFSET) -#define NVIC_PID3 (CORTEXM3_NVIC_BASE + NVIC_PID3_OFFSET) -#define NVIC_CID0 (CORTEXM3_NVIC_BASE + NVIC_CID0_OFFSET) -#define NVIC_CID1 (CORTEXM3_NVIC_BASE + NVIC_CID1_OFFSET) -#define NVIC_CID2 (CORTEXM3_NVIC_BASE + NVIC_CID2_OFFSET) -#define NVIC_CID3 (CORTEXM3_NVIC_BASE + NVIC_CID3_OFFSET) - -/* NVIC register bit definitions ****************************************************/ - -/* Interrrupt controller type (INCTCTL_TYPE) */ - -#define NVIC_INTCTRL_TYPE_INTLINESNUM_SHIFT 0 /* Bits 4-0: Number of interrupt intputs / 32 */ -#define NVIC_INTCTRL_TYPE_INTLINESNUM_MASK (0x1f << NVIC_INTCTRL_TYPE_INTLINESNUM_SHIFT) - -/* SysTick control and status register (SYSTICK_CTRL) */ - -#define NVIC_SYSTICK_CTRL_ENABLE (1 << 0) /* Bit 0: Enable */ -#define NVIC_SYSTICK_CTRL_TICKINT (1 << 1) /* Bit 1: Tick interrupt */ -#define NVIC_SYSTICK_CTRL_CLKSOURCE (1 << 2) /* Bit 2: Clock source */ -#define NVIC_SYSTICK_CTRL_COUNTFLAG (1 << 16) /* Bit 16: Count Flag */ - -/* SysTick reload value register (SYSTICK_RELOAD) */ - -#define NVIC_SYSTICK_RELOAD_SHIFT 0 /* Bits 23-0: Timer reload value */ -#define NVIC_SYSTICK_RELOAD_MASK (0x00ffffff << NVIC_SYSTICK_RELOAD_SHIFT) - -/* SysTick current value registe (SYSTICK_CURRENT) */ - -#define NVIC_SYSTICK_CURRENT_SHIFT 0 /* Bits 23-0: Timer current value */ -#define NVIC_SYSTICK_CURRENT_MASK (0x00ffffff << NVIC_SYSTICK_RELOAD_SHIFT) - -/* SysTick calibration value register (SYSTICK_CALIB) */ - -#define NVIC_SYSTICK_CALIB_TENMS_SHIFT 0 /* Bits 23-0: Calibration value */ -#define NVIC_SYSTICK_CALIB_TENMS_MASK (0x00ffffff << NVIC_SYSTICK_CALIB_TENMS_SHIFT) -#define NVIC_SYSTICK_CALIB_SKEW (1 << 30) /* Bit 30: Calibration value inexact */ -#define NVIC_SYSTICK_CALIB_NOREF (1 << 31) /* Bit 31: No external reference clock */ - -/* Interrupt control state register (INTCTRL) */ - -#define NVIC_INTCTRL_NMIPENDSET (1 << 31) /* Bit 31: Set pending NMI bit */ -#define NVIC_INTCTRL_PENDSVSET (1 << 28) /* Bit 28: Set pending PendSV bit */ -#define NVIC_INTCTRL_PENDSVCLR (1 << 27) /* Bit 27: Clear pending PendSV bit */ -#define NVIC_INTCTRL_PENDSTSET (1 << 26) /* Bit 26: Set pending SysTick bit */ -#define NVIC_INTCTRL_PENDSTCLR (1 << 25) /* Bit 25: Clear pending SysTick bit */ -#define NVIC_INTCTRL_ISPREEMPOT (1 << 23) /* Bit 23: Pending active next cycle */ -#define NVIC_INTCTRL_ISRPENDING (1 << 22) /* Bit 22: Interrupt pending flag */ -#define NVIC_INTCTRL_VECTPENDING_SHIFT 12 /* Bits 21-12: Pending ISR number field */ -#define NVIC_INTCTRL_VECTPENDING_MASK (0x3ff << NVIC_INTCTRL_VECTPENDING_SHIFT) -#define NVIC_INTCTRL_RETTOBASE (1 << 11) /* Bit 11: no other exceptions pending */ -#define NVIC_INTCTRL_VECTACTIVE_SHIFT 0 /* Bits 8-0: Active ISR number */ -#define NVIC_INTCTRL_VECTACTIVE_MASK (0x1ff << NVIC_INTCTRL_VECTACTIVE_SHIFT) - -/* System handler 4-7 priority register */ - -#define NVIC_SYSH_PRIORITY_PR4_SHIFT 0 -#define NVIC_SYSH_PRIORITY_PR4_MASK (0xff << NVIC_SYSH_PRIORITY_PR4_SHIFT) -#define NVIC_SYSH_PRIORITY_PR5_SHIFT 8 -#define NVIC_SYSH_PRIORITY_PR5_MASK (0xff << NVIC_SYSH_PRIORITY_PR5_SHIFT) -#define NVIC_SYSH_PRIORITY_PR6_SHIFT 16 -#define NVIC_SYSH_PRIORITY_PR6_MASK (0xff << NVIC_SYSH_PRIORITY_PR6_SHIFT) -#define NVIC_SYSH_PRIORITY_PR7_SHIFT 24 -#define NVIC_SYSH_PRIORITY_PR7_MASK (0xff << NVIC_SYSH_PRIORITY_PR7_SHIFT) - -/* System handler 8-11 priority register */ - -#define NVIC_SYSH_PRIORITY_PR8_SHIFT 0 -#define NVIC_SYSH_PRIORITY_PR8_MASK (0xff << NVIC_SYSH_PRIORITY_PR8_SHIFT) -#define NVIC_SYSH_PRIORITY_PR9_SHIFT 8 -#define NVIC_SYSH_PRIORITY_PR9_MASK (0xff << NVIC_SYSH_PRIORITY_PR9_SHIFT) -#define NVIC_SYSH_PRIORITY_PR10_SHIFT 16 -#define NVIC_SYSH_PRIORITY_PR10_MASK (0xff << NVIC_SYSH_PRIORITY_PR10_SHIFT) -#define NVIC_SYSH_PRIORITY_PR11_SHIFT 24 -#define NVIC_SYSH_PRIORITY_PR11_MASK (0xff << NVIC_SYSH_PRIORITY_PR11_SHIFT) - -/* System handler 12-15 priority register */ - -#define NVIC_SYSH_PRIORITY_PR12_SHIFT 0 -#define NVIC_SYSH_PRIORITY_PR12_MASK (0xff << NVIC_SYSH_PRIORITY_PR12_SHIFT) -#define NVIC_SYSH_PRIORITY_PR13_SHIFT 8 -#define NVIC_SYSH_PRIORITY_PR13_MASK (0xff << NVIC_SYSH_PRIORITY_PR13_SHIFT) -#define NVIC_SYSH_PRIORITY_PR14_SHIFT 16 -#define NVIC_SYSH_PRIORITY_PR14_MASK (0xff << NVIC_SYSH_PRIORITY_PR14_SHIFT) -#define NVIC_SYSH_PRIORITY_PR15_SHIFT 24 -#define NVIC_SYSH_PRIORITY_PR15_MASK (0xff << NVIC_SYSH_PRIORITY_PR15_SHIFT) - -/* System handler control and state register (SYSHCON) */ - -#define NVIC_SYSHCON_MEMFAULTACT (1 << 0) /* Bit 0: MemManage is active */ -#define NVIC_SYSHCON_BUSFAULTACT (1 << 1) /* Bit 1: BusFault is active */ -#define NVIC_SYSHCON_USGFAULTACT (1 << 3) /* Bit 3: UsageFault is active */ -#define NVIC_SYSHCON_SVCALLACT (1 << 7) /* Bit 7: SVCall is active */ -#define NVIC_SYSHCON_MONITORACT (1 << 8) /* Bit 8: Monitor is active */ -#define NVIC_SYSHCON_PENDSVACT (1 << 10) /* Bit 10: PendSV is active */ -#define NVIC_SYSHCON_SYSTICKACT (1 << 11) /* Bit 11: SysTick is active */ -#define NVIC_SYSHCON_USGFAULTPENDED (1 << 12) /* Bit 12: Usage fault is pended */ -#define NVIC_SYSHCON_MEMFAULTPENDED (1 << 13) /* Bit 13: MemManage is pended */ -#define NVIC_SYSHCON_BUSFAULTPENDED (1 << 14) /* Bit 14: BusFault is pended */ -#define NVIC_SYSHCON_SVCALLPENDED (1 << 15) /* Bit 15: SVCall is pended */ -#define NVIC_SYSHCON_MEMFAULTENA (1 << 16) /* Bit 16: MemFault enabled */ -#define NVIC_SYSHCON_BUSFAULTENA (1 << 17) /* Bit 17: BusFault enabled */ -#define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_COMMON_CORTEXM3_NVIC_H */ diff --git a/nuttx/arch/arm/src/common/cortexm3_psr.h b/nuttx/arch/arm/src/common/cortexm3_psr.h deleted file mode 100644 index 9f7d2cc72..000000000 --- a/nuttx/arch/arm/src/common/cortexm3_psr.h +++ /dev/null @@ -1,91 +0,0 @@ -/************************************************************************************ - * arch/arm/src/common/cortexm3_psr.h - * - * Copyright (C) 2009 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. - * - ************************************************************************************/ - -#ifndef __ARCH_ARM_SRC_COMMON_CORTEXM_PSR_H -#define __ARCH_ARM_SRC_COMMON_CORTEXM_PSR_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#ifndef __ASSEMBLY__ -# include -#endif - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Application Program Status Register (APSR) */ - -#define CORTEXM3_APSR_Q (1 << 27) /* Bit 27: Sticky saturation flag */ -#define CORTEXM3_APSR_V (1 << 28) /* Bit 28: Overflow flag */ -#define CORTEXM3_APSR_C (1 << 29) /* Bit 29: Carry/borrow flag */ -#define CORTEXM3_APSR_Z (1 << 30) /* Bit 30: Zero flag */ -#define CORTEXM3_APSR_N (1 << 31) /* Bit 31: Negative, less than flag */ - -/* Interrupt Program Status Register (IPSR) */ - -#define CORTEXM3_IPSR_ISR_SHIFT 0 /* Bits 8-0: ISR number */ -#define CORTEXM3_IPSR_ISR_MASK (0x1ff << CORTEXM3_IPSR_ISR_SHIFT) - -/* Execution PSR Register (EPSR) */ - -#define CORTEXM3_EPSR_ICIIT1_SHIFT 10 /* Bits 15-10: Interrupt-Continuable-Instruction/If-Then bits */ -#define CORTEXM3_EPSR_ICIIT1_MASK (3 << CORTEXM3_EPSR_ICIIT1_SHIFT) -#define CORTEXM3_EPSR_T (1 << 24) /* Bit 24: T-bit */ -#define CORTEXM3_EPSR_ICIIT2_SHIFT 25 /* Bits 26-25: Interrupt-Continuable-Instruction/If-Then bits */ -#define CORTEXM3_EPSR_ICIIT2_MASK (3 << CORTEXM3_EPSR_ICIIT2_SHIFT) - -/* Save xPSR bits */ - -#define CORTEXM3_XPSR_ISR_SHIFT CORTEXM3_IPSR_ISR_SHIFT -#define CORTEXM3_XPSR_ISR_MASK CORTEXM3_IPSR_ISR_MASK -#define CORTEXM3_XPSR_ICIIT1_SHIFT CORTEXM3_EPSR_ICIIT1_SHIFT/ -#define CORTEXM3_XPSR_ICIIT1_MASK CORTEXM3_EPSR_ICIIT1_MASK -#define CORTEXM3_XPSR_T CORTEXM3_EPSR_T -#define CORTEXM3_XPSR_ICIIT2_SHIFT CORTEXM3_EPSR_ICIIT2_SHIFT -#define CORTEXM3_XPSR_ICIIT2_MASK CORTEXM3_EPSR_ICIIT2_MASK -#define CORTEXM3_XPSR_Q CORTEXM3_APSR_Q -#define CORTEXM3_XPSR_V CORTEXM3_APSR_V -#define CORTEXM3_XPSR_C CORTEXM3_APSR_C -#define CORTEXM3_XPSR_Z CORTEXM3_APSR_Z -#define CORTEXM3_XPSR_N CORTEXM3_APSR_N - -/************************************************************************************ - * Inline Functions - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_COMMON_CORTEXM_PSR_H */ diff --git a/nuttx/arch/arm/src/common/up_arch.h b/nuttx/arch/arm/src/common/up_arch.h index 71a33bb3e..6c8a2a6e3 100644 --- a/nuttx/arch/arm/src/common/up_arch.h +++ b/nuttx/arch/arm/src/common/up_arch.h @@ -45,7 +45,6 @@ # include #endif -#include "arm.h" #include #include "chip.h" diff --git a/nuttx/arch/arm/src/common/up_assert.c b/nuttx/arch/arm/src/common/up_assert.c deleted file mode 100644 index dcb254e60..000000000 --- a/nuttx/arch/arm/src/common/up_assert.c +++ /dev/null @@ -1,327 +0,0 @@ -/**************************************************************************** - * common/up_assert.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 - -#include -#include - -#include "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Output debug info if stack dump is selected -- even if - * debug is not selected. - */ - -#ifdef CONFIG_ARCH_STACKDUMP -# undef lldbg -# define lldbg lib_lowprintf -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_getsp - ****************************************************************************/ - -/* I don't know if the builtin to get SP is enabled */ - -static inline uint32 up_getsp(void) -{ - uint32 sp; - __asm__ - ( - "\tmov %0, sp\n\t" - : "=r"(sp) - ); - return sp; -} - -/**************************************************************************** - * Name: up_stackdump - ****************************************************************************/ - -#ifdef CONFIG_ARCH_STACKDUMP -static void up_stackdump(uint32 sp, uint32 stack_base) -{ - uint32 stack ; - - for (stack = sp & ~0x1f; stack < stack_base; stack += 32) - { - uint32 *ptr = (uint32*)stack; - lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n", - stack, ptr[0], ptr[1], ptr[2], ptr[3], - ptr[4], ptr[5], ptr[6], ptr[7]); - } -} -#else -# define up_stackdump() -#endif - -/**************************************************************************** - * Name: up_registerdump - ****************************************************************************/ - -#ifdef CONFIG_ARCH_STACKDUMP -static inline void up_registerdump(void) -{ - /* Are user registers available from interrupt processing? */ - - if (current_regs) - { -#ifdef __thumb2__ - /* Yes.. dump the interrupt registers */ - - lldbg("R0: %08x %08x %08x %08x %08x %08x %08x %08x\n", - current_regs[REG_R0], current_regs[REG_R1], - current_regs[REG_R2], current_regs[REG_R3], - current_regs[REG_R4], current_regs[REG_R5], - current_regs[REG_R6], current_regs[REG_R7]); - lldbg("R8: %08x %08x %08x %08x %08x %08x %08x %08x\n", - current_regs[REG_R8], current_regs[REG_R9], - current_regs[REG_R10], current_regs[REG_R11], - current_regs[REG_R12], current_regs[REG_R13], - current_regs[REG_R14], current_regs[REG_R15]); - lldbg("xPSR: %08x PRIMASK: %08x\n", - current_regs[REG_XPSR], current_regs[REG_PRIMASK]); -#else - int regs; - - /* Yes.. dump the interrupt registers */ - - for (regs = REG_R0; regs <= REG_R15; regs += 8) - { - uint32 *ptr = (uint32*)¤t_regs[regs]; - lldbg("R%d: %08x %08x %08x %08x %08x %08x %08x %08x\n", - regs, ptr[0], ptr[1], ptr[2], ptr[3], - ptr[4], ptr[5], ptr[6], ptr[7]); - } - - lldbg("CPSR: %08x\n", current_regs[REG_CPSR]); -#endif - } -} -#else -# define up_registerdump() -#endif - -/**************************************************************************** - * Name: up_dumpstate - ****************************************************************************/ - -#ifdef CONFIG_ARCH_STACKDUMP -static void up_dumpstate(void) -{ - _TCB *rtcb = (_TCB*)g_readytorun.head; - uint32 sp = up_getsp(); - uint32 ustackbase; - uint32 ustacksize; -#if CONFIG_ARCH_INTERRUPTSTACK > 3 - uint32 istackbase; - uint32 istacksize; -#endif - - /* Get the limits on the user stack memory */ - - if (rtcb->pid == 0) - { - ustackbase = g_heapbase - 4; - ustacksize = CONFIG_IDLETHREAD_STACKSIZE; - } - else - { - ustackbase = (uint32)rtcb->adj_stack_ptr; - ustacksize = (uint32)rtcb->adj_stack_size; - } - - /* Get the limits on the interrupt stack memory */ - -#if CONFIG_ARCH_INTERRUPTSTACK > 3 - istackbase = (uint32)&g_userstack; - istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4; - - /* Show interrupt stack info */ - - lldbg("sp: %08x\n", sp); - lldbg("IRQ stack:\n"); - lldbg(" base: %08x\n", istackbase); - lldbg(" size: %08x\n", istacksize); - - /* Does the current stack pointer lie within the interrupt - * stack? - */ - - if (sp <= istackbase && sp > istackbase - istacksize) - { - /* Yes.. dump the interrupt stack */ - - up_stackdump(sp, istackbase); - - /* Extract the user stack pointer which should lie - * at the base of the interrupt stack. - */ - - sp = g_userstack; - lldbg("sp: %08x\n", sp); - } - - /* Show user stack info */ - - lldbg("User stack:\n"); - lldbg(" base: %08x\n", ustackbase); - lldbg(" size: %08x\n", ustacksize); -#else - lldbg("sp: %08x\n", sp); - lldbg("stack base: %08x\n", ustackbase); - lldbg("stack size: %08x\n", ustacksize); -#endif - - /* Dump the user stack if the stack pointer lies within the allocated user - * stack memory. - */ - - if (sp > ustackbase || sp <= ustackbase - ustacksize) - { -#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4 - lldbg("ERROR: Stack pointer is not within allocated stack\n"); -#endif - } - else - { - up_stackdump(sp, ustackbase); - } - - /* Then dump the registers (if available) */ - - up_registerdump(); -} -#else -# define up_dumpstate() -#endif - -/**************************************************************************** - * Name: _up_assert - ****************************************************************************/ - -static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */ -{ - /* Are we in an interrupt handler or the idle task? */ - - if (current_regs || ((_TCB*)g_readytorun.head)->pid == 0) - { - (void)irqsave(); - for(;;) - { -#ifdef CONFIG_ARCH_LEDS - up_ledon(LED_PANIC); - up_mdelay(250); - up_ledoff(LED_PANIC); - up_mdelay(250); -#endif - } - } - else - { - exit(errorcode); - } -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_assert - ****************************************************************************/ - -void up_assert(const ubyte *filename, int lineno) -{ -#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG) - _TCB *rtcb = (_TCB*)g_readytorun.head; -#endif - - up_ledon(LED_ASSERTION); -#if CONFIG_TASK_NAME_SIZE > 0 - lldbg("Assertion failed at file:%s line: %d task: %s\n", - filename, lineno, rtcb->name); -#else - lldbg("Assertion failed at file:%s line: %d\n", - filename, lineno); -#endif - up_dumpstate(); - _up_assert(EXIT_FAILURE); -} - -/**************************************************************************** - * Name: up_assert_code - ****************************************************************************/ - -void up_assert_code(const ubyte *filename, int lineno, int errorcode) -{ -#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG) - _TCB *rtcb = (_TCB*)g_readytorun.head; -#endif - - up_ledon(LED_ASSERTION); -#if CONFIG_TASK_NAME_SIZE > 0 - lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n", - filename, lineno, rtcb->name, errorcode); -#else - lldbg("Assertion failed at file:%s line: %d error code: %d\n", - filename, lineno, errorcode); -#endif - up_dumpstate(); - _up_assert(errorcode); -} diff --git a/nuttx/arch/arm/src/common/up_cache.S b/nuttx/arch/arm/src/common/up_cache.S deleted file mode 100644 index 571217f0e..000000000 --- a/nuttx/arch/arm/src/common/up_cache.S +++ /dev/null @@ -1,74 +0,0 @@ -/**************************************************************************** - * common/up_cache.S - * - * Copyright (C) 2007, 2009 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 "up_internal.h" -#include "up_arch.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -#define CACHE_DLINESIZE 32 - -/**************************************************************************** - * Assembly Macros - ****************************************************************************/ - -/**************************************************************************** - * Name: up_flushicache - ****************************************************************************/ - -/* Esure coherency between the Icache and the Dcache in the region described - * by r0=start and r1=end. - */ - .globl up_flushicache - .type up_flushicache,%function -up_flushicache: - bic r0, r0, #CACHE_DLINESIZE - 1 -1: mcr p15, 0, r0, c7, c10, 1 /* Clean D entry */ - mcr p15, 0, r0, c7, c5, 1 /* Invalidate I entry */ - add r0, r0, #CACHE_DLINESIZE - cmp r0, r1 - blo 1b - mcr p15, 0, r0, c7, c10, 4 /* Drain WB */ - mov pc, lr - .size up_flushicache, .-up_flushicache - .end - diff --git a/nuttx/arch/arm/src/common/up_copystate.c b/nuttx/arch/arm/src/common/up_copystate.c deleted file mode 100644 index b73c6c95c..000000000 --- a/nuttx/arch/arm/src/common/up_copystate.c +++ /dev/null @@ -1,90 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_copystate.c - * - * Copyright (C) 2007-2009 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 "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_undefinedinsn - ****************************************************************************/ - -/* A little faster than most memcpy's */ - -void up_copystate(uint32 *dest, uint32 *src) -{ - int i; - - /* In the current ARM model, the state is always copied to and from the - * stack and TCB. In the Cortex-M3 model, the state is copied from the - * stack to the TCB, but only a referenced is passed to get the the state - * from the TCB. So the following check makes sense only for the Cortex-M3 - * model: - */ - -#ifdef __thumb2__ - if (src != dest) -#endif - { - for (i = 0; i < XCPTCONTEXT_REGS; i++) - { - *dest++ = *src++; - } - } -} - diff --git a/nuttx/arch/arm/src/common/up_dataabort.c b/nuttx/arch/arm/src/common/up_dataabort.c deleted file mode 100644 index 334cdc4c1..000000000 --- a/nuttx/arch/arm/src/common/up_dataabort.c +++ /dev/null @@ -1,81 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_dataabort.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 "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Output debug info if stack dump is selected -- even if - * debug is not selected. - */ - -#ifdef CONFIG_ARCH_STACKDUMP -# undef lldbg -# define lldbg lib_lowprintf -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_dataabort - ****************************************************************************/ - -void up_dataabort(uint32 *regs) -{ - lldbg("Data abort at 0x%x\n", regs[REG_PC]); - current_regs = regs; - PANIC(OSERR_ERREXCEPTION); -} diff --git a/nuttx/arch/arm/src/common/up_doirq.c b/nuttx/arch/arm/src/common/up_doirq.c deleted file mode 100644 index 861f5f3d8..000000000 --- a/nuttx/arch/arm/src/common/up_doirq.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_doirq.c - * - * Copyright (C) 2007-2009 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 -#include "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -#ifdef __thumb2__ -uint32 *up_doirq(int irq, uint32 *regs) -#else -void up_doirq(int irq, uint32 *regs) -#endif -{ - up_ledon(LED_INIRQ); -#ifdef CONFIG_SUPPRESS_INTERRUPTS - PANIC(OSERR_ERREXCEPTION); -#else - if ((unsigned)irq < NR_IRQS) - { - /* Current regs non-zero indicates that we are processing - * an interrupt; current_regs is also used to manage - * interrupt level context switches. - */ - - current_regs = regs; - - /* Mask and acknowledge the interrupt */ - - up_maskack_irq(irq); - - /* Deliver the IRQ */ - - irq_dispatch(irq, regs); - - /* If a context switch occurred while processing the interrupt - * then current_regs may have value (depending upon the implementaton - * of context switching for te particular chip. - */ - -#ifdef __thumb2__ - regs = current_regs; -#endif - /* Indicate that we are no long in an interrupt handler */ - - current_regs = NULL; - - /* Unmask the last interrupt (global interrupts are still - * disabled. - */ - - up_enable_irq(irq); - } - up_ledoff(LED_INIRQ); -#endif -#ifdef __thumb2__ - return regs; -#endif -} diff --git a/nuttx/arch/arm/src/common/up_fullcontextrestore.S b/nuttx/arch/arm/src/common/up_fullcontextrestore.S deleted file mode 100644 index 43dcf6573..000000000 --- a/nuttx/arch/arm/src/common/up_fullcontextrestore.S +++ /dev/null @@ -1,117 +0,0 @@ -/************************************************************************** - * common/up_fullcontextrestore.S - * - * Copyright (C) 2007, 2009 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 "up_internal.h" - -/************************************************************************** - * Private Definitions - **************************************************************************/ - -/************************************************************************** - * Private Types - **************************************************************************/ - -/************************************************************************** - * Private Function Prototypes - **************************************************************************/ - -/************************************************************************** - * Global Variables - **************************************************************************/ - -/************************************************************************** - * Private Variables - **************************************************************************/ - -/************************************************************************** - * Private Functions - **************************************************************************/ - -/************************************************************************** - * Public Functions - **************************************************************************/ - -/************************************************************************** - * Name: up_fullcontextrestore - **************************************************************************/ - - .globl up_fullcontextrestore - .type up_fullcontextrestore, function -up_fullcontextrestore: - - /* On entry, a1 (r0) holds address of the register save area */ - - /* Recover all registers except for r0, r1, R15, and CPSR */ - - add r1, r0, #(4*REG_R2) /* Offset to REG_R2 storage */ - ldmia r1, {r2-r14} /* Recover registers */ - - /* Create a stack frame to hold the PC */ - - sub sp, sp, #(3*4) /* Frame for three registers */ - ldr r1, [r0, #(4*REG_R0)] /* Fetch the stored r0 value */ - str r1, [sp] /* Save it at the top of the stack */ - ldr r1, [r0, #(4*REG_R1)] /* Fetch the stored r1 value */ - str r1, [sp, #4] /* Save it in the stack */ - ldr r1, [r0, #(4*REG_PC)] /* Fetch the stored pc value */ - str r1, [sp, #8] /* Save it at the bottom of the frame */ - - /* Now we can restore the CPSR. We wait until we are completely - * finished with the context save data to do this. Restore the CPSR - * may re-enable and interrupts and we couldt be in a context - * where save structure is only protected by interrupts being disabled. - */ - - ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the stored CPSR value */ - msr cpsr, r1 /* Set the CPSR */ - - /* Now recover r0 and r1 */ - - ldr r0, [sp] - ldr r1, [sp, #4] - add sp, sp, #(2*4) - - /* Then return to the address at the stop of the stack, - * destroying the stack frame - */ - - ldr pc, [sp], #4 - .size up_fullcontextrestore, . - up_fullcontextrestore - diff --git a/nuttx/arch/arm/src/common/up_head.S b/nuttx/arch/arm/src/common/up_head.S deleted file mode 100644 index 0b4666221..000000000 --- a/nuttx/arch/arm/src/common/up_head.S +++ /dev/null @@ -1,369 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_head.S - * - * Copyright (C) 2007, 2009 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 "up_internal.h" -#include "up_arch.h" - -/********************************************************************************** - * Conditional Compilation - **********************************************************************************/ - -#undef ALIGNMENT_TRAP -#undef CPU_DCACHE_WRITETHROUGH -#undef CPU_CACHE_ROUND_ROBIN -#undef CPU_DCACHE_DISABLE -#undef CPU_ICACHE_DISABLE - -/* There are three operational memory configurations: - * - * 1. We execute in place in FLASH (CONFIG_BOOT_RUNFROMFLASH=y). In this case - * the boot logic must: - * - * - Configure SDRAM and, - * - Initialize the .data section in RAM. - */ - -#ifdef CONFIG_BOOT_RUNFROMFLASH -# define CONFIGURE_SDRAM - -/* 2. We boot in FLASH but copy ourselves to DRAM from better performance. - * (CONFIG_BOOT_RUNFROMFLASH=n && CONFIG_BOOT_COPYTORAM=y). In this case - * the boot logic must: - * - * - Configure SDRAM and, - * - Copy ourself to DRAM (after mapping it) - */ - -#elif defined(CONFIG_BOOT_COPYTORAM) -# define CONFIG_SDRAM - -/* 3. There is bootloader that copies us to DRAM (but probably not to the beginning) - * (CONFIG_BOOT_RUNFROMFLASH=n && CONFIG_BOOT_COPYTORAM=n). In this case the - * boot logic must: - * - * - Nothing special. - */ - -#endif - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* The physical address of the beginning of SDRAM is provided by - * CONFIG_DRAM_START. The size of installed SDRAM is provided by - * CONFIG_DRAM_SIZE. The virtual address of SDRAM is provided by - * CONFIG_DRAM_VSTART. - */ - -#define NSDRAM_SECTIONS (CONFIG_DRAM_SIZE >> 20) - -/**************************************************************************** - * Assembly Macros - ****************************************************************************/ - -/* Since the page table is closely related to the NuttX base - * address, we can convert the page table base address to the - * base address of the section containing both. - */ - - .macro mksection, section, pgtable - bic \section, \pgtable, #0x000ff000 - .endm - -/* This macro will modify r0, r1, r2 and r14 */ - -#ifdef CONFIG_DEBUG - .macro showprogress, code - mov r0, #\code - bl up_lowputc - .endm -#else - .macro showprogress, code - .endm -#endif - -/**************************************************************************** - * Name: __start - ****************************************************************************/ - -/* We assume the bootloader has already initialized most of the h/w for - * us and that only leaves us having to do some os specific things - * below. - */ - .text - .global __start - .type __start, #function -__start: - /* Make sure that we are in SVC mode with all IRQs disabled */ - - mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT) - msr cpsr_c, r0 - - /* Initialize DRAM using a macro provided by board-specific logic */ - -#ifdef CONFIG_SDRAM - config_sdram -#endif - /* Clear the 16K level 1 page table */ - - ldr r4, .LCppgtable /* r4=phys. page table */ - mov r0, r4 - mov r1, #0 - add r2, r0, #PGTABLE_SIZE -.Lpgtableclear: - str r1, [r0], #4 - str r1, [r0], #4 - str r1, [r0], #4 - str r1, [r0], #4 - teq r0, r2 - bne .Lpgtableclear - - /* Create identity mapping for first MB section to support - * this startup logic executing out of the physical address - * space. This identity mapping will be removed by .Lvstart - * (see below). - */ - - mksection r0, r4 /* r0=phys. base section */ - ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */ - add r3, r1, r0 /* r3=flags + base */ - str r3, [r4, r0, lsr #18] /* identity mapping */ - - /* Create a "normal" single section mapping for the first - * MB of memory. Now, we have the first 1MB mapping to - * both phyical and virtual addresses. The reset of the - * SDRAM mapping will be completed in .Lvstart once we have - * moved the physical mapping out of the way. - */ - - ldr r2, .LCvpgtable /* r2=virt. page table */ - mksection r0, r2 /* r0=virt. base section */ - str r3, [r4, r0, lsr #18] /* identity mapping */ - - /* The following logic will set up the ARM920/ARM926 for normal operation */ - - mov r0, #0 - mcr p15, 0, r0, c7, c7 /* Invalidate I,D caches */ - mcr p15, 0, r0, c7, c10, 4 /* Drain write buffer */ - mcr p15, 0, r0, c8, c7 /* Invalidate I,D TLBs */ - mcr p15, 0, r4, c2, c0 /* Load page table pointer */ - -#ifdef CPU_DCACHE_WRITETHROUGH - mov r0, #4 /* Disable write-back on caches explicitly */ - mcr p15, 7, r0, c15, c0, 0 -#endif - - /* Enable the MMU and caches - * lr = Resume at .Lvstart with the MMU enabled - */ - - ldr lr, .LCvstart /* Abs. virtual address */ - - mov r0, #0x1f /* Domains 0, 1 = client */ - mcr p15, 0, r0, c3, c0 /* Load domain access register */ - mrc p15, 0, r0, c1, c0 /* Get control register */ - - /* Clear bits (see arm.h) */ - - bic r0, r0, #(CR_R|CR_F|CR_Z) - bic r0, r0, #(CR_A|CR_C|CR_W) - bic r0, r0, #(CR_I) - - /* Set bits (see arm.h) */ - - orr r0, r0, #(CR_M|CR_P|CR_D) - - /* In most architectures, vectors are reloated to 0xffff0000. - * -- but not all - */ - -#ifndef CONFIG_ARCH_LOWVECTORS - orr r0, r0, #(CR_S) -#else - orr r0, r0, #(CR_S|CR_V) -#endif -#ifdef CPU_CACHE_ROUND_ROBIN - orr r0, r0, #(CR_RR) -#endif -#ifndef CPU_DCACHE_DISABLE - orr r0, r0, #(CR_C) -#endif -#ifndef CPU_ICACHE_DISABLE - orr r0, r0, #(CR_I) -#endif -#ifdef ALIGNMENT_TRAP - orr r0, r0, #(CR_A) -#endif - mcr p15, 0, r0, c1, c0, 0 /* write control reg */ - - /* Get TMP=2 Processor ID register */ - - mrc p15, 0, r1, c0, c0, 0 /* read id reg */ - mov r1, r1 - mov r1, r1 - - mov pc, lr - -/********************************************************************************** - * PC_Relative Data - **********************************************************************************/ - - /* These addresses are all virtual address */ - - .type .LCvstart, %object -.LCvstart: - .long .Lvstart - .type .LCmmuflags, %object -.LCmmuflags: - .long MMU_MEMFLAGS - .type .LCppagetable, %object -.LCppgtable: - .long CONFIG_DRAM_START /* Physical start of DRAM */ - .type .LCvpagetable, %object -.LCvpgtable: - .long CONFIG_DRAM_VSTART /* Virtual start of DRAM */ - .size _start, .-_start - -/********************************************************************************** - * Name: .Lvstart - **********************************************************************************/ - -/* The following is executed after the MMU has been enabled. This uses - * absolute addresses; this is not position independent. - */ - .align 5 - .local .Lvstart - .type .Lvstart, %function -.Lvstart: - - /* Remove the temporary null mapping */ - - ldr r4, .LCvpgtable /* r4=virtual page table */ - ldr r1, .LCppgtable /* r1=phys. page table */ - mksection r3, r1 /* r2=phys. base addr */ - mov r0, #0 /* flags + base = 0 */ - str r0, [r4, r3, lsr #18] /* Undo identity mapping */ - - /* Now setup the pagetables for our normal SDRAM mappings - * mapped region. We round NUTTX_START_VADDR down to the - * nearest megabyte boundary. - */ - - ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */ - add r3, r3, r1 /* r3=flags + base */ - - add r0, r4, #(NUTTX_START_VADDR & 0xff000000) >> 18 - bic r2, r3, #0x00f00000 - str r2, [r0] - - add r0, r0, #(NUTTX_START_VADDR & 0x00f00000) >> 18 - str r3, [r0], #4 - - /* Now map the remaining NSDRAM_SECTIONS-1 SDRAM sections */ - - .rept NSDRAM_SECTIONS-1 - add r3, r3, #SECTION_SIZE - str r3, [r0], #4 - .endr - - /* Zero BSS and set up the stack pointer */ - - adr r0, .Linitparms - ldmia r0, {r0, r1, sp} - - /* Clear the frame pointer and .bss */ - - mov fp, #0 - -.Lbssinit: - cmp r0, r1 /* Clear up to _bss_end_ */ - strcc fp, [r0],#4 - bcc .Lbssinit - - /* Perform early C-level initialization */ - - bl up_boot - - /* Set up the LEDs */ - -#ifdef CONFIG_ARCH_LEDS - bl up_ledinit -#endif - /* Perform early serial initialization */ - -#ifdef CONFIG_USE_EARLYSERIALINIT - bl up_earlyserialinit -#endif - - /* Finally branch to the OS entry point */ - - mov lr, #0 - b os_start - - /* Variables: - * _sbss is the start of the BSS region (see ld.script) - * _ebss is the end of the BSS regsion (see ld.script) - * The idle task stack starts at the end of BSS and is - * of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues - * from there until the end of memory. See g_heapbase - * below. - */ - -.Linitparms: - .long _sbss - .long _ebss - .long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4 - .size .Lvstart, .-.Lvstart - - /* This global variable is unsigned long g_heapbase and is - * exported from here only because of its coupling to .Linitparms - * above. - */ - - .data - .align 4 - .globl g_heapbase - .type g_heapbase, object -g_heapbase: - .long _ebss+CONFIG_IDLETHREAD_STACKSIZE - .size g_heapbase, .-g_heapbase - .end - diff --git a/nuttx/arch/arm/src/common/up_initialstate.c b/nuttx/arch/arm/src/common/up_initialstate.c deleted file mode 100644 index 9c683a950..000000000 --- a/nuttx/arch/arm/src/common/up_initialstate.c +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_initialstate.c - * - * Copyright (C) 2007-2009 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 "up_internal.h" -#include "up_arch.h" - -#ifdef __thumb2__ -# include "cortexm3_psr.h" -#endif - -/**************************************************************************** - * 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)); - - /* Save the initial stack point */ - - xcp->regs[REG_SP] = (uint32)tcb->adj_stack_ptr; - -#ifdef __thumb2__ - /* Save the task entry point (stripping off the thumb bit) */ - - xcp->regs[REG_PC] = (uint32)tcb->start & ~1; - - /* Specify thumb mode */ - - xcp->regs[REG_XPSR] = CORTEXM3_XPSR_T; - - /* Enable or disable interrupts, based on user configuration */ - -# ifdef CONFIG_SUPPRESS_INTERRUPTS - xcp->regs[REG_PRIMASK] = 1; -# endif -#else /* __thumb2__ */ - /* Save the task entry point */ - - xcp->regs[REG_PC] = (uint32)tcb->start; - - /* Enable or disable interrupts, based on user configuration */ - -# ifdef CONFIG_SUPPRESS_INTERRUPTS - xcp->regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT; -# else - xcp->regs[REG_CPSR] = SVC_MODE | PSR_F_BIT; -# endif -#endif /* __thumb2__ */ -} diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h index 34a7918e1..d5c350e1e 100644 --- a/nuttx/arch/arm/src/common/up_internal.h +++ b/nuttx/arch/arm/src/common/up_internal.h @@ -77,7 +77,7 @@ * a referenced is passed to get the the state from the TCB. */ -#ifdef __thumb2__ +#ifdef CONFIG_ARCH_CORTEXM3 # define up_savestate(regs) up_copystate(regs, current_regs) # define up_restorestate(regs) (current_regs = regs) #else @@ -136,7 +136,7 @@ extern void up_boot(void); extern void up_copystate(uint32 *dest, uint32 *src); extern void up_dataabort(uint32 *regs); extern void up_decodeirq(uint32 *regs); -#ifdef __thumb2__ +#ifdef CONFIG_ARCH_CORTEXM3 extern uint32 *up_doirq(int irq, uint32 *regs); #else extern void up_doirq(int irq, uint32 *regs); diff --git a/nuttx/arch/arm/src/common/up_nommuhead.S b/nuttx/arch/arm/src/common/up_nommuhead.S deleted file mode 100644 index e6ff048bb..000000000 --- a/nuttx/arch/arm/src/common/up_nommuhead.S +++ /dev/null @@ -1,165 +0,0 @@ -/**************************************************************************** - * common/up_nommuhead.S - * - * Copyright (C) 2007, 2009 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 "up_internal.h" -#include "up_arch.h" - -/**************************************************************************** - * Macros - ****************************************************************************/ - - /* This macro will modify r0, r1, r2 and r14 */ - -#ifdef CONFIG_DEBUG - .macro showprogress, code - mov r0, #\code - bl up_lowputc - .endm -#else - .macro showprogress, code - .endm -#endif - -/**************************************************************************** - * OS Entry Point - ****************************************************************************/ - -/* We assume the bootloader has already initialized most of the h/w for - * us and that only leaves us having to do some os specific things - * below. - */ - .text - .global __start - .type __start, #function -__start: - - /* First, setup initial processor mode */ - - mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT ) - msr cpsr, r0 - - showprogress 'A' - - /* Setup system stack (and get the BSS range) */ - - adr r0, LC0 - ldmia r0, {r4, r5, sp} - - /* Clear system BSS section */ - - mov r0, #0 -1: cmp r4, r5 - strcc r0, [r4], #4 - bcc 1b - - showprogress 'B' - - /* Copy system .data sections to new home in RAM. */ - -#ifdef CONFIG_BOOT_RUNFROMFLASH - - adr r3, LC2 - ldmia r3, {r0, r1, r2} - -1: ldmia r0!, {r3 - r10} - stmia r1!, {r3 - r10} - cmp r1, r2 - blt 1b - -#endif - - /* Perform early serial initialization */ - - mov fp, #0 -#ifdef CONFIG_USE_EARLYSERIALINIT - bl up_earlyserialinit -#endif - -#ifdef CONFIG_DEBUG - mov r0, #'C' - bl up_putc - mov r0, #'\n' - bl up_putc -#endif - /* Initialize onboard LEDs */ - -#ifdef CONFIG_ARCH_LEDS - bl up_ledinit -#endif - - /* Then jump to OS entry */ - - b os_start - - /* Variables: - * _sbss is the start of the BSS region (see ld.script) - * _ebss is the end of the BSS regsion (see ld.script) - * The idle task stack starts at the end of BSS and is - * of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues - * from there until the end of memory. See g_heapbase - * below. - */ - -LC0: .long _sbss - .long _ebss - .long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4 - -#ifdef CONFIG_BOOT_RUNFROMFLASH -LC2: .long _eronly /* Where .data defaults are stored in FLASH */ - .long _sdata /* Where .data needs to reside in SDRAM */ - .long _edata -#endif - .size __start, .-__start - - /* This global variable is unsigned long g_heapbase and is - * exported from here only because of its coupling to LCO - * above. - */ - - .data - .align 4 - .globl g_heapbase - .type g_heapbase, object -g_heapbase: - .long _ebss+CONFIG_IDLETHREAD_STACKSIZE - .size g_heapbase, .-g_heapbase - - .end - diff --git a/nuttx/arch/arm/src/common/up_prefetchabort.c b/nuttx/arch/arm/src/common/up_prefetchabort.c deleted file mode 100644 index 809c90d95..000000000 --- a/nuttx/arch/arm/src/common/up_prefetchabort.c +++ /dev/null @@ -1,81 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_prefetchabort.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 "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Output debug info if stack dump is selected -- even if - * debug is not selected. - */ - -#ifdef CONFIG_ARCH_STACKDUMP -# undef lldbg -# define lldbg lib_lowprintf -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_prefetchabort - ****************************************************************************/ - -void up_prefetchabort(uint32 *regs) -{ - lldbg("Prefetch abort at 0x%x\n", regs[REG_PC]); - current_regs = regs; - PANIC(OSERR_ERREXCEPTION); -} diff --git a/nuttx/arch/arm/src/common/up_saveusercontext.S b/nuttx/arch/arm/src/common/up_saveusercontext.S deleted file mode 100644 index dfae477c4..000000000 --- a/nuttx/arch/arm/src/common/up_saveusercontext.S +++ /dev/null @@ -1,119 +0,0 @@ -/************************************************************************** - * common/up_saveusercontext.S - * - * Copyright (C) 2007, 2009 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 "up_internal.h" - -/************************************************************************** - * Private Definitions - **************************************************************************/ - -/************************************************************************** - * Private Types - **************************************************************************/ - -/************************************************************************** - * Private Function Prototypes - **************************************************************************/ - -/************************************************************************** - * Global Variables - **************************************************************************/ - -/************************************************************************** - * Private Variables - **************************************************************************/ - -/************************************************************************** - * Private Functions - **************************************************************************/ - -/************************************************************************** - * Public Functions - **************************************************************************/ - -/************************************************************************** - * Name: up_saveusercontext - **************************************************************************/ - - .text - .globl up_saveusercontext - .type up_saveusercontext, function -up_saveusercontext: - /* On entry, a1 (r0) holds address of struct xcptcontext. - * Offset to the user region. - */ - - /* Make sure that the return value will be non-zero (the - * value of the other volatile registers don't matter -- - * r1-r3, ip). This function is called throught the - * noraml C calling conventions and the values of these - * registers cannot be assumed at the point of setjmp - * return. - */ - - mov ip, #1 - str ip, [r0, #(4*REG_R0)] - - /* Save the volatile registers (plus r12 which really - * doesn't need to be saved) - */ - - add r1, r0, #(4*REG_R4) - stmia r1, {r4-r14} - - /* Save the current cpsr */ - - mrs r2, cpsr /* R3 = CPSR value */ - add r1, r0, #(4*REG_CPSR) - str r2, [r1] - - /* Finally save the return address as the PC so that we - * return to the exit from this function. - */ - - add r1, r0, #(4*REG_PC) - str lr, [r1] - - /* Return 0 */ - - mov r0, #0 /* Return value == 0 */ - mov pc, lr /* Return */ - .size up_saveusercontext, . - up_saveusercontext - diff --git a/nuttx/arch/arm/src/common/up_schedulesigaction.c b/nuttx/arch/arm/src/common/up_schedulesigaction.c deleted file mode 100644 index a4ae20953..000000000 --- a/nuttx/arch/arm/src/common/up_schedulesigaction.c +++ /dev/null @@ -1,223 +0,0 @@ -/**************************************************************************** - * common/up_schedulesigaction.c - * - * Copyright (C) 2007-2009 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 - -#include "os_internal.h" -#include "up_internal.h" -#include "up_arch.h" - -#ifndef CONFIG_DISABLE_SIGNALS - -/**************************************************************************** - * Private Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_schedule_sigaction - * - * Description: - * This function is called by the OS when one or more - * signal handling actions have been queued for execution. - * The architecture specific code must configure things so - * that the 'igdeliver' callback is executed on the thread - * specified by 'tcb' as soon as possible. - * - * This function may be called from interrupt handling logic. - * - * This operation should not cause the task to be unblocked - * nor should it cause any immediate execution of sigdeliver. - * Typically, a few cases need to be considered: - * - * (1) This function may be called from an interrupt handler - * During interrupt processing, all xcptcontext structures - * should be valid for all tasks. That structure should - * be modified to invoke sigdeliver() either on return - * from (this) interrupt or on some subsequent context - * switch to the recipient task. - * (2) If not in an interrupt handler and the tcb is NOT - * the currently executing task, then again just modify - * the saved xcptcontext structure for the recipient - * task so it will invoke sigdeliver when that task is - * later resumed. - * (3) If not in an interrupt handler and the tcb IS the - * currently executing task -- just call the signal - * handler now. - * - ****************************************************************************/ - -void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver) -{ - /* Refuse to handle nested signal actions */ - - sdbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver); - - if (!tcb->xcp.sigdeliver) - { - irqstate_t flags; - - /* Make sure that interrupts are disabled */ - - flags = irqsave(); - - /* First, handle some special cases when the signal is - * being delivered to the currently executing task. - */ - - sdbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs); - - if (tcb == (_TCB*)g_readytorun.head) - { - /* CASE 1: We are not in an interrupt handler and - * a task is signalling itself for some reason. - */ - - if (!current_regs) - { - /* In this case just deliver the signal now. */ - - sigdeliver(tcb); - } - - /* CASE 2: We are in an interrupt handler AND the - * interrupted task is the same as the one that - * must receive the signal, then we will have to modify - * the return state as well as the state in the TCB. - * - * Hmmm... there looks like a latent bug here: The following - * logic would fail in the strange case where we are in an - * interrupt handler, the thread is signalling itself, but - * a context switch to another task has occurred so that - * current_regs does not refer to the thread at g_readytorun.head! - */ - - else - { - /* Save the return lr and cpsr and one scratch register - * These will be restored by the signal trampoline after - * the signals have been delivered. - */ - - tcb->xcp.sigdeliver = sigdeliver; - tcb->xcp.saved_pc = current_regs[REG_PC]; -#ifdef __thumb2__ - tcb->xcp.saved_primask = current_regs[REG_PRIMASK]; - tcb->xcp.saved_xpsr = current_regs[REG_XPSR]; -#else - tcb->xcp.saved_cpsr = current_regs[REG_CPSR]; -#endif - - /* Then set up to vector to the trampoline with interrupts - * disabled - */ - - current_regs[REG_PC] = (uint32)up_sigdeliver; -#ifdef __thumb2__ - current_regs[REG_PRIMASK] = 1; - current_regs[REG_XPSR] = 0; -#else - current_regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT; -#endif - - /* And make sure that the saved context in the TCB - * is the same as the interrupt return context. - */ - - up_savestate(tcb->xcp.regs); - } - } - - /* Otherwise, we are (1) signaling a task is not running - * from an interrupt handler or (2) we are not in an - * interrupt handler and the running task is signalling - * some non-running task. - */ - - else - { - /* Save the return lr and cpsr and one scratch register - * These will be restored by the signal trampoline after - * the signals have been delivered. - */ - - tcb->xcp.sigdeliver = sigdeliver; - tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC]; -#ifdef __thumb2__ - tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK]; - tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR]; -#else - tcb->xcp.saved_cpsr = tcb->xcp.regs[REG_CPSR]; -#endif - - /* Then set up to vector to the trampoline with interrupts - * disabled - */ - - tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver; -#ifdef __thumb2__ - tcb->xcp.regs[REG_PRIMASK] = 1; - tcb->xcp.regs[REG_XPSR] = 0; -#else - tcb->xcp.regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT; -#endif - } - - irqrestore(flags); - } -} - -#endif /* !CONFIG_DISABLE_SIGNALS */ diff --git a/nuttx/arch/arm/src/common/up_sigdeliver.c b/nuttx/arch/arm/src/common/up_sigdeliver.c deleted file mode 100644 index aff743884..000000000 --- a/nuttx/arch/arm/src/common/up_sigdeliver.c +++ /dev/null @@ -1,154 +0,0 @@ -/**************************************************************************** - * common/up_sigdeliver.c - * - * Copyright (C) 2007-2009 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 -#include - -#include "os_internal.h" -#include "up_internal.h" -#include "up_arch.h" - -#ifndef CONFIG_DISABLE_SIGNALS - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_sigdeliver - * - * Description: - * This is the a signal handling trampoline. When a - * signal action was posted. The task context was mucked - * with and forced to branch to this location with interrupts - * disabled. - * - ****************************************************************************/ - -void up_sigdeliver(void) -{ -#ifndef CONFIG_DISABLE_SIGNALS - _TCB *rtcb = (_TCB*)g_readytorun.head; - uint32 regs[XCPTCONTEXT_REGS]; - sig_deliver_t sigdeliver; - - /* Save the errno. This must be preserved throughout the - * signal handling so that the the user code final gets - * the correct errno value (probably EINTR). - */ - - int saved_errno = rtcb->pterrno; - - up_ledon(LED_SIGNAL); - - sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n", - rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head); - ASSERT(rtcb->xcp.sigdeliver != NULL); - - /* Save the real return state on the stack. */ - - up_copystate(regs, rtcb->xcp.regs); - regs[REG_PC] = rtcb->xcp.saved_pc; -#ifdef __thumb2__ - regs[REG_PRIMASK] = rtcb->xcp.saved_primask; - regs[REG_XPSR] = rtcb->xcp.saved_xpsr; -#else - regs[REG_CPSR] = rtcb->xcp.saved_cpsr; -#endif - - /* Get a local copy of the sigdeliver function pointer. - * we do this so that we can nullify the sigdeliver - * function point in the TCB and accept more signal - * deliveries while processing the current pending - * signals. - */ - - sigdeliver = rtcb->xcp.sigdeliver; - rtcb->xcp.sigdeliver = NULL; - - /* Then restore the task interrupt statat. */ - -#ifdef __thumb2__ - irqrestore((uint16)regs[REG_PRIMASK]); -#else - irqrestore(regs[REG_CPSR]); -#endif - - /* Deliver the signals */ - - sigdeliver(rtcb); - - /* Output any debug messaged BEFORE restoreing errno - * (becuase they may alter errno), then restore the - * original errno that is needed by the user logic - * (it is probably EINTR). - */ - - sdbg("Resuming\n"); - rtcb->pterrno = saved_errno; - - /* Then restore the correct state for this thread of - * execution. - */ - - up_ledoff(LED_SIGNAL); - up_fullcontextrestore(regs); -#endif -} - -#endif /* !CONFIG_DISABLE_SIGNALS */ - diff --git a/nuttx/arch/arm/src/common/up_syscall.c b/nuttx/arch/arm/src/common/up_syscall.c deleted file mode 100644 index 2fef9594a..000000000 --- a/nuttx/arch/arm/src/common/up_syscall.c +++ /dev/null @@ -1,94 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_syscall.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 "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Output debug info if stack dump is selected -- even if - * debug is not selected. - */ - -#ifdef CONFIG_ARCH_STACKDUMP -# undef lldbg -# define lldbg lib_lowprintf -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * vectors - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_syscall - * - * Description: - * SWI interrupts will vection here with insn=the SWI - * instruction and xcp=the interrupt context - * - * The handler may get the SWI number be de-referencing - * the return address saved in the xcp and decoding - * the SWI instruction - * - ****************************************************************************/ - -void up_syscall(uint32 *regs) -{ - lldbg("Syscall from 0x%x\n", regs[REG_PC]); - current_regs = regs; - PANIC(OSERR_ERREXCEPTION); -} diff --git a/nuttx/arch/arm/src/common/up_undefinedinsn.c b/nuttx/arch/arm/src/common/up_undefinedinsn.c deleted file mode 100644 index 3a6bd39f6..000000000 --- a/nuttx/arch/arm/src/common/up_undefinedinsn.c +++ /dev/null @@ -1,81 +0,0 @@ -/**************************************************************************** - * arch/arm/src/common/up_undefinedinsn.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 "os_internal.h" -#include "up_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Output debug info if stack dump is selected -- even if - * debug is not selected. - */ - -#ifdef CONFIG_ARCH_STACKDUMP -# undef lldbg -# define lldbg lib_lowprintf -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_undefinedinsn - ****************************************************************************/ - -void up_undefinedinsn(uint32 *regs) -{ - lldbg("Undefined instruction at 0x%x\n", regs[REG_PC]); - current_regs = regs; - PANIC(OSERR_UNDEFINEDINSN); -} diff --git a/nuttx/arch/arm/src/common/up_vectoraddrexcptn.S b/nuttx/arch/arm/src/common/up_vectoraddrexcptn.S deleted file mode 100644 index 09d7afc93..000000000 --- a/nuttx/arch/arm/src/common/up_vectoraddrexcptn.S +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************ - * arch/arm/src/common/up_vectoraddrexceptn.S - * - * Copyright (C) 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 "up_arch.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Global Data - ************************************************************************************/ - -/************************************************************************************ - * Assembly Macros - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - - .text - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - - .text - -/************************************************************************************ - * Name: up_vectoraddrexcption - * - * Description: - * Shouldn't happen. This exception handler is in a separate file from other - * vector handlers because some processors (e.g., lpc2148) do not support the - * the Address Exception vector. - * - ************************************************************************************/ - - .globl up_vectoraddrexcptn - .type up_vectoraddrexcptn, %function -up_vectoraddrexcptn: - b up_vectoraddrexcptn - .size up_vectoaddrexcptn, . - up_vectoraddrexcptn - .end diff --git a/nuttx/arch/arm/src/common/up_vectors.S b/nuttx/arch/arm/src/common/up_vectors.S deleted file mode 100644 index 97e2b0343..000000000 --- a/nuttx/arch/arm/src/common/up_vectors.S +++ /dev/null @@ -1,440 +0,0 @@ -/************************************************************************************ - * arch/arm/src/common/up_vectors.S - * - * Copyright (C) 2007-2009 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 "up_arch.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Global Data - ************************************************************************************/ - - .data -g_irqtmp: - .word 0 /* Saved lr */ - .word 0 /* Saved spsr */ -g_undeftmp: - .word 0 /* Saved lr */ - .word 0 /* Saved spsr */ -g_aborttmp: - .word 0 /* Saved lr */ - .word 0 /* Saved spsr */ - -/************************************************************************************ - * Assembly Macros - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - - .text - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - - .text - -/************************************************************************************ - * Name: up_vectorirq - * - * Description: - * Interrupt excetpion. Entered in IRQ mode with spsr = SVC - * CPSR, lr = SVC PC - ************************************************************************************/ - - .globl up_vectorirq - .type up_vectorirq, %function -up_vectorirq: - /* On entry, we are in IRQ mode. We are free to use - * the IRQ mode r13 and r14. - * - */ - - ldr r13, .Lirqtmp - sub lr, lr, #4 - str lr, [r13] @ save lr_IRQ - mrs lr, spsr - str lr, [r13, #4] @ save spsr_IRQ - - /* Then switch back to SVC mode */ - - bic lr, lr, #MODE_MASK /* Keep F and T bits */ - orr lr, lr, #(SVC_MODE | PSR_I_BIT) - msr cpsr_c, lr /* Switch to SVC mode */ - - /* Create a context structure. First set aside a stack frame - * and store r0-r12 into the frame. - */ - - sub sp, sp, #XCPTCONTEXT_SIZE - stmia sp, {r0-r12} /* Save the SVC mode regs */ - - /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ - - add r1, sp, #XCPTCONTEXT_SIZE - mov r2, r14 - - /* Get the values for r15(pc) and CPSR in r3 and r4 */ - - ldr r0, .Lirqtmp /* Points to temp storage */ - ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ - - add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ - stmia r0, {r1-r4} - - /* Then call the IRQ handler with interrupts disabled. */ - - mov fp, #0 /* Init frame pointer */ - mov r0, sp /* Get r0=xcp */ - -#if CONFIG_ARCH_INTERRUPTSTACK > 3 - ldr sp, .Lirqstackbase /* SP = interrupt stack base */ - str r0, [sp] /* Save the user stack pointer */ - bl up_decodeirq /* Call the handler */ - ldr sp, [sp] /* Restore the user stack pointer */ -#else - bl up_decodeirq /* Call the handler */ -#endif - - /* Restore the CPSR, SVC modr registers and return */ -.Lnoirqset: - ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ - msr spsr, r0 - ldmia sp, {r0-r15}^ /* Return */ - -.Lirqtmp: - .word g_irqtmp -#if CONFIG_ARCH_INTERRUPTSTACK > 3 -.Lirqstackbase: - .word up_stackbase -#endif - .size up_vectorirq, . - up_vectorirq - .align 5 - -/************************************************************************************ - * Function: up_vectorswi - * - * Description: - * SWI interrupt. We enter the SWI in SVC mode - ************************************************************************************/ - - .globl up_vectorswi - .type up_vectorswi, %function -up_vectorswi: - - /* Create a context structure. First set aside a stack frame - * and store r0-r12 into the frame. - */ - - sub sp, sp, #XCPTCONTEXT_SIZE - stmia sp, {r0-r12} /* Save the SVC mode regs */ - - /* Get the correct values of r13(sp), r14(lr), r15(pc) - * and CPSR in r1-r4 */ - - add r1, sp, #XCPTCONTEXT_SIZE - mov r2, r14 /* R14 is altered on return from SWI */ - mov r3, r14 /* Save r14 as the PC as well */ - mrs r4, spsr /* Get the saved CPSR */ - - add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ - stmia r0, {r1-r4} - - /* Then call the SWI handler with interrupts disabled. - * void up_syscall(struct xcptcontext *xcp) - */ - - mov fp, #0 /* Init frame pointer */ - mov r0, sp /* Get r0=xcp */ - bl up_syscall /* Call the handler */ - - /* Restore the CPSR, SVC modr registers and return */ - - ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ - msr spsr, r0 - ldmia sp, {r0-r15}^ /* Return */ - .size up_vectorswi, . - up_vectorswi - - .align 5 - -/************************************************************************************ - * Name: up_vectordata - * - * Description: - * Data abort Exception dispatcher. Give control to data - * abort handler. This function is entered in ABORT mode - * with spsr = SVC CPSR, lr = SVC PC - * - ************************************************************************************/ - - .globl up_vectordata - .type up_vectordata, %function -up_vectordata: - /* On entry we are free to use the ABORT mode registers - * r13 and r14 - */ - - ldr r13, .Ldaborttmp /* Points to temp storage */ - sub lr, lr, #8 /* Fixup return */ - str lr, [r13] /* Save in temp storage */ - mrs lr, spsr /* Get SPSR */ - str lr, [r13, #4] /* Save in temp storage */ - - /* Then switch back to SVC mode */ - - bic lr, lr, #MODE_MASK /* Keep F and T bits */ - orr lr, lr, #(SVC_MODE | PSR_I_BIT) - msr cpsr_c, lr /* Switch to SVC mode */ - - /* Create a context structure. First set aside a stack frame - * and store r0-r12 into the frame. - */ - - sub sp, sp, #XCPTCONTEXT_SIZE - stmia sp, {r0-r12} /* Save the SVC mode regs */ - - /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ - - add r1, sp, #XCPTCONTEXT_SIZE - mov r2, r14 - - /* Get the values for r15(pc) and CPSR in r3 and r4 */ - - ldr r0, .Ldaborttmp /* Points to temp storage */ - ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ - - add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ - stmia r0, {r1-r4} - - /* Then call the data abort handler with interrupts disabled. - * void up_dataabort(struct xcptcontext *xcp) - */ - - mov fp, #0 /* Init frame pointer */ - mov r0, sp /* Get r0=xcp */ - bl up_dataabort /* Call the handler */ - - /* Restore the CPSR, SVC modr registers and return */ - - ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ - msr spsr_cxsf, r0 - ldmia sp, {r0-r15}^ /* Return */ - -.Ldaborttmp: - .word g_aborttmp - .size up_vectordata, . - up_vectordata - - .align 5 - -/************************************************************************************ - * Name: up_vectorprefetch - * - * Description: - * Prefetch abort exception. Entered in ABT mode with - * spsr = SVC CPSR, lr = SVC PC - ************************************************************************************/ - - .globl up_vectorprefetch - .type up_vectorprefetch, %function -up_vectorprefetch: - /* On entry we are free to use the ABORT mode registers - * r13 and r14 - */ - - ldr r13, .Lpaborttmp /* Points to temp storage */ - sub lr, lr, #4 /* Fixup return */ - str lr, [r13] /* Save in temp storage */ - mrs lr, spsr /* Get SPSR */ - str lr, [r13, #4] /* Save in temp storage */ - - /* Then switch back to SVC mode */ - - bic lr, lr, #MODE_MASK /* Keep F and T bits */ - orr lr, lr, #(SVC_MODE | PSR_I_BIT) - msr cpsr_c, lr /* Switch to SVC mode */ - - /* Create a context structure. First set aside a stack frame - * and store r0-r12 into the frame. - */ - - sub sp, sp, #XCPTCONTEXT_SIZE - stmia sp, {r0-r12} /* Save the SVC mode regs */ - - /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ - - add r1, sp, #XCPTCONTEXT_SIZE - mov r2, r14 - - /* Get the values for r15(pc) and CPSR in r3 and r4 */ - - ldr r0, .Lpaborttmp /* Points to temp storage */ - ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ - - add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ - stmia r0, {r1-r4} - - /* Then call the prefetch abort handler with interrupts disabled. - * void up_prefetchabort(struct xcptcontext *xcp) - */ - - mov fp, #0 /* Init frame pointer */ - mov r0, sp /* Get r0=xcp */ - bl up_prefetchabort /* Call the handler */ - - /* Restore the CPSR, SVC modr registers and return */ - - ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ - msr spsr_cxsf, r0 - ldmia sp, {r0-r15}^ /* Return */ - -.Lpaborttmp: - .word g_aborttmp - .size up_vectorprefetch, . - up_vectorprefetch - - .align 5 - -/************************************************************************************ - * Name: up_vectorundefinsn - * - * Description: - * Undefined instruction entry exception. Entered in - * UND mode, spsr = SVC CPSR, lr = SVC PC - * - ************************************************************************************/ - - .globl up_vectorundefinsn - .type up_vectorundefinsn, %function -up_vectorundefinsn: - /* On entry we are free to use the UND mode registers - * r13 and r14 - */ - - ldr r13, .Lundeftmp /* Points to temp storage */ - str lr, [r13] /* Save in temp storage */ - mrs lr, spsr /* Get SPSR */ - str lr, [r13, #4] /* Save in temp storage */ - - /* Then switch back to SVC mode */ - - bic lr, lr, #MODE_MASK /* Keep F and T bits */ - orr lr, lr, #(SVC_MODE | PSR_I_BIT) - msr cpsr_c, lr /* Switch to SVC mode */ - - /* Create a context structure. First set aside a stack frame - * and store r0-r12 into the frame. - */ - - sub sp, sp, #XCPTCONTEXT_SIZE - stmia sp, {r0-r12} /* Save the SVC mode regs */ - - /* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */ - - add r1, sp, #XCPTCONTEXT_SIZE - mov r2, r14 - - /* Get the values for r15(pc) and CPSR in r3 and r4 */ - - ldr r0, .Lundeftmp /* Points to temp storage */ - ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */ - - add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */ - stmia r0, {r1-r4} - - /* Then call the undef insn handler with interrupts disabled. - * void up_undefinedinsn(struct xcptcontext *xcp) - */ - - mov fp, #0 /* Init frame pointer */ - mov r0, sp /* Get r0=xcp */ - bl up_undefinedinsn /* Call the handler */ - - /* Restore the CPSR, SVC modr registers and return */ - - ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */ - msr spsr_cxsf, r0 - ldmia sp, {r0-r15}^ /* Return */ - -.Lundeftmp: - .word g_undeftmp - .size up_vectorundefinsn, . - up_vectorundefinsn - - .align 5 - -/************************************************************************************ - * Name: up_vectorfiq - * - * Description: - * Shouldn't happen - ************************************************************************************/ - - .globl up_vectorfiq - .type up_vectorfiq, %function -up_vectorfiq: - subs pc, lr, #4 - .size up_vectofiq, . - up_vectorfiq - -/************************************************************************************ - * Name: up_interruptstack/g_userstack - * - * Description: - * Shouldn't happen - * - ************************************************************************************/ - -#if CONFIG_ARCH_INTERRUPTSTACK > 3 - .bss - .align 4 - .globl g_userstack - .type g_userstack, object -up_interruptstack: - .skip ((CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4) -g_userstack: -up_stackbase: - .skip 4 - .size g_userstack, 4 - .size up_interruptstack, (CONFIG_ARCH_INTERRUPTSTACK & ~3) -#endif - .end diff --git a/nuttx/arch/arm/src/common/up_vectortab.S b/nuttx/arch/arm/src/common/up_vectortab.S deleted file mode 100644 index 0fad04ad6..000000000 --- a/nuttx/arch/arm/src/common/up_vectortab.S +++ /dev/null @@ -1,103 +0,0 @@ -/**************************************************************************** - * common/up_vectortab.S - * - * Copyright (C) 2007, 2009 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 - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Global Data - ****************************************************************************/ - -/**************************************************************************** - * Assembly Macros - ****************************************************************************/ - -/**************************************************************************** - * Name: _vector_start - * - * Description: - * Vector initialization block - ****************************************************************************/ - - .globl _vector_start - -/* These will be relocated to VECTOR_BASE. */ - -_vector_start: - ldr pc, .Lresethandler /* 0x00: Reset */ - ldr pc, .Lundefinedhandler /* 0x04: Undefined instruction */ - ldr pc, .Lswihandler /* 0x08: Software interrupt */ - ldr pc, .Lprefetchaborthandler /* 0x0c: Prefetch abort */ - ldr pc, .Ldataaborthandler /* 0x10: Data abort */ - ldr pc, .Laddrexcptnhandler /* 0x14: Address exception */ - ldr pc, .Lirqhandler /* 0x18: IRQ */ - ldr pc, .Lfiqhandler /* 0x1c: FIQ */ - - .globl __start - .globl up_vectorundefinsn - .globl up_vectorswi - .globl up_vectorprefetch - .globl up_vectordata - .globl up_vectoraddrexcptn - .globl up_vectorirq - .globl up_vectorfiq - -.Lresethandler: - .long __start -.Lundefinedhandler: - .long up_vectorundefinsn -.Lswihandler: - .long up_vectorswi -.Lprefetchaborthandler: - .long up_vectorprefetch -.Ldataaborthandler: - .long up_vectordata -.Laddrexcptnhandler: - .long up_vectoraddrexcptn -.Lirqhandler: - .long up_vectorirq -.Lfiqhandler: - .long up_vectorfiq - - .globl _vector_end -_vector_end: - .end diff --git a/nuttx/arch/arm/src/cortexm3/nvic.h b/nuttx/arch/arm/src/cortexm3/nvic.h new file mode 100644 index 000000000..3cd094133 --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/nvic.h @@ -0,0 +1,489 @@ +/************************************************************************************ + * arch/arm/src/cortexm3/nvic.h + * + * Copyright (C) 2009 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_COMMON_CORTEXM3_NVIC_H +#define __ARCH_ARM_SRC_COMMON_CORTEXM3_NVIC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* NVIC base address ****************************************************************/ + +#define CORTEXM3_NVIC_BASE 0xe000e000 + +/* NVIC register offsets ************************************************************/ + +#define NVIC_INTCTRL_TYPE_OFFSET 0x0004 /* Interrupt controller type */ +#define NVIC_SYSTICK_CTRL_OFFSET 0x0010 /* SysTick control and status register */ +#define NVIC_SYSTICK_RELOAD_OFFSET 0x0014 /* SysTick reload value register */ +#define NVIC_SYSTICK_CURRENT_OFFSET 0x0018 /* SysTick current value register */ +#define NVIC_SYSTICK_CALIB_OFFSET 0x001c /* SysTick calibration value register */ + +#define NVIC_IRQ_ENABLE_OFFSET(n) (0x0100 + 4*((n) >> 5)) +#define NVIC_IRQ0_31_ENABLE_OFFSET 0x0100 /* IRQ 0-31 set enable register */ +#define NVIC_IRQ32_63_ENABLE_OFFSET 0x0104 /* IRQ 32-63 set enable register */ +#define NVIC_IRQ64_95_ENABLE_OFFSET 0x0108 /* IRQ 64-95 set enable register */ +#define NVIC_IRQ96_127_ENABLE_OFFSET 0x010c /* IRQ 96-127 set enable register */ +#define NVIC_IRQ128_159_ENABLE_OFFSET 0x0110 /* IRQ 128-159 set enable register */ +#define NVIC_IRQ160_191_ENABLE_OFFSET 0x0114 /* IRQ 160-191 set enable register */ +#define NVIC_IRQ192_223_ENABLE_OFFSET 0x0118 /* IRQ 192-223 set enable register */ +#define NVIC_IRQ224_239_ENABLE_OFFSET 0x011c /* IRQ 224-239 set enable register */ + +#define NVIC_IRQ_CLEAR_OFFSET(n) (0x0180 + 4*((n) >> 5)) +#define NVIC_IRQ0_31_CLEAR_OFFSET 0x0180 /* IRQ 0-31 clear enable register */ +#define NVIC_IRQ32_63_CLEAR_OFFSET 0x0184 /* IRQ 32-63 clear enable register */ +#define NVIC_IRQ64_95_CLEAR_OFFSET 0x0188 /* IRQ 64-95 clear enable register */ +#define NVIC_IRQ96_127_CLEAR_OFFSET 0x018c /* IRQ 96-127 clear enable register */ +#define NVIC_IRQ128_159_CLEAR_OFFSET 0x0190 /* IRQ 128-159 clear enable register */ +#define NVIC_IRQ160_191_CLEAR_OFFSET 0x0194 /* IRQ 160-191 clear enable register */ +#define NVIC_IRQ192_223_CLEAR_OFFSET 0x0198 /* IRQ 192-223 clear enable register */ +#define NVIC_IRQ224_239_CLEAR_OFFSET 0x019c /* IRQ 224-2391 clear enable register */ + +#define NVIC_IRQ_PEND_OFFSET(n) (0x0200 + 4*((n) >> 5)) +#define NVIC_IRQ0_31_PEND_OFFSET 0x0200 /* IRQ 0-31 set pending register */ +#define NVIC_IRQ32_63_PEND_OFFSET 0x0204 /* IRQ 32-63 set pending register */ +#define NVIC_IRQ64_95_PEND_OFFSET 0x0208 /* IRQ 64-95 set pending register */ +#define NVIC_IRQ96_127_PEND_OFFSET 0x020c /* IRQ 96-127 set pending register */ +#define NVIC_IRQ128_159_PEND_OFFSET 0x0210 /* IRQ 128-159 set pending register */ +#define NVIC_IRQ160_191_PEND_OFFSET 0x0214 /* IRQ 160-191 set pending register */ +#define NVIC_IRQ192_223_PEND_OFFSET 0x0218 /* IRQ 192-2231 set pending register */ +#define NVIC_IRQ224_239_PEND_OFFSET 0x021c /* IRQ 224-2391 set pending register */ + +#define NVIC_IRQ_CLRPEND_OFFSET(n) (0x0280 + 4*((n) >> 5)) +#define NVIC_IRQ0_31_CLRPEND_OFFSET 0x0280 /* IRQ 0-31 clear pending register */ +#define NVIC_IRQ32_63_CLRPEND_OFFSET 0x0284 /* IRQ 32-63 clear pending register */ +#define NVIC_IRQ64_95_CLRPEND_OFFSET 0x0288 /* IRQ 64-95 clear pending register */ +#define NVIC_IRQ96_127_CLRPEND_OFFSET 0x028c /* IRQ 96-127 clear pending register */ +#define NVIC_IRQ128_159_CLRPEND_OFFSET 0x0290 /* IRQ 128-159 clear pending register */ +#define NVIC_IRQ160_191_CLRPEND_OFFSET 0x0294 /* IRQ 160-191 clear pending register */ +#define NVIC_IRQ192_223_CLRPEND_OFFSET 0x0298 /* IRQ 192-223 clear pending register */ +#define NVIC_IRQ224_239_CLRPEND_OFFSET 0x029c /* IRQ 224-239 clear pending register */ + +#define NVIC_IRQ_ACTIVE_OFFSET(n) (0x0300 + 4*((n) >> 5)) +#define NVIC_IRQ0_31_ACTIVE_OFFSET 0x0300 /* IRQ 0-31 active bit register */ +#define NVIC_IRQ32_63_ACTIVE_OFFSET 0x0304 /* IRQ 32-63 active bit register */ +#define NVIC_IRQ64_95_ACTIVE_OFFSET 0x0308 /* IRQ 64-95 active bit register */ +#define NVIC_IRQ96_127_ACTIVE_OFFSET 0x030c /* IRQ 96-127 active bit register */ +#define NVIC_IRQ128_159_ACTIVE_OFFSET 0x0310 /* IRQ 128-159 active bit register */ +#define NVIC_IRQ160_191_ACTIVE_OFFSET 0x0314 /* IRQ 160-191 active bit register */ +#define NVIC_IRQ192_223_ACTIVE_OFFSET 0x0318 /* IRQ 192-223 active bit register */ +#define NVIC_IRQ224_239_ACTIVE_OFFSET 0x031c /* IRQ 224-239 active bit register */ + +#define NVIC_IRQ_PRIORITY_OFFSET(n) (0x0400 + 4*((n) >> 2)) +#define NVIC_IRQ0_3_PRIORITY_OFFSET 0x0400 /* IRQ 0-3 priority register */ +#define NVIC_IRQ4_7_PRIORITY_OFFSET 0x0404 /* IRQ 4-7 priority register */ +#define NVIC_IRQ8_11_PRIORITY_OFFSET 0x0408 /* IRQ 8-11 priority register */ +#define NVIC_IRQ12_15_PRIORITY_OFFSET 0x040c /* IRQ 12-15 priority register */ +#define NVIC_IRQ16_19_PRIORITY_OFFSET 0x0410 /* IRQ 16-19 priority register */ +#define NVIC_IRQ20_23_PRIORITY_OFFSET 0x0414 /* IRQ 20-23 priority register */ +#define NVIC_IRQ24_27_PRIORITY_OFFSET 0x0418 /* IRQ 24-29 priority register */ +#define NVIC_IRQ28_31_PRIORITY_OFFSET 0x041c /* IRQ 28-31 priority register */ +#define NVIC_IRQ32_35_PRIORITY_OFFSET 0x0420 /* IRQ 32-35 priority register */ +#define NVIC_IRQ36_39_PRIORITY_OFFSET 0x0424 /* IRQ 36-39 priority register */ +#define NVIC_IRQ40_43_PRIORITY_OFFSET 0x0428 /* IRQ 40-43 priority register */ +#define NVIC_IRQ44_47_PRIORITY_OFFSET 0x042c /* IRQ 44-47 priority register */ +#define NVIC_IRQ48_51_PRIORITY_OFFSET 0x0430 /* IRQ 48-51 priority register */ +#define NVIC_IRQ52_55_PRIORITY_OFFSET 0x0434 /* IRQ 52-55 priority register */ +#define NVIC_IRQ56_59_PRIORITY_OFFSET 0x0438 /* IRQ 56-59 priority register */ +#define NVIC_IRQ60_63_PRIORITY_OFFSET 0x043c /* IRQ 60-63 priority register */ +#define NVIC_IRQ64_67_PRIORITY_OFFSET 0x0440 /* IRQ 64-67 priority register */ +#define NVIC_IRQ68_71_PRIORITY_OFFSET 0x0444 /* IRQ 68-71 priority register */ +#define NVIC_IRQ72_75_PRIORITY_OFFSET 0x0448 /* IRQ 72-75 priority register */ +#define NVIC_IRQ76_79_PRIORITY_OFFSET 0x044c /* IRQ 76-79 priority register */ +#define NVIC_IRQ80_83_PRIORITY_OFFSET 0x0450 /* IRQ 80-83 priority register */ +#define NVIC_IRQ84_87_PRIORITY_OFFSET 0x0454 /* IRQ 84-87 priority register */ +#define NVIC_IRQ88_91_PRIORITY_OFFSET 0x0458 /* IRQ 88-91 priority register */ +#define NVIC_IRQ92_95_PRIORITY_OFFSET 0x045c /* IRQ 92-95 priority register */ +#define NVIC_IRQ96_99_PRIORITY_OFFSET 0x0460 /* IRQ 96-99 priority register */ +#define NVIC_IRQ100_103_PRIORITY_OFFSET 0x0464 /* IRQ 100-103 priority register */ +#define NVIC_IRQ104_107_PRIORITY_OFFSET 0x0468 /* IRQ 104-107 priority register */ +#define NVIC_IRQ108_111_PRIORITY_OFFSET 0x046c /* IRQ 108-111 priority register */ +#define NVIC_IRQ112_115_PRIORITY_OFFSET 0x0470 /* IRQ 112-115 priority register */ +#define NVIC_IRQ116_119_PRIORITY_OFFSET 0x0474 /* IRQ 116-119 priority register */ +#define NVIC_IRQ120_123_PRIORITY_OFFSET 0x0478 /* IRQ 120-123 priority register */ +#define NVIC_IRQ124_127_PRIORITY_OFFSET 0x047c /* IRQ 124-127 priority register */ +#define NVIC_IRQ128_131_PRIORITY_OFFSET 0x0480 /* IRQ 128-131 priority register */ +#define NVIC_IRQ132_135_PRIORITY_OFFSET 0x0484 /* IRQ 132-135 priority register */ +#define NVIC_IRQ136_139_PRIORITY_OFFSET 0x0488 /* IRQ 136-139 priority register */ +#define NVIC_IRQ140_143_PRIORITY_OFFSET 0x048c /* IRQ 140-143 priority register */ +#define NVIC_IRQ144_147_PRIORITY_OFFSET 0x0490 /* IRQ 144-147 priority register */ +#define NVIC_IRQ148_151_PRIORITY_OFFSET 0x0494 /* IRQ 148-151 priority register */ +#define NVIC_IRQ152_155_PRIORITY_OFFSET 0x0498 /* IRQ 152-155 priority register */ +#define NVIC_IRQ156_159_PRIORITY_OFFSET 0x049c /* IRQ 156-159 priority register */ +#define NVIC_IRQ160_163_PRIORITY_OFFSET 0x04a0 /* IRQ 160-163 priority register */ +#define NVIC_IRQ164_167_PRIORITY_OFFSET 0x04a4 /* IRQ 164-167 priority register */ +#define NVIC_IRQ168_171_PRIORITY_OFFSET 0x04a8 /* IRQ 168-171 priority register */ +#define NVIC_IRQ172_175_PRIORITY_OFFSET 0x04ac /* IRQ 172-175 priority register */ +#define NVIC_IRQ176_179_PRIORITY_OFFSET 0x04b0 /* IRQ 176-179 priority register */ +#define NVIC_IRQ180_183_PRIORITY_OFFSET 0x04b4 /* IRQ 180-183 priority register */ +#define NVIC_IRQ184_187_PRIORITY_OFFSET 0x04b8 /* IRQ 184-187 priority register */ +#define NVIC_IRQ188_191_PRIORITY_OFFSET 0x04bc /* IRQ 188-191 priority register */ +#define NVIC_IRQ192_195_PRIORITY_OFFSET 0x04c0 /* IRQ 192-195 priority register */ +#define NVIC_IRQ196_199_PRIORITY_OFFSET 0x04c4 /* IRQ 196-199 priority register */ +#define NVIC_IRQ200_203_PRIORITY_OFFSET 0x04c8 /* IRQ 200-203 priority register */ +#define NVIC_IRQ204_207_PRIORITY_OFFSET 0x04cc /* IRQ 204-207 priority register */ +#define NVIC_IRQ208_211_PRIORITY_OFFSET 0x04d0 /* IRQ 208-211 priority register */ +#define NVIC_IRQ212_215_PRIORITY_OFFSET 0x04d4 /* IRQ 212-215 priority register */ +#define NVIC_IRQ216_219_PRIORITY_OFFSET 0x04d8 /* IRQ 216-219 priority register */ +#define NVIC_IRQ220_223_PRIORITY_OFFSET 0x04dc /* IRQ 220-223 priority register */ +#define NVIC_IRQ224_227_PRIORITY_OFFSET 0x04e0 /* IRQ 224-227 priority register */ +#define NVIC_IRQ228_231_PRIORITY_OFFSET 0x04e4 /* IRQ 228-231 priority register */ +#define NVIC_IRQ232_235_PRIORITY_OFFSET 0x04e8 /* IRQ 232-235 priority register */ +#define NVIC_IRQ236_239_PRIORITY_OFFSET 0x04ec /* IRQ 236-239 priority register */ + +#define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */ +#define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */ +#define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */ +#define NVIC_AIRC_OFFSET 0x0d0c /* Application interrupt/reset contol registr */ +#define NVIC_SYSCON_OFFSET 0x0d10 /* System control register */ +#define NVIC_CFGCON_OFFSET 0x0d14 /* Configuration control register */ +#define NVIC_SYSH_PRIORITY_OFFSET(n) (0x0d14 + 4*((n) >> 2)) +#define NVIC_SYSH4_7_PRIORITY_OFFSET 0x0d18 /* System handlers 4-7 priority register */ +#define NVIC_SYSH8_11_PRIORITY_OFFSET 0x0d1c /* System handler 8-11 priority register */ +#define NVIC_SYSH12_15_PRIORITY_OFFSET 0x0d20 /* System handler 12-15 priority register */ +#define NVIC_SYSHCON_OFFSET 0x0d24 /* System handler control and state register */ +#define NVIC_CFAULTS_OFFSET 0x0d28 /* Configurable fault status register */ +#define NVIC_HFAULTS_OFFSET 0x0d2c /* Hard fault status register */ +#define NVIC_DFAULTS_OFFSET 0x0d30 /* Debug fault status register */ +#define NVIC_MEMMANAGE_ADDR_OFFSET 0x0d34 /* Mem manage address register */ +#define NVIC_BFAULT_ADDR_OFFSET 0x0d38 /* Bus fault address register */ +#define NVIC_AFAULTS_OFFSET 0x0d3c /* Auxiliary fault status register */ +#define NVIC_PFR0_OFFSET 0x0d40 /* Processor feature register 0 */ +#define NVIC_PFR1_OFFSET 0x0d44 /* Processor feature register 1 */ +#define NVIC_DFR0_OFFSET 0x0d48 /* Debug feature register 0 */ +#define NVIC_AFR0_OFFSET 0x0d4c /* Auxiliary feature register 0 */ +#define NVIC_MMFR0_OFFSET 0x0d50 /* Memory model feature register 0 */ +#define NVIC_MMFR1_OFFSET 0x0d54 /* Memory model feature register 1 */ +#define NVIC_MMFR2_OFFSET 0x0d58 /* Memory model feature register 2 */ +#define NVIC_MMFR3_OFFSET 0x0d5c /* Memory model feature register 3 */ +#define NVIC_ISAR0_OFFSET 0x0d60 /* ISA feature register 0 */ +#define NVIC_ISAR1_OFFSET 0x0d64 /* ISA feature register 1 */ +#define NVIC_ISAR2_OFFSET 0x0d68 /* ISA feature register 2 */ +#define NVIC_ISAR3_OFFSET 0x0d6c /* ISA feature register 3 */ +#define NVIC_ISAR4_OFFSET 0x0d70 /* ISA feature register 4 */ +#define NVIC_STIR_OFFSET 0x0f00 /* Software trigger interrupt register */ +#define NVIC_PID4_OFFSET 0x0fd0 /* Peripheral identification register (PID4) */ +#define NVIC_PID5_OFFSET 0x0fd4 /* Peripheral identification register (PID5) */ +#define NVIC_PID6_OFFSET 0x0fd8 /* Peripheral identification register (PID6) */ +#define NVIC_PID7_OFFSET 0x0fdc /* Peripheral identification register (PID7) */ +#define NVIC_PID0_OFFSET 0x0fe0 /* Peripheral identification register bits 7:0 (PID0) */ +#define NVIC_PID1_OFFSET 0x0fe4 /* Peripheral identification register bits 15:8 (PID1) */ +#define NVIC_PID2_OFFSET 0x0fe8 /* Peripheral identification register bits 23:16 (PID2) */ +#define NVIC_PID3_OFFSET 0x0fec /* Peripheral identification register bits 23:16 (PID3) */ +#define NVIC_CID0_OFFSET 0x0ff0 /* Component identification register bits 7:0 (CID0) */ +#define NVIC_CID1_OFFSET 0x0ff4 /* Component identification register bits 15:8 (CID0) */ +#define NVIC_CID2_OFFSET 0x0ff8 /* Component identification register bits 23:16 (CID0) */ +#define NVIC_CID3_OFFSET 0x0ffc /* Component identification register bits 23:16 (CID0) */ + +/* NVIC register addresses **********************************************************/ + +#define NVIC_INTCTRL_TYPE (CORTEXM3_NVIC_BASE + NVIC_INTCTRL_TYPE_OFFSET) +#define NVIC_SYSTICK_CTRL (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_CTRL_OFFSET) +#define NVIC_SYSTICK_RELOAD (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_RELOAD_OFFSET) +#define NVIC_SYSTICK_CURRENT (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_CURRENT_OFFSET) +#define NVIC_SYSTICK_CALIB (CORTEXM3_NVIC_BASE + NVIC_SYSTICK_CALIB_OFFSET) + +#define NVIC_IRQ_ENABLE(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_ENABLE_OFFSET(n)) +#define NVIC_IRQ0_31_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_ENABLE_OFFSET) +#define NVIC_IRQ32_63_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_ENABLE_OFFSET) +#define NVIC_IRQ64_95_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_ENABLE_OFFSET) +#define NVIC_IRQ96_127_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_ENABLE_OFFSET) +#define NVIC_IRQ128_159_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_ENABLE_OFFSET) +#define NVIC_IRQ160_191_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_ENABLE_OFFSET) +#define NVIC_IRQ192_223_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_ENABLE_OFFSET) +#define NVIC_IRQ224_239_ENABLE (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_ENABLE_OFFSET) + +#define NVIC_IRQ_CLEAR(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_CLEAR_OFFSET(n)) +#define NVIC_IRQ0_31_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_CLEAR_OFFSET) +#define NVIC_IRQ32_63_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_CLEAR_OFFSET) +#define NVIC_IRQ64_95_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_CLEAR_OFFSET) +#define NVIC_IRQ96_127_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_CLEAR_OFFSET) +#define NVIC_IRQ128_159_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_CLEAR_OFFSET) +#define NVIC_IRQ160_191_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_CLEAR_OFFSET) +#define NVIC_IRQ192_223_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_CLEAR_OFFSET) +#define NVIC_IRQ224_239_CLEAR (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_CLEAR_OFFSET) + +#define NVIC_IRQ_PEND(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_PEND_OFFSET(n)) +#define NVIC_IRQ0_31_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_PEND_OFFSET) +#define NVIC_IRQ32_63_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_PEND_OFFSET) +#define NVIC_IRQ64_95_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_PEND_OFFSET) +#define NVIC_IRQ96_127_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_PEND_OFFSET) +#define NVIC_IRQ128_159_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_PEND_OFFSET) +#define NVIC_IRQ160_191_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_PEND_OFFSET) +#define NVIC_IRQ192_223_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_PEND_OFFSET) +#define NVIC_IRQ224_239_PEND (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_PEND_OFFSET) + +#define NVIC_IRQ_CLRPEND(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_CLRPEND_OFFSET(n)) +#define NVIC_IRQ0_31_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_CLRPEND_OFFSET) +#define NVIC_IRQ32_63_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_CLRPEND_OFFSET) +#define NVIC_IRQ64_95_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_CLRPEND_OFFSET) +#define NVIC_IRQ96_127_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_CLRPEND_OFFSET) +#define NVIC_IRQ128_159_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_CLRPEND_OFFSET) +#define NVIC_IRQ160_191_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_CLRPEND_OFFSET) +#define NVIC_IRQ192_223_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_CLRPEND_OFFSET) +#define NVIC_IRQ224_239_CLRPEND (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_CLRPEND_OFFSET) + +#define NVIC_IRQ_ACTIVE(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_ACTIVE_OFFSET(n)) +#define NVIC_IRQ0_31_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ0_31_ACTIVE_OFFSET) +#define NVIC_IRQ32_63_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ32_63_ACTIVE_OFFSET) +#define NVIC_IRQ64_95_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ64_95_ACTIVE_OFFSET) +#define NVIC_IRQ96_127_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ96_127_ACTIVE_OFFSET) +#define NVIC_IRQ128_159_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ128_159_ACTIVE_OFFSET) +#define NVIC_IRQ160_191_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ160_191_ACTIVE_OFFSET) +#define NVIC_IRQ192_223_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ192_223_ACTIVE_OFFSET) +#define NVIC_IRQ224_239_ACTIVE (CORTEXM3_NVIC_BASE + NVIC_IRQ224_239_ACTIVE_OFFSET) + +#define NVIC_IRQ_PRIORITY(n) (CORTEXM3_NVIC_BASE + NVIC_IRQ_PRIORITY_OFFSET(n)) +#define NVIC_IRQ0_3_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ0_3_PRIORITY_OFFSET) +#define NVIC_IRQ4_7_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ4_7_PRIORITY_OFFSET) +#define NVIC_IRQ8_11_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ8_11_PRIORITY_OFFSET) +#define NVIC_IRQ12_15_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ12_15_PRIORITY_OFFSET) +#define NVIC_IRQ16_19_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ16_19_PRIORITY_OFFSET) +#define NVIC_IRQ20_23_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ20_23_PRIORITY_OFFSET) +#define NVIC_IRQ24_27_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ24_27_PRIORITY_OFFSET) +#define NVIC_IRQ28_31_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ28_31_PRIORITY_OFFSET) +#define NVIC_IRQ32_35_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ32_35_PRIORITY_OFFSET) +#define NVIC_IRQ36_39_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ36_39_PRIORITY_OFFSET) +#define NVIC_IRQ40_43_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ40_43_PRIORITY_OFFSET) +#define NVIC_IRQ44_47_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ44_47_PRIORITY_OFFSET) +#define NVIC_IRQ48_51_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ48_51_PRIORITY_OFFSET) +#define NVIC_IRQ52_55_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ52_55_PRIORITY_OFFSET) +#define NVIC_IRQ56_59_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ56_59_PRIORITY_OFFSET) +#define NVIC_IRQ60_63_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ60_63_PRIORITY_OFFSET) +#define NVIC_IRQ64_67_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ64_67_PRIORITY_OFFSET) +#define NVIC_IRQ68_71_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ68_71_PRIORITY_OFFSET) +#define NVIC_IRQ72_75_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ72_75_PRIORITY_OFFSET) +#define NVIC_IRQ76_79_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ76_79_PRIORITY_OFFSET) +#define NVIC_IRQ80_83_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ80_83_PRIORITY_OFFSET) +#define NVIC_IRQ84_87_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ84_87_PRIORITY_OFFSET) +#define NVIC_IRQ88_91_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ88_91_PRIORITY_OFFSET) +#define NVIC_IRQ92_95_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ92_95_PRIORITY_OFFSET) +#define NVIC_IRQ96_99_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ96_99_PRIORITY_OFFSET) +#define NVIC_IRQ100_103_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ100_103_PRIORITY_OFFSET) +#define NVIC_IRQ104_107_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ104_107_PRIORITY_OFFSET) +#define NVIC_IRQ108_111_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ108_111_PRIORITY_OFFSET) +#define NVIC_IRQ112_115_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ112_115_PRIORITY_OFFSET) +#define NVIC_IRQ116_119_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ116_119_PRIORITY_OFFSET) +#define NVIC_IRQ120_123_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ120_123_PRIORITY_OFFSET) +#define NVIC_IRQ124_127_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ124_127_PRIORITY_OFFSET) +#define NVIC_IRQ128_131_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ128_131_PRIORITY_OFFSET) +#define NVIC_IRQ132_135_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ132_135_PRIORITY_OFFSET) +#define NVIC_IRQ136_139_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ136_139_PRIORITY_OFFSET) +#define NVIC_IRQ140_143_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ140_143_PRIORITY_OFFSET) +#define NVIC_IRQ144_147_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ144_147_PRIORITY_OFFSET) +#define NVIC_IRQ148_151_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ148_151_PRIORITY_OFFSET) +#define NVIC_IRQ152_155_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ152_155_PRIORITY_OFFSET) +#define NVIC_IRQ156_159_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ156_159_PRIORITY_OFFSET) +#define NVIC_IRQ160_163_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ160_163_PRIORITY_OFFSET) +#define NVIC_IRQ164_167_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ164_167_PRIORITY_OFFSET) +#define NVIC_IRQ168_171_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ168_171_PRIORITY_OFFSET) +#define NVIC_IRQ172_175_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ172_175_PRIORITY_OFFSET) +#define NVIC_IRQ176_179_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ176_179_PRIORITY_OFFSET) +#define NVIC_IRQ180_183_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ180_183_PRIORITY_OFFSET) +#define NVIC_IRQ184_187_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ184_187_PRIORITY_OFFSET) +#define NVIC_IRQ188_191_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ188_191_PRIORITY_OFFSET) +#define NVIC_IRQ192_195_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ192_195_PRIORITY_OFFSET) +#define NVIC_IRQ196_199_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ196_199_PRIORITY_OFFSET) +#define NVIC_IRQ200_203_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ200_203_PRIORITY_OFFSET) +#define NVIC_IRQ204_207_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ204_207_PRIORITY_OFFSET) +#define NVIC_IRQ208_211_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ208_211_PRIORITY_OFFSET) +#define NVIC_IRQ212_215_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ212_215_PRIORITY_OFFSET) +#define NVIC_IRQ216_219_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ216_219_PRIORITY_OFFSET) +#define NVIC_IRQ220_223_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ220_223_PRIORITY_OFFSET) +#define NVIC_IRQ224_227_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ224_227_PRIORITY_OFFSET) +#define NVIC_IRQ228_231_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ228_231_PRIORITY_OFFSET) +#define NVIC_IRQ232_235_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_IRQ232_235_PRIORITY_OFFSET) + +#define NVIC_CPUID_BASE (CORTEXM3_NVIC_BASE + NVIC_CPUID_BASE_OFFSET) +#define NVIC_INTCTRL (CORTEXM3_NVIC_BASE + NVIC_INTCTRL_OFFSET) +#define NVIC_VECTAB (CORTEXM3_NVIC_BASE + NVIC_VECTAB_OFFSET) +#define NVIC_AIRC (CORTEXM3_NVIC_BASE + NVIC_AIRC_OFFSET) +#define NVIC_SYSCON (CORTEXM3_NVIC_BASE + NVIC_SYSCON_OFFSET) +#define NVIC_CFGCON (CORTEXM3_NVIC_BASE + NVIC_CFGCON_OFFSET) +#define NVIC_SYSH_PRIORITY(n) (CORTEXM3_NVIC_BASE + NVIC_SYSH_PRIORITY_OFFSET(n)) +#define NVIC_SYSH4_7_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_SYSH4_7_PRIORITY_OFFSET) +#define NVIC_SYSH8_11_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_SYSH8_11_PRIORITY_OFFSET) +#define NVIC_SYSH12_15_PRIORITY (CORTEXM3_NVIC_BASE + NVIC_SYSH12_15_PRIORITY_OFFSET) +#define NVIC_SYSHCON (CORTEXM3_NVIC_BASE + NVIC_SYSHCON_OFFSET) +#define NVIC_CFAULTS (CORTEXM3_NVIC_BASE + NVIC_CFAULTS_OFFSET) +#define NVIC_HFAULTS (CORTEXM3_NVIC_BASE + NVIC_HFAULTS_OFFSET) +#define NVIC_DFAULTS (CORTEXM3_NVIC_BASE + NVIC_DFAULTS_OFFSET) +#define NVIC_MEMMANAGE_ADDR (CORTEXM3_NVIC_BASE + NVIC_MEMMANAGE_ADDR_OFFSET) +#define NVIC_BFAULT_ADDR (CORTEXM3_NVIC_BASE + NVIC_BFAULT_ADDR_OFFSET) +#define NVIC_AFAULTS (CORTEXM3_NVIC_BASE + NVIC_AFAULTS_OFFSET) +#define NVIC_PFR0 (CORTEXM3_NVIC_BASE + NVIC_PFR0_OFFSET) +#define NVIC_PFR1 (CORTEXM3_NVIC_BASE + NVIC_PFR1_OFFSET) +#define NVIC_DFR0 (CORTEXM3_NVIC_BASE + NVIC_DFR0_OFFSET) +#define NVIC_AFR0 (CORTEXM3_NVIC_BASE + NVIC_AFR0_OFFSET) +#define NVIC_MMFR0 (CORTEXM3_NVIC_BASE + NVIC_MMFR0_OFFSET) +#define NVIC_MMFR1 (CORTEXM3_NVIC_BASE + NVIC_MMFR1_OFFSET) +#define NVIC_MMFR2 (CORTEXM3_NVIC_BASE + NVIC_MMFR2_OFFSET) +#define NVIC_MMFR3 (CORTEXM3_NVIC_BASE + NVIC_MMFR3_OFFSET) +#define NVIC_ISAR0 (CORTEXM3_NVIC_BASE + NVIC_ISAR0_OFFSET) +#define NVIC_ISAR1 (CORTEXM3_NVIC_BASE + NVIC_ISAR1_OFFSET) +#define NVIC_ISAR2 (CORTEXM3_NVIC_BASE + NVIC_ISAR2_OFFSET) +#define NVIC_ISAR3 (CORTEXM3_NVIC_BASE + NVIC_ISAR3_OFFSET) +#define NVIC_ISAR4 (CORTEXM3_NVIC_BASE + NVIC_ISAR4_OFFSET) +#define NVIC_STIR (CORTEXM3_NVIC_BASE + NVIC_STIR_OFFSET) +#define NVIC_PID4 (CORTEXM3_NVIC_BASE + NVIC_PID4_OFFSET) +#define NVIC_PID5 (CORTEXM3_NVIC_BASE + NVIC_PID5_OFFSET) +#define NVIC_PID6 (CORTEXM3_NVIC_BASE + NVIC_PID6_OFFSET) +#define NVIC_PID7 (CORTEXM3_NVIC_BASE + NVIC_PID7_OFFSET) +#define NVIC_PID0 (CORTEXM3_NVIC_BASE + NVIC_PID0_OFFSET) +#define NVIC_PID1 (CORTEXM3_NVIC_BASE + NVIC_PID1_OFFSET) +#define NVIC_PID2 (CORTEXM3_NVIC_BASE + NVIC_PID2_OFFSET) +#define NVIC_PID3 (CORTEXM3_NVIC_BASE + NVIC_PID3_OFFSET) +#define NVIC_CID0 (CORTEXM3_NVIC_BASE + NVIC_CID0_OFFSET) +#define NVIC_CID1 (CORTEXM3_NVIC_BASE + NVIC_CID1_OFFSET) +#define NVIC_CID2 (CORTEXM3_NVIC_BASE + NVIC_CID2_OFFSET) +#define NVIC_CID3 (CORTEXM3_NVIC_BASE + NVIC_CID3_OFFSET) + +/* NVIC register bit definitions ****************************************************/ + +/* Interrrupt controller type (INCTCTL_TYPE) */ + +#define NVIC_INTCTRL_TYPE_INTLINESNUM_SHIFT 0 /* Bits 4-0: Number of interrupt intputs / 32 */ +#define NVIC_INTCTRL_TYPE_INTLINESNUM_MASK (0x1f << NVIC_INTCTRL_TYPE_INTLINESNUM_SHIFT) + +/* SysTick control and status register (SYSTICK_CTRL) */ + +#define NVIC_SYSTICK_CTRL_ENABLE (1 << 0) /* Bit 0: Enable */ +#define NVIC_SYSTICK_CTRL_TICKINT (1 << 1) /* Bit 1: Tick interrupt */ +#define NVIC_SYSTICK_CTRL_CLKSOURCE (1 << 2) /* Bit 2: Clock source */ +#define NVIC_SYSTICK_CTRL_COUNTFLAG (1 << 16) /* Bit 16: Count Flag */ + +/* SysTick reload value register (SYSTICK_RELOAD) */ + +#define NVIC_SYSTICK_RELOAD_SHIFT 0 /* Bits 23-0: Timer reload value */ +#define NVIC_SYSTICK_RELOAD_MASK (0x00ffffff << NVIC_SYSTICK_RELOAD_SHIFT) + +/* SysTick current value registe (SYSTICK_CURRENT) */ + +#define NVIC_SYSTICK_CURRENT_SHIFT 0 /* Bits 23-0: Timer current value */ +#define NVIC_SYSTICK_CURRENT_MASK (0x00ffffff << NVIC_SYSTICK_RELOAD_SHIFT) + +/* SysTick calibration value register (SYSTICK_CALIB) */ + +#define NVIC_SYSTICK_CALIB_TENMS_SHIFT 0 /* Bits 23-0: Calibration value */ +#define NVIC_SYSTICK_CALIB_TENMS_MASK (0x00ffffff << NVIC_SYSTICK_CALIB_TENMS_SHIFT) +#define NVIC_SYSTICK_CALIB_SKEW (1 << 30) /* Bit 30: Calibration value inexact */ +#define NVIC_SYSTICK_CALIB_NOREF (1 << 31) /* Bit 31: No external reference clock */ + +/* Interrupt control state register (INTCTRL) */ + +#define NVIC_INTCTRL_NMIPENDSET (1 << 31) /* Bit 31: Set pending NMI bit */ +#define NVIC_INTCTRL_PENDSVSET (1 << 28) /* Bit 28: Set pending PendSV bit */ +#define NVIC_INTCTRL_PENDSVCLR (1 << 27) /* Bit 27: Clear pending PendSV bit */ +#define NVIC_INTCTRL_PENDSTSET (1 << 26) /* Bit 26: Set pending SysTick bit */ +#define NVIC_INTCTRL_PENDSTCLR (1 << 25) /* Bit 25: Clear pending SysTick bit */ +#define NVIC_INTCTRL_ISPREEMPOT (1 << 23) /* Bit 23: Pending active next cycle */ +#define NVIC_INTCTRL_ISRPENDING (1 << 22) /* Bit 22: Interrupt pending flag */ +#define NVIC_INTCTRL_VECTPENDING_SHIFT 12 /* Bits 21-12: Pending ISR number field */ +#define NVIC_INTCTRL_VECTPENDING_MASK (0x3ff << NVIC_INTCTRL_VECTPENDING_SHIFT) +#define NVIC_INTCTRL_RETTOBASE (1 << 11) /* Bit 11: no other exceptions pending */ +#define NVIC_INTCTRL_VECTACTIVE_SHIFT 0 /* Bits 8-0: Active ISR number */ +#define NVIC_INTCTRL_VECTACTIVE_MASK (0x1ff << NVIC_INTCTRL_VECTACTIVE_SHIFT) + +/* System handler 4-7 priority register */ + +#define NVIC_SYSH_PRIORITY_PR4_SHIFT 0 +#define NVIC_SYSH_PRIORITY_PR4_MASK (0xff << NVIC_SYSH_PRIORITY_PR4_SHIFT) +#define NVIC_SYSH_PRIORITY_PR5_SHIFT 8 +#define NVIC_SYSH_PRIORITY_PR5_MASK (0xff << NVIC_SYSH_PRIORITY_PR5_SHIFT) +#define NVIC_SYSH_PRIORITY_PR6_SHIFT 16 +#define NVIC_SYSH_PRIORITY_PR6_MASK (0xff << NVIC_SYSH_PRIORITY_PR6_SHIFT) +#define NVIC_SYSH_PRIORITY_PR7_SHIFT 24 +#define NVIC_SYSH_PRIORITY_PR7_MASK (0xff << NVIC_SYSH_PRIORITY_PR7_SHIFT) + +/* System handler 8-11 priority register */ + +#define NVIC_SYSH_PRIORITY_PR8_SHIFT 0 +#define NVIC_SYSH_PRIORITY_PR8_MASK (0xff << NVIC_SYSH_PRIORITY_PR8_SHIFT) +#define NVIC_SYSH_PRIORITY_PR9_SHIFT 8 +#define NVIC_SYSH_PRIORITY_PR9_MASK (0xff << NVIC_SYSH_PRIORITY_PR9_SHIFT) +#define NVIC_SYSH_PRIORITY_PR10_SHIFT 16 +#define NVIC_SYSH_PRIORITY_PR10_MASK (0xff << NVIC_SYSH_PRIORITY_PR10_SHIFT) +#define NVIC_SYSH_PRIORITY_PR11_SHIFT 24 +#define NVIC_SYSH_PRIORITY_PR11_MASK (0xff << NVIC_SYSH_PRIORITY_PR11_SHIFT) + +/* System handler 12-15 priority register */ + +#define NVIC_SYSH_PRIORITY_PR12_SHIFT 0 +#define NVIC_SYSH_PRIORITY_PR12_MASK (0xff << NVIC_SYSH_PRIORITY_PR12_SHIFT) +#define NVIC_SYSH_PRIORITY_PR13_SHIFT 8 +#define NVIC_SYSH_PRIORITY_PR13_MASK (0xff << NVIC_SYSH_PRIORITY_PR13_SHIFT) +#define NVIC_SYSH_PRIORITY_PR14_SHIFT 16 +#define NVIC_SYSH_PRIORITY_PR14_MASK (0xff << NVIC_SYSH_PRIORITY_PR14_SHIFT) +#define NVIC_SYSH_PRIORITY_PR15_SHIFT 24 +#define NVIC_SYSH_PRIORITY_PR15_MASK (0xff << NVIC_SYSH_PRIORITY_PR15_SHIFT) + +/* System handler control and state register (SYSHCON) */ + +#define NVIC_SYSHCON_MEMFAULTACT (1 << 0) /* Bit 0: MemManage is active */ +#define NVIC_SYSHCON_BUSFAULTACT (1 << 1) /* Bit 1: BusFault is active */ +#define NVIC_SYSHCON_USGFAULTACT (1 << 3) /* Bit 3: UsageFault is active */ +#define NVIC_SYSHCON_SVCALLACT (1 << 7) /* Bit 7: SVCall is active */ +#define NVIC_SYSHCON_MONITORACT (1 << 8) /* Bit 8: Monitor is active */ +#define NVIC_SYSHCON_PENDSVACT (1 << 10) /* Bit 10: PendSV is active */ +#define NVIC_SYSHCON_SYSTICKACT (1 << 11) /* Bit 11: SysTick is active */ +#define NVIC_SYSHCON_USGFAULTPENDED (1 << 12) /* Bit 12: Usage fault is pended */ +#define NVIC_SYSHCON_MEMFAULTPENDED (1 << 13) /* Bit 13: MemManage is pended */ +#define NVIC_SYSHCON_BUSFAULTPENDED (1 << 14) /* Bit 14: BusFault is pended */ +#define NVIC_SYSHCON_SVCALLPENDED (1 << 15) /* Bit 15: SVCall is pended */ +#define NVIC_SYSHCON_MEMFAULTENA (1 << 16) /* Bit 16: MemFault enabled */ +#define NVIC_SYSHCON_BUSFAULTENA (1 << 17) /* Bit 17: BusFault enabled */ +#define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_COMMON_CORTEXM3_NVIC_H */ diff --git a/nuttx/arch/arm/src/cortexm3/psr.h b/nuttx/arch/arm/src/cortexm3/psr.h new file mode 100644 index 000000000..dea45555a --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/psr.h @@ -0,0 +1,91 @@ +/************************************************************************************ + * arch/arm/src/cortexm3/psr.h + * + * Copyright (C) 2009 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. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_COMMON_CORTEXM_PSR_H +#define __ARCH_ARM_SRC_COMMON_CORTEXM_PSR_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#ifndef __ASSEMBLY__ +# include +#endif + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Application Program Status Register (APSR) */ + +#define CORTEXM3_APSR_Q (1 << 27) /* Bit 27: Sticky saturation flag */ +#define CORTEXM3_APSR_V (1 << 28) /* Bit 28: Overflow flag */ +#define CORTEXM3_APSR_C (1 << 29) /* Bit 29: Carry/borrow flag */ +#define CORTEXM3_APSR_Z (1 << 30) /* Bit 30: Zero flag */ +#define CORTEXM3_APSR_N (1 << 31) /* Bit 31: Negative, less than flag */ + +/* Interrupt Program Status Register (IPSR) */ + +#define CORTEXM3_IPSR_ISR_SHIFT 0 /* Bits 8-0: ISR number */ +#define CORTEXM3_IPSR_ISR_MASK (0x1ff << CORTEXM3_IPSR_ISR_SHIFT) + +/* Execution PSR Register (EPSR) */ + +#define CORTEXM3_EPSR_ICIIT1_SHIFT 10 /* Bits 15-10: Interrupt-Continuable-Instruction/If-Then bits */ +#define CORTEXM3_EPSR_ICIIT1_MASK (3 << CORTEXM3_EPSR_ICIIT1_SHIFT) +#define CORTEXM3_EPSR_T (1 << 24) /* Bit 24: T-bit */ +#define CORTEXM3_EPSR_ICIIT2_SHIFT 25 /* Bits 26-25: Interrupt-Continuable-Instruction/If-Then bits */ +#define CORTEXM3_EPSR_ICIIT2_MASK (3 << CORTEXM3_EPSR_ICIIT2_SHIFT) + +/* Save xPSR bits */ + +#define CORTEXM3_XPSR_ISR_SHIFT CORTEXM3_IPSR_ISR_SHIFT +#define CORTEXM3_XPSR_ISR_MASK CORTEXM3_IPSR_ISR_MASK +#define CORTEXM3_XPSR_ICIIT1_SHIFT CORTEXM3_EPSR_ICIIT1_SHIFT/ +#define CORTEXM3_XPSR_ICIIT1_MASK CORTEXM3_EPSR_ICIIT1_MASK +#define CORTEXM3_XPSR_T CORTEXM3_EPSR_T +#define CORTEXM3_XPSR_ICIIT2_SHIFT CORTEXM3_EPSR_ICIIT2_SHIFT +#define CORTEXM3_XPSR_ICIIT2_MASK CORTEXM3_EPSR_ICIIT2_MASK +#define CORTEXM3_XPSR_Q CORTEXM3_APSR_Q +#define CORTEXM3_XPSR_V CORTEXM3_APSR_V +#define CORTEXM3_XPSR_C CORTEXM3_APSR_C +#define CORTEXM3_XPSR_Z CORTEXM3_APSR_Z +#define CORTEXM3_XPSR_N CORTEXM3_APSR_N + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_COMMON_CORTEXM_PSR_H */ diff --git a/nuttx/arch/arm/src/cortexm3/up_assert.c b/nuttx/arch/arm/src/cortexm3/up_assert.c new file mode 100644 index 000000000..ec2339887 --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/up_assert.c @@ -0,0 +1,311 @@ +/**************************************************************************** + * arch/arm/src/cortexm3/up_assert.c + * + * Copyright (C) 2009 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 + +#include +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Output debug info if stack dump is selected -- even if + * debug is not selected. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_getsp + ****************************************************************************/ + +/* I don't know if the builtin to get SP is enabled */ + +static inline uint32 up_getsp(void) +{ + uint32 sp; + __asm__ + ( + "\tmov %0, sp\n\t" + : "=r"(sp) + ); + return sp; +} + +/**************************************************************************** + * Name: up_stackdump + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static void up_stackdump(uint32 sp, uint32 stack_base) +{ + uint32 stack ; + + for (stack = sp & ~0x1f; stack < stack_base; stack += 32) + { + uint32 *ptr = (uint32*)stack; + lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n", + stack, ptr[0], ptr[1], ptr[2], ptr[3], + ptr[4], ptr[5], ptr[6], ptr[7]); + } +} +#else +# define up_stackdump() +#endif + +/**************************************************************************** + * Name: up_registerdump + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static inline void up_registerdump(void) +{ + /* Are user registers available from interrupt processing? */ + + if (current_regs) + { + /* Yes.. dump the interrupt registers */ + + lldbg("R0: %08x %08x %08x %08x %08x %08x %08x %08x\n", + current_regs[REG_R0], current_regs[REG_R1], + current_regs[REG_R2], current_regs[REG_R3], + current_regs[REG_R4], current_regs[REG_R5], + current_regs[REG_R6], current_regs[REG_R7]); + lldbg("R8: %08x %08x %08x %08x %08x %08x %08x %08x\n", + current_regs[REG_R8], current_regs[REG_R9], + current_regs[REG_R10], current_regs[REG_R11], + current_regs[REG_R12], current_regs[REG_R13], + current_regs[REG_R14], current_regs[REG_R15]); + lldbg("xPSR: %08x PRIMASK: %08x\n", + current_regs[REG_XPSR], current_regs[REG_PRIMASK]); + } +} +#else +# define up_registerdump() +#endif + +/**************************************************************************** + * Name: up_dumpstate + ****************************************************************************/ + +#ifdef CONFIG_ARCH_STACKDUMP +static void up_dumpstate(void) +{ + _TCB *rtcb = (_TCB*)g_readytorun.head; + uint32 sp = up_getsp(); + uint32 ustackbase; + uint32 ustacksize; +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + uint32 istackbase; + uint32 istacksize; +#endif + + /* Get the limits on the user stack memory */ + + if (rtcb->pid == 0) + { + ustackbase = g_heapbase - 4; + ustacksize = CONFIG_IDLETHREAD_STACKSIZE; + } + else + { + ustackbase = (uint32)rtcb->adj_stack_ptr; + ustacksize = (uint32)rtcb->adj_stack_size; + } + + /* Get the limits on the interrupt stack memory */ + +#if CONFIG_ARCH_INTERRUPTSTACK > 3 + istackbase = (uint32)&g_userstack; + istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4; + + /* Show interrupt stack info */ + + lldbg("sp: %08x\n", sp); + lldbg("IRQ stack:\n"); + lldbg(" base: %08x\n", istackbase); + lldbg(" size: %08x\n", istacksize); + + /* Does the current stack pointer lie within the interrupt + * stack? + */ + + if (sp <= istackbase && sp > istackbase - istacksize) + { + /* Yes.. dump the interrupt stack */ + + up_stackdump(sp, istackbase); + + /* Extract the user stack pointer which should lie + * at the base of the interrupt stack. + */ + + sp = g_userstack; + lldbg("sp: %08x\n", sp); + } + + /* Show user stack info */ + + lldbg("User stack:\n"); + lldbg(" base: %08x\n", ustackbase); + lldbg(" size: %08x\n", ustacksize); +#else + lldbg("sp: %08x\n", sp); + lldbg("stack base: %08x\n", ustackbase); + lldbg("stack size: %08x\n", ustacksize); +#endif + + /* Dump the user stack if the stack pointer lies within the allocated user + * stack memory. + */ + + if (sp > ustackbase || sp <= ustackbase - ustacksize) + { +#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4 + lldbg("ERROR: Stack pointer is not within allocated stack\n"); +#endif + } + else + { + up_stackdump(sp, ustackbase); + } + + /* Then dump the registers (if available) */ + + up_registerdump(); +} +#else +# define up_dumpstate() +#endif + +/**************************************************************************** + * Name: _up_assert + ****************************************************************************/ + +static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */ +{ + /* Are we in an interrupt handler or the idle task? */ + + if (current_regs || ((_TCB*)g_readytorun.head)->pid == 0) + { + (void)irqsave(); + for(;;) + { +#ifdef CONFIG_ARCH_LEDS + up_ledon(LED_PANIC); + up_mdelay(250); + up_ledoff(LED_PANIC); + up_mdelay(250); +#endif + } + } + else + { + exit(errorcode); + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_assert + ****************************************************************************/ + +void up_assert(const ubyte *filename, int lineno) +{ +#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG) + _TCB *rtcb = (_TCB*)g_readytorun.head; +#endif + + up_ledon(LED_ASSERTION); +#if CONFIG_TASK_NAME_SIZE > 0 + lldbg("Assertion failed at file:%s line: %d task: %s\n", + filename, lineno, rtcb->name); +#else + lldbg("Assertion failed at file:%s line: %d\n", + filename, lineno); +#endif + up_dumpstate(); + _up_assert(EXIT_FAILURE); +} + +/**************************************************************************** + * Name: up_assert_code + ****************************************************************************/ + +void up_assert_code(const ubyte *filename, int lineno, int errorcode) +{ +#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG) + _TCB *rtcb = (_TCB*)g_readytorun.head; +#endif + + up_ledon(LED_ASSERTION); +#if CONFIG_TASK_NAME_SIZE > 0 + lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n", + filename, lineno, rtcb->name, errorcode); +#else + lldbg("Assertion failed at file:%s line: %d error code: %d\n", + filename, lineno, errorcode); +#endif + up_dumpstate(); + _up_assert(errorcode); +} diff --git a/nuttx/arch/arm/src/cortexm3/up_copystate.c b/nuttx/arch/arm/src/cortexm3/up_copystate.c new file mode 100644 index 000000000..a7e7b1166 --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/up_copystate.c @@ -0,0 +1,86 @@ +/**************************************************************************** + * arch/arm/src/cortexm3/up_copystate.c + * + * Copyright (C) 2009 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 "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_undefinedinsn + ****************************************************************************/ + +/* A little faster than most memcpy's */ + +void up_copystate(uint32 *dest, uint32 *src) +{ + int i; + + /* In the Cortex-M3 model, the state is copied from the stack to the TCB, + * but only a reference is passed to get the state from the TCB. So the + * following check avoids copying the TCB save area onto itself: + */ + + if (src != dest) + { + for (i = 0; i < XCPTCONTEXT_REGS; i++) + { + *dest++ = *src++; + } + } +} + diff --git a/nuttx/arch/arm/src/cortexm3/up_doirq.c b/nuttx/arch/arm/src/cortexm3/up_doirq.c new file mode 100644 index 000000000..8c749ce5f --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/up_doirq.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * arch/arm/src/cortexm3/up_doirq.c + * + * Copyright (C) 2009 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 +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +uint32 *up_doirq(int irq, uint32 *regs) +{ + up_ledon(LED_INIRQ); +#ifdef CONFIG_SUPPRESS_INTERRUPTS + PANIC(OSERR_ERREXCEPTION); +#else + if ((unsigned)irq < NR_IRQS) + { + /* Current regs non-zero indicates that we are processing + * an interrupt; current_regs is also used to manage + * interrupt level context switches. + */ + + current_regs = regs; + + /* Mask and acknowledge the interrupt */ + + up_maskack_irq(irq); + + /* Deliver the IRQ */ + + irq_dispatch(irq, regs); + + /* If a context switch occurred while processing the interrupt + * then current_regs may have change value. If we return any value + * different from the input regs, then the lower level will know + * that a context switch occurred during interrupt processing. + */ + + regs = current_regs; + + /* Indicate that we are no long in an interrupt handler */ + + current_regs = NULL; + + /* Unmask the last interrupt (global interrupts are still + * disabled. + */ + + up_enable_irq(irq); + } + up_ledoff(LED_INIRQ); +#endif + return regs; +} diff --git a/nuttx/arch/arm/src/cortexm3/up_initialstate.c b/nuttx/arch/arm/src/cortexm3/up_initialstate.c new file mode 100644 index 000000000..c529064d4 --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/up_initialstate.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * arch/arm/src/cortexm3/up_initialstate.c + * + * Copyright (C) 2009 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 "up_internal.h" +#include "up_arch.h" +#include "psr.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)); + + /* Save the initial stack pointer */ + + xcp->regs[REG_SP] = (uint32)tcb->adj_stack_ptr; + + /* Save the task entry point (stripping off the thumb bit) */ + + xcp->regs[REG_PC] = (uint32)tcb->start & ~1; + + /* Specify thumb mode */ + + xcp->regs[REG_XPSR] = CORTEXM3_XPSR_T; + + /* Enable or disable interrupts, based on user configuration */ + +# ifdef CONFIG_SUPPRESS_INTERRUPTS + xcp->regs[REG_PRIMASK] = 1; +# endif +} + diff --git a/nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c b/nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c new file mode 100644 index 000000000..31219874b --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/up_schedulesigaction.c @@ -0,0 +1,208 @@ +/**************************************************************************** + * arch/arm/src/cortexm3/up_schedulesigaction.c + * + * Copyright (C) 2009 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 + +#include "psr.h" +#include "os_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#ifndef CONFIG_DISABLE_SIGNALS + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_schedule_sigaction + * + * Description: + * This function is called by the OS when one or more + * signal handling actions have been queued for execution. + * The architecture specific code must configure things so + * that the 'igdeliver' callback is executed on the thread + * specified by 'tcb' as soon as possible. + * + * This function may be called from interrupt handling logic. + * + * This operation should not cause the task to be unblocked + * nor should it cause any immediate execution of sigdeliver. + * Typically, a few cases need to be considered: + * + * (1) This function may be called from an interrupt handler + * During interrupt processing, all xcptcontext structures + * should be valid for all tasks. That structure should + * be modified to invoke sigdeliver() either on return + * from (this) interrupt or on some subsequent context + * switch to the recipient task. + * (2) If not in an interrupt handler and the tcb is NOT + * the currently executing task, then again just modify + * the saved xcptcontext structure for the recipient + * task so it will invoke sigdeliver when that task is + * later resumed. + * (3) If not in an interrupt handler and the tcb IS the + * currently executing task -- just call the signal + * handler now. + * + ****************************************************************************/ + +void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver) +{ + /* Refuse to handle nested signal actions */ + + sdbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver); + + if (!tcb->xcp.sigdeliver) + { + irqstate_t flags; + + /* Make sure that interrupts are disabled */ + + flags = irqsave(); + + /* First, handle some special cases when the signal is + * being delivered to the currently executing task. + */ + + sdbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs); + + if (tcb == (_TCB*)g_readytorun.head) + { + /* CASE 1: We are not in an interrupt handler and + * a task is signalling itself for some reason. + */ + + if (!current_regs) + { + /* In this case just deliver the signal now. */ + + sigdeliver(tcb); + } + + /* CASE 2: We are in an interrupt handler AND the + * interrupted task is the same as the one that + * must receive the signal, then we will have to modify + * the return state as well as the state in the TCB. + * + * Hmmm... there looks like a latent bug here: The following + * logic would fail in the strange case where we are in an + * interrupt handler, the thread is signalling itself, but + * a context switch to another task has occurred so that + * current_regs does not refer to the thread at g_readytorun.head! + */ + + else + { + /* Save the return lr and cpsr and one scratch register + * These will be restored by the signal trampoline after + * the signals have been delivered. + */ + + tcb->xcp.sigdeliver = sigdeliver; + tcb->xcp.saved_pc = current_regs[REG_PC]; + tcb->xcp.saved_primask = current_regs[REG_PRIMASK]; + tcb->xcp.saved_xpsr = current_regs[REG_XPSR]; + + /* Then set up to vector to the trampoline with interrupts + * disabled + */ + + current_regs[REG_PC] = (uint32)up_sigdeliver; + current_regs[REG_PRIMASK] = 1; + current_regs[REG_XPSR] = CORTEXM3_XPSR_T; + + /* And make sure that the saved context in the TCB + * is the same as the interrupt return context. + */ + + up_savestate(tcb->xcp.regs); + } + } + + /* Otherwise, we are (1) signaling a task is not running + * from an interrupt handler or (2) we are not in an + * interrupt handler and the running task is signalling + * some non-running task. + */ + + else + { + /* Save the return lr and cpsr and one scratch register + * These will be restored by the signal trampoline after + * the signals have been delivered. + */ + + tcb->xcp.sigdeliver = sigdeliver; + tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC]; + tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK]; + tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR]; + + /* Then set up to vector to the trampoline with interrupts + * disabled + */ + + tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver; + tcb->xcp.regs[REG_PRIMASK] = 1; + tcb->xcp.regs[REG_XPSR] = CORTEXM3_XPSR_T; + } + + irqrestore(flags); + } +} + +#endif /* !CONFIG_DISABLE_SIGNALS */ diff --git a/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c b/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c new file mode 100644 index 000000000..d0241dfa1 --- /dev/null +++ b/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c @@ -0,0 +1,144 @@ +/**************************************************************************** + * arch/arm/src/cortexm3/up_sigdeliver.c + * + * Copyright (C) 2009 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 +#include + +#include "os_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#ifndef CONFIG_DISABLE_SIGNALS + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_sigdeliver + * + * Description: + * This is the a signal handling trampoline. When a + * signal action was posted. The task context was mucked + * with and forced to branch to this location with interrupts + * disabled. + * + ****************************************************************************/ + +void up_sigdeliver(void) +{ + _TCB *rtcb = (_TCB*)g_readytorun.head; + uint32 regs[XCPTCONTEXT_REGS]; + sig_deliver_t sigdeliver; + + /* Save the errno. This must be preserved throughout the + * signal handling so that the the user code final gets + * the correct errno value (probably EINTR). + */ + + int saved_errno = rtcb->pterrno; + + up_ledon(LED_SIGNAL); + + sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n", + rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head); + ASSERT(rtcb->xcp.sigdeliver != NULL); + + /* Save the real return state on the stack. */ + + up_copystate(regs, rtcb->xcp.regs); + regs[REG_PC] = rtcb->xcp.saved_pc; + regs[REG_PRIMASK] = rtcb->xcp.saved_primask; + regs[REG_XPSR] = rtcb->xcp.saved_xpsr; + + /* Get a local copy of the sigdeliver function pointer. + * we do this so that we can nullify the sigdeliver + * function point in the TCB and accept more signal + * deliveries while processing the current pending + * signals. + */ + + sigdeliver = rtcb->xcp.sigdeliver; + rtcb->xcp.sigdeliver = NULL; + + /* Then restore the task interrupt statat. */ + + irqrestore((uint16)regs[REG_PRIMASK]); + + /* Deliver the signals */ + + sigdeliver(rtcb); + + /* Output any debug messaged BEFORE restoreing errno + * (becuase they may alter errno), then restore the + * original errno that is needed by the user logic + * (it is probably EINTR). + */ + + sdbg("Resuming\n"); + rtcb->pterrno = saved_errno; + + /* Then restore the correct state for this thread of + * execution. + */ + + up_ledoff(LED_SIGNAL); + up_fullcontextrestore(regs); +} + +#endif /* !CONFIG_DISABLE_SIGNALS */ + diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs index 3eb33dd58..3e0ab3488 100644 --- a/nuttx/arch/arm/src/lm3s/Make.defs +++ b/nuttx/arch/arm/src/lm3s/Make.defs @@ -37,13 +37,12 @@ HEAD_ASRC = lm3s_vectors.S CMN_ASRCS = CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c up_exit.c \ + up_createstack.c up_mdelay.c up_udelay.c up_exit.c \ up_idle.c up_initialize.c up_initialstate.c up_interruptcontext.c \ up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ - up_prefetchabort.c up_releasepending.c up_releasestack.c \ - up_reprioritizertr.c up_schedulesigaction.c \ - up_sigdeliver.c up_syscall.c up_unblocktask.c \ - up_undefinedinsn.c up_usestack.c up_doirq.c + up_releasepending.c up_releasestack.c up_reprioritizertr.c \ + up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \ + up_usestack.c up_doirq.c CHIP_ASRCS = lm3s_context.S CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c lm3s_svcall.c \ diff --git a/nuttx/arch/arm/src/lm3s/chip.h b/nuttx/arch/arm/src/lm3s/chip.h index 129cd9f37..6d113cbb7 100644 --- a/nuttx/arch/arm/src/lm3s/chip.h +++ b/nuttx/arch/arm/src/lm3s/chip.h @@ -47,7 +47,6 @@ #include "lm3s_syscontrol.h" /* System control module */ #include "lm3s_gpio.h" /* GPIO module */ #include "lm3s_uart.h" /* UART peripherals */ -#include "cortexm3_nvic.h" /* Nested, vectored interrupt controller */ /************************************************************************************ * Definitions diff --git a/nuttx/arch/arm/src/lm3s/lm3s_context.S b/nuttx/arch/arm/src/lm3s/lm3s_context.S index 7641b0109..efef06630 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_context.S +++ b/nuttx/arch/arm/src/lm3s/lm3s_context.S @@ -40,7 +40,7 @@ #include #include -#include "cortexm3_nvic.h" +#include "nvic.h" /************************************************************************************ * Preprocessor Definitions diff --git a/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c b/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c index 7a9c76611..7a3e60623 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_hardfault.c @@ -49,7 +49,7 @@ #include "up_arch.h" #include "os_internal.h" -#include "cortexm3_nvic.h" +#include "nvic.h" #include "lm3s_internal.h" /**************************************************************************** diff --git a/nuttx/arch/arm/src/lm3s/lm3s_irq.c b/nuttx/arch/arm/src/lm3s/lm3s_irq.c index d75d33304..374c4bfc7 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_irq.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_irq.c @@ -47,6 +47,7 @@ #include #include +#include "nvic.h" #include "up_arch.h" #include "os_internal.h" #include "up_internal.h" diff --git a/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c b/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c index 95b358df1..714d68c7d 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_timerisr.c @@ -44,6 +44,7 @@ #include #include +#include "nvic.h" #include "clock_internal.h" #include "up_internal.h" #include "up_arch.h" -- cgit v1.2.3