Attach mem mgmt fault handle if MPU is enabled

git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3471 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2011-04-06 01:51:07 +00:00
parent d2d2e51e62
commit a864ab2137
18 changed files with 2090 additions and 1967 deletions

View File

@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/include/lm3s/irq.h
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@ -63,7 +63,7 @@
/* Vector 1: Reset (not handler as an IRQ) */
#define LM3S_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
#define LM3S_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
#define LM3S_IRQ_MPU (4) /* Vector 4: Memory management (MPU) */
#define LM3S_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
#define LM3S_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
#define LM3S_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
#define LM3S_IRQ_SVCALL (11) /* Vector 11: SVC call */

View File

@ -64,7 +64,7 @@
/* Vector 1: Reset (not handler as an IRQ) */
#define LPC17_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
#define LPC17_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
#define LPC17_IRQ_MPU (4) /* Vector 4: Memory management (MPU) */
#define LPC17_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
#define LPC17_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
#define LPC17_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
#define LPC17_IRQ_SVCALL (11) /* Vector 11: SVC call */

View File

@ -1,7 +1,7 @@
/****************************************************************************************
* arch/arm/include/sam3u/irq.h
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@ -94,7 +94,7 @@
/* Vector 1: Reset (not handler as an IRQ) */
#define SAM3U_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
#define SAM3U_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
#define SAM3U_IRQ_MPU (4) /* Vector 4: Memory management (MPU) */
#define SAM3U_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
#define SAM3U_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
#define SAM3U_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
#define SAM3U_IRQ_SVCALL (11) /* Vector 11: SVC call */

View File

@ -63,7 +63,7 @@
/* Vector 1: Reset (not handler as an IRQ) */
#define STM32_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
#define STM32_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
#define STM32_IRQ_MPU (4) /* Vector 4: Memory management (MPU) */
#define STM32_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
#define STM32_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
#define STM32_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
#define STM32_IRQ_SVCALL (11) /* Vector 11: SVC call */

View File

@ -181,6 +181,7 @@ extern void up_lowputs(const char *str);
extern uint32_t *up_doirq(int irq, uint32_t *regs);
extern int up_svcall(int irq, FAR void *context);
extern int up_hardfault(int irq, FAR void *context);
extern int up_memfault(int irq, FAR void *context);
#else /* CONFIG_ARCH_CORTEXM3 */

View File

@ -0,0 +1,110 @@
/****************************************************************************
* arch/arm/src/cortexm3/up_memfault.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <assert.h>
#include <debug.h>
#include <arch/irq.h>
#include "up_arch.h"
#include "os_internal.h"
#include "nvic.h"
#include "up_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#undef DEBUG_MEMFAULTS /* Define to debug memory management faults */
#ifdef DEBUG_MEMFAULTS
# define mfdbg(format, arg...) lldbg(format, ##arg)
#else
# define mfdbg(x...)
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_memfault
*
* Description:
* This is Memory Management Fault exception handler. Normally we get here
* when the Cortex M3 MPU is enabled and an MPU fault is detected. However,
* I understand that there are other error conditions that can also generate
* memory management faults.
*
****************************************************************************/
int up_memfault(int irq, FAR void *context)
{
/* Dump some memory management fault info */
(void)irqsave();
lldbg("PANIC!!! Memory Management Fault:\n");
mfdbg(" IRQ: %d context: %p\n", irq, regs);
lldbg(" CFAULTS: %08x MMFAR: %08x\n",
getreg32(NVIC_CFAULTS), getreg32(NVIC_MEMMANAGE_ADDR));
mfdbg(" R0: %08x %08x %08x %08x %08x %08x %08x %08x\n",
regs[REG_R0], regs[REG_R1], regs[REG_R2], regs[REG_R3],
regs[REG_R4], regs[REG_R5], regs[REG_R6], regs[REG_R7]);
mfdbg(" R8: %08x %08x %08x %08x %08x %08x %08x %08x\n",
regs[REG_R8], regs[REG_R9], regs[REG_R10], regs[REG_R11],
regs[REG_R12], regs[REG_R13], regs[REG_R14], regs[REG_R15]);
mfdbg(" PSR=%08x\n", regs[REG_XPSR]);
PANIC(OSERR_UNEXPECTEDISR);
return OK;
}

View File

@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/lm3s/Make.defs
#
# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
# Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@ -39,7 +39,7 @@ CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.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_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.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 up_hardfault.c up_svcall.c

View File

@ -2,7 +2,7 @@
* arch/arm/src/lm3s/lm3s_irq.c
* arch/arm/src/chip/lm3s_irq.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@ -128,7 +128,7 @@ static void lm3s_dumpnvic(const char *msg, int irq)
#endif
/****************************************************************************
* Name: lm3s_nmi, lm3s_mpu, lm3s_busfault, lm3s_usagefault, lm3s_pendsv,
* Name: lm3s_nmi, lm3s_busfault, lm3s_usagefault, lm3s_pendsv,
* lm3s_dbgmonitor, lm3s_pendsv, lm3s_reserved
*
* Description:
@ -147,14 +147,6 @@ static int lm3s_nmi(int irq, FAR void *context)
return 0;
}
static int lm3s_mpu(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! MPU interrupt received\n");
PANIC(OSERR_UNEXPECTEDISR);
return 0;
}
static int lm3s_busfault(int irq, FAR void *context)
{
(void)irqsave();
@ -234,7 +226,7 @@ static int lm3s_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit)
else
{
*regaddr = NVIC_SYSHCON;
if (irq == LM3S_IRQ_MPU)
if (irq == LM3S_IRQ_MEMFAULT)
{
*bit = NVIC_SYSHCON_MEMFAULTENA;
}
@ -324,11 +316,22 @@ void up_irqinitialize(void)
/* up_prioritize_irq(LM3S_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
/* If the MPU is enabled, then attach and enable the Memory Management
* Fault handler.
*/
#ifdef CONFIG_CORTEXM3_MPU
irq_attach(LM3S_IRQ_MEMFAULT, up_memfault);
up_enable_irq(LM3S_IRQ_MEMFAULT);
#endif
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG
irq_attach(LM3S_IRQ_NMI, lm3s_nmi);
irq_attach(LM3S_IRQ_MPU, lm3s_mpu);
#ifndef CONFIG_CORTEXM3_MPU
irq_attach(LM3S_IRQ_MEMFAULT, up_memfault);
#endif
irq_attach(LM3S_IRQ_BUSFAULT, lm3s_busfault);
irq_attach(LM3S_IRQ_USAGEFAULT, lm3s_usagefault);
irq_attach(LM3S_IRQ_PENDSV, lm3s_pendsv);
@ -434,7 +437,7 @@ int up_prioritize_irq(int irq, int priority)
uint32_t regval;
int shift;
DEBUGASSERT(irq >= LM3S_IRQ_MPU && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
DEBUGASSERT(irq >= LM3S_IRQ_MEMFAULT && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
if (irq < LM3S_IRQ_INTERRUPTS)
{

File diff suppressed because it is too large Load Diff

View File

@ -41,7 +41,7 @@ HEAD_ASRC = lpc17_vectors.S
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \
up_mdelay.c up_udelay.c up_exit.c up_initialize.c \
up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c \
up_initialstate.c up_interruptcontext.c up_modifyreg8.c \
up_modifyreg16.c up_modifyreg32.c up_releasepending.c \
up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \

View File

@ -127,7 +127,7 @@ static void lpc17_dumpnvic(const char *msg, int irq)
#endif
/****************************************************************************
* Name: lpc17_nmi, lpc17_mpu, lpc17_busfault, lpc17_usagefault, lpc17_pendsv,
* Name: lpc17_nmi, lpc17_busfault, lpc17_usagefault, lpc17_pendsv,
* lpc17_dbgmonitor, lpc17_pendsv, lpc17_reserved
*
* Description:
@ -146,14 +146,6 @@ static int lpc17_nmi(int irq, FAR void *context)
return 0;
}
static int lpc17_mpu(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! MPU interrupt received\n");
PANIC(OSERR_UNEXPECTEDISR);
return 0;
}
static int lpc17_busfault(int irq, FAR void *context)
{
(void)irqsave();
@ -233,7 +225,7 @@ static int lpc17_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit)
else
{
*regaddr = NVIC_SYSHCON;
if (irq == LPC17_IRQ_MPU)
if (irq == LPC17_IRQ_MEMFAULT)
{
*bit = NVIC_SYSHCON_MEMFAULTENA;
}
@ -312,11 +304,22 @@ void up_irqinitialize(void)
/* up_prioritize_irq(LPC17_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
/* If the MPU is enabled, then attach and enable the Memory Management
* Fault handler.
*/
#ifdef CONFIG_CORTEXM3_MPU
irq_attach(LPC17_IRQ_MEMFAULT, up_memfault);
up_enable_irq(LPC17_IRQ_MEMFAULT);
#endif
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG
irq_attach(LPC17_IRQ_NMI, lpc17_nmi);
irq_attach(LPC17_IRQ_MPU, lpc17_mpu);
#ifndef CONFIG_CORTEXM3_MPU
irq_attach(LPC17_IRQ_MEMFAULT, up_memfault);
#endif
irq_attach(LPC17_IRQ_BUSFAULT, lpc17_busfault);
irq_attach(LPC17_IRQ_USAGEFAULT, lpc17_usagefault);
irq_attach(LPC17_IRQ_PENDSV, lpc17_pendsv);
@ -449,7 +452,7 @@ int up_prioritize_irq(int irq, int priority)
uint32_t regval;
int shift;
DEBUGASSERT(irq >= LPC17_IRQ_MPU && irq < LPC17_IRQ_NIRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
DEBUGASSERT(irq >= LPC17_IRQ_MEMFAULT && irq < LPC17_IRQ_NIRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
if (irq < LPC17_IRQ_EXTINT)
{

View File

@ -1,351 +1,351 @@
/************************************************************************************************
* arch/arm/src/lpc17xx/lpc17_vectors.S
* arch/arm/src/chip/lpc17_vectors.S
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************************/
/************************************************************************************************
* Included Files
************************************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
/************************************************************************************************
* Preprocessor Definitions
************************************************************************************************/
/* Memory Map:
*
* 0x0000:0000 - Beginning of FLASH. Address of vectors
* 0x0003:ffff - End of flash
* 0x1000:0000 - Start of CPU SRAM and start of .data (_sdata)
* - End of .data (_edata) and start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap. NOTE
* that the ARM uses a decrement before store stack so that the correct initial
* value is the end of the stack + 4;
* 0x1000:7fff - End of CPU SRAM and end of heap (1st region)
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
* thread mode and covers state from the main stack point, the MSP (vs. the MSP).
*/
#define EXC_RETURN 0xfffffff9
/************************************************************************************************
* Global Symbols
************************************************************************************************/
.globl __start
.syntax unified
.thumb
.file "lpc17_vectors.S"
/************************************************************************************************
* Macros
************************************************************************************************/
/* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
* registers on the stack, then branches to an instantantiation of the following
* macro. This macro simply loads the IRQ number into R0, then jumps to the common
* IRQ handling logic.
*/
.macro HANDLER, label, irqno
.thumb_func
\label:
mov r0, #\irqno
b lpc17_common
.endm
/************************************************************************************************
* Vectors
************************************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl lpc17_vectors
.type lpc17_vectors, function
lpc17_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
.word __start /* Vector 1: Reset vector */
.word lpc17_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word lpc17_hardfault /* Vector 3: Hard fault */
.word lpc17_mpu /* Vector 4: Memory management (MPU) */
.word lpc17_busfault /* Vector 5: Bus fault */
.word lpc17_usagefault /* Vector 6: Usage fault */
.word lpc17_reserved /* Vector 7: Reserved */
.word lpc17_reserved /* Vector 8: Reserved */
.word lpc17_reserved /* Vector 9: Reserved */
.word lpc17_reserved /* Vector 10: Reserved */
.word lpc17_svcall /* Vector 11: SVC call */
.word lpc17_dbgmonitor /* Vector 12: Debug monitor */
.word lpc17_reserved /* Vector 13: Reserved */
.word lpc17_pendsv /* Vector 14: Pendable system service request */
.word lpc17_systick /* Vector 15: System tick */
/* External Interrupts */
.word lpc17_wdt /* Vector 16+0: Watchdog timer */
.word lpc17_tmr0 /* Vector 16+1: Timer 0 */
.word lpc17_tmr1 /* Vector 16+2: Timer 1 */
.word lpc17_tmr2 /* Vector 16+3: Timer 2 */
.word lpc17_tmr3 /* Vector 16+4: Timer 3 */
.word lpc17_uart0 /* Vector 16+5: UART 0 */
.word lpc17_uart1 /* Vector 16+6: UART 1 */
.word lpc17_uart2 /* Vector 16+7: UART 2 */
.word lpc17_uart3 /* Vector 16+8: UART 3 */
.word lpc17_pwm1 /* Vector 16+9: PWM */
.word lpc17_i2c0 /* Vector 16+10: I2C 0 */
.word lpc17_i2c1 /* Vector 16+11: I2C 1 */
.word lpc17_i2c2 /* Vector 16+12: I2C 2 */
.word lpc17_spif /* Vector 16+13: SPI */
.word lpc17_ssp0 /* Vector 16+14: SSP 0 */
.word lpc17_ssp1 /* Vector 16+15: SSP 1 */
.word lpc17_pll0 /* Vector 16+16: PLL 0 */
.word lpc17_rtc /* Vector 16+17: Real time clock */
.word lpc17_eint0 /* Vector 16+18: External interrupt 0 */
.word lpc17_eint1 /* Vector 16+19: External interrupt 1 */
.word lpc17_eint2 /* Vector 16+20: External interrupt 2 */
.word lpc17_eint3 /* Vector 16+21: External interrupt 3 */
.word lpc17_adc /* Vector 16+22: A/D Converter */
.word lpc17_bod /* Vector 16+23: Brown Out detect */
.word lpc17_usb /* Vector 16+24: USB */
.word lpc17_can /* Vector 16+25: CAN */
.word lpc17_gpdma /* Vector 16+26: GPDMA */
.word lpc17_i2s /* Vector 16+27: I2S */
.word lpc17_eth /* Vector 16+28: Ethernet */
.word lpc17_ritint /* Vector 16+29: Repetitive Interrupt Timer */
.word lpc17_mcpwm /* Vector 16+30: Motor Control PWM */
.word lpc17_qei /* Vector 16+31: Quadrature Encoder */
.word lpc17_pll1 /* Vector 16+32: PLL 1 */
.word lpc17_usbact /* Vector 16+33: USB Activity Interrupt */
.word lpc17_canact /* Vector 16+34: CAN Activity Interrupt */
.size lpc17_vectors, .-lpc17_vectors
/************************************************************************************************
* .text
************************************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER lpc17_reserved, LPC17_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER lpc17_nmi, LPC17_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER lpc17_hardfault, LPC17_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER lpc17_mpu, LPC17_IRQ_MPU /* Vector 4: Memory management (MPU) */
HANDLER lpc17_busfault, LPC17_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER lpc17_usagefault, LPC17_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER lpc17_svcall, LPC17_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER lpc17_dbgmonitor, LPC17_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER lpc17_pendsv, LPC17_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER lpc17_systick, LPC17_IRQ_SYSTICK /* Vector 15: System tick */
HANDLER lpc17_wdt, LPC17_IRQ_WDT /* Vector 16+0: Watchdog timer */
HANDLER lpc17_tmr0, LPC17_IRQ_TMR0 /* Vector 16+1: Timer 0 */
HANDLER lpc17_tmr1, LPC17_IRQ_TMR1 /* Vector 16+2: Timer 1 */
HANDLER lpc17_tmr2, LPC17_IRQ_TMR2 /* Vector 16+3: Timer 2 */
HANDLER lpc17_tmr3, LPC17_IRQ_TMR3 /* Vector 16+4: Timer 3 */
HANDLER lpc17_uart0, LPC17_IRQ_UART0 /* Vector 16+5: UART 0 */
HANDLER lpc17_uart1, LPC17_IRQ_UART1 /* Vector 16+6: UART 1 */
HANDLER lpc17_uart2, LPC17_IRQ_UART2 /* Vector 16+7: UART 2 */
HANDLER lpc17_uart3, LPC17_IRQ_UART3 /* Vector 16+8: UART 3 */
HANDLER lpc17_pwm1, LPC17_IRQ_PWM1 /* Vector 16+9: PWM 1 */
HANDLER lpc17_i2c0, LPC17_IRQ_I2C0 /* Vector 16+10: I2C 0 */
HANDLER lpc17_i2c1, LPC17_IRQ_I2C1 /* Vector 16+11: I2C 1 */
HANDLER lpc17_i2c2, LPC17_IRQ_I2C2 /* Vector 16+12: I2C 2 */
HANDLER lpc17_spif, LPC17_IRQ_SPIF /* Vector 16+13: SPI */
HANDLER lpc17_ssp0, LPC17_IRQ_SSP0 /* Vector 16+14: SSP 0 */
HANDLER lpc17_ssp1, LPC17_IRQ_SSP1 /* Vector 16+15: SSP 1 */
HANDLER lpc17_pll0, LPC17_IRQ_PLL0 /* Vector 16+16: PLL 0 */
HANDLER lpc17_rtc, LPC17_IRQ_RTC /* Vector 16+17: Real time clock */
HANDLER lpc17_eint0, LPC17_IRQ_EINT0 /* Vector 16+18: External interrupt 0 */
HANDLER lpc17_eint1, LPC17_IRQ_EINT1 /* Vector 16+19: External interrupt 1 */
HANDLER lpc17_eint2, LPC17_IRQ_EINT2 /* Vector 16+20: External interrupt 2 */
HANDLER lpc17_eint3, LPC17_IRQ_EINT3 /* Vector 16+21: External interrupt 3 */
HANDLER lpc17_adc, LPC17_IRQ_ADC /* Vector 16+22: A/D Converter */
HANDLER lpc17_bod, LPC17_IRQ_BOD /* Vector 16+23: Brown Out detect */
HANDLER lpc17_usb, LPC17_IRQ_USB /* Vector 16+24: USB */
HANDLER lpc17_can, LPC17_IRQ_CAN /* Vector 16+25: CAN */
HANDLER lpc17_gpdma, LPC17_IRQ_GPDMA /* Vector 16+26: GPDMA */
HANDLER lpc17_i2s, LPC17_IRQ_I2S /* Vector 16+27: I2S */
HANDLER lpc17_eth, LPC17_IRQ_ETH /* Vector 16+28: Ethernet */
HANDLER lpc17_ritint, LPC17_IRQ_RITINT /* Vector 16+29: Repetitive Interrupt Timer */
HANDLER lpc17_mcpwm, LPC17_IRQ_MCPWM /* Vector 16+30: Motor Control PWM */
HANDLER lpc17_qei, LPC17_IRQ_QEI /* Vector 16+31: Quadrature Encoder */
HANDLER lpc17_pll1, LPC17_IRQ_PLL1 /* Vector 16+32: PLL 1 */
HANDLER lpc17_usbact, LPC17_IRQ_USBACT /* Vector 16+33: USB Activity Interrupt */
HANDLER lpc17_canact, LPC17_IRQ_CANACT /* Vector 16+34: CAN Activity Interrupt */
/* Common IRQ handling logic. On entry here, the stack is like the following:
*
* REG_XPSR
* REG_R15
* REG_R14
* REG_R12
* REG_R3
* REG_R2
* REG_R1
* MSP->REG_R0
*
* and R0 contains the IRQ number
*/
lpc17_common:
/* Complete the context save */
mrs r1, msp /* R1=The main stack pointer */
mov r2, r1 /* R2=Copy of the main stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will use a special interrupt
* stack pointer. The way that this is done here prohibits nested interrupts!
* Otherwise, we will re-use the main stack for interrupt level processing.
*/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
ldr sp, =g_intstackbase
str r1, [sp, #-4]! /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
ldr r1, [sp, #+4]! /* Recover R1=main stack pointer */
#else
mov sp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, sp /* Recover R1=main stack pointer */
#endif
/* On return from up_doirq, R0 will hold a pointer to register context
* array to use for the interrupt return. If that return value is the same
* as current stack pointer, then things are relatively easy.
*/
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*/
1:
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
2:
msr msp, r1 /* Recover the return MSP value */
/* Restore the interrupt state. Preload r14 with the special return
* value first (so that the return actually occurs with interrupts
* still disabled).
*/
ldr r14, =EXC_RETURN /* Load the special value */
msr primask, r3 /* Restore interrupts */
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
*/
bx r14 /* And return */
.size handlers, .-handlers
/************************************************************************************************
* Name: up_interruptstack/g_intstackbase
*
* Description:
* Shouldn't happen
*
************************************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
.bss
.global g_intstackbase
.align 4
up_interruptstack:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~3)
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
/************************************************************************************************
* .rodata
************************************************************************************************/
.section .rodata, "a"
/* 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 IDLE thread is the thread that
* the system boots on and, eventually, becomes the idle, do nothing task that runs
* only when there is nothing else to run. The heap continues from there until the
* end of memory. See g_heapbase below.
*/
.globl g_heapbase
.type g_heapbase, object
g_heapbase:
.word HEAP_BASE
.size g_heapbase, .-g_heapbase
.end
/************************************************************************************************
* arch/arm/src/lpc17xx/lpc17_vectors.S
* arch/arm/src/chip/lpc17_vectors.S
*
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************************/
/************************************************************************************************
* Included Files
************************************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
/************************************************************************************************
* Preprocessor Definitions
************************************************************************************************/
/* Memory Map:
*
* 0x0000:0000 - Beginning of FLASH. Address of vectors
* 0x0003:ffff - End of flash
* 0x1000:0000 - Start of CPU SRAM and start of .data (_sdata)
* - End of .data (_edata) and start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap. NOTE
* that the ARM uses a decrement before store stack so that the correct initial
* value is the end of the stack + 4;
* 0x1000:7fff - End of CPU SRAM and end of heap (1st region)
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
* thread mode and covers state from the main stack point, the MSP (vs. the MSP).
*/
#define EXC_RETURN 0xfffffff9
/************************************************************************************************
* Global Symbols
************************************************************************************************/
.globl __start
.syntax unified
.thumb
.file "lpc17_vectors.S"
/************************************************************************************************
* Macros
************************************************************************************************/
/* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
* registers on the stack, then branches to an instantantiation of the following
* macro. This macro simply loads the IRQ number into R0, then jumps to the common
* IRQ handling logic.
*/
.macro HANDLER, label, irqno
.thumb_func
\label:
mov r0, #\irqno
b lpc17_common
.endm
/************************************************************************************************
* Vectors
************************************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl lpc17_vectors
.type lpc17_vectors, function
lpc17_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
.word __start /* Vector 1: Reset vector */
.word lpc17_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word lpc17_hardfault /* Vector 3: Hard fault */
.word lpc17_mpu /* Vector 4: Memory management (MPU) */
.word lpc17_busfault /* Vector 5: Bus fault */
.word lpc17_usagefault /* Vector 6: Usage fault */
.word lpc17_reserved /* Vector 7: Reserved */
.word lpc17_reserved /* Vector 8: Reserved */
.word lpc17_reserved /* Vector 9: Reserved */
.word lpc17_reserved /* Vector 10: Reserved */
.word lpc17_svcall /* Vector 11: SVC call */
.word lpc17_dbgmonitor /* Vector 12: Debug monitor */
.word lpc17_reserved /* Vector 13: Reserved */
.word lpc17_pendsv /* Vector 14: Pendable system service request */
.word lpc17_systick /* Vector 15: System tick */
/* External Interrupts */
.word lpc17_wdt /* Vector 16+0: Watchdog timer */
.word lpc17_tmr0 /* Vector 16+1: Timer 0 */
.word lpc17_tmr1 /* Vector 16+2: Timer 1 */
.word lpc17_tmr2 /* Vector 16+3: Timer 2 */
.word lpc17_tmr3 /* Vector 16+4: Timer 3 */
.word lpc17_uart0 /* Vector 16+5: UART 0 */
.word lpc17_uart1 /* Vector 16+6: UART 1 */
.word lpc17_uart2 /* Vector 16+7: UART 2 */
.word lpc17_uart3 /* Vector 16+8: UART 3 */
.word lpc17_pwm1 /* Vector 16+9: PWM */
.word lpc17_i2c0 /* Vector 16+10: I2C 0 */
.word lpc17_i2c1 /* Vector 16+11: I2C 1 */
.word lpc17_i2c2 /* Vector 16+12: I2C 2 */
.word lpc17_spif /* Vector 16+13: SPI */
.word lpc17_ssp0 /* Vector 16+14: SSP 0 */
.word lpc17_ssp1 /* Vector 16+15: SSP 1 */
.word lpc17_pll0 /* Vector 16+16: PLL 0 */
.word lpc17_rtc /* Vector 16+17: Real time clock */
.word lpc17_eint0 /* Vector 16+18: External interrupt 0 */
.word lpc17_eint1 /* Vector 16+19: External interrupt 1 */
.word lpc17_eint2 /* Vector 16+20: External interrupt 2 */
.word lpc17_eint3 /* Vector 16+21: External interrupt 3 */
.word lpc17_adc /* Vector 16+22: A/D Converter */
.word lpc17_bod /* Vector 16+23: Brown Out detect */
.word lpc17_usb /* Vector 16+24: USB */
.word lpc17_can /* Vector 16+25: CAN */
.word lpc17_gpdma /* Vector 16+26: GPDMA */
.word lpc17_i2s /* Vector 16+27: I2S */
.word lpc17_eth /* Vector 16+28: Ethernet */
.word lpc17_ritint /* Vector 16+29: Repetitive Interrupt Timer */
.word lpc17_mcpwm /* Vector 16+30: Motor Control PWM */
.word lpc17_qei /* Vector 16+31: Quadrature Encoder */
.word lpc17_pll1 /* Vector 16+32: PLL 1 */
.word lpc17_usbact /* Vector 16+33: USB Activity Interrupt */
.word lpc17_canact /* Vector 16+34: CAN Activity Interrupt */
.size lpc17_vectors, .-lpc17_vectors
/************************************************************************************************
* .text
************************************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER lpc17_reserved, LPC17_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER lpc17_nmi, LPC17_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER lpc17_hardfault, LPC17_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER lpc17_mpu, LPC17_IRQ_MEMFAULT /* Vector 4: Memory management (MPU) */
HANDLER lpc17_busfault, LPC17_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER lpc17_usagefault, LPC17_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER lpc17_svcall, LPC17_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER lpc17_dbgmonitor, LPC17_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER lpc17_pendsv, LPC17_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER lpc17_systick, LPC17_IRQ_SYSTICK /* Vector 15: System tick */
HANDLER lpc17_wdt, LPC17_IRQ_WDT /* Vector 16+0: Watchdog timer */
HANDLER lpc17_tmr0, LPC17_IRQ_TMR0 /* Vector 16+1: Timer 0 */
HANDLER lpc17_tmr1, LPC17_IRQ_TMR1 /* Vector 16+2: Timer 1 */
HANDLER lpc17_tmr2, LPC17_IRQ_TMR2 /* Vector 16+3: Timer 2 */
HANDLER lpc17_tmr3, LPC17_IRQ_TMR3 /* Vector 16+4: Timer 3 */
HANDLER lpc17_uart0, LPC17_IRQ_UART0 /* Vector 16+5: UART 0 */
HANDLER lpc17_uart1, LPC17_IRQ_UART1 /* Vector 16+6: UART 1 */
HANDLER lpc17_uart2, LPC17_IRQ_UART2 /* Vector 16+7: UART 2 */
HANDLER lpc17_uart3, LPC17_IRQ_UART3 /* Vector 16+8: UART 3 */
HANDLER lpc17_pwm1, LPC17_IRQ_PWM1 /* Vector 16+9: PWM 1 */
HANDLER lpc17_i2c0, LPC17_IRQ_I2C0 /* Vector 16+10: I2C 0 */
HANDLER lpc17_i2c1, LPC17_IRQ_I2C1 /* Vector 16+11: I2C 1 */
HANDLER lpc17_i2c2, LPC17_IRQ_I2C2 /* Vector 16+12: I2C 2 */
HANDLER lpc17_spif, LPC17_IRQ_SPIF /* Vector 16+13: SPI */
HANDLER lpc17_ssp0, LPC17_IRQ_SSP0 /* Vector 16+14: SSP 0 */
HANDLER lpc17_ssp1, LPC17_IRQ_SSP1 /* Vector 16+15: SSP 1 */
HANDLER lpc17_pll0, LPC17_IRQ_PLL0 /* Vector 16+16: PLL 0 */
HANDLER lpc17_rtc, LPC17_IRQ_RTC /* Vector 16+17: Real time clock */
HANDLER lpc17_eint0, LPC17_IRQ_EINT0 /* Vector 16+18: External interrupt 0 */
HANDLER lpc17_eint1, LPC17_IRQ_EINT1 /* Vector 16+19: External interrupt 1 */
HANDLER lpc17_eint2, LPC17_IRQ_EINT2 /* Vector 16+20: External interrupt 2 */
HANDLER lpc17_eint3, LPC17_IRQ_EINT3 /* Vector 16+21: External interrupt 3 */
HANDLER lpc17_adc, LPC17_IRQ_ADC /* Vector 16+22: A/D Converter */
HANDLER lpc17_bod, LPC17_IRQ_BOD /* Vector 16+23: Brown Out detect */
HANDLER lpc17_usb, LPC17_IRQ_USB /* Vector 16+24: USB */
HANDLER lpc17_can, LPC17_IRQ_CAN /* Vector 16+25: CAN */
HANDLER lpc17_gpdma, LPC17_IRQ_GPDMA /* Vector 16+26: GPDMA */
HANDLER lpc17_i2s, LPC17_IRQ_I2S /* Vector 16+27: I2S */
HANDLER lpc17_eth, LPC17_IRQ_ETH /* Vector 16+28: Ethernet */
HANDLER lpc17_ritint, LPC17_IRQ_RITINT /* Vector 16+29: Repetitive Interrupt Timer */
HANDLER lpc17_mcpwm, LPC17_IRQ_MCPWM /* Vector 16+30: Motor Control PWM */
HANDLER lpc17_qei, LPC17_IRQ_QEI /* Vector 16+31: Quadrature Encoder */
HANDLER lpc17_pll1, LPC17_IRQ_PLL1 /* Vector 16+32: PLL 1 */
HANDLER lpc17_usbact, LPC17_IRQ_USBACT /* Vector 16+33: USB Activity Interrupt */
HANDLER lpc17_canact, LPC17_IRQ_CANACT /* Vector 16+34: CAN Activity Interrupt */
/* Common IRQ handling logic. On entry here, the stack is like the following:
*
* REG_XPSR
* REG_R15
* REG_R14
* REG_R12
* REG_R3
* REG_R2
* REG_R1
* MSP->REG_R0
*
* and R0 contains the IRQ number
*/
lpc17_common:
/* Complete the context save */
mrs r1, msp /* R1=The main stack pointer */
mov r2, r1 /* R2=Copy of the main stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will use a special interrupt
* stack pointer. The way that this is done here prohibits nested interrupts!
* Otherwise, we will re-use the main stack for interrupt level processing.
*/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
ldr sp, =g_intstackbase
str r1, [sp, #-4]! /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
ldr r1, [sp, #+4]! /* Recover R1=main stack pointer */
#else
mov sp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, sp /* Recover R1=main stack pointer */
#endif
/* On return from up_doirq, R0 will hold a pointer to register context
* array to use for the interrupt return. If that return value is the same
* as current stack pointer, then things are relatively easy.
*/
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*/
1:
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
2:
msr msp, r1 /* Recover the return MSP value */
/* Restore the interrupt state. Preload r14 with the special return
* value first (so that the return actually occurs with interrupts
* still disabled).
*/
ldr r14, =EXC_RETURN /* Load the special value */
msr primask, r3 /* Restore interrupts */
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
*/
bx r14 /* And return */
.size handlers, .-handlers
/************************************************************************************************
* Name: up_interruptstack/g_intstackbase
*
* Description:
* Shouldn't happen
*
************************************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
.bss
.global g_intstackbase
.align 4
up_interruptstack:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~3)
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
/************************************************************************************************
* .rodata
************************************************************************************************/
.section .rodata, "a"
/* 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 IDLE thread is the thread that
* the system boots on and, eventually, becomes the idle, do nothing task that runs
* only when there is nothing else to run. The heap continues from there until the
* end of memory. See g_heapbase below.
*/
.globl g_heapbase
.type g_heapbase, object
g_heapbase:
.word HEAP_BASE
.size g_heapbase, .-g_heapbase
.end

View File

@ -42,7 +42,7 @@ HEAD_ASRC = sam3u_vectors.S
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.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_initialstate.c up_interruptcontext.c up_memfault.c up_modifyreg8.c \
up_modifyreg16.c up_modifyreg32.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 \

View File

@ -2,7 +2,7 @@
* arch/arm/src/sam3u/sam3u_irq.c
* arch/arm/src/chip/sam3u_irq.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@ -124,7 +124,7 @@ static void sam3u_dumpnvic(const char *msg, int irq)
#endif
/****************************************************************************
* Name: sam3u_nmi, sam3u_mpu, sam3u_busfault, sam3u_usagefault, sam3u_pendsv,
* Name: sam3u_nmi, sam3u_busfault, sam3u_usagefault, sam3u_pendsv,
* sam3u_dbgmonitor, sam3u_pendsv, sam3u_reserved
*
* Description:
@ -143,14 +143,6 @@ static int sam3u_nmi(int irq, FAR void *context)
return 0;
}
static int sam3u_mpu(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! MPU interrupt received\n");
PANIC(OSERR_UNEXPECTEDISR);
return 0;
}
static int sam3u_busfault(int irq, FAR void *context)
{
(void)irqsave();
@ -225,7 +217,7 @@ static int sam3u_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit)
else
{
*regaddr = NVIC_SYSHCON;
if (irq == SAM3U_IRQ_MPU)
if (irq == SAM3U_IRQ_MEMFAULT)
{
*bit = NVIC_SYSHCON_MEMFAULTENA;
}
@ -305,11 +297,22 @@ void up_irqinitialize(void)
/* up_prioritize_irq(SAM3U_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
/* If the MPU is enabled, then attach and enable the Memory Management
* Fault handler.
*/
#ifdef CONFIG_CORTEXM3_MPU
irq_attach(SAM3U_IRQ_MEMFAULT, up_memfault);
up_enable_irq(SAM3U_IRQ_MEMFAULT);
#endif
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG
irq_attach(SAM3U_IRQ_NMI, sam3u_nmi);
irq_attach(SAM3U_IRQ_MPU, sam3u_mpu);
#ifndef CONFIG_CORTEXM3_MPU
irq_attach(SAM3U_IRQ_MEMFAULT, up_memfault);
#endif
irq_attach(SAM3U_IRQ_BUSFAULT, sam3u_busfault);
irq_attach(SAM3U_IRQ_USAGEFAULT, sam3u_usagefault);
irq_attach(SAM3U_IRQ_PENDSV, sam3u_pendsv);
@ -439,7 +442,7 @@ int up_prioritize_irq(int irq, int priority)
uint32_t regval;
int shift;
DEBUGASSERT(irq >= SAM3U_IRQ_MPU && irq < SAM3U_IRQ_NIRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
DEBUGASSERT(irq >= SAM3U_IRQ_MEMFAULT && irq < SAM3U_IRQ_NIRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
if (irq < SAM3U_IRQ_EXTINT)
{

View File

@ -1,342 +1,342 @@
/************************************************************************************************
* arch/arm/src/sam3u/sam3u_vectors.S
* arch/arm/src/chip/sam3u_vectors.S
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************************/
/************************************************************************************************
* Included Files
************************************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
/************************************************************************************************
* Preprocessor Definitions
************************************************************************************************/
/* Memory Map:
*
* 0x0800:0000 - Beginning of FLASH. Address of vectors. Mapped to address 0x0000:0000 at boot
* time.
* 0x0803:ffff - End of flash
* 0x2000:0000 - Start of SRAM and start of .data (_sdata)
* - End of .data (_edata) and start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap. NOTE
* that the ARM uses a decrement before store stack so that the correct initial
* value is the end of the stack + 4;
* 0x2000:bfff - End of SRAM and end of heap
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
* thread mode and covers state from the main stack point, the MSP (vs. the MSP).
*/
#define EXC_RETURN 0xfffffff9
/************************************************************************************************
* Global Symbols
************************************************************************************************/
.globl __start
.syntax unified
.thumb
.file "sam3u_vectors.S"
/************************************************************************************************
* Macros
************************************************************************************************/
/* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
* registers on the stack, then branches to an instantantiation of the following
* macro. This macro simply loads the IRQ number into R0, then jumps to the common
* IRQ handling logic.
*/
.macro HANDLER, label, irqno
.thumb_func
\label:
mov r0, #\irqno
b sam3u_common
.endm
/************************************************************************************************
* Vectors
************************************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl sam3u_vectors
.type sam3u_vectors, function
sam3u_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
.word __start /* Vector 1: Reset vector */
.word sam3u_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word sam3u_hardfault /* Vector 3: Hard fault */
.word sam3u_mpu /* Vector 4: Memory management (MPU) */
.word sam3u_busfault /* Vector 5: Bus fault */
.word sam3u_usagefault /* Vector 6: Usage fault */
.word sam3u_reserved /* Vector 7: Reserved */
.word sam3u_reserved /* Vector 8: Reserved */
.word sam3u_reserved /* Vector 9: Reserved */
.word sam3u_reserved /* Vector 10: Reserved */
.word sam3u_svcall /* Vector 11: SVC call */
.word sam3u_dbgmonitor /* Vector 12: Debug monitor */
.word sam3u_reserved /* Vector 13: Reserved */
.word sam3u_pendsv /* Vector 14: Pendable system service request */
.word sam3u_systick /* Vector 15: System tick */
/* External Interrupts */
.word sam3u_supc /* Vector 16+0: Supply Controller */
.word sam3u_rstc /* Vector 16+1: Reset Controller */
.word sam3u_rtc /* Vector 16+2: Real Time Clock */
.word sam3u_rtt /* Vector 16+3: Real Time Timer */
.word sam3u_wdt /* Vector 16+4: Watchdog Timer */
.word sam3u_pmc /* Vector 16+5: Power Management Controller */
.word sam3u_eefc0 /* Vector 16+6: Enhanced Embedded Flash Controller 0 */
.word sam3u_eefc1 /* Vector 16+7: Enhanced Embedded Flash Controller 1 */
.word sam3u_uart /* Vector 16+8: Universal Asynchronous Receiver Transmitter */
.word sam3u_smc /* Vector 16+9: Static Memory Controller */
.word sam3u_pioa /* Vector 16+10: Parallel I/O Controller A */
.word sam3u_piob /* Vector 16+11: Parallel I/O Controller B */
.word sam3u_pioc /* Vector 16+12: Parallel I/O Controller C */
.word sam3u_usart0 /* Vector 16+13: USART 0 */
.word sam3u_usart1 /* Vector 16+14: USART 1 */
.word sam3u_usart2 /* Vector 16+15: USART 2 */
.word sam3u_usart3 /* Vector 16+16: USART 3 */
.word sam3u_hsmci /* Vector 16+17: High Speed Multimedia Card Interface */
.word sam3u_twi0 /* Vector 16+18: Two-Wire Interface 0 */
.word sam3u_twi1 /* Vector 16+19: Two-Wire Interface 1 */
.word sam3u_spi /* Vector 16+20: Serial Peripheral Interface */
.word sam3u_ssc /* Vector 16+21: Synchronous Serial Controller */
.word sam3u_tc0 /* Vector 16+22: Timer Counter 0 */
.word sam3u_tc1 /* Vector 16+23: Timer Counter 1 */
.word sam3u_tc2 /* Vector 16+24: Timer Counter 2 */
.word sam3u_pwm /* Vector 16+25: Pulse Width Modulation Controller */
.word sam3u_adc12b /* Vector 16+26: 12-bit ADC Controller */
.word sam3u_adc /* Vector 16+27: 10-bit ADC Controller */
.word sam3u_dmac /* Vector 16+28: DMA Controller */
.word sam3u_udphs /* Vector 16+29: USB Device High Speed */
.size sam3u_vectors, .-sam3u_vectors
/************************************************************************************************
* .text
************************************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER sam3u_reserved, SAM3U_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER sam3u_nmi, SAM3U_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER sam3u_hardfault, SAM3U_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER sam3u_mpu, SAM3U_IRQ_MPU /* Vector 4: Memory management (MPU) */
HANDLER sam3u_busfault, SAM3U_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER sam3u_usagefault, SAM3U_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER sam3u_svcall, SAM3U_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER sam3u_dbgmonitor, SAM3U_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER sam3u_pendsv, SAM3U_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER sam3u_systick, SAM3U_IRQ_SYSTICK /* Vector 15: System tick */
HANDLER sam3u_supc, SAM3U_IRQ_SUPC /* Vector 16+0: Supply Controller */
HANDLER sam3u_rstc, SAM3U_IRQ_RSTC /* Vector 16+1: Reset Controller */
HANDLER sam3u_rtc, SAM3U_IRQ_RTC /* Vector 16+2: Real Time Clock */
HANDLER sam3u_rtt, SAM3U_IRQ_RTT /* Vector 16+3: Real Time Timer */
HANDLER sam3u_wdt, SAM3U_IRQ_WDT /* Vector 16+4: Watchdog Timer */
HANDLER sam3u_pmc, SAM3U_IRQ_PMC /* Vector 16+5: Power Management Controller */
HANDLER sam3u_eefc0, SAM3U_IRQ_EEFC0 /* Vector 16+6: Enhanced Embedded Flash Controller 0 */
HANDLER sam3u_eefc1, SAM3U_IRQ_EEFC1 /* Vector 16+7: Enhanced Embedded Flash Controller 1 */
HANDLER sam3u_uart, SAM3U_IRQ_UART /* Vector 16+8: Universal Asynchronous Receiver Transmitter */
HANDLER sam3u_smc, SAM3U_IRQ_SMC /* Vector 16+9: Static Memory Controller */
HANDLER sam3u_pioa, SAM3U_IRQ_PIOA /* Vector 16+10: Parallel I/O Controller A */
HANDLER sam3u_piob, SAM3U_IRQ_PIOB /* Vector 16+11: Parallel I/O Controller B */
HANDLER sam3u_pioc, SAM3U_IRQ_PIOC /* Vector 16+12: Parallel I/O Controller C */
HANDLER sam3u_usart0, SAM3U_IRQ_USART0 /* Vector 16+13: USART 0 */
HANDLER sam3u_usart1, SAM3U_IRQ_USART1 /* Vector 16+14: USART 1 */
HANDLER sam3u_usart2, SAM3U_IRQ_USART2 /* Vector 16+15: USART 2 */
HANDLER sam3u_usart3, SAM3U_IRQ_USART3 /* Vector 16+16: USART 3 */
HANDLER sam3u_hsmci, SAM3U_IRQ_HSMCI /* Vector 16+17: High Speed Multimedia Card Interface */
HANDLER sam3u_twi0, SAM3U_IRQ_TWI0 /* Vector 16+18: Two-Wire Interface 0 */
HANDLER sam3u_twi1, SAM3U_IRQ_TWI1 /* Vector 16+19: Two-Wire Interface 1 */
HANDLER sam3u_spi, SAM3U_IRQ_SPI /* Vector 16+20: Serial Peripheral Interface */
HANDLER sam3u_ssc, SAM3U_IRQ_SSC /* Vector 16+21: Synchronous Serial Controller */
HANDLER sam3u_tc0, SAM3U_IRQ_TC0 /* Vector 16+22: Timer Counter 0 */
HANDLER sam3u_tc1, SAM3U_IRQ_TC1 /* Vector 16+23: Timer Counter 1 */
HANDLER sam3u_tc2, SAM3U_IRQ_TC2 /* Vector 16+24: Timer Counter 2 */
HANDLER sam3u_pwm, SAM3U_IRQ_PWM /* Vector 16+25: Pulse Width Modulation Controller */
HANDLER sam3u_adc12b, SAM3U_IRQ_ADC12B /* Vector 16+26: 12-bit ADC Controller */
HANDLER sam3u_adc, SAM3U_IRQ_ADC /* Vector 16+27: 10-bit ADC Controller */
HANDLER sam3u_dmac, SAM3U_IRQ_DMAC /* Vector 16+28: DMA Controller */
HANDLER sam3u_udphs, SAM3U_IRQ_UDPHS /* Vector 16+29: USB Device High Speed */
/* Common IRQ handling logic. On entry here, the stack is like the following:
*
* REG_XPSR
* REG_R15
* REG_R14
* REG_R12
* REG_R3
* REG_R2
* REG_R1
* MSP->REG_R0
*
* and R0 contains the IRQ number
*/
sam3u_common:
/* Complete the context save */
mrs r1, msp /* R1=The main stack pointer */
mov r2, r1 /* R2=Copy of the main stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will use a special interrupt
* stack pointer. The way that this is done here prohibits nested interrupts!
* Otherwise, we will re-use the main stack for interrupt level processing.
*/
#ifdef CONFIG_ARCH_INTERRUPTSTACK
ldr sp, =g_intstackbase
str r1, [sp, #-4]! /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
ldr r1, [sp, #+4]! /* Recover R1=main stack pointer */
#else
mov sp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, sp /* Recover R1=main stack pointer */
#endif
/* On return from up_doirq, R0 will hold a pointer to register context
* array to use for the interrupt return. If that return value is the same
* as current stack pointer, then things are relatively easy.
*/
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*/
1:
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
2:
msr msp, r1 /* Recover the return MSP value */
/* Restore the interrupt state. Preload r14 with the special return
* value first (so that the return actually occurs with interrupts
* still disabled).
*/
ldr r14, =EXC_RETURN /* Load the special value */
msr primask, r3 /* Restore interrupts */
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
*/
bx r14 /* And return */
.size handlers, .-handlers
/************************************************************************************************
* Name: up_interruptstack/g_intstackbase
*
* Description:
* Shouldn't happen
*
************************************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
.bss
.global g_intstackbase
.align 4
up_interruptstack:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~3)
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
/************************************************************************************************
* .rodata
************************************************************************************************/
.section .rodata, "a"
/* 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 IDLE thread is the thread that
* the system boots on and, eventually, becomes the idle, do nothing task that runs
* only when there is nothing else to run. The heap continues from there until the
* end of memory. See g_heapbase below.
*/
.globl g_heapbase
.type g_heapbase, object
g_heapbase:
.word HEAP_BASE
.size g_heapbase, .-g_heapbase
.end
/************************************************************************************************
* arch/arm/src/sam3u/sam3u_vectors.S
* arch/arm/src/chip/sam3u_vectors.S
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************************/
/************************************************************************************************
* Included Files
************************************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
/************************************************************************************************
* Preprocessor Definitions
************************************************************************************************/
/* Memory Map:
*
* 0x0800:0000 - Beginning of FLASH. Address of vectors. Mapped to address 0x0000:0000 at boot
* time.
* 0x0803:ffff - End of flash
* 0x2000:0000 - Start of SRAM and start of .data (_sdata)
* - End of .data (_edata) and start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap. NOTE
* that the ARM uses a decrement before store stack so that the correct initial
* value is the end of the stack + 4;
* 0x2000:bfff - End of SRAM and end of heap
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
* thread mode and covers state from the main stack point, the MSP (vs. the MSP).
*/
#define EXC_RETURN 0xfffffff9
/************************************************************************************************
* Global Symbols
************************************************************************************************/
.globl __start
.syntax unified
.thumb
.file "sam3u_vectors.S"
/************************************************************************************************
* Macros
************************************************************************************************/
/* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
* registers on the stack, then branches to an instantantiation of the following
* macro. This macro simply loads the IRQ number into R0, then jumps to the common
* IRQ handling logic.
*/
.macro HANDLER, label, irqno
.thumb_func
\label:
mov r0, #\irqno
b sam3u_common
.endm
/************************************************************************************************
* Vectors
************************************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl sam3u_vectors
.type sam3u_vectors, function
sam3u_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
.word __start /* Vector 1: Reset vector */
.word sam3u_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word sam3u_hardfault /* Vector 3: Hard fault */
.word sam3u_mpu /* Vector 4: Memory management (MPU) */
.word sam3u_busfault /* Vector 5: Bus fault */
.word sam3u_usagefault /* Vector 6: Usage fault */
.word sam3u_reserved /* Vector 7: Reserved */
.word sam3u_reserved /* Vector 8: Reserved */
.word sam3u_reserved /* Vector 9: Reserved */
.word sam3u_reserved /* Vector 10: Reserved */
.word sam3u_svcall /* Vector 11: SVC call */
.word sam3u_dbgmonitor /* Vector 12: Debug monitor */
.word sam3u_reserved /* Vector 13: Reserved */
.word sam3u_pendsv /* Vector 14: Pendable system service request */
.word sam3u_systick /* Vector 15: System tick */
/* External Interrupts */
.word sam3u_supc /* Vector 16+0: Supply Controller */
.word sam3u_rstc /* Vector 16+1: Reset Controller */
.word sam3u_rtc /* Vector 16+2: Real Time Clock */
.word sam3u_rtt /* Vector 16+3: Real Time Timer */
.word sam3u_wdt /* Vector 16+4: Watchdog Timer */
.word sam3u_pmc /* Vector 16+5: Power Management Controller */
.word sam3u_eefc0 /* Vector 16+6: Enhanced Embedded Flash Controller 0 */
.word sam3u_eefc1 /* Vector 16+7: Enhanced Embedded Flash Controller 1 */
.word sam3u_uart /* Vector 16+8: Universal Asynchronous Receiver Transmitter */
.word sam3u_smc /* Vector 16+9: Static Memory Controller */
.word sam3u_pioa /* Vector 16+10: Parallel I/O Controller A */
.word sam3u_piob /* Vector 16+11: Parallel I/O Controller B */
.word sam3u_pioc /* Vector 16+12: Parallel I/O Controller C */
.word sam3u_usart0 /* Vector 16+13: USART 0 */
.word sam3u_usart1 /* Vector 16+14: USART 1 */
.word sam3u_usart2 /* Vector 16+15: USART 2 */
.word sam3u_usart3 /* Vector 16+16: USART 3 */
.word sam3u_hsmci /* Vector 16+17: High Speed Multimedia Card Interface */
.word sam3u_twi0 /* Vector 16+18: Two-Wire Interface 0 */
.word sam3u_twi1 /* Vector 16+19: Two-Wire Interface 1 */
.word sam3u_spi /* Vector 16+20: Serial Peripheral Interface */
.word sam3u_ssc /* Vector 16+21: Synchronous Serial Controller */
.word sam3u_tc0 /* Vector 16+22: Timer Counter 0 */
.word sam3u_tc1 /* Vector 16+23: Timer Counter 1 */
.word sam3u_tc2 /* Vector 16+24: Timer Counter 2 */
.word sam3u_pwm /* Vector 16+25: Pulse Width Modulation Controller */
.word sam3u_adc12b /* Vector 16+26: 12-bit ADC Controller */
.word sam3u_adc /* Vector 16+27: 10-bit ADC Controller */
.word sam3u_dmac /* Vector 16+28: DMA Controller */
.word sam3u_udphs /* Vector 16+29: USB Device High Speed */
.size sam3u_vectors, .-sam3u_vectors
/************************************************************************************************
* .text
************************************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER sam3u_reserved, SAM3U_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER sam3u_nmi, SAM3U_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER sam3u_hardfault, SAM3U_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER sam3u_mpu, SAM3U_IRQ_MEMFAULT /* Vector 4: Memory management (MPU) */
HANDLER sam3u_busfault, SAM3U_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER sam3u_usagefault, SAM3U_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER sam3u_svcall, SAM3U_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER sam3u_dbgmonitor, SAM3U_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER sam3u_pendsv, SAM3U_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER sam3u_systick, SAM3U_IRQ_SYSTICK /* Vector 15: System tick */
HANDLER sam3u_supc, SAM3U_IRQ_SUPC /* Vector 16+0: Supply Controller */
HANDLER sam3u_rstc, SAM3U_IRQ_RSTC /* Vector 16+1: Reset Controller */
HANDLER sam3u_rtc, SAM3U_IRQ_RTC /* Vector 16+2: Real Time Clock */
HANDLER sam3u_rtt, SAM3U_IRQ_RTT /* Vector 16+3: Real Time Timer */
HANDLER sam3u_wdt, SAM3U_IRQ_WDT /* Vector 16+4: Watchdog Timer */
HANDLER sam3u_pmc, SAM3U_IRQ_PMC /* Vector 16+5: Power Management Controller */
HANDLER sam3u_eefc0, SAM3U_IRQ_EEFC0 /* Vector 16+6: Enhanced Embedded Flash Controller 0 */
HANDLER sam3u_eefc1, SAM3U_IRQ_EEFC1 /* Vector 16+7: Enhanced Embedded Flash Controller 1 */
HANDLER sam3u_uart, SAM3U_IRQ_UART /* Vector 16+8: Universal Asynchronous Receiver Transmitter */
HANDLER sam3u_smc, SAM3U_IRQ_SMC /* Vector 16+9: Static Memory Controller */
HANDLER sam3u_pioa, SAM3U_IRQ_PIOA /* Vector 16+10: Parallel I/O Controller A */
HANDLER sam3u_piob, SAM3U_IRQ_PIOB /* Vector 16+11: Parallel I/O Controller B */
HANDLER sam3u_pioc, SAM3U_IRQ_PIOC /* Vector 16+12: Parallel I/O Controller C */
HANDLER sam3u_usart0, SAM3U_IRQ_USART0 /* Vector 16+13: USART 0 */
HANDLER sam3u_usart1, SAM3U_IRQ_USART1 /* Vector 16+14: USART 1 */
HANDLER sam3u_usart2, SAM3U_IRQ_USART2 /* Vector 16+15: USART 2 */
HANDLER sam3u_usart3, SAM3U_IRQ_USART3 /* Vector 16+16: USART 3 */
HANDLER sam3u_hsmci, SAM3U_IRQ_HSMCI /* Vector 16+17: High Speed Multimedia Card Interface */
HANDLER sam3u_twi0, SAM3U_IRQ_TWI0 /* Vector 16+18: Two-Wire Interface 0 */
HANDLER sam3u_twi1, SAM3U_IRQ_TWI1 /* Vector 16+19: Two-Wire Interface 1 */
HANDLER sam3u_spi, SAM3U_IRQ_SPI /* Vector 16+20: Serial Peripheral Interface */
HANDLER sam3u_ssc, SAM3U_IRQ_SSC /* Vector 16+21: Synchronous Serial Controller */
HANDLER sam3u_tc0, SAM3U_IRQ_TC0 /* Vector 16+22: Timer Counter 0 */
HANDLER sam3u_tc1, SAM3U_IRQ_TC1 /* Vector 16+23: Timer Counter 1 */
HANDLER sam3u_tc2, SAM3U_IRQ_TC2 /* Vector 16+24: Timer Counter 2 */
HANDLER sam3u_pwm, SAM3U_IRQ_PWM /* Vector 16+25: Pulse Width Modulation Controller */
HANDLER sam3u_adc12b, SAM3U_IRQ_ADC12B /* Vector 16+26: 12-bit ADC Controller */
HANDLER sam3u_adc, SAM3U_IRQ_ADC /* Vector 16+27: 10-bit ADC Controller */
HANDLER sam3u_dmac, SAM3U_IRQ_DMAC /* Vector 16+28: DMA Controller */
HANDLER sam3u_udphs, SAM3U_IRQ_UDPHS /* Vector 16+29: USB Device High Speed */
/* Common IRQ handling logic. On entry here, the stack is like the following:
*
* REG_XPSR
* REG_R15
* REG_R14
* REG_R12
* REG_R3
* REG_R2
* REG_R1
* MSP->REG_R0
*
* and R0 contains the IRQ number
*/
sam3u_common:
/* Complete the context save */
mrs r1, msp /* R1=The main stack pointer */
mov r2, r1 /* R2=Copy of the main stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will use a special interrupt
* stack pointer. The way that this is done here prohibits nested interrupts!
* Otherwise, we will re-use the main stack for interrupt level processing.
*/
#ifdef CONFIG_ARCH_INTERRUPTSTACK
ldr sp, =g_intstackbase
str r1, [sp, #-4]! /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
ldr r1, [sp, #+4]! /* Recover R1=main stack pointer */
#else
mov sp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, sp /* Recover R1=main stack pointer */
#endif
/* On return from up_doirq, R0 will hold a pointer to register context
* array to use for the interrupt return. If that return value is the same
* as current stack pointer, then things are relatively easy.
*/
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*/
1:
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
2:
msr msp, r1 /* Recover the return MSP value */
/* Restore the interrupt state. Preload r14 with the special return
* value first (so that the return actually occurs with interrupts
* still disabled).
*/
ldr r14, =EXC_RETURN /* Load the special value */
msr primask, r3 /* Restore interrupts */
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
*/
bx r14 /* And return */
.size handlers, .-handlers
/************************************************************************************************
* Name: up_interruptstack/g_intstackbase
*
* Description:
* Shouldn't happen
*
************************************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
.bss
.global g_intstackbase
.align 4
up_interruptstack:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~3)
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
/************************************************************************************************
* .rodata
************************************************************************************************/
.section .rodata, "a"
/* 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 IDLE thread is the thread that
* the system boots on and, eventually, becomes the idle, do nothing task that runs
* only when there is nothing else to run. The heap continues from there until the
* end of memory. See g_heapbase below.
*/
.globl g_heapbase
.type g_heapbase, object
g_heapbase:
.word HEAP_BASE
.size g_heapbase, .-g_heapbase
.end

View File

@ -39,7 +39,7 @@ CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
up_initialize.c up_initialstate.c up_interruptcontext.c \
up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.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 up_hardfault.c up_svcall.c

View File

@ -2,7 +2,7 @@
* arch/arm/src/stm32/stm32_irq.c
* arch/arm/src/chip/stm32_irq.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@ -134,7 +134,7 @@ static void stm32_dumpnvic(const char *msg, int irq)
#endif
/****************************************************************************
* Name: stm32_nmi, stm32_mpu, stm32_busfault, stm32_usagefault, stm32_pendsv,
* Name: stm32_nmi, stm32_busfault, stm32_usagefault, stm32_pendsv,
* stm32_dbgmonitor, stm32_pendsv, stm32_reserved
*
* Description:
@ -153,14 +153,6 @@ static int stm32_nmi(int irq, FAR void *context)
return 0;
}
static int stm32_mpu(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! MPU interrupt received\n");
PANIC(OSERR_UNEXPECTEDISR);
return 0;
}
static int stm32_busfault(int irq, FAR void *context)
{
(void)irqsave();
@ -245,7 +237,7 @@ static int stm32_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit)
else
{
*regaddr = NVIC_SYSHCON;
if (irq == STM32_IRQ_MPU)
if (irq == STM32_IRQ_MEMFAULT)
{
*bit = NVIC_SYSHCON_MEMFAULTENA;
}
@ -339,11 +331,22 @@ void up_irqinitialize(void)
/* up_prioritize_irq(STM32_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
/* If the MPU is enabled, then attach and enable the Memory Management
* Fault handler.
*/
#ifdef CONFIG_CORTEXM3_MPU
irq_attach(STM32_IRQ_MEMFAULT, up_memfault);
up_enable_irq(STM32_IRQ_MEMFAULT);
#endif
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG
irq_attach(STM32_IRQ_NMI, stm32_nmi);
irq_attach(STM32_IRQ_MPU, stm32_mpu);
#ifndef CONFIG_CORTEXM3_MPU
irq_attach(STM32_IRQ_MEMFAULT, up_memfault);
#endif
irq_attach(STM32_IRQ_BUSFAULT, stm32_busfault);
irq_attach(STM32_IRQ_USAGEFAULT, stm32_usagefault);
irq_attach(STM32_IRQ_PENDSV, stm32_pendsv);
@ -449,7 +452,7 @@ int up_prioritize_irq(int irq, int priority)
uint32_t regval;
int shift;
DEBUGASSERT(irq >= STM32_IRQ_MPU && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
if (irq < STM32_IRQ_INTERRUPTS)
{

File diff suppressed because it is too large Load Diff