arch/arm/src/lc823450: This commit removes support for the dedicated vector handling from the LC823450 architecture support. Only common vectors are now supported.

This commit is contained in:
Gregory Nutt 2018-06-20 10:04:38 -06:00
parent ade6751345
commit 9a51854223
11 changed files with 114 additions and 618 deletions

View File

@ -125,6 +125,7 @@ config ARCH_CHIP_LC823450
select ARCH_HAVE_MULTICPU
select ARCH_HAVE_I2CRESET
select ARCH_GLOBAL_IRQDISABLE
select ARMV7M_CMNVECTOR
---help---
ON Semiconductor LC823450 architectures (ARM dual Cortex-M3)

View File

@ -154,6 +154,7 @@
#define LC823450_IRQ_EXTINT4 (LC823450_IRQ_INTERRUPTS+63) /* 79: ExternalINT4 interrupt */
#define LC823450_IRQ_EXTINT5 (LC823450_IRQ_INTERRUPTS+64) /* 80: ExternalINT5 interrupt */
#define LC823450_IRQ_NEXTINT (65)
#define LC823450_IRQ_NIRQS (LC823450_IRQ_EXTINT5 + 1)
#define LC823450_IRQ_GPIO00 (LC823450_IRQ_NIRQS + 0) /* 81: GPIO00 */
@ -258,7 +259,8 @@
#endif /* CONFIG_LC823450_VIRQ */
#define NR_VECTORS (LC823450_IRQ_NIRQS)
#define NR_IRQS (LC823450_IRQ_NIRQS + LC823450_IRQ_NGPIOIRQS + LC823450_IRQ_NVIRTUALIRQS)
#define NR_IRQS (LC823450_IRQ_NIRQS + LC823450_IRQ_NGPIOIRQS + \
LC823450_IRQ_NVIRTUALIRQS)
/****************************************************************************
* Public Types

View File

@ -202,7 +202,7 @@ static inline void kinetis_fpuconfig(void)
setcontrol(regval);
/* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend
* with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we
* with the lazy FP context save behavior. Clear FPCCR.ASPEN since we
* are going to keep CONTROL.FPCA off for all contexts.
*/

View File

@ -35,11 +35,7 @@
#
############################################################################
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
HEAD_ASRC =
else
HEAD_ASRC = lc823450_vectors.S
endif
CMN_UASRCS =
CMN_UCSRCS =

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/lc823450/chip.h
*
* Copyright 2014,2017 Sony Video & Sound Products Inc.
* Copyright 2014, 2017 Sony Video & Sound Products Inc.
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
*
@ -43,18 +43,25 @@
#include <sys/types.h>
#include <arch/lc823450/chip.h>
#include <arch/lc823450/irq.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Provide the required number of peripheral interrupt vector definitions.
* The definition LC823450_IRQ_NEXTINT simply comes from the chip-specific
* IRQ header file included by arch/lc823450/irq.h.
*/
#define ARMV7M_PERIPHERAL_INTERRUPTS LC823450_IRQ_NEXTINT
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/lc823450/lc823450_start.c
*
* Copyright 2014,2015,2016,2017 Sony Video & Sound Products Inc.
* Copyright 2014, 2015, 2016, 2017 Sony Video & Sound Products Inc.
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
* Author: Yasuhiro Osaki <Yasuhiro.Osaki@jp.sony.com>
@ -35,7 +35,6 @@
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
@ -82,6 +81,38 @@
# include "lc823450_sdram.h"
#endif
#include "lc823450_start.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* .data is positioned first in the primary RAM followed immediately by .bss.
* The IDLE thread stack lies just after .bss and has size give by
* CONFIG_IDLETHREAD_STACKSIZE; The heap then begins just after the IDLE.
* ARM EABI requires 64 bit stack alignment.
*/
#define IDLE_STACKSIZE (CONFIG_IDLETHREAD_STACKSIZE & ~7)
#define IDLE_STACK ((uintptr_t)&_ebss + IDLE_STACKSIZE)
#define HEAP_BASE ((uintptr_t)&_ebss + IDLE_STACKSIZE)
/****************************************************************************
* Public Data
****************************************************************************/
/* g_idle_topstack: _sbss is the start of the BSS region as defined by the
* linker script. _ebss lies at the end of the BSS region. 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.
* g_idle_topstack is a read-only variable the provides this computed
* address.
*/
const uintptr_t g_idle_topstack = HEAP_BASE;
/****************************************************************************
* Public Data
****************************************************************************/

View File

@ -0,0 +1,65 @@
/************************************************************************************
* arch/arm/src/lc823450/lc823450_start.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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_LC823450_LC823450_H
#define __ARCH_ARM_SRC_LC823450_LC823450_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Public Data
************************************************************************************/
/* g_idle_topstack: _sbss is the start of the BSS region as defined by the
* linker script. _ebss lies at the end of the BSS region. 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.
* g_idle_topstack is a read-only variable the provides this computed
* address.
*/
extern const uintptr_t g_idle_topstack;
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
#endif /* __ARCH_ARM_SRC_LC823450_LC823450_H */

View File

@ -1,482 +0,0 @@
/****************************************************************************
* arch/arm/src/lc823450/lc823450_vectors.S
*
* Copyright 2014,2015,2016,2017 Sony Video & Sound Products Inc.
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
*
* 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>
#include "chip.h"
#include "exc_return.h"
/*****************************************************************************
* Preprocessor Definitions
****************************************************************************/
/* Configuration ************************************************************/
#ifdef CONFIG_ARCH_HIPRI_INTERRUPT
/* In kernel mode without an interrupt stack, this interrupt handler will set the
* MSP to the stack pointer of the interrupted thread. If the interrupted thread
* was a privileged thread, that will be the MSP otherwise it will be the PSP. If
* the PSP is used, then the value of the MSP will be invalid when the interrupt
* handler returns because it will be a pointer to an old position in the
* unprivileged stack. Then when the high priority interrupt occurs and uses this
* stale MSP, there will most likely be a system failure.
*
* If the interrupt stack is selected, on the other hand, then the interrupt
* handler will always set the the MSP to the interrupt stack. So when the high
* priority interrupt occurs, it will either use the MSP of the last privileged
* thread to run or, in the case of the nested interrupt, the interrupt stack if
* no privileged task has run.
*/
# if defined(CONFIG_BUILD_PROTECTED) && CONFIG_ARCH_INTERRUPTSTACK < 4
# error Interrupt stack must be used with high priority interrupts in kernel mode
# endif
/* Use the the BASEPRI to control interrupts is required if nested, high
* priority interrupts are supported.
*/
# ifndef CONFIG_ARMV7M_USEBASEPRI
# error CONFIG_ARMV7M_USEBASEPRI must be used with CONFIG_ARCH_HIPRI_INTERRUPT
# endif
#endif
/* Memory Map ***************************************************************/
/*
* 0x0800:0000 - Beginning of FLASH. Address of vectors (if not using bootloader)
* Mapped to address 0x0000:0000 at boot time.
* 0x0800:3000 - Address of vectors if using bootloader
* 0x0803:ffff - End of flash
* 0x2000:0000 - Start of SRAM and start of .data (_sdata)
* - End of .data (_edata) abd start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap
* 0x2000:ffff - End of SRAM and end of heap
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
/*****************************************************************************
* Global Symbols
****************************************************************************/
.syntax unified
.thumb
.file "lc823450_vectors.S"
/* Check if common ARMv7 interrupt vectoring is used (see arch/arm/src/armv7-m/up_vectors.S) */
#ifndef CONFIG_ARMV7M_CMNVECTOR
.globl __start
/*****************************************************************************
* 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 exception_common
.endm
/*****************************************************************************
* Vectors
****************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl _vectors
.type _vectors, function
_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
#ifdef CONFIG_SPIFLASH_BOOT
.word __start_main /* Vector 1: Reset vector */
#else /* CONFIG_SPIFLASH_BOOT */
.word __start /* Vector 1: Reset vector */
#endif /* CONFIG_SPIFLASH_BOOT */
.word lc823450_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word lc823450_hardfault /* Vector 3: Hard fault */
.word lc823450_mpu /* Vector 4: Memory management (MPU) */
.word lc823450_busfault /* Vector 5: Bus fault */
.word lc823450_usagefault /* Vector 6: Usage fault */
.word lc823450_reserved /* Vector 7: Reserved */
.word lc823450_reserved /* Vector 8: Reserved */
.word lc823450_reserved /* Vector 9: Reserved */
.word lc823450_reserved /* Vector 10: Reserved */
.word lc823450_svcall /* Vector 11: SVC call */
.word lc823450_dbgmonitor /* Vector 12: Debug monitor */
.word lc823450_reserved /* Vector 13: Reserved */
.word lc823450_pendsv /* Vector 14: Pendable system service request */
.word lc823450_systick /* Vector 15: System tick */
/* External Interrupts */
#undef VECTOR
#define VECTOR(l,i) .word l
#undef UNUSED
#define UNUSED(i) .word lc823450_reserved
#include "lc823450_vectors.h"
.size _vectors, .-_vectors
/*****************************************************************************
* .text
****************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER lc823450_reserved, LC823450_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER lc823450_nmi, LC823450_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER lc823450_hardfault, LC823450_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER lc823450_mpu, LC823450_IRQ_MEMFAULT /* Vector 4: Memory management (MPU) */
HANDLER lc823450_busfault, LC823450_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER lc823450_usagefault, LC823450_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER lc823450_svcall, LC823450_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER lc823450_dbgmonitor, LC823450_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER lc823450_pendsv, LC823450_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER lc823450_systick, LC823450_IRQ_SYSTICK /* Vector 15: System tick */
#undef VECTOR
#define VECTOR(l,i) HANDLER l, i
#undef UNUSED
#define UNUSED(i)
#include "lc823450_vectors.h"
/* Common IRQ handling logic. On entry here, the return stack is on either
* the PSP or the MSP and looks 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
* R14 Contains the EXC_RETURN value
* We are in handler mode and the current SP is the MSP
*/
.globl exception_common
.type exception_common, function
exception_common:
/* Complete the context save */
#ifdef CONFIG_BUILD_PROTECTED
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the stack is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
tst r14, #EXC_RETURN_PROCESS_STACK /* nonzero if context on process stack */
beq 1f /* Branch if context already on the MSP */
mrs r1, psp /* R1=The process stack pointer (PSP) */
mov sp, r1 /* Set the MSP to the PSP */
1:
#endif
/* r1 holds the value of the stack pointer AFTER the exception handling logic
* pushed the various registers onto the stack. Get r2 = the value of the
* stack pointer BEFORE the interrupt modified it.
*/
mov r2, sp /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
#ifdef CONFIG_ARMV7M_USEBASEPRI
mrs r3, basepri /* R3=Current BASEPRI setting */
#else
mrs r3, primask /* R3=Current PRIMASK setting */
#endif
/* Save the remaining registers on the stack after the registers pushed
* by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11,
* r14=register values.
*/
#ifdef CONFIG_BUILD_PROTECTED
stmdb sp!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
stmdb sp!, {r2-r11} /* Save the remaining registers plus the SP value */
#endif
#ifndef CONFIG_ARCH_HIPRI_INTERRUPT
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
#else
/* Set the BASEPRI register so that further normal interrupts will be
* masked. Nested, high priority may still occur, however.
*/
mov r2, #NVIC_SYSH_DISABLE_PRIORITY
msr basepri, r2 /* Set the BASEPRI */
#endif
/* There are two arguments to up_doirq:
*
* R0 = The IRQ number
* R1 = The top of the stack points to the saved state
*/
mov r1, sp
/* Also save the top of the stack in a preserved register */
mov r4, sp
#if CONFIG_ARCH_INTERRUPTSTACK > 7
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will set the MSP to use
* a special special interrupt stack pointer. The way that this is done
* here prohibits nested interrupts without some additional logic!
*/
ldr sp, =g_intstackbase
#ifdef CONFIG_SMP
ldr r2, coreid_reg
ldr r2, [r2, 0] /* r2 = getreg32(coreid_reg) */
and r2, r2, 1 /* r2 = COREID */
cmp r2, #0
beq after_setstack
ldr sp, =g_intstackbase2
after_setstack:
#endif /* CONFIG_SMP */
#else
/* Otherwise, we will re-use the interrupted thread's stack. That may
* mean using either MSP or PSP stack for interrupt level processing (in
* kernel mode).
*/
bic r2, r4, #7 /* Get the stack pointer with 8-byte alignment */
mov sp, r2 /* Instantiate the aligned stack */
#endif
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, r4 /* Recover R1=main stack pointer */
/* 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 2f /* 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 in the
* stack but, rather, 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 */
#ifdef CONFIG_BUILD_PROTECTED
ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
b 3f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*
* Here:
* r1 = Address of the return stack (same as r0)
*/
2:
#ifdef CONFIG_BUILD_PROTECTED
ldmia r1!, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
/* Set up to return from the exception
*
* Here:
* r1 = Address on the target thread's stack position at the start of
* the registers saved by hardware
* r3 = primask or basepri
* r4-r11 = restored register values
*/
3:
#ifdef CONFIG_BUILD_PROTECTED
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the stack is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
mrs r2, control /* R2=Contents of the control register */
tst r14, #EXC_RETURN_PROCESS_STACK /* nonzero if context on process stack */
beq 4f /* Branch if privileged */
orr r2, r2, #1 /* Unprivileged mode */
msr psp, r1 /* R1=The process stack pointer */
b 5f
4:
bic r2, r2, #1 /* Privileged mode */
msr msp, r1 /* R1=The main stack pointer */
5:
msr control, r2 /* Save the updated control register */
#else
msr msp, r1 /* Recover the return MSP value */
/* Preload r14 with the special return value first (so that the return
* actually occurs with interrupts still disabled).
*/
ldr r14, =EXC_RETURN_PRIVTHR /* Load the special value */
#endif
/* Restore the interrupt state */
#ifdef CONFIG_ARMV7M_USEBASEPRI
msr basepri, r3 /* Restore interrupts priority masking */
#ifndef CONFIG_ARCH_HIPRI_INTERRUPT
cpsie i /* Re-enable interrupts */
#endif
#else
msr primask, r3 /* Restore interrupts */
#endif
/* 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 */
#ifdef CONFIG_SMP
coreid_reg:
.word 0xe00fe000
#endif /* CONFIG_SMP */
.size handlers, .-handlers
/*****************************************************************************
* Name: g_intstackalloc/g_intstackbase
*
* Description:
* Shouldn't happen
*
****************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 7
.bss
.global g_intstackalloc
.global g_intstackbase
.align 8
g_intstackalloc:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~7)
g_intstackbase:
.size g_intstackalloc, .-g_intstackalloc
#ifdef CONFIG_SMP
.bss
.global g_intstackalloc2
.global g_intstackbase2
.align 8
g_intstackalloc2:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~7)
g_intstackbase2:
.size g_intstackalloc2, .-g_intstackalloc2
#endif /* CONFIG_SMP */
#endif /* CONFIG_ARCH_INTERRUPTSTACK */
#endif /* CONFIG_ARMV7M_CMNVECTOR */
/*****************************************************************************
* .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_idle_topstack below.
*/
.globl g_idle_topstack
.type g_idle_topstack, object
g_idle_topstack:
.word HEAP_BASE
.size g_idle_topstack, .-g_idle_topstack
.end

View File

@ -1,126 +0,0 @@
/****************************************************************************
* arch/arm/src/lc823450/chip/lc823450_vectors.h
*
* Copyright 2014,2017 Sony Video & Sound Products Inc.
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
*
* 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.
*
****************************************************************************/
/****************************************************************************
* Pre-processor definitions
****************************************************************************/
/* This file is included by lc823450_vectors.S. It provides the macro VECTOR
* that supplies a LC823450 vector in terms of a (lower-case) ISR label and
* an (upper-case) IRQ number as defined in arch/arm/include/lc823450/irq.h.
* lc823450_vectors.S will defined the VECTOR in different ways in order to
* generate the interrupt vectors and handlers in their final form.
*/
/* If the common ARMv7-M vector handling is used, then all it needs is the
* following definition that provides the number of supported vectors.
*/
#ifdef CONFIG_ARMV7M_CMNVECTOR
/* Reserve interrupt table entries for I/O interrupts. */
# define ARMV7M_PERIPHERAL_INTERRUPTS 82
#else
VECTOR(lc823450_ctxm3_00, LC823450_IRQ_CTXM3_00) /* Vector 16+0: CortexM3_00 interrupt */
VECTOR(lc823450_ctxm3_01, LC823450_IRQ_CTXM3_01) /* Vector 16+1: CortexM3_01 interrupt */
VECTOR(lc823450_ctxm3_02, LC823450_IRQ_CTXM3_02) /* Vector 16+2: CortexM3_02 interrupt */
VECTOR(lc823450_ctxm3_03, LC823450_IRQ_CTXM3_03) /* Vector 16+3: CortexM3_03 interrupt */
VECTOR(lc823450_ctxm3_10, LC823450_IRQ_CTXM3_10) /* Vector 16+4: CortexM3_00 interrupt */
VECTOR(lc823450_ctxm3_11, LC823450_IRQ_CTXM3_11) /* Vector 16+5: CortexM3_01 interrupt */
VECTOR(lc823450_ctxm3_12, LC823450_IRQ_CTXM3_12) /* Vector 16+6: CortexM3_02 interrupt */
VECTOR(lc823450_ctxm3_13, LC823450_IRQ_CTXM3_13) /* Vector 16+7: CortexM3_03 interrupt */
VECTOR(lc823450_lpdsp0, LC823450_IRQ_LPDSP0) /* Vector 16+8: LPDSP0 interrupt */
VECTOR(lc823450_lpdsp1, LC823450_IRQ_LPDSP1) /* Vector 16+9: LPDSP1 interrupt */
VECTOR(lc823450_lpdsp2, LC823450_IRQ_LPDSP2) /* Vector 16+10: LPDSP2 interrupt */
VECTOR(lc823450_lpdsp3, LC823450_IRQ_LPDSP3) /* Vector 16+11: LPDSP3 interrupt */
VECTOR(lc823450_wdt0, LC823450_IRQ_WDT0) /* Vector 16+12: WatchDogTimer0 interrupt */
VECTOR(lc823450_wdt1, LC823450_IRQ_WDT1) /* Vector 16+13: WatchDogTimer1 interrupt */
VECTOR(lc823450_wdt2, LC823450_IRQ_WDT2) /* Vector 16+14: WatchDogTimer2 interrupt */
VECTOR(lc823450_btimer0, LC823450_IRQ_BTIMER0) /* Vector 16+15: BasicTimer0 interrupt */
VECTOR(lc823450_btimer1, LC823450_IRQ_BTIMER1) /* Vector 16+16: BasicTimer0 interrupt */
VECTOR(lc823450_btimer2, LC823450_IRQ_BTIMER2) /* Vector 16+17: BasicTimer0 interrupt */
VECTOR(lc823450_mtimer00, LC823450_IRQ_MTIMER00) /* Vector 16+18: MultipleTimer00 interrupt */
VECTOR(lc823450_mtimer01, LC823450_IRQ_MTIMER01) /* Vector 16+19: MultipleTimer01 interrupt */
VECTOR(lc823450_mtimer10, LC823450_IRQ_MTIMER10) /* Vector 16+20: MultipleTimer10 interrupt */
VECTOR(lc823450_mtimer11, LC823450_IRQ_MTIMER11) /* Vector 16+21: MultipleTimer11 interrupt */
VECTOR(lc823450_mtimer20, LC823450_IRQ_MTIMER20) /* Vector 16+22: MultipleTimer20 interrupt */
VECTOR(lc823450_mtimer21, LC823450_IRQ_MTIMER21) /* Vector 16+23: MultipleTimer21 interrupt */
VECTOR(lc823450_mtimer30, LC823450_IRQ_MTIMER30) /* Vector 16+24: MultipleTimer30 interrupt */
VECTOR(lc823450_mtimer31, LC823450_IRQ_MTIMER31) /* Vector 16+25: MultipleTimer31 interrupt */
VECTOR(lc823450_ehci, LC823450_IRQ_EHCI) /* Vector 16+26: USB HOST EHCI interrupt */
VECTOR(lc823450_ohci, LC823450_IRQ_OHCI) /* Vector 16+27: USB HOST OHCI interrupt */
VECTOR(lc823450_serflash, LC823450_IRQ_SERFLASH) /* Vector 16+28: USB HOST OHCI interrupt */
VECTOR(lc823450_dmac, LC823450_IRQ_DMAC) /* Vector 16+29: DMA Controller interrupt */
VECTOR(lc823450_sdcsync0, LC823450_IRQ_SDCSYNC0) /* Vector 16+30: SDCardSync0 interrupt */
VECTOR(lc823450_sdcsync1, LC823450_IRQ_SDCSYNC1) /* Vector 16+31: SDCardSync1 interrupt */
VECTOR(lc823450_sdcsync2, LC823450_IRQ_SDCSYNC2) /* Vector 16+32: SDCardSync2 interrupt */
VECTOR(lc823450_sdcasync0, LC823450_IRQ_SDCASYNC0) /* Vector 16+33: SDCardAsync0 interrupt */
VECTOR(lc823450_sdcasync1, LC823450_IRQ_SDCASYNC1) /* Vector 16+34: SDCardAsync1 interrupt */
VECTOR(lc823450_sdcasync2, LC823450_IRQ_SDCASYNC2) /* Vector 16+35: SDCardAsync2 interrupt */
VECTOR(lc823450_memstick, LC823450_IRQ_MEMSTICK) /* Vector 16+36: MemoryStick interrupt */
VECTOR(lc823450_memstickins, LC823450_IRQ_MEMSTICKINS) /* Vector 16+37: MemoryStick ins interrupt */
VECTOR(lc823450_dspcmd, LC823450_IRQ_DSPCMD) /* Vector 16+38: DSP cmd interface interrupt */
VECTOR(lc823450_adc, LC823450_IRQ_ADC) /* Vector 16+39: AD Converter interrupt */
VECTOR(lc823450_sio, LC823450_IRQ_SIO) /* Vector 16+40: SIO interrupt */
VECTOR(lc823450_i2c0, LC823450_IRQ_I2C0) /* Vector 16+41: I2C0 interrupt */
VECTOR(lc823450_i2c1, LC823450_IRQ_I2C1) /* Vector 16+42: I2C1 interrupt */
VECTOR(lc823450_uart0, LC823450_IRQ_UART0) /* Vector 16+43: UART0 interrupt */
VECTOR(lc823450_uart1, LC823450_IRQ_UART1) /* Vector 16+44: UART1 interrupt */
VECTOR(lc823450_uart2, LC823450_IRQ_UART2) /* Vector 16+45: UART2 interrupt */
VECTOR(lc823450_rtc, LC823450_IRQ_RTC) /* Vector 16+46: RTC interrupt */
VECTOR(lc823450_rtckey, LC823450_IRQ_RTCKEY) /* Vector 16+47: RTCKEY interrupt */
VECTOR(lc823450_audiobuf0, LC823450_IRQ_AUDIOBUF0) /* Vector 16+48: AudioBuffer0 interrupt */
VECTOR(lc823450_audiobuf1, LC823450_IRQ_AUDIOBUF1) /* Vector 16+49: AudioBuffer1 interrupt */
VECTOR(lc823450_audiobuf2, LC823450_IRQ_AUDIOBUF2) /* Vector 16+50: AudioBuffer2 interrupt */
VECTOR(lc823450_audiobuf3, LC823450_IRQ_AUDIOBUF3) /* Vector 16+51: AudioBuffer3 interrupt */
VECTOR(lc823450_audiostat0, LC823450_IRQ_AUDIOSTAT0) /* Vector 16+52: AudioStatus0 interrupt */
VECTOR(lc823450_audiostat1, LC823450_IRQ_AUDIOSTAT1) /* Vector 16+53: AudioStatus1 interrupt */
VECTOR(lc823450_audiostat2, LC823450_IRQ_AUDIOSTAT2) /* Vector 16+54: AudioStatus2 interrupt */
VECTOR(lc823450_audiostat3, LC823450_IRQ_AUDIOSTAT3) /* Vector 16+55: AudioStatus3 interrupt */
VECTOR(lc823450_audiotm0, LC823450_IRQ_AUDIOTM0) /* Vector 16+56: AudioTimer0 interrupt */
VECTOR(lc823450_audiotm1, LC823450_IRQ_AUDIOTM1) /* Vector 16+57: AudioTimer1 interrupt */
VECTOR(lc823450_usbdev, LC823450_IRQ_USBDEV) /* Vector 16+58: USB Device interrupt */
VECTOR(lc823450_extint0, LC823450_IRQ_EXTINT0) /* Vector 16+59: ExternalINT0 interrupt */
VECTOR(lc823450_extint1, LC823450_IRQ_EXTINT1) /* Vector 16+60: ExternalINT1 interrupt */
VECTOR(lc823450_extint2, LC823450_IRQ_EXTINT2) /* Vector 16+61: ExternalINT2 interrupt */
VECTOR(lc823450_extint3, LC823450_IRQ_EXTINT3) /* Vector 16+62: ExternalINT3 interrupt */
VECTOR(lc823450_extint4, LC823450_IRQ_EXTINT4) /* Vector 16+63: ExternalINT4 interrupt */
VECTOR(lc823450_extint5, LC823450_IRQ_EXTINT5) /* Vector 16+64: ExternalINT5 interrupt */
#endif /* CONFIG_ARMV7M_CMNVECTOR */

View File

@ -42,6 +42,7 @@ MEMORY
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
SECTIONS
{

View File

@ -41,6 +41,7 @@ MEMORY
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
SECTIONS
{