forked from Archive/PX4-Autopilot
Drop these; they should not have been added.
This commit is contained in:
parent
8a8b6b7165
commit
12b3a39e39
|
@ -1,451 +0,0 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/arm/arm.h
|
||||
*
|
||||
* Copyright (C) 2007-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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_COMMON_ARM_H
|
||||
#define __ARCH_ARM_SRC_COMMON_ARM_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
#undef CONFIG_ALIGNMENT_TRAP
|
||||
#undef CONFIG_DCACHE_WRITETHROUGH
|
||||
#undef CONFIG_CACHE_ROUND_ROBIN
|
||||
#undef CONFIG_DCACHE_DISABLE
|
||||
#undef CONFIG_ICACHE_DISABLE
|
||||
|
||||
/* ARM9EJS **************************************************************************/
|
||||
|
||||
/* PSR bits */
|
||||
|
||||
#define MODE_MASK 0x0000001f /* Bits 0-4: Mode bits */
|
||||
# define USR26_MODE 0x00000000 /* 26-bit User mode */
|
||||
# define FIQ26_MODE 0x00000001 /* 26-bit FIQ mode */
|
||||
# define IRQ26_MODE 0x00000002 /* 26-bit IRQ mode */
|
||||
# define SVC26_MODE 0x00000003 /* 26-bit Supervisor mode */
|
||||
# define MODE32_BIT 0x00000010 /* Bit 4: 32-bit mode */
|
||||
# define USR_MODE 0x00000010 /* 32-bit User mode */
|
||||
# define FIQ_MODE 0x00000011 /* 32-bit FIQ mode */
|
||||
# define IRQ_MODE 0x00000012 /* 32-bit IRQ mode */
|
||||
# define SVC_MODE 0x00000013 /* 32-bit Supervisor mode */
|
||||
# define ABT_MODE 0x00000017 /* 32-bit Abort mode */
|
||||
# define UND_MODE 0x0000001b /* 32-bit Undefined mode */
|
||||
# define SYSTEM_MODE 0x0000001f /* 32-bit System mode */
|
||||
#define PSR_T_BIT 0x00000020 /* Bit 5: Thumb state */
|
||||
#define PSR_F_BIT 0x00000040 /* Bit 6: FIQ disable */
|
||||
#define PSR_I_BIT 0x00000080 /* Bit 7: IRQ disable */
|
||||
/* Bits 8-23: Reserved */
|
||||
#define PSR_J_BIT 0x01000000 /* Bit 24: Jazelle state bit */
|
||||
/* Bits 25-26: Reserved */
|
||||
#define PSR_Q_BIT 0x08000000 /* Bit 27: Sticky overflow */
|
||||
#define PSR_V_BIT 0x10000000 /* Bit 28: Overflow */
|
||||
#define PSR_C_BIT 0x20000000 /* Bit 29: Carry/Borrow/Extend */
|
||||
#define PSR_Z_BIT 0x40000000 /* Bit 30: Zero */
|
||||
#define PSR_N_BIT 0x80000000 /* Bit 31: Negative/Less than */
|
||||
|
||||
/* CR1 bits (CP#15 CR1) */
|
||||
|
||||
#define CR_M 0x00000001 /* MMU enable */
|
||||
#define CR_A 0x00000002 /* Alignment abort enable */
|
||||
#define CR_C 0x00000004 /* Dcache enable */
|
||||
#define CR_W 0x00000008 /* Write buffer enable */
|
||||
#define CR_P 0x00000010 /* 32-bit exception handler */
|
||||
#define CR_D 0x00000020 /* 32-bit data address range */
|
||||
#define CR_L 0x00000040 /* Implementation defined */
|
||||
#define CR_B 0x00000080 /* Big endian */
|
||||
#define CR_S 0x00000100 /* System MMU protection */
|
||||
#define CR_R 0x00000200 /* ROM MMU protection */
|
||||
#define CR_F 0x00000400 /* Implementation defined */
|
||||
#define CR_Z 0x00000800 /* Implementation defined */
|
||||
#define CR_I 0x00001000 /* Icache enable */
|
||||
#define CR_V 0x00002000 /* Vectors relocated to 0xffff0000 */
|
||||
#define CR_RR 0x00004000 /* Round Robin cache replacement */
|
||||
#define CR_L4 0x00008000 /* LDR pc can set T bit */
|
||||
#define CR_DT 0x00010000
|
||||
#define CR_IT 0x00040000
|
||||
#define CR_ST 0x00080000
|
||||
#define CR_FI 0x00200000 /* Fast interrupt (lower latency mode) */
|
||||
#define CR_U 0x00400000 /* Unaligned access operation */
|
||||
#define CR_XP 0x00800000 /* Extended page tables */
|
||||
#define CR_VE 0x01000000 /* Vectored interrupts */
|
||||
|
||||
/* The lowest 4-bits of the FSR register indicates the fault generated by
|
||||
* the MMU.
|
||||
*/
|
||||
|
||||
#define FSR_MASK 15 /* Bits 0-3: Type of fault */
|
||||
#define FSR_VECTOR 0 /* Vector exception */
|
||||
#define FSR_ALIGN1 1 /* Alignment fault */
|
||||
#define FSR_TERMINAL 2 /* Terminal exception */
|
||||
#define FSR_ALIGN2 3 /* Alignment fault */
|
||||
#define FSR_LINESECT 4 /* External abort on linefetch for section translation */
|
||||
#define FSR_SECT 5 /* Section translation fault (unmapped virtual address) */
|
||||
#define FSR_LINEPAGE 6 /* External abort on linefetch for page translation */
|
||||
#define FSR_PAGE 7 /* Page translation fault (unmapped virtual address) */
|
||||
#define FSR_NLINESECT 8 /* External abort on non-linefetch for section translation */
|
||||
#define FSR_DOMSECT 9 /* Domain fault on section translation (i.e. accessing invalid domain) */
|
||||
#define FSR_NLINEPAGE 10 /* External abort on non-linefetch for page translation */
|
||||
#define FSR_DOMPAGE 11 /* Domain fault on page translation (i.e. accessing invalid domain) */
|
||||
#define FSR_EXTERN1 12 /* External abort on first level translation */
|
||||
#define FSR_PERMSECT 13 /* Permission fault on section (i.e. no permission to access virtual address) */
|
||||
#define FSR_EXTERN2 14 /* External abort on second level translation */
|
||||
#define FSR_PERMPAGE 15 /* Permission fault on page (i.e. no permission to access virtual address) */
|
||||
|
||||
#define FSR_DOM_SHIFT 4 /* Bits 4-7: Domain */
|
||||
#define FSR_DOM_MASK (15 << FSR_DOM_SHIFT)
|
||||
|
||||
/* Hardware page table definitions.
|
||||
*
|
||||
* Level 1 Descriptor (PMD)
|
||||
*
|
||||
* Common definitions.
|
||||
*/
|
||||
|
||||
#define PMD_TYPE_MASK 0x00000003 /* Bits 1:0: Type of descriptor */
|
||||
#define PMD_TYPE_FAULT 0x00000000
|
||||
#define PMD_TYPE_COARSE 0x00000001
|
||||
#define PMD_TYPE_SECT 0x00000002
|
||||
#define PMD_TYPE_FINE 0x00000003
|
||||
/* Bits 3:2: Depends on descriptor */
|
||||
#define PMD_BIT4 0x00000010 /* Bit 4: Must be one */
|
||||
#define PMD_DOMAIN_MASK 0x000001e0 /* Bits 8:5: Domain control bits */
|
||||
#define PMD_DOMAIN(x) ((x) << 5)
|
||||
#define PMD_PROTECTION 0x00000200 /* Bit 9: v5 only */
|
||||
/* Bits 31:10: Depend on descriptor */
|
||||
|
||||
/* Level 1 Section Descriptor. Section descriptors allow fast, single
|
||||
* level mapping between 1Mb address regions.
|
||||
*/
|
||||
/* Bits 1:0: Type of mapping */
|
||||
#define PMD_SECT_BUFFERABLE 0x00000004 /* Bit 2: 1=bufferable */
|
||||
#define PMD_SECT_CACHEABLE 0x00000008 /* Bit 3: 1=cacheable */
|
||||
/* Bit 4: Common, must be one */
|
||||
/* Bits 8:5: Common domain control */
|
||||
/* Bit 9: Common protection */
|
||||
#define PMD_SECT_AP_MASK 0x00000c00 /* Bits 11:10: Access permission */
|
||||
#define PMD_SECT_AP_WRITE 0x00000400
|
||||
#define PMD_SECT_AP_READ 0x00000800
|
||||
/* Bits 19:20: Should be zero */
|
||||
#define PMD_SECT_TEX_MASK 0xfff00000 /* Bits 31:20: v5, Physical page */
|
||||
#define PMD_SECT_APX 0x00008000 /* Bit 15: v6 only */
|
||||
#define PMD_SECT_S 0x00010000 /* Bit 16: v6 only */
|
||||
#define PMD_SECT_nG 0x00020000 /* Bit 17: v6 only */
|
||||
|
||||
#define PMD_SECT_UNCACHED (0)
|
||||
#define PMD_SECT_BUFFERED (PMD_SECT_BUFFERABLE)
|
||||
#define PMD_SECT_WT (PMD_SECT_CACHEABLE)
|
||||
#define PMD_SECT_WB (PMD_SECT_CACHEABLE|PMD_SECT_BUFFERABLE)
|
||||
#define PMD_SECT_MINICACHE (PMD_SECT_TEX(1)|PMD_SECT_CACHEABLE)
|
||||
#define PMD_SECT_WBWA (PMD_SECT_TEX(1)|PMD_SECT_CACHEABLE|PMD_SECT_BUFFERABLE)
|
||||
|
||||
/* Level 1 Coarse Table Descriptor. Coarse Table Descriptors support
|
||||
* two level mapping between 16Kb memory regions.
|
||||
*/
|
||||
/* Bits 1:0: Type of mapping */
|
||||
/* Bits 3:2: Should be zero */
|
||||
/* Bit 4: Common, must be one */
|
||||
/* Bits 8:5: Common domain control */
|
||||
/* Bits 9: Should be zero */
|
||||
#define PMD_COARSE_TEX_MASK 0xfffffc00 /* Bits 31:10: v5, Physical page */
|
||||
|
||||
/* Level 1 Fine Table Descriptor. Coarse Table Descriptors support
|
||||
* two level mapping between 4Kb memory regions.
|
||||
*/
|
||||
|
||||
/* Bits 1:0: Type of mapping */
|
||||
/* Bits 3:2: Should be zero */
|
||||
/* Bit 4: Common, must be one */
|
||||
/* Bits 8:5: Common domain control */
|
||||
/* Bits 11:9: Should be zero */
|
||||
#define PMD_FINE_TEX_MASK 0xfffff000 /* Bits 31:12: v5, Physical page */
|
||||
|
||||
/* Level 2 Table Descriptor (PTE). A section descriptor provides the base address
|
||||
* of a 1MB block of memory. The page table descriptors provide the base address of
|
||||
* a page table that contains second-level descriptors. There are two sizes of page
|
||||
* table:
|
||||
* - Coarse page tables have 256 entries, splitting the 1MB that the table
|
||||
* describes into 4KB blocks
|
||||
* - Fine/tiny page tables have 1024 entries, splitting the 1MB that the table
|
||||
* describes into 1KB blocks.
|
||||
*
|
||||
* The following definitions apply to all L2 tables:
|
||||
*/
|
||||
|
||||
#define PTE_TYPE_MASK (3 << 0) /* Bits: 1:0: Type of mapping */
|
||||
#define PTE_TYPE_FAULT (0 << 0) /* None */
|
||||
#define PTE_TYPE_LARGE (1 << 0) /* 64Kb of memory */
|
||||
#define PTE_TYPE_SMALL (2 << 0) /* 4Kb of memory */
|
||||
#define PTE_TYPE_TINY (3 << 0) /* 1Kb of memory (v5)*/
|
||||
#define PTE_BUFFERABLE (1 << 2) /* Bit 2: 1=bufferable */
|
||||
#define PTE_CACHEABLE (1 << 3) /* Bit 3: 1=cacheable */
|
||||
/* Bits 31:4: Depend on type */
|
||||
|
||||
/* Large page -- 64Kb */
|
||||
/* Bits: 1:0: Type of mapping */
|
||||
/* Bits: 3:2: Bufferable/cacheable */
|
||||
#define PTE_LARGE_AP_MASK (0xff << 4) /* Bits 11:4 Access permissions */
|
||||
#define PTE_LARGE_AP_UNO_SRO (0x00 << 4)
|
||||
#define PTE_LARGE_AP_UNO_SRW (0x55 << 4)
|
||||
#define PTE_LARGE_AP_URO_SRW (0xaa << 4)
|
||||
#define PTE_LARGE_AP_URW_SRW (0xff << 4)
|
||||
/* Bits 15:12: Should be zero */
|
||||
#define PTE_LARGE_TEX_MASK 0xffff0000 /* Bits 31:16: v5, Physical page */
|
||||
|
||||
/* Small page -- 4Kb */
|
||||
|
||||
/* Bits: 1:0: Type of mapping */
|
||||
/* Bits: 3:2: Bufferable/cacheable */
|
||||
#define PTE_SMALL_AP_MASK (0xff << 4) /* Bits: 11:4: Access permissions */
|
||||
#define PTE_SMALL_AP_UNO_SRO (0x00 << 4)
|
||||
#define PTE_SMALL_AP_UNO_SRW (0x55 << 4)
|
||||
#define PTE_SMALL_AP_URO_SRW (0xaa << 4)
|
||||
#define PTE_SMALL_AP_URW_SRW (0xff << 4)
|
||||
#define PTE_SMALL_TEX_MASK 0xfffff000 /* Bits: 31:12: Physical page */
|
||||
|
||||
#define PTE_SMALL_NPAGES 256 /* 256 Coarse PTE's per section */
|
||||
|
||||
/* Fine/Tiny page -- 1Kb */
|
||||
|
||||
/* Bits: 1:0: Type of mapping */
|
||||
/* Bits: 3:2: Bufferable/cacheable */
|
||||
#define PTE_EXT_AP_MASK (3 << 4) /* Bits: 5:4: Access persions */
|
||||
#define PTE_EXT_AP_UNO_SRO (0 << 4)
|
||||
#define PTE_EXT_AP_UNO_SRW (1 << 4)
|
||||
#define PTE_EXT_AP_URO_SRW (2 << 4)
|
||||
#define PTE_EXT_AP_URW_SRW (3 << 4)
|
||||
/* Bits: 9:6: Should be zero */
|
||||
#define PTE_TINY_TEX_MASK 0xfffffc00 /* Bits: 31:10: Physical page */
|
||||
|
||||
#define PTE_TINY_NPAGES 1024 /* 1024 Tiny PTE's per section */
|
||||
|
||||
/* Default MMU flags for RAM memory, IO, vector region */
|
||||
|
||||
#define MMU_ROMFLAGS \
|
||||
(PMD_TYPE_SECT|PMD_BIT4|PMD_SECT_AP_READ)
|
||||
|
||||
#define MMU_MEMFLAGS \
|
||||
(PMD_TYPE_SECT|PMD_SECT_WB|PMD_BIT4|PMD_SECT_AP_WRITE|PMD_SECT_AP_READ)
|
||||
|
||||
#define MMU_IOFLAGS \
|
||||
(PMD_TYPE_SECT|PMD_BIT4|PMD_SECT_AP_WRITE|PMD_SECT_AP_READ)
|
||||
|
||||
#define MMU_L1_VECTORFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
|
||||
#define MMU_L2_VECTORFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW)
|
||||
|
||||
/* Mapped section size */
|
||||
|
||||
#define SECTION_SIZE (1 << 20) /* 1Mb */
|
||||
|
||||
/* CP15 register c2 contains a pointer to the base address of a paged table in
|
||||
* physical memory. Only bits 14-31 of the page table address is retained there;
|
||||
* The full 30-bit address is formed by ORing in bits 2-13 or the virtual address
|
||||
* (MVA). As a consequence, the page table must be aligned to a 16Kb address in
|
||||
* physical memory and could require up to 16Kb of memory.
|
||||
*/
|
||||
|
||||
#define PGTABLE_SIZE 0x00004000
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/* Get the current value of the CP15 C1 control register */
|
||||
|
||||
static inline unsigned int get_cp15c1(void)
|
||||
{
|
||||
unsigned int retval;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmrc p15, 0, %0, c1, c0"
|
||||
: "=r" (retval)
|
||||
:
|
||||
: "memory");
|
||||
return retval;
|
||||
}
|
||||
|
||||
/* Get the current value of the CP15 C2 page table pointer register */
|
||||
|
||||
static inline unsigned int get_cp15c2(void)
|
||||
{
|
||||
unsigned int retval;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmrc p15, 0, %0, c2, c0"
|
||||
: "=r" (retval)
|
||||
:
|
||||
: "memory");
|
||||
return retval;
|
||||
}
|
||||
/* Get the current value of the CP15 C3 domain access register */
|
||||
|
||||
static inline unsigned int get_cp15c3(void)
|
||||
{
|
||||
unsigned int retval;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmrc p15, 0, %0, c3, c0"
|
||||
: "=r" (retval)
|
||||
:
|
||||
: "memory");
|
||||
return retval;
|
||||
}
|
||||
|
||||
/* ARMv4/ARMv5 operation: Invalidate TLB
|
||||
* ARM926EJ-S operation: Invalidate set-associative
|
||||
* Data: Should be zero
|
||||
*/
|
||||
|
||||
static inline void tlb_invalidate(void)
|
||||
{
|
||||
unsigned int sbz = 0;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmcr p15, 0, %0, c8, c7, 0"
|
||||
:
|
||||
: "r" (sbz)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
/* ARMv4/ARMv5 operation: Invalidate TLB single entry (MVA)
|
||||
* ARM926EJ-S operation: Invalidate single entry
|
||||
* Data: MVA
|
||||
*/
|
||||
|
||||
static inline void tlb_invalidate_single(unsigned int mva)
|
||||
{
|
||||
mva &= 0xfffffc00;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"mcr p15, 0, %0, c8, c7, 1"
|
||||
:
|
||||
: "r" (mva)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
/* ARMv4/ARMv5 operation: Invalidate instruction TLB
|
||||
* ARM926EJ-S operation: Invalidate set-associative TLB
|
||||
* Data: Should be zero
|
||||
*/
|
||||
|
||||
static inline void tlb_instr_invalidate(void)
|
||||
{
|
||||
unsigned int sbz = 0;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmcr p15, 0, %0, c8, c5, 0"
|
||||
:
|
||||
: "r" (sbz)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
/* ARMv4/ARMv5 operation: Invalidate instruction TLB single entry (MVA)
|
||||
* ARM926EJ-S operation: Invalidate single entry
|
||||
* Data: MVA
|
||||
*/
|
||||
|
||||
static inline void tlb_inst_invalidate_single(unsigned int mva)
|
||||
{
|
||||
mva &= 0xfffffc00;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"mcr p15, 0, %0, c8, c5, 1"
|
||||
:
|
||||
: "r" (mva)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
/* ARMv4/ARMv5 operation: Invalidate data TLB
|
||||
* ARM926EJ-S operation: Invalidate set-associative TLB
|
||||
* Data: Should be zero
|
||||
*/
|
||||
|
||||
static inline void tlb_data_invalidate(void)
|
||||
{
|
||||
unsigned int sbz = 0;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmcr p15, 0, %0, c8, c6, 0"
|
||||
:
|
||||
: "r" (sbz)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
/* ARMv4/ARMv5 operation: Invalidate data TLB single entry (MVA)
|
||||
* ARM926EJ-S operation: Invalidate single entry
|
||||
* Data: MVA
|
||||
*/
|
||||
|
||||
static inline void tlb_data_invalidate_single(unsigned int mva)
|
||||
{
|
||||
mva &= 0xfffffc00;
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"mcr p15, 0, %0, c8, c6, 1"
|
||||
:
|
||||
: "r" (mva)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
/****************************************************************************
|
||||
* Public Variables
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_COMMON_ARM_H */
|
|
@ -1,522 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/pg_macros.h
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* Do not change this macro definition without making corresponding name
|
||||
* changes in other files. This macro name is used in various places to
|
||||
* assure that some file inclusion ordering dependencies are enforced.
|
||||
*/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_ARM_PG_MACROS_H
|
||||
#define __ARCH_ARM_SRC_ARM_PG_MACROS_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/page.h>
|
||||
|
||||
#include "arm.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
/* Sanity check -- we cannot be using a ROM page table and supporting on-
|
||||
* demand paging.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_ROMPGTABLE
|
||||
# error "Cannot support both CONFIG_PAGING and CONFIG_ARCH_ROMPGTABLE"
|
||||
#endif
|
||||
|
||||
/* Virtual Page Table Location **********************************************/
|
||||
|
||||
/* Check if the virtual address of the page table has been defined. It should
|
||||
* not be defined: architecture specific logic should suppress defining
|
||||
* PGTABLE_BASE_VADDR unless: (1) it is defined in the NuttX configuration
|
||||
* file, or (2) the page table is position in low memory (because the vectors
|
||||
* are in high memory).
|
||||
*/
|
||||
|
||||
#ifndef PGTABLE_BASE_VADDR
|
||||
# define PGTABLE_BASE_VADDR (PG_LOCKED_VBASE + PG_TEXT_VSIZE + PG_DATA_SIZE)
|
||||
|
||||
/* Virtual base of the address of the L2 page tables need to recalculates
|
||||
* using this new virtual base address of the L2 page table.
|
||||
*/
|
||||
|
||||
# undef PGTABLE_L2_FINE_VBASE
|
||||
# define PGTABLE_L2_FINE_VBASE (PGTABLE_BASE_VADDR+PGTABLE_L2_FINE_OFFSET)
|
||||
|
||||
# undef PGTABLE_L2_COARSE_VBASE
|
||||
# define PGTABLE_L2_COARSE_VBASE (PGTABLE_BASE_VADDR+PGTABLE_L2_COARSE_OFFSET)
|
||||
#endif
|
||||
|
||||
/* Page Size Selections *****************************************************/
|
||||
|
||||
/* Create some friendly definitions to handle some differences between
|
||||
* small and tiny pages.
|
||||
*/
|
||||
|
||||
#if CONFIG_PAGING_PAGESIZE == 1024
|
||||
|
||||
/* Base of the L2 page table (aligned to 4Kb byte boundaries) */
|
||||
|
||||
# define PGTABLE_L2_BASE_PADDR PGTABLE_L2_FINE_PBASE
|
||||
# define PGTABLE_L2_BASE_VADDR PGTABLE_L2_FINE_VBASE
|
||||
|
||||
/* Number of pages in an L2 table per L1 entry */
|
||||
|
||||
# define PTE_NPAGES PTE_TINY_NPAGES
|
||||
|
||||
/* Mask to get the page table physical address from an L1 entry */
|
||||
|
||||
# define PG_L1_PADDRMASK PMD_FINE_TEX_MASK
|
||||
|
||||
/* MMU Flags for each memory region */
|
||||
|
||||
# define MMU_L1_TEXTFLAGS (PMD_TYPE_FINE|PMD_BIT4)
|
||||
# define MMU_L2_TEXTFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRO|PTE_CACHEABLE)
|
||||
# define MMU_L1_DATAFLAGS (PMD_TYPE_FINE|PMD_BIT4)
|
||||
# define MMU_L2_DATAFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW|PTE_CACHEABLE|PTE_BUFFERABLE)
|
||||
# define MMU_L2_ALLOCFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW)
|
||||
# define MMU_L1_PGTABFLAGS (PMD_TYPE_FINE|PMD_BIT4)
|
||||
# define MMU_L2_PGTABFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW)
|
||||
|
||||
# define MMU_L2_VECTRWFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRW)
|
||||
# define MMU_L2_VECTROFLAGS (PTE_TYPE_TINY|PTE_EXT_AP_UNO_SRO|PTE_CACHEABLE)
|
||||
|
||||
#elif CONFIG_PAGING_PAGESIZE == 4096
|
||||
|
||||
/* Base of the L2 page table (aligned to 1Kb byte boundaries) */
|
||||
|
||||
# define PGTABLE_L2_BASE_PADDR PGTABLE_L2_COARSE_PBASE
|
||||
# define PGTABLE_L2_BASE_VADDR PGTABLE_L2_COARSE_VBASE
|
||||
|
||||
/* Number of pages in an L2 table per L1 entry */
|
||||
|
||||
# define PTE_NPAGES PTE_SMALL_NPAGES
|
||||
|
||||
/* Mask to get the page table physical address from an L1 entry */
|
||||
|
||||
# define PG_L1_PADDRMASK PMD_COARSE_TEX_MASK
|
||||
|
||||
/* MMU Flags for each memory region. */
|
||||
|
||||
# define MMU_L1_TEXTFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
|
||||
# define MMU_L2_TEXTFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRO|PTE_CACHEABLE)
|
||||
# define MMU_L1_DATAFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
|
||||
# define MMU_L2_DATAFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW|PTE_CACHEABLE|PTE_BUFFERABLE)
|
||||
# define MMU_L2_ALLOCFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW)
|
||||
# define MMU_L1_PGTABFLAGS (PMD_TYPE_COARSE|PMD_BIT4)
|
||||
# define MMU_L2_PGTABFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW)
|
||||
|
||||
# define MMU_L2_VECTRWFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRW)
|
||||
# define MMU_L2_VECTROFLAGS (PTE_TYPE_SMALL|PTE_SMALL_AP_UNO_SRO|PTE_CACHEABLE)
|
||||
|
||||
#else
|
||||
# error "Need extended definitions for CONFIG_PAGING_PAGESIZE"
|
||||
#endif
|
||||
|
||||
#define PT_SIZE (4*PTE_NPAGES)
|
||||
|
||||
/* Addresses of Memory Regions **********************************************/
|
||||
|
||||
/* We position the locked region PTEs at an offset into the first
|
||||
* L2 page table. The L1 entry points to an 1Mb aligned virtual
|
||||
* address. The actual L2 entry will be offset into the aligned
|
||||
* L2 table.
|
||||
*
|
||||
* Coarse: PG_L1_PADDRMASK=0xfffffc00
|
||||
* OFFSET=(((a) & 0x000fffff) >> 12) << 2)
|
||||
* Fine: PG_L1_PADDRMASK=0xfffff000
|
||||
* OFFSET=(((a) & 0x000fffff) >> 10) << 2)
|
||||
*/
|
||||
|
||||
#define PG_L1_LOCKED_PADDR (PGTABLE_BASE_PADDR + ((PG_LOCKED_VBASE >> 20) << 2))
|
||||
#define PG_L1_LOCKED_VADDR (PGTABLE_BASE_VADDR + ((PG_LOCKED_VBASE >> 20) << 2))
|
||||
|
||||
#define PG_L2_LOCKED_OFFSET (((PG_LOCKED_VBASE & 0x000fffff) >> PAGESHIFT) << 2)
|
||||
#define PG_L2_LOCKED_PADDR (PGTABLE_L2_BASE_PADDR + PG_L2_LOCKED_OFFSET)
|
||||
#define PG_L2_LOCKED_VADDR (PGTABLE_L2_BASE_VADDR + PG_L2_LOCKED_OFFSET)
|
||||
#define PG_L2_LOCKED_SIZE (4*CONFIG_PAGING_NLOCKED)
|
||||
|
||||
/* We position the paged region PTEs immediately after the locked
|
||||
* region PTEs. NOTE that the size of the paged regions is much
|
||||
* larger than the size of the physical paged region. That is the
|
||||
* core of what the On-Demanding Paging feature provides.
|
||||
*/
|
||||
|
||||
#define PG_L1_PAGED_PADDR (PGTABLE_BASE_PADDR + ((PG_PAGED_VBASE >> 20) << 2))
|
||||
#define PG_L1_PAGED_VADDR (PGTABLE_BASE_VADDR + ((PG_PAGED_VBASE >> 20) << 2))
|
||||
|
||||
#define PG_L2_PAGED_PADDR (PG_L2_LOCKED_PADDR + PG_L2_LOCKED_SIZE)
|
||||
#define PG_L2_PAGED_VADDR (PG_L2_LOCKED_VADDR + PG_L2_LOCKED_SIZE)
|
||||
#define PG_L2_PAGED_SIZE (4*CONFIG_PAGING_NVPAGED)
|
||||
|
||||
/* This describes the overall text region */
|
||||
|
||||
#define PG_L1_TEXT_PADDR PG_L1_LOCKED_PADDR
|
||||
#define PG_L1_TEXT_VADDR PG_L1_LOCKED_VADDR
|
||||
|
||||
#define PG_L2_TEXT_PADDR PG_L2_LOCKED_PADDR
|
||||
#define PG_L2_TEXT_VADDR PG_L2_LOCKED_VADDR
|
||||
#define PG_L2_TEXT_SIZE (PG_L2_LOCKED_SIZE + PG_L2_PAGED_SIZE)
|
||||
|
||||
/* We position the data section PTEs just after the text region PTE's */
|
||||
|
||||
#define PG_L1_DATA_PADDR (PGTABLE_BASE_PADDR + ((PG_DATA_VBASE >> 20) << 2))
|
||||
#define PG_L1_DATA_VADDR (PGTABLE_BASE_VADDR + ((PG_DATA_VBASE >> 20) << 2))
|
||||
|
||||
#define PG_L2_DATA_PADDR (PG_L2_LOCKED_PADDR + PG_L2_TEXT_SIZE)
|
||||
#define PG_L2_DATA_VADDR (PG_L2_LOCKED_VADDR + PG_L2_TEXT_SIZE)
|
||||
#define PG_L2_DATA_SIZE (4*PG_DATA_NPAGES)
|
||||
|
||||
/* Page Table Info **********************************************************/
|
||||
|
||||
/* The number of pages in the in the page table (PG_PGTABLE_NPAGES). We
|
||||
* position the pagetable PTEs just after the data section PTEs.
|
||||
*/
|
||||
|
||||
#define PG_PGTABLE_NPAGES (PGTABLE_SIZE >> PAGESHIFT)
|
||||
#define PG_L1_PGTABLE_PADDR (PGTABLE_BASE_PADDR + ((PGTABLE_BASE_VADDR >> 20) << 2))
|
||||
#define PG_L1_PGTABLE_VADDR (PGTABLE_BASE_VADDR + ((PGTABLE_BASE_VADDR >> 20) << 2))
|
||||
|
||||
#define PG_L2_PGTABLE_PADDR (PG_L2_DATA_PADDR + PG_L2_DATA_SIZE)
|
||||
#define PG_L2_PGTABLE_VADDR (PG_L2_DATA_VADDR + PG_L2_DATA_SIZE)
|
||||
#define PG_L2_PGTABLE_SIZE (4*PG_DATA_NPAGES)
|
||||
|
||||
/* Vector Mapping ***********************************************************/
|
||||
|
||||
/* One page is required to map the vector table. The vector table could lie
|
||||
* at virtual address zero (or at the start of RAM which is aliased to address
|
||||
* zero on the ea3131) or at virtual address 0xfff00000. We only have logic
|
||||
* here to support the former case.
|
||||
*
|
||||
* NOTE: If the vectors are at address zero, the page table will be
|
||||
* forced to the highest RAM addresses. If the vectors are at 0xfff0000,
|
||||
* then the page table is forced to the beginning of RAM.
|
||||
*
|
||||
* When the vectors are at the beginning of RAM, they will probably overlap
|
||||
* the first page of the locked text region. In any other case, the
|
||||
* configuration must set CONFIG_PAGING_VECPPAGE to provide the physical
|
||||
* address of the page to use for the vectors.
|
||||
*
|
||||
* When the vectors overlap the first page of the locked text region (the
|
||||
* only case in use so far), then the text page will be temporarily be made
|
||||
* writable in order to copy the vectors.
|
||||
*
|
||||
* PG_VECT_PBASE - This the physical address of the page in memory to be
|
||||
* mapped to the vector address.
|
||||
* PG_L2_VECT_PADDR - This is the physical address of the L2 page table
|
||||
* entry to use for the vector mapping.
|
||||
* PG_L2_VECT_VADDR - This is the virtual address of the L2 page table
|
||||
* entry to use for the vector mapping.
|
||||
*/
|
||||
|
||||
/* Case 1: The configuration tells us everything */
|
||||
|
||||
#if defined(CONFIG_PAGING_VECPPAGE)
|
||||
# define PG_VECT_PBASE CONFIG_PAGING_VECPPAGE
|
||||
# define PG_L2_VECT_PADDR CONFIG_PAGING_VECL2PADDR
|
||||
# define PG_L2_VECT_VADDR CONFIG_PAGING_VECL2VADDR
|
||||
|
||||
/* Case 2: Vectors are in low memory and the locked text region starts at
|
||||
* the beginning of SRAM (which will be aliased to address 0x00000000).
|
||||
* However, the beginning of SRAM may not be aligned to the beginning
|
||||
* of the L2 page table (because the beginning of RAM is offset into
|
||||
* the table.
|
||||
*/
|
||||
|
||||
#elif defined(CONFIG_ARCH_LOWVECTORS) && !defined(CONFIG_PAGING_LOCKED_PBASE)
|
||||
# define PG_VECT_PBASE PG_LOCKED_PBASE
|
||||
# define PG_L2_VECT_OFFSET (((PG_LOCKED_VBASE & 0x000fffff) >> PAGESHIFT) << 2)
|
||||
# define PG_L2_VECT_PADDR (PGTABLE_L2_BASE_PADDR + PG_L2_VECT_OFFSET)
|
||||
# define PG_L2_VECT_VADDR (PGTABLE_L2_BASE_VADDR + PG_L2_VECT_OFFSET)
|
||||
|
||||
/* Case 3: High vectors or the locked region is not at the beginning or SRAM */
|
||||
|
||||
#else
|
||||
# error "Logic missing for high vectors in this case"
|
||||
#endif
|
||||
|
||||
/* Page Usage ***************************************************************/
|
||||
|
||||
/* This is the total number of pages used in the text/data mapping: */
|
||||
|
||||
#define PG_TOTAL_NPPAGES (PG_TEXT_NPPAGES + PG_DATA_NPAGES + PG_PGTABLE_NPAGES)
|
||||
#define PG_TOTAL_NVPAGES (PG_TEXT_NVPAGES + PG_DATA_NPAGES + PG_PGTABLE_NPAGES)
|
||||
#define PG_TOTAL_PSIZE (PG_TOTAL_NPPAGES << PAGESHIFT)
|
||||
#define PG_TOTAL_VSIZE (PG_TOTAL_NVPAGES << PAGESHIFT)
|
||||
|
||||
/* Sanity check: */
|
||||
|
||||
#if PG_TOTAL_NPPAGES > PG_RAM_PAGES
|
||||
# error "Total pages required exceeds RAM size"
|
||||
#endif
|
||||
|
||||
/* Page Management **********************************************************/
|
||||
|
||||
/* For page managment purposes, the following summarize the "heap" of
|
||||
* free pages, operations on free pages and the L2 page table.
|
||||
*
|
||||
* PG_POOL_VA2L1OFFSET(va) - Given a virtual address, return the L1 table
|
||||
* offset (in bytes).
|
||||
* PG_POOL_VA2L1VADDR(va) - Given a virtual address, return the virtual
|
||||
* address of the L1 table entry
|
||||
* PG_POOL_L12PPTABLE(L1) - Given the value of an L1 table entry return
|
||||
* the physical address of the start of the L2
|
||||
* page table
|
||||
* PG_POOL_L12PPTABLE(L1) - Given the value of an L1 table entry return
|
||||
* the virtual address of the start of the L2
|
||||
* page table.
|
||||
*
|
||||
* PG_POOL_L1VBASE - The virtual address of the start of the L1
|
||||
* page table range corresponding to the first
|
||||
* virtual address of the paged text region.
|
||||
* PG_POOL_L1VEND - The virtual address of the end+1 of the L1
|
||||
* page table range corresponding to the last
|
||||
* virtual address+1 of the paged text region.
|
||||
*
|
||||
* PG_POOL_VA2L2NDX(va) - Converts a virtual address within the paged
|
||||
* text region to the most compact possible
|
||||
* representation. Each PAGESIZE of address
|
||||
* corresponds to 1 index in the L2 page table;
|
||||
* Index 0 corresponds to the first L2 page table
|
||||
* entry for the first page in the virtual paged
|
||||
* text address space.
|
||||
* PG_POOL_NDX2VA(ndx) - Performs the opposite conversion.. convests
|
||||
* an index into a virtual address in the paged
|
||||
* text region (the address at the beginning of
|
||||
* the page).
|
||||
* PG_POOL_MAXL2NDX - This is the maximum value+1 of such an index.
|
||||
*
|
||||
* PG_POOL_PGPADDR(ndx) - Converts an page index into the corresponding
|
||||
* (physical) address of the backing page memory.
|
||||
* PG_POOL_PGVADDR(ndx) - Converts an page index into the corresponding
|
||||
* (virtual)address of the backing page memory.
|
||||
*
|
||||
* These are used as follows: If a miss occurs at some virtual address, va,
|
||||
* A new page index, ndx, is allocated. PG_POOL_PGPADDR(i) converts the index
|
||||
* into the physical address of the page memory; PG_POOL_L2VADDR(va) converts
|
||||
* the virtual address in the L2 page table there the new mapping will be
|
||||
* written.
|
||||
*/
|
||||
|
||||
#define PG_POOL_VA2L1OFFSET(va) (((va) >> 20) << 2)
|
||||
#define PG_POOL_VA2L1VADDR(va) (PGTABLE_BASE_VADDR + PG_POOL_VA2L1OFFSET(va))
|
||||
#define PG_POOL_L12PPTABLE(L1) ((L1) & PG_L1_PADDRMASK)
|
||||
#define PG_POOL_L12VPTABLE(L1) (PG_POOL_L12PPTABLE(L1) - PGTABLE_BASE_PADDR + PGTABLE_BASE_VADDR)
|
||||
|
||||
#define PG_POOL_L1VBASE (PGTABLE_BASE_VADDR + ((PG_PAGED_VBASE >> 20) << 2))
|
||||
#define PG_POOL_L1VEND (PG_POOL_L1VBASE + (CONFIG_PAGING_NVPAGED << 2))
|
||||
|
||||
#define PG_POOL_VA2L2NDX(va) (((va) - PG_PAGED_VBASE) >> PAGESHIFT)
|
||||
#define PG_POOL_NDX2VA(ndx) (((ndx) << PAGESHIFT) + PG_PAGED_VBASE)
|
||||
#define PG_POOL_MAXL2NDX PG_POOL_VA2L2NDX(PG_PAGED_VEND)
|
||||
|
||||
#define PG_POOL_PGPADDR(ndx) (PG_PAGED_PBASE + ((ndx) << PAGESHIFT))
|
||||
#define PG_POOL_PGVADDR(ndx) (PG_PAGED_VBASE + ((ndx) << PAGESHIFT))
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
||||
|
||||
/****************************************************************************
|
||||
* Assembly Macros
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pg_l2map
|
||||
*
|
||||
* Description:
|
||||
* Write several, contiguous L2 page table entries. npages entries will be
|
||||
* written. This macro is used when CONFIG_PAGING is enable. This case,
|
||||
* it is used asfollows:
|
||||
*
|
||||
* ldr r0, =PGTABLE_L2_BASE_PADDR <-- Address in L2 table
|
||||
* ldr r1, =PG_LOCKED_PBASE <-- Physical page memory address
|
||||
* ldr r2, =CONFIG_PAGING_NLOCKED <-- number of pages
|
||||
* ldr r3, =MMUFLAGS <-- L2 MMU flags
|
||||
* pg_l2map r0, r1, r2, r3, r4
|
||||
*
|
||||
* Inputs:
|
||||
* l2 - Physical or virtual start address in the L2 page table, depending
|
||||
* upon the context. (modified)
|
||||
* ppage - The physical address of the start of the region to span. Must
|
||||
* be aligned to 1Mb section boundaries (modified)
|
||||
* npages - Number of pages to write in the section (modified)
|
||||
* mmuflags - L2 MMU FLAGS
|
||||
*
|
||||
* Scratch registers (modified): tmp
|
||||
* l2 - Next address in the L2 page table.
|
||||
* ppage - Start of next physical page
|
||||
* npages - Loop counter
|
||||
* tmp - scratch
|
||||
*
|
||||
* Assumptions:
|
||||
* - The MMU is not yet enabled
|
||||
* - The L2 page tables have been zeroed prior to calling this function
|
||||
* - pg_l1span has been called to initialize the L1 table.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
.macro pg_l2map, l2, ppage, npages, mmuflags, tmp
|
||||
b 2f
|
||||
1:
|
||||
/* Write the one L2 entries. First, get tmp = (ppage | mmuflags),
|
||||
* the value to write into the L2 PTE
|
||||
*/
|
||||
|
||||
orr \tmp, \ppage, \mmuflags
|
||||
|
||||
/* Write value into table at the current table address
|
||||
* (and increment the L2 page table address by 4)
|
||||
*/
|
||||
|
||||
str \tmp, [\l2], #4
|
||||
|
||||
/* Update the physical address that will correspond to the next
|
||||
* table entry.
|
||||
*/
|
||||
|
||||
add \ppage, \ppage, #CONFIG_PAGING_PAGESIZE
|
||||
|
||||
/* Decrement the number of pages written */
|
||||
|
||||
sub \npages, \npages, #1
|
||||
2:
|
||||
/* Check if all of the pages have been written. If not, then
|
||||
* loop and write the next PTE.
|
||||
*/
|
||||
cmp \npages, #0
|
||||
bgt 1b
|
||||
.endm
|
||||
#endif /* CONFIG_PAGING */
|
||||
|
||||
/****************************************************************************
|
||||
* Name: pg_l1span
|
||||
*
|
||||
* Description:
|
||||
* Write several, contiguous unmapped coarse L1 page table entries. As
|
||||
* many entries will be written as many as needed to span npages. This
|
||||
* macro is used when CONFIG_PAGING is enable. This case, it is used as
|
||||
* follows:
|
||||
*
|
||||
* ldr r0, =PG_L1_PGTABLE_PADDR <-- Address in the L1 table
|
||||
* ldr r1, =PG_L2_PGTABLE_PADDR <-- Physical address of L2 page table
|
||||
* ldr r2, =PG_PGTABLE_NPAGES <-- Total number of pages
|
||||
* ldr r3, =PG_PGTABLE_NPAGE1 <-- Number of pages in the first PTE
|
||||
* ldr r4, =MMU_L1_PGTABFLAGS <-- L1 MMU flags
|
||||
* pg_l1span r0, r1, r2, r3, r4, r4
|
||||
*
|
||||
* Inputs (unmodified unless noted):
|
||||
* l1 - Physical or virtual address in the L1 table to begin writing (modified)
|
||||
* l2 - Physical start address in the L2 page table (modified)
|
||||
* npages - Number of pages to required to span that memory region (modified)
|
||||
* ppage - The number of pages in page 1 (modified)
|
||||
* mmuflags - L1 MMU flags to use
|
||||
*
|
||||
* Scratch registers (modified): l1, l2, npages, tmp
|
||||
* l1 - Next L1 table address
|
||||
* l2 - Physical start address of the next L2 page table
|
||||
* npages - Loop counter
|
||||
* ppage - After the first page, this will be the full number of pages.
|
||||
* tmp - scratch
|
||||
*
|
||||
* Return:
|
||||
* Nothing of interest.
|
||||
*
|
||||
* Assumptions:
|
||||
* - The MMU is not yet enabled
|
||||
* - The L2 page tables have been zeroed prior to calling this function
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
.macro pg_l1span, l1, l2, npages, ppage, mmuflags, tmp
|
||||
b 2f
|
||||
1:
|
||||
/* Write the L1 table entry that refers to this (unmapped) coarse page
|
||||
* table.
|
||||
*
|
||||
* tmp = (l2table | mmuflags), the value to write into the page table
|
||||
*/
|
||||
|
||||
orr \tmp, \l2, \mmuflags
|
||||
|
||||
/* Write the value into the L1 table at the correct offset.
|
||||
* (and increment the L1 table address by 4)
|
||||
*/
|
||||
|
||||
str \tmp, [\l1], #4
|
||||
|
||||
/* Update the L2 page table address for the next L1 table entry. */
|
||||
|
||||
add \l2, \l2, #PT_SIZE /* Next L2 page table start address */
|
||||
|
||||
/* Update the number of pages that we have account for (with
|
||||
* non-mappings). NOTE that the first page may have fewer than
|
||||
* the maximum entries per page table.
|
||||
*/
|
||||
|
||||
sub \npages, \npages, \ppage
|
||||
mov \ppage, #PTE_NPAGES
|
||||
2:
|
||||
/* Check if all of the pages have been written. If not, then
|
||||
* loop and write the next L1 entry.
|
||||
*/
|
||||
|
||||
cmp \npages, #0
|
||||
bgt 1b
|
||||
.endm
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
/****************************************************************************
|
||||
* Inline Functions
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_ARM_SRC_ARM_PG_MACROS_H */
|
|
@ -1,243 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_allocpage.c
|
||||
* Allocate a new page and map it to the fault address of a task.
|
||||
*
|
||||
* 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/sched.h>
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
#include <nuttx/page.h>
|
||||
|
||||
#include "pg_macros.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
#if CONFIG_PAGING_NPPAGED < 256
|
||||
typedef uint8_t pgndx_t;
|
||||
#elif CONFIG_PAGING_NPPAGED < 65536
|
||||
typedef uint16_t pgndx_t;
|
||||
#else
|
||||
typedef uint32_t pgndx_t;
|
||||
#endif
|
||||
|
||||
#if PG_POOL_MAXL1NDX < 256
|
||||
typedef uint8_t L1ndx_t;
|
||||
#elif PG_POOL_MAXL1NDX < 65536
|
||||
typedef uint16_t L1ndx_t;
|
||||
#else
|
||||
typedef uint32_t L1ndx_t;
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/* Free pages in memory are managed by indices ranging from up to
|
||||
* CONFIG_PAGING_NPAGED. Initially all pages are free so the page can be
|
||||
* simply allocated in order: 0, 1, 2, ... . After all CONFIG_PAGING_NPAGED
|
||||
* pages have be filled, then they are blindly freed and re-used in the
|
||||
* same order 0, 1, 2, ... because we don't know any better. No smart "least
|
||||
* recently used" kind of logic is supported.
|
||||
*/
|
||||
|
||||
static pgndx_t g_pgndx;
|
||||
|
||||
/* After CONFIG_PAGING_NPAGED have been allocated, the pages will be re-used.
|
||||
* In order to re-used the page, we will have un-map the page from its previous
|
||||
* mapping. In order to that, we need to be able to map a physical address to
|
||||
* to an index into the PTE where it was mapped. The following table supports
|
||||
* this backward lookup - it is indexed by the page number index, and holds
|
||||
* another index to the mapped virtual page.
|
||||
*/
|
||||
|
||||
static L1ndx_t g_ptemap[CONFIG_PAGING_NPPAGED];
|
||||
|
||||
/* The contents of g_ptemap[] are not valid until g_pgndx has wrapped at
|
||||
* least one time.
|
||||
*/
|
||||
|
||||
static bool g_pgwrap;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_allocpage()
|
||||
*
|
||||
* Description:
|
||||
* This architecture-specific function will set aside page in memory and map
|
||||
* the page to its correct virtual address. Architecture-specific context
|
||||
* information saved within the TCB will provide the function with the
|
||||
* information needed to identify the virtual miss address.
|
||||
*
|
||||
* This function will return the allocated physical page address in vpage.
|
||||
* The size of the underlying physical page is determined by the
|
||||
* configuration setting CONFIG_PAGING_PAGESIZE.
|
||||
*
|
||||
* NOTE 1: This function must always return a page allocation. If all
|
||||
* available pages are in-use (the typical case), then this function will
|
||||
* select a page in-use, un-map it, and make it available.
|
||||
*
|
||||
* NOTE 2: If an in-use page is un-mapped, it may be necessary to flush the
|
||||
* instruction cache in some architectures.
|
||||
*
|
||||
* NOTE 3: Allocating and filling a page is a two step process. up_allocpage()
|
||||
* allocates the page, and up_fillpage() fills it with data from some non-
|
||||
* volatile storage device. This distinction is made because up_allocpage()
|
||||
* can probably be implemented in board-independent logic whereas up_fillpage()
|
||||
* probably must be implemented as board-specific logic.
|
||||
*
|
||||
* NOTE 4: The initial mapping of vpage should be read-able and write-
|
||||
* able (but not cached). No special actions will be required of
|
||||
* up_fillpage() in order to write into this allocated page.
|
||||
*
|
||||
* Input Parameters:
|
||||
* tcb - A reference to the task control block of the task that needs to
|
||||
* have a page fill. Architecture-specific logic can retrieve page
|
||||
* fault information from the architecture-specific context
|
||||
* information in this TCB to perform the mapping.
|
||||
*
|
||||
* Returned Value:
|
||||
* This function will return zero (OK) if the allocation was successful.
|
||||
* A negated errno value may be returned if an error occurs. All errors,
|
||||
* however, are fatal.
|
||||
*
|
||||
* Assumptions:
|
||||
* - This function is called from the normal tasking context (but with
|
||||
* interrupts disabled). The implementation must take whatever actions
|
||||
* are necessary to assure that the operation is safe within this
|
||||
* context.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int up_allocpage(FAR _TCB *tcb, FAR void **vpage)
|
||||
{
|
||||
uintptr_t vaddr;
|
||||
uintptr_t paddr;
|
||||
uint32_t *pte;
|
||||
unsigned int pgndx;
|
||||
|
||||
/* Since interrupts are disabled, we don't need to anything special. */
|
||||
|
||||
DEBUGASSERT(tcb && vpage);
|
||||
|
||||
/* Get the virtual address that caused the fault */
|
||||
|
||||
vaddr = tcb->xcp.far;
|
||||
DEBUGASSERT(vaddr >= PG_PAGED_VBASE && vaddr < PG_PAGED_VEND);
|
||||
|
||||
/* Allocate page memory to back up the mapping. Start by getting the
|
||||
* index of the next page that we are going to allocate.
|
||||
*/
|
||||
|
||||
pgndx = g_pgndx++;
|
||||
if (g_pgndx >= CONFIG_PAGING)
|
||||
{
|
||||
g_pgndx = 0;
|
||||
g_pgwrap = true;
|
||||
}
|
||||
|
||||
/* Was this physical page previously mapped? If so, then we need to un-map
|
||||
* it.
|
||||
*/
|
||||
|
||||
if (g_pgwrap)
|
||||
{
|
||||
/* Yes.. Get a pointer to the L2 entry corresponding to the previous
|
||||
* mapping -- then zero it!
|
||||
*/
|
||||
|
||||
uintptr_t oldvaddr = PG_POOL_NDX2VA(g_ptemap[pgndx]);
|
||||
pte = up_va2pte(oldvaddr);
|
||||
*pte = 0;
|
||||
|
||||
/* Invalidate the instruction TLB corresponding to the virtual address */
|
||||
|
||||
tlb_inst_invalidate_single(oldvaddr);
|
||||
|
||||
/* I do not believe that it is necessary to flush the I-Cache in this
|
||||
* case: The I-Cache uses a virtual address index and, hence, since the
|
||||
* NuttX address space is flat, the cached instruction value should be
|
||||
* correct even if the page mapping is no longer in place.
|
||||
*/
|
||||
}
|
||||
|
||||
/* Then convert the index to a (physical) page address. */
|
||||
|
||||
paddr = PG_POOL_PGPADDR(pgndx);
|
||||
|
||||
/* Now setup up the new mapping. Get a pointer to the L2 entry
|
||||
* corresponding to the new mapping. Then set it map to the newly
|
||||
* allocated page address. The inital mapping is read/write but
|
||||
* non-cached (MMU_L2_ALLOCFLAGS)
|
||||
*/
|
||||
|
||||
pte = up_va2pte(vaddr);
|
||||
*pte = (paddr | MMU_L2_ALLOCFLAGS);
|
||||
|
||||
/* And save the new L1 index */
|
||||
|
||||
g_ptemap[pgndx] = PG_POOL_VA2L2NDX(vaddr);
|
||||
|
||||
/* Finally, return the virtual address of allocated page */
|
||||
|
||||
*vpage = (void*)(vaddr & ~PAGEMASK);
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
|
@ -1,325 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_assert.c
|
||||
*
|
||||
* Copyright (C) 2007-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 <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Output debug info if stack dump is selected -- even if
|
||||
* debug is not selected.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
# undef lldbg
|
||||
# define lldbg lib_lowprintf
|
||||
#endif
|
||||
|
||||
/* The following is just intended to keep some ugliness out of the mainline
|
||||
* code. We are going to print the task name if:
|
||||
*
|
||||
* CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name
|
||||
* (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used)
|
||||
* defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used
|
||||
*/
|
||||
|
||||
#undef CONFIG_PRINT_TASKNAME
|
||||
#if CONFIG_TASK_NAME_SIZE > 0 && (defined(CONFIG_DEBUG) || defined(CONFIG_ARCH_STACKDUMP))
|
||||
# define CONFIG_PRINT_TASKNAME 1
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_getsp
|
||||
****************************************************************************/
|
||||
|
||||
/* I don't know if the builtin to get SP is enabled */
|
||||
|
||||
static inline uint32_t up_getsp(void)
|
||||
{
|
||||
uint32_t sp;
|
||||
__asm__
|
||||
(
|
||||
"\tmov %0, sp\n\t"
|
||||
: "=r"(sp)
|
||||
);
|
||||
return sp;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_stackdump
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
static void up_stackdump(uint32_t sp, uint32_t stack_base)
|
||||
{
|
||||
uint32_t stack ;
|
||||
|
||||
for (stack = sp & ~0x1f; stack < stack_base; stack += 32)
|
||||
{
|
||||
uint32_t *ptr = (uint32_t*)stack;
|
||||
lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n",
|
||||
stack, ptr[0], ptr[1], ptr[2], ptr[3],
|
||||
ptr[4], ptr[5], ptr[6], ptr[7]);
|
||||
}
|
||||
}
|
||||
#else
|
||||
# define up_stackdump()
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_registerdump
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
static inline void up_registerdump(void)
|
||||
{
|
||||
/* Are user registers available from interrupt processing? */
|
||||
|
||||
if (current_regs)
|
||||
{
|
||||
int regs;
|
||||
|
||||
/* Yes.. dump the interrupt registers */
|
||||
|
||||
for (regs = REG_R0; regs <= REG_R15; regs += 8)
|
||||
{
|
||||
uint32_t *ptr = (uint32_t*)¤t_regs[regs];
|
||||
lldbg("R%d: %08x %08x %08x %08x %08x %08x %08x %08x\n",
|
||||
regs, ptr[0], ptr[1], ptr[2], ptr[3],
|
||||
ptr[4], ptr[5], ptr[6], ptr[7]);
|
||||
}
|
||||
|
||||
lldbg("CPSR: %08x\n", current_regs[REG_CPSR]);
|
||||
}
|
||||
}
|
||||
#else
|
||||
# define up_registerdump()
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_dumpstate
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
static void up_dumpstate(void)
|
||||
{
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
uint32_t sp = up_getsp();
|
||||
uint32_t ustackbase;
|
||||
uint32_t ustacksize;
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
uint32_t istackbase;
|
||||
uint32_t istacksize;
|
||||
#endif
|
||||
|
||||
/* Get the limits on the user stack memory */
|
||||
|
||||
if (rtcb->pid == 0)
|
||||
{
|
||||
ustackbase = g_heapbase - 4;
|
||||
ustacksize = CONFIG_IDLETHREAD_STACKSIZE;
|
||||
}
|
||||
else
|
||||
{
|
||||
ustackbase = (uint32_t)rtcb->adj_stack_ptr;
|
||||
ustacksize = (uint32_t)rtcb->adj_stack_size;
|
||||
}
|
||||
|
||||
/* Get the limits on the interrupt stack memory */
|
||||
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
istackbase = (uint32_t)&g_userstack;
|
||||
istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4;
|
||||
|
||||
/* Show interrupt stack info */
|
||||
|
||||
lldbg("sp: %08x\n", sp);
|
||||
lldbg("IRQ stack:\n");
|
||||
lldbg(" base: %08x\n", istackbase);
|
||||
lldbg(" size: %08x\n", istacksize);
|
||||
|
||||
/* Does the current stack pointer lie within the interrupt
|
||||
* stack?
|
||||
*/
|
||||
|
||||
if (sp <= istackbase && sp > istackbase - istacksize)
|
||||
{
|
||||
/* Yes.. dump the interrupt stack */
|
||||
|
||||
up_stackdump(sp, istackbase);
|
||||
|
||||
/* Extract the user stack pointer which should lie
|
||||
* at the base of the interrupt stack.
|
||||
*/
|
||||
|
||||
sp = g_userstack;
|
||||
lldbg("sp: %08x\n", sp);
|
||||
}
|
||||
|
||||
/* Show user stack info */
|
||||
|
||||
lldbg("User stack:\n");
|
||||
lldbg(" base: %08x\n", ustackbase);
|
||||
lldbg(" size: %08x\n", ustacksize);
|
||||
#else
|
||||
lldbg("sp: %08x\n", sp);
|
||||
lldbg("stack base: %08x\n", ustackbase);
|
||||
lldbg("stack size: %08x\n", ustacksize);
|
||||
#endif
|
||||
|
||||
/* Dump the user stack if the stack pointer lies within the allocated user
|
||||
* stack memory.
|
||||
*/
|
||||
|
||||
if (sp > ustackbase || sp <= ustackbase - ustacksize)
|
||||
{
|
||||
#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4
|
||||
lldbg("ERROR: Stack pointer is not within allocated stack\n");
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
up_stackdump(sp, ustackbase);
|
||||
}
|
||||
|
||||
/* Then dump the registers (if available) */
|
||||
|
||||
up_registerdump();
|
||||
}
|
||||
#else
|
||||
# define up_dumpstate()
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: _up_assert
|
||||
****************************************************************************/
|
||||
|
||||
static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
|
||||
{
|
||||
/* Are we in an interrupt handler or the idle task? */
|
||||
|
||||
if (current_regs || ((_TCB*)g_readytorun.head)->pid == 0)
|
||||
{
|
||||
(void)irqsave();
|
||||
for(;;)
|
||||
{
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
up_ledon(LED_PANIC);
|
||||
up_mdelay(250);
|
||||
up_ledoff(LED_PANIC);
|
||||
up_mdelay(250);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
exit(errorcode);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_assert
|
||||
****************************************************************************/
|
||||
|
||||
void up_assert(const uint8_t *filename, int lineno)
|
||||
{
|
||||
#ifdef CONFIG_PRINT_TASKNAME
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
#endif
|
||||
|
||||
up_ledon(LED_ASSERTION);
|
||||
#ifdef CONFIG_PRINT_TASKNAME
|
||||
lldbg("Assertion failed at file:%s line: %d task: %s\n",
|
||||
filename, lineno, rtcb->name);
|
||||
#else
|
||||
lldbg("Assertion failed at file:%s line: %d\n",
|
||||
filename, lineno);
|
||||
#endif
|
||||
up_dumpstate();
|
||||
_up_assert(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_assert_code
|
||||
****************************************************************************/
|
||||
|
||||
void up_assert_code(const uint8_t *filename, int lineno, int errorcode)
|
||||
{
|
||||
#ifdef CONFIG_PRINT_TASKNAME
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
#endif
|
||||
|
||||
up_ledon(LED_ASSERTION);
|
||||
|
||||
#ifdef CONFIG_PRINT_TASKNAME
|
||||
lldbg("Assertion failed at file:%s line: %d task: %s error code: %d\n",
|
||||
filename, lineno, rtcb->name, errorcode);
|
||||
#else
|
||||
lldbg("Assertion failed at file:%s line: %d error code: %d\n",
|
||||
filename, lineno, errorcode);
|
||||
#endif
|
||||
up_dumpstate();
|
||||
_up_assert(errorcode);
|
||||
}
|
|
@ -1,167 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_blocktask.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <stdbool.h>
|
||||
#include <sched.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_block_task
|
||||
*
|
||||
* Description:
|
||||
* The currently executing task at the head of
|
||||
* the ready to run list must be stopped. Save its context
|
||||
* and move it to the inactive list specified by task_state.
|
||||
*
|
||||
* Inputs:
|
||||
* tcb: Refers to a task in the ready-to-run list (normally
|
||||
* the task at the head of the list). It most be
|
||||
* stopped, its context saved and moved into one of the
|
||||
* waiting task lists. It it was the task at the head
|
||||
* of the ready-to-run list, then a context to the new
|
||||
* ready to run task must be performed.
|
||||
* task_state: Specifies which waiting task list should be
|
||||
* hold the blocked task TCB.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_block_task(_TCB *tcb, tstate_t task_state)
|
||||
{
|
||||
/* Verify that the context switch can be performed */
|
||||
|
||||
if ((tcb->task_state < FIRST_READY_TO_RUN_STATE) ||
|
||||
(tcb->task_state > LAST_READY_TO_RUN_STATE))
|
||||
{
|
||||
PANIC(OSERR_BADBLOCKSTATE);
|
||||
}
|
||||
else
|
||||
{
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
bool switch_needed;
|
||||
|
||||
/* Remove the tcb task from the ready-to-run list. If we
|
||||
* are blocking the task at the head of the task list (the
|
||||
* most likely case), then a context switch to the next
|
||||
* ready-to-run task is needed. In this case, it should
|
||||
* also be true that rtcb == tcb.
|
||||
*/
|
||||
|
||||
switch_needed = sched_removereadytorun(tcb);
|
||||
|
||||
/* Add the task to the specified blocked task list */
|
||||
|
||||
sched_addblocked(tcb, (tstate_t)task_state);
|
||||
|
||||
/* If there are any pending tasks, then add them to the g_readytorun
|
||||
* task list now
|
||||
*/
|
||||
|
||||
if (g_pendingtasks.head)
|
||||
{
|
||||
switch_needed |= sched_mergepending();
|
||||
}
|
||||
|
||||
/* Now, perform the context switch if one is needed */
|
||||
|
||||
if (switch_needed)
|
||||
{
|
||||
/* Are we in an interrupt handler? */
|
||||
|
||||
if (current_regs)
|
||||
{
|
||||
/* Yes, then we have to do things differently.
|
||||
* Just copy the current_regs into the OLD rtcb.
|
||||
*/
|
||||
|
||||
up_savestate(rtcb->xcp.regs);
|
||||
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_restorestate(rtcb->xcp.regs);
|
||||
}
|
||||
|
||||
/* Copy the user C context into the TCB at the (old) head of the
|
||||
* g_readytorun Task list. if up_saveusercontext returns a non-zero
|
||||
* value, then this is really the previously running task restarting!
|
||||
*/
|
||||
|
||||
else if (!up_saveusercontext(rtcb->xcp.regs))
|
||||
{
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_fullcontextrestore(rtcb->xcp.regs);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
|
@ -1,74 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_cache.S
|
||||
*
|
||||
* Copyright (C) 2007, 2009 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 "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define CACHE_DLINESIZE 32
|
||||
|
||||
/****************************************************************************
|
||||
* Assembly Macros
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_flushicache
|
||||
****************************************************************************/
|
||||
|
||||
/* Esure coherency between the Icache and the Dcache in the region described
|
||||
* by r0=start and r1=end.
|
||||
*/
|
||||
.globl up_flushicache
|
||||
.type up_flushicache,%function
|
||||
up_flushicache:
|
||||
bic r0, r0, #CACHE_DLINESIZE - 1
|
||||
1: mcr p15, 0, r0, c7, c10, 1 /* Clean D entry */
|
||||
mcr p15, 0, r0, c7, c5, 1 /* Invalidate I entry */
|
||||
add r0, r0, #CACHE_DLINESIZE
|
||||
cmp r0, r1
|
||||
blo 1b
|
||||
mcr p15, 0, r0, c7, c10, 4 /* Drain WB */
|
||||
mov pc, lr
|
||||
.size up_flushicache, .-up_flushicache
|
||||
.end
|
||||
|
|
@ -1,123 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_checkmapping.c
|
||||
* Check if the current task's fault address has been mapped into the virtual
|
||||
* address space.
|
||||
*
|
||||
* 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 <stdint.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/sched.h>
|
||||
#include <nuttx/page.h>
|
||||
|
||||
#include "up_internal.h"
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_checkmapping()
|
||||
*
|
||||
* Description:
|
||||
* The function up_checkmapping() returns an indication if the page fill
|
||||
* still needs to performed or not. In certain conditions, the page fault
|
||||
* may occur on several threads and be queued multiple times. This function
|
||||
* will prevent the same page from be filled multiple times.
|
||||
*
|
||||
* Input Parameters:
|
||||
* tcb - A reference to the task control block of the task that we believe
|
||||
* needs to have a page fill. Architecture-specific logic can
|
||||
* retrieve page fault information from the architecture-specific
|
||||
* context information in this TCB and can consult processor resources
|
||||
* (page tables or TLBs or ???) to determine if the fill still needs
|
||||
* to be performed or not.
|
||||
*
|
||||
* Returned Value:
|
||||
* This function will return true if the mapping is in place and false
|
||||
* if the mapping is still needed. Errors encountered should be
|
||||
* interpreted as fatal.
|
||||
*
|
||||
* Assumptions:
|
||||
* - This function is called from the normal tasking context (but with
|
||||
* interrupts disabled). The implementation must take whatever actions
|
||||
* are necessary to assure that the operation is safe within this
|
||||
* context.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
bool up_checkmapping(FAR _TCB *tcb)
|
||||
{
|
||||
uintptr_t vaddr;
|
||||
uint32_t *pte;
|
||||
|
||||
/* Since interrupts are disabled, we don't need to anything special. */
|
||||
|
||||
DEBUGASSERT(tcb);
|
||||
|
||||
/* Get the virtual address that caused the fault */
|
||||
|
||||
vaddr = tcb->xcp.far;
|
||||
DEBUGASSERT(vaddr >= PG_PAGED_VBASE && vaddr < PG_PAGED_VEND);
|
||||
|
||||
/* Get the PTE associated with this virtual address */
|
||||
|
||||
pte = up_va2pte(vaddr);
|
||||
|
||||
/* Return true if this virtual address is mapped. */
|
||||
|
||||
return (*pte != 0);
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
|
@ -1,82 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_copystate.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <stdint.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_undefinedinsn
|
||||
****************************************************************************/
|
||||
|
||||
/* A little faster than most memcpy's */
|
||||
|
||||
void up_copystate(uint32_t *dest, uint32_t *src)
|
||||
{
|
||||
int i;
|
||||
|
||||
/* In the current ARM model, the state is always copied to and from the
|
||||
* stack and TCB.
|
||||
*/
|
||||
|
||||
for (i = 0; i < XCPTCONTEXT_REGS; i++)
|
||||
{
|
||||
*dest++ = *src++;
|
||||
}
|
||||
}
|
||||
|
|
@ -1,201 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_dataabort.c
|
||||
*
|
||||
* Copyright (C) 2007-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 <stdint.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
# include <nuttx/page.h>
|
||||
# include "arm.h"
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Output debug info if stack dump is selected -- even if
|
||||
* debug is not selected.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
# undef lldbg
|
||||
# define lldbg lib_lowprintf
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_dataabort
|
||||
*
|
||||
* Input parameters:
|
||||
* regs - The standard, ARM register save array.
|
||||
*
|
||||
* If CONFIG_PAGING is selected in the NuttX configuration file, then these
|
||||
* additional input values are expected:
|
||||
*
|
||||
* far - Fault address register. On a data abort, the ARM MMU places the
|
||||
* miss virtual address (MVA) into the FAR register. This is the address
|
||||
* of the data which, when accessed, caused the fault.
|
||||
* fsr - Fault status register. On a data a abort, the ARM MMU places an
|
||||
* encoded four-bit value, the fault status, along with the four-bit
|
||||
* encoded domain number, in the data FSR
|
||||
*
|
||||
* Description:
|
||||
* This is the data abort exception handler. The ARM data abort exception
|
||||
* occurs when a memory fault is detected during a data transfer.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
void up_dataabort(uint32_t *regs, uint32_t far, uint32_t fsr)
|
||||
{
|
||||
FAR _TCB *tcb = (FAR _TCB *)g_readytorun.head;
|
||||
#ifdef CONFIG_PAGING
|
||||
uint32_t *savestate;
|
||||
|
||||
/* Save the saved processor context in current_regs where it can be accessed
|
||||
* for register dumps and possibly context switching.
|
||||
*/
|
||||
|
||||
|
||||
savestate = (uint32_t*)current_regs;
|
||||
#endif
|
||||
current_regs = regs;
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
/* In the NuttX on-demand paging implementation, only the read-only, .text
|
||||
* section is paged. However, the ARM compiler generated PC-relative data
|
||||
* fetches from within the .text sections. Also, it is customary to locate
|
||||
* read-only data (.rodata) within the same section as .text so that it
|
||||
* does not require copying to RAM. Misses in either of these case should
|
||||
* cause a data abort.
|
||||
*
|
||||
* We are only interested in data aborts due to page translations faults.
|
||||
* Sections should already be in place and permissions should already be
|
||||
* be set correctly (to read-only) so any other data abort reason is a
|
||||
* fatal error.
|
||||
*/
|
||||
|
||||
pglldbg("FSR: %08x FAR: %08x\n", fsr, far);
|
||||
if ((fsr & FSR_MASK) != FSR_PAGE)
|
||||
{
|
||||
goto segfault;
|
||||
}
|
||||
|
||||
/* Check the (virtual) address of data that caused the data abort. When
|
||||
* the exception occurred, this address was provided in the FAR register.
|
||||
* (It has not yet been saved in the register context save area).
|
||||
*/
|
||||
|
||||
pgllvdbg("VBASE: %08x VEND: %08x\n", PG_PAGED_VBASE, PG_PAGED_VEND);
|
||||
if (far < PG_PAGED_VBASE || far >= PG_PAGED_VEND)
|
||||
{
|
||||
goto segfault;
|
||||
}
|
||||
|
||||
/* Save the offending data address as the fault address in the TCB of
|
||||
* the currently task. This fault address is also used by the prefetch
|
||||
* abort handling; this will allow common paging logic for both
|
||||
* prefetch and data aborts.
|
||||
*/
|
||||
|
||||
tcb->xcp.far = regs[REG_R15];
|
||||
|
||||
/* Call pg_miss() to schedule the page fill. A consequences of this
|
||||
* call are:
|
||||
*
|
||||
* (1) The currently executing task will be blocked and saved on
|
||||
* on the g_waitingforfill task list.
|
||||
* (2) An interrupt-level context switch will occur so that when
|
||||
* this function returns, it will return to a different task,
|
||||
* most likely the page fill worker thread.
|
||||
* (3) The page fill worker task has been signalled and should
|
||||
* execute immediately when we return from this exception.
|
||||
*/
|
||||
|
||||
pg_miss();
|
||||
|
||||
/* Restore the previous value of current_regs. NULL would indicate that
|
||||
* we are no longer in an interrupt handler. It will be non-NULL if we
|
||||
* are returning from a nested interrupt.
|
||||
*/
|
||||
|
||||
current_regs = savestate;
|
||||
return;
|
||||
|
||||
segfault:
|
||||
#endif
|
||||
lldbg("Data abort. PC: %08x FAR: %08x FSR: %08x\n", regs[REG_PC], far, fsr);
|
||||
PANIC(OSERR_ERREXCEPTION);
|
||||
}
|
||||
|
||||
#else /* CONFIG_PAGING */
|
||||
|
||||
void up_dataabort(uint32_t *regs)
|
||||
{
|
||||
/* Save the saved processor context in current_regs where it can be accessed
|
||||
* for register dumps and possibly context switching.
|
||||
*/
|
||||
|
||||
current_regs = regs;
|
||||
|
||||
/* Crash -- possibly showing diagnost debug information. */
|
||||
|
||||
lldbg("Data abort. PC: %08x\n", regs[REG_PC]);
|
||||
PANIC(OSERR_ERREXCEPTION);
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
|
@ -1,114 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_doirq.c
|
||||
*
|
||||
* Copyright (C) 2007-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
|
||||
* 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 <stdint.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <assert.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
void up_doirq(int irq, uint32_t *regs)
|
||||
{
|
||||
up_ledon(LED_INIRQ);
|
||||
#ifdef CONFIG_SUPPRESS_INTERRUPTS
|
||||
PANIC(OSERR_ERREXCEPTION);
|
||||
#else
|
||||
uint32_t *savestate;
|
||||
|
||||
/* Nested interrupts are not supported in this implementation. If you want
|
||||
* implemented nested interrupts, you would have to (1) change the way that
|
||||
* current regs is handled and (2) the design associated with
|
||||
* CONFIG_ARCH_INTERRUPTSTACK.
|
||||
*/
|
||||
|
||||
/* Current regs non-zero indicates that we are processing an interrupt;
|
||||
* current_regs is also used to manage interrupt level context switches.
|
||||
*/
|
||||
|
||||
savestate = (uint32_t*)current_regs;
|
||||
current_regs = regs;
|
||||
|
||||
/* Mask and acknowledge the interrupt */
|
||||
|
||||
up_maskack_irq(irq);
|
||||
|
||||
/* Deliver the IRQ */
|
||||
|
||||
irq_dispatch(irq, regs);
|
||||
|
||||
/* Restore the previous value of current_regs. NULL would indicate that
|
||||
* we are no longer in an interrupt handler. It will be non-NULL if we
|
||||
* are returning from a nested interrupt.
|
||||
*/
|
||||
|
||||
current_regs = savestate;
|
||||
|
||||
/* Unmask the last interrupt (global interrupts are still disabled) */
|
||||
|
||||
up_enable_irq(irq);
|
||||
#endif
|
||||
up_ledoff(LED_INIRQ);
|
||||
}
|
|
@ -1,118 +0,0 @@
|
|||
/**************************************************************************
|
||||
* arch/arm/src/arm/up_fullcontextrestore.S
|
||||
*
|
||||
* Copyright (C) 2007, 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/irq.h>
|
||||
#include "up_internal.h"
|
||||
|
||||
/**************************************************************************
|
||||
* Private Definitions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Types
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Function Prototypes
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Global Variables
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Variables
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Functions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Public Functions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Name: up_fullcontextrestore
|
||||
**************************************************************************/
|
||||
|
||||
.globl up_fullcontextrestore
|
||||
.type up_fullcontextrestore, function
|
||||
up_fullcontextrestore:
|
||||
|
||||
/* On entry, a1 (r0) holds address of the register save area */
|
||||
|
||||
/* Recover all registers except for r0, r1, R15, and CPSR */
|
||||
|
||||
add r1, r0, #(4*REG_R2) /* Offset to REG_R2 storage */
|
||||
ldmia r1, {r2-r14} /* Recover registers */
|
||||
|
||||
/* Create a stack frame to hold the PC */
|
||||
|
||||
sub sp, sp, #(3*4) /* Frame for three registers */
|
||||
ldr r1, [r0, #(4*REG_R0)] /* Fetch the stored r0 value */
|
||||
str r1, [sp] /* Save it at the top of the stack */
|
||||
ldr r1, [r0, #(4*REG_R1)] /* Fetch the stored r1 value */
|
||||
str r1, [sp, #4] /* Save it in the stack */
|
||||
ldr r1, [r0, #(4*REG_PC)] /* Fetch the stored pc value */
|
||||
str r1, [sp, #8] /* Save it at the bottom of the frame */
|
||||
|
||||
/* Now we can restore the CPSR. We wait until we are completely
|
||||
* finished with the context save data to do this. Restore the CPSR
|
||||
* may re-enable and interrupts and we could be in a context
|
||||
* where the save structure is only protected by interrupts being
|
||||
* disabled.
|
||||
*/
|
||||
|
||||
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the stored CPSR value */
|
||||
msr cpsr, r1 /* Set the CPSR */
|
||||
|
||||
/* Now recover r0 and r1 */
|
||||
|
||||
ldr r0, [sp]
|
||||
ldr r1, [sp, #4]
|
||||
add sp, sp, #(2*4)
|
||||
|
||||
/* Then return to the address at the stop of the stack,
|
||||
* destroying the stack frame
|
||||
*/
|
||||
|
||||
ldr pc, [sp], #4
|
||||
.size up_fullcontextrestore, . - up_fullcontextrestore
|
||||
|
|
@ -1,638 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_head.S
|
||||
*
|
||||
* Copyright (C) 2007, 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 "arm.h"
|
||||
#include "chip.h"
|
||||
#include "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
# include <nuttx/page.h>
|
||||
# include "pg_macros.h"
|
||||
#endif
|
||||
|
||||
/**********************************************************************************
|
||||
* Configuration
|
||||
**********************************************************************************/
|
||||
|
||||
#undef ALIGNMENT_TRAP
|
||||
#undef CPU_DCACHE_WRITETHROUGH
|
||||
#undef CPU_CACHE_ROUND_ROBIN
|
||||
#undef CPU_DCACHE_DISABLE
|
||||
#undef CPU_ICACHE_DISABLE
|
||||
|
||||
/* There are three operational memory configurations:
|
||||
*
|
||||
* 1. We execute in place in FLASH (CONFIG_BOOT_RUNFROMFLASH=y). In this case
|
||||
* the boot logic must:
|
||||
*
|
||||
* - Configure SDRAM,
|
||||
* - Initialize the .data section in RAM, and
|
||||
* - Clear .bss section
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_BOOT_RUNFROMFLASH
|
||||
# error "Configuration not implemented"
|
||||
# define CONFIG_SDRAM 1
|
||||
|
||||
/* Check for the identity mapping: For this configuration, this would be
|
||||
* the case where the virtual beginning of FLASH is the same as the physical
|
||||
* beginning of FLASH.
|
||||
*/
|
||||
|
||||
# if CONFIG_FLASH_START == CONFIG_FLASH_VSTART
|
||||
# define CONFIG_IDENTITY_TEXTMAP 1
|
||||
# endif
|
||||
|
||||
/* 2. We boot in FLASH but copy ourselves to DRAM from better performance.
|
||||
* (CONFIG_BOOT_RUNFROMFLASH=n && CONFIG_BOOT_COPYTORAM=y). In this case
|
||||
* the boot logic must:
|
||||
*
|
||||
* - Configure SDRAM,
|
||||
* - Copy ourself to DRAM (after mapping it), and
|
||||
* - Clear .bss section
|
||||
*
|
||||
* In this case, we assume that the logic within this file executes from FLASH.
|
||||
*/
|
||||
|
||||
#elif defined(CONFIG_BOOT_COPYTORAM)
|
||||
# error "configuration not implemented
|
||||
# define CONFIG_SDRAM 1
|
||||
|
||||
/* Check for the identity mapping: For this configuration, this would be
|
||||
* the case where the virtual beginning of FLASH is the same as the physical
|
||||
* beginning of FLASH.
|
||||
*/
|
||||
|
||||
# if CONFIG_FLASH_START == CONFIG_FLASH_VSTART
|
||||
# define CONFIG_IDENTITY_TEXTMAP 1
|
||||
# endif
|
||||
|
||||
/* 3. There is bootloader that copies us to DRAM (but probably not to the beginning)
|
||||
* (CONFIG_BOOT_RUNFROMFLASH=n && CONFIG_BOOT_COPYTORAM=n). In this case SDRAM
|
||||
* was initialized by the boot loader, and this boot logic must:
|
||||
*
|
||||
* - Clear .bss section
|
||||
*/
|
||||
|
||||
#else
|
||||
|
||||
/* Check for the identity mapping: For this configuration, this would be
|
||||
* the case where the virtual beginning of RAM is the same as the physical
|
||||
* beginning of RAM.
|
||||
*/
|
||||
|
||||
# if CONFIG_DRAM_START == CONFIG_DRAM_VSTART
|
||||
# define CONFIG_IDENTITY_TEXTMAP 1
|
||||
# endif
|
||||
|
||||
#endif
|
||||
|
||||
/* For each page table offset, the following provide (1) the physical address of
|
||||
* the start of the page table and (2) the number of page table entries in the
|
||||
* first page table.
|
||||
*
|
||||
* Coarse: PG_L1_PADDRMASK=0xfffffc00
|
||||
* NPAGE1=(256 -((a) & 0x000003ff) >> 2) NPAGE1=1-256
|
||||
* Fine: PG_L1_PADDRMASK=0xfffff000
|
||||
* NPAGE1=(1024 -((a) & 0x00000fff) >> 2) NPAGE1=1-1024
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
# define PG_L2_TEXT_PBASE (PG_L2_TEXT_PADDR & PG_L1_PADDRMASK)
|
||||
# define PG_L2_TEXT_NPAGE1 (PTE_NPAGES - ((PG_L2_TEXT_PADDR & ~PG_L1_PADDRMASK) >> 2))
|
||||
# define PG_L2_PGTABLE_PBASE (PG_L2_PGTABLE_PADDR & PG_L1_PADDRMASK)
|
||||
# define PG_L2_PGTABLE_NPAGE1 (PTE_NPAGES - ((PG_L2_PGTABLE_PADDR & ~PG_L1_PADDRMASK) >> 2))
|
||||
# define PG_L2_DATA_PBASE (PG_L2_DATA_PADDR & PG_L1_PADDRMASK)
|
||||
# define PG_L2_DATA_NPAGE1 (PTE_NPAGES - ((PG_L2_DATA_PADDR & ~PG_L1_PADDRMASK) >> 2))
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* RX_NSECTIONS determines the number of 1Mb sections to map for the
|
||||
* Read/eXecute address region. This is based on CONFIG_DRAM_SIZE. For most
|
||||
* ARM9 architectures, CONFIG_DRAM_SIZE describes the size of installed SDRAM.
|
||||
* But for other architectures, this might refer to the size of FLASH or
|
||||
* SRAM regions. (bad choice of naming).
|
||||
*/
|
||||
|
||||
#define RX_NSECTIONS ((CONFIG_DRAM_SIZE+0x000fffff) >> 20)
|
||||
|
||||
/****************************************************************************
|
||||
* Assembly Macros
|
||||
****************************************************************************/
|
||||
|
||||
/* The ARM9 L1 page table can be placed at the beginning or at the end of the
|
||||
* RAM space. This decision is based on the placement of the vector area:
|
||||
* If the vectors are place in low memory at address 0x0000 0000, then the
|
||||
* page table is placed in high memory; if the vectors are placed in high
|
||||
* memory at address 0xfff0 0000, then the page table is locating at the
|
||||
* beginning of RAM.
|
||||
*
|
||||
* For the special case where (1) the program executes out of RAM, and (2) the
|
||||
* page is located at the beginning of RAM, then the following macro can
|
||||
* easily find the physical address of the section that includes the first
|
||||
* part of the text region: Since the page table is closely related to the
|
||||
* NuttX base address in this case, we can convert the page table base address
|
||||
* to the base address of the section containing both.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_LOWVECTORS
|
||||
.macro mksection, section, pgtable
|
||||
bic \section, \pgtable, #0x000ff000
|
||||
.endm
|
||||
#endif
|
||||
|
||||
/* This macro will modify r0, r1, r2 and r14 */
|
||||
|
||||
#ifdef CONFIG_DEBUG
|
||||
.macro showprogress, code
|
||||
mov r0, #\code
|
||||
bl up_lowputc
|
||||
.endm
|
||||
#else
|
||||
.macro showprogress, code
|
||||
.endm
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: __start
|
||||
****************************************************************************/
|
||||
|
||||
/* We assume the bootloader has already initialized most of the h/w for us
|
||||
* and that only leaves us having to do some os specific things below.
|
||||
*/
|
||||
.text
|
||||
.global __start
|
||||
.type __start, #function
|
||||
__start:
|
||||
/* Make sure that we are in SVC mode with all IRQs disabled */
|
||||
|
||||
mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT)
|
||||
msr cpsr_c, r0
|
||||
|
||||
/* Initialize DRAM using a macro provided by board-specific logic */
|
||||
|
||||
#ifdef CONFIG_SDRAM
|
||||
config_sdram
|
||||
#endif
|
||||
/* Clear the 16K level 1 page table */
|
||||
|
||||
ldr r4, .LCppgtable /* r4=phys. page table */
|
||||
#ifndef CONFIG_ARCH_ROMPGTABLE
|
||||
mov r0, r4
|
||||
mov r1, #0
|
||||
add r2, r0, #PGTABLE_SIZE
|
||||
.Lpgtableclear:
|
||||
str r1, [r0], #4
|
||||
str r1, [r0], #4
|
||||
str r1, [r0], #4
|
||||
str r1, [r0], #4
|
||||
teq r0, r2
|
||||
bne .Lpgtableclear
|
||||
|
||||
/* Create identity mapping for first MB of the .text section to support
|
||||
* this startup logic executing out of the physical address space. This
|
||||
* identity mapping will be removed by .Lvstart (see below). Of course,
|
||||
* we would only do this if the physical-virtual mapping is not already
|
||||
* the identity mapping.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_IDENTITY_TEXTMAP
|
||||
mksection r0, r4 /* r0=phys. base section */
|
||||
ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */
|
||||
add r3, r1, r0 /* r3=flags + base */
|
||||
str r3, [r4, r0, lsr #18] /* identity mapping */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
/* Map the read-only .text region in place. This must be done
|
||||
* before the MMU is enabled and the virtual addressing takes
|
||||
* effect. First populate the L1 table for the locked and paged
|
||||
* text regions.
|
||||
*
|
||||
* We could probably make the the pg_l1span and pg_l2map macros into
|
||||
* call-able subroutines, but we would have to be carefully during
|
||||
* this phase while we are operating in a physical address space.
|
||||
*
|
||||
* NOTE: That the value of r5 (L1 table base address) must be
|
||||
* preserved through the following.
|
||||
*/
|
||||
|
||||
adr r0, .Ltxtspan
|
||||
ldmia r0, {r0, r1, r2, r3, r5}
|
||||
pg_l1span r0, r1, r2, r3, r5, r6
|
||||
|
||||
/* Then populate the L2 table for the locked text region only. */
|
||||
|
||||
adr r0, .Ltxtmap
|
||||
ldmia r0, {r0, r1, r2, r3}
|
||||
pg_l2map r0, r1, r2, r3, r5
|
||||
|
||||
/* Make sure that the page table is itself mapped and and read/write-able.
|
||||
* First, populate the L1 table:
|
||||
*/
|
||||
|
||||
adr r0, .Lptabspan
|
||||
ldmia r0, {r0, r1, r2, r3, r5}
|
||||
pg_l1span r0, r1, r2, r3, r5, r6
|
||||
|
||||
/* Then populate the L2 table. */
|
||||
|
||||
adr r0, .Lptabmap
|
||||
ldmia r0, {r0, r1, r2, r3}
|
||||
pg_l2map r0, r1, r2, r3, r5
|
||||
|
||||
#else /* CONFIG_PAGING */
|
||||
|
||||
/* Create a virtual single section mapping for the first MB of the .text
|
||||
* address space. Now, we have the first 1MB mapping to both phyical and
|
||||
* virtual addresses. The rest of the .text mapping will be completed in
|
||||
* .Lvstart once we have moved the physical mapping out of the way.
|
||||
*
|
||||
* Here we expect to have:
|
||||
* r4 = Address of the base of the L1 table
|
||||
*/
|
||||
|
||||
ldr r2, .LCvpgtable /* r2=virt. page table */
|
||||
mksection r0, r2 /* r0=virt. base section */
|
||||
str r3, [r4, r0, lsr #18] /* identity mapping */
|
||||
|
||||
/* NOTE: No .data/.bss access should be attempted. This temporary mapping
|
||||
* can only be assumed to cover the initial .text region.
|
||||
*/
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
||||
#endif /* CONFIG_ARCH_ROMPGTABLE */
|
||||
|
||||
/* The following logic will set up the ARM920/ARM926 for normal operation.
|
||||
*
|
||||
* Here we expect to have:
|
||||
* r4 = Address of the base of the L1 table
|
||||
*/
|
||||
|
||||
mov r0, #0
|
||||
mcr p15, 0, r0, c7, c7 /* Invalidate I,D caches */
|
||||
mcr p15, 0, r0, c7, c10, 4 /* Drain write buffer */
|
||||
mcr p15, 0, r0, c8, c7 /* Invalidate I,D TLBs */
|
||||
mcr p15, 0, r4, c2, c0 /* Load page table pointer */
|
||||
|
||||
#ifdef CPU_DCACHE_WRITETHROUGH
|
||||
mov r0, #4 /* Disable write-back on caches explicitly */
|
||||
mcr p15, 7, r0, c15, c0, 0
|
||||
#endif
|
||||
|
||||
/* Enable the MMU and caches
|
||||
* lr = Resume at .Lvstart with the MMU enabled
|
||||
*/
|
||||
|
||||
ldr lr, .LCvstart /* Abs. virtual address */
|
||||
|
||||
mov r0, #0x1f /* Domains 0, 1 = client */
|
||||
mcr p15, 0, r0, c3, c0 /* Load domain access register */
|
||||
mrc p15, 0, r0, c1, c0 /* Get control register */
|
||||
|
||||
/* Clear bits (see arm.h)
|
||||
*
|
||||
* CR_R - ROM MMU protection
|
||||
* CR_F - Implementation defined
|
||||
* CR_Z - Implementation defined
|
||||
*
|
||||
* CR_A - Alignment abort enable
|
||||
* CR_C - Dcache enable
|
||||
* CR_W - Write buffer enable
|
||||
*
|
||||
* CR_I - Icache enable
|
||||
*/
|
||||
|
||||
bic r0, r0, #(CR_R|CR_F|CR_Z)
|
||||
bic r0, r0, #(CR_A|CR_C|CR_W)
|
||||
bic r0, r0, #(CR_I)
|
||||
|
||||
/* Set bits (see arm.h)
|
||||
*
|
||||
* CR_M - MMU enable
|
||||
* CR_P - 32-bit exception handler
|
||||
* CR_D - 32-bit data address range
|
||||
*/
|
||||
|
||||
orr r0, r0, #(CR_M|CR_P|CR_D)
|
||||
|
||||
/* In most architectures, vectors are relocated to 0xffff0000.
|
||||
* -- but not all
|
||||
*
|
||||
* CR_S - System MMU protection
|
||||
* CR_V - Vectors relocated to 0xffff0000
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_ARCH_LOWVECTORS
|
||||
orr r0, r0, #(CR_S|CR_V)
|
||||
#else
|
||||
orr r0, r0, #(CR_S)
|
||||
#endif
|
||||
/* CR_RR - Round Robin cache replacement */
|
||||
|
||||
#ifdef CPU_CACHE_ROUND_ROBIN
|
||||
orr r0, r0, #(CR_RR)
|
||||
#endif
|
||||
/* CR_C - Dcache enable */
|
||||
|
||||
#ifndef CPU_DCACHE_DISABLE
|
||||
orr r0, r0, #(CR_C)
|
||||
#endif
|
||||
/* CR_C - Dcache enable */
|
||||
|
||||
#ifndef CPU_ICACHE_DISABLE
|
||||
orr r0, r0, #(CR_I)
|
||||
#endif
|
||||
/* CR_A - Alignment abort enable */
|
||||
|
||||
#ifdef ALIGNMENT_TRAP
|
||||
orr r0, r0, #(CR_A)
|
||||
#endif
|
||||
mcr p15, 0, r0, c1, c0, 0 /* write control reg */
|
||||
|
||||
/* Get TMP=2 Processor ID register */
|
||||
|
||||
mrc p15, 0, r1, c0, c0, 0 /* read id reg */
|
||||
mov r1,r1 /* Null-avoiding nop */
|
||||
mov r1,r1 /* Null-avoiding nop */
|
||||
|
||||
/* And "jump" to .Lvstart */
|
||||
|
||||
mov pc, lr
|
||||
|
||||
/****************************************************************************
|
||||
* PC_Relative Data
|
||||
****************************************************************************/
|
||||
|
||||
/* Most addresses are all virtual address */
|
||||
|
||||
.type .LCvstart, %object
|
||||
.LCvstart:
|
||||
.long .Lvstart
|
||||
|
||||
#ifndef CONFIG_ARCH_ROMPGTABLE
|
||||
.type .LCmmuflags, %object
|
||||
.LCmmuflags:
|
||||
.long MMU_MEMFLAGS /* MMU flags for memory sections */
|
||||
#endif
|
||||
|
||||
.type .LCppgtable, %object
|
||||
.LCppgtable:
|
||||
.long PGTABLE_BASE_PADDR /* Physical start of page table */
|
||||
|
||||
#ifndef CONFIG_ARCH_ROMPGTABLE
|
||||
.type .LCvpgtable, %object
|
||||
.LCvpgtable:
|
||||
.long PGTABLE_BASE_VADDR /* Virtual start of page table */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
.Ltxtspan:
|
||||
.long PG_L1_TEXT_PADDR /* Physical address in the L1 table */
|
||||
.long PG_L2_TEXT_PBASE /* Physical address of the start of the L2 page table */
|
||||
.long PG_TEXT_NVPAGES /* Total (virtual) text pages to be mapped */
|
||||
.long PG_L2_TEXT_NPAGE1 /* The number of text pages in the first page table */
|
||||
.long MMU_L1_TEXTFLAGS /* L1 MMU flags to use */
|
||||
|
||||
.Ltxtmap:
|
||||
.long PG_L2_LOCKED_PADDR /* Physical address in the L2 table */
|
||||
.long PG_LOCKED_PBASE /* Physical address of locked base memory */
|
||||
.long CONFIG_PAGING_NLOCKED /* Number of pages in the locked region */
|
||||
.long MMU_L2_TEXTFLAGS /* L2 MMU flags to use */
|
||||
|
||||
.Lptabspan:
|
||||
.long PG_L1_PGTABLE_PADDR /* Physical address in the L1 table */
|
||||
.long PG_L2_PGTABLE_PBASE /* Physical address of the start of the L2 page table */
|
||||
.long PG_PGTABLE_NPAGES /* Total mapped page table pages */
|
||||
.long PG_L2_PGTABLE_NPAGE1 /* The number of text pages in the first page table */
|
||||
.long MMU_L1_PGTABFLAGS /* L1 MMU flags to use */
|
||||
|
||||
.Lptabmap:
|
||||
.long PG_L2_PGTABLE_PADDR /* Physical address in the L2 table */
|
||||
.long PGTABLE_BASE_PADDR /* Physical address of the page table memory */
|
||||
.long PG_PGTABLE_NPAGES /* Total mapped page table pages */
|
||||
.long MMU_L2_PGTABFLAGS /* L2 MMU flags to use */
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
||||
.size __start, .-__start
|
||||
|
||||
/****************************************************************************
|
||||
* Name: .Lvstart
|
||||
***************************************************************************/
|
||||
|
||||
/* The following is executed after the MMU has been enabled. This uses
|
||||
* absolute addresses; this is not position independent.
|
||||
*/
|
||||
.align 5
|
||||
.local .Lvstart
|
||||
.type .Lvstart, %function
|
||||
.Lvstart:
|
||||
|
||||
/* Remove the temporary mapping (if one was made). The following assumes
|
||||
* that the total RAM size is > 1Mb and extends that initial mapping to
|
||||
* cover additinal RAM sections.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef CONFIG_ARCH_ROMPGTABLE
|
||||
#ifndef CONFIG_IDENTITY_TEXTMAP
|
||||
ldr r4, .LCvpgtable /* r4=virtual page table */
|
||||
ldr r1, .LCppgtable /* r1=phys. page table */
|
||||
mksection r3, r1 /* r2=phys. base addr */
|
||||
mov r0, #0 /* flags + base = 0 */
|
||||
str r0, [r4, r3, lsr #18] /* Undo identity mapping */
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_PAGING)
|
||||
/* Populate the L1 table for the data region */
|
||||
|
||||
adr r0, .Ldataspan
|
||||
ldmia r0, {r0, r1, r2, r3, r4}
|
||||
pg_l1span r0, r1, r2, r3, r4, r5
|
||||
|
||||
/* Populate the L2 table for the data region */
|
||||
|
||||
adr r0, .Ldatamap
|
||||
ldmia r0, {r0, r1, r2, r3}
|
||||
pg_l2map r0, r1, r2, r3, r4
|
||||
|
||||
#elif defined(CONFIG_BOOT_RUNFROMFLASH)
|
||||
# error "Logic not implemented"
|
||||
#else
|
||||
/* Now setup the pagetables for our normal SDRAM mappings mapped region.
|
||||
* We round NUTTX_START_VADDR down to the nearest megabyte boundary.
|
||||
*/
|
||||
|
||||
ldr r1, .LCmmuflags /* FLGS=MMU_MEMFLAGS */
|
||||
add r3, r3, r1 /* r3=flags + base */
|
||||
|
||||
add r0, r4, #(NUTTX_START_VADDR & 0xff000000) >> 18
|
||||
bic r2, r3, #0x00f00000
|
||||
str r2, [r0]
|
||||
|
||||
add r0, r0, #(NUTTX_START_VADDR & 0x00f00000) >> 18
|
||||
str r3, [r0], #4
|
||||
|
||||
/* Now map the remaining RX_NSECTIONS-1 sections of the executable
|
||||
* memory region.
|
||||
*/
|
||||
|
||||
.rept RX_NSECTIONS-1
|
||||
add r3, r3, #SECTION_SIZE
|
||||
str r3, [r0], #4
|
||||
.endr
|
||||
|
||||
/* If we are executing from RAM with a fixed page configuration, then
|
||||
* we can assume that the above contiguous mapping included all of the
|
||||
* .text, .data, .bss, heap, etc. But if we are executing from FLASH,
|
||||
* then the RAM area is probably in a separate physical address region
|
||||
* and will require a separate mapping. Or, if we are supporting on-demand
|
||||
* paging of the .text region, then the RAM-based .data/.bss/heap section
|
||||
* will still probably be located in a separate (virtual) address region.
|
||||
*/
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
||||
#endif /* CONFIG_ARCH_ROMPGTABLE */
|
||||
|
||||
/* Zero BSS and set up the stack pointer */
|
||||
|
||||
adr r0, .Linitparms
|
||||
ldmia r0, {r0, r1, sp}
|
||||
|
||||
/* Clear the frame pointer and .bss */
|
||||
|
||||
mov fp, #0
|
||||
|
||||
.Lbssinit:
|
||||
cmp r0, r1 /* Clear up to _bss_end_ */
|
||||
strcc fp, [r0],#4
|
||||
bcc .Lbssinit
|
||||
|
||||
/* If the .data section is in a separate, unitialized address space,
|
||||
* then we will also need to copy the initial values of of the .data
|
||||
* section from the .text region into that .data region. This would
|
||||
* be the case if we are executing from FLASH and the .data section
|
||||
* lies in a different physical address region OR if we are support
|
||||
* on-demand paging and the .data section lies in a different virtual
|
||||
* address region.
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_BOOT_RUNFROMFLASH) || defined(CONFIG_PAGING)
|
||||
adr r3, .Ldatainit
|
||||
ldmia r3, {r0, r1, r2}
|
||||
|
||||
1: ldmia r0!, {r3 - r10}
|
||||
stmia r1!, {r3 - r10}
|
||||
cmp r1, r2
|
||||
blt 1b
|
||||
#endif
|
||||
|
||||
/* Perform early C-level, platform-specific initialization */
|
||||
|
||||
bl up_boot
|
||||
|
||||
/* Finally branch to the OS entry point */
|
||||
|
||||
mov lr, #0
|
||||
b os_start
|
||||
|
||||
/* Text-section constants:
|
||||
*
|
||||
* _sbss is the start of the BSS region (see ld.script)
|
||||
* _ebss is the end of the BSS regsion (see ld.script)
|
||||
*
|
||||
* The idle task stack starts at the end of BSS and is of size
|
||||
* CONFIG_IDLETHREAD_STACKSIZE. The heap continues from there until the
|
||||
* end of memory. See g_heapbase below.
|
||||
*/
|
||||
|
||||
.Linitparms:
|
||||
.long _sbss
|
||||
.long _ebss
|
||||
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
.Ldataspan:
|
||||
.long PG_L1_DATA_VADDR /* Virtual address in the L1 table */
|
||||
.long PG_L2_DATA_PBASE /* Physical address of the start of the L2 page table */
|
||||
.long PG_DATA_NPAGES /* Number of pages in the data region */
|
||||
.long PG_L2_DATA_NPAGE1 /* The number of text pages in the first page table */
|
||||
.long MMU_L1_DATAFLAGS /* L1 MMU flags to use */
|
||||
|
||||
.Ldatamap:
|
||||
.long PG_L2_DATA_VADDR /* Virtual address in the L2 table */
|
||||
.long PG_DATA_PBASE /* Physical address of data memory */
|
||||
.long PG_DATA_NPAGES /* Number of pages in the data region */
|
||||
.long MMU_L2_DATAFLAGS /* L2 MMU flags to use */
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
||||
|
||||
#if defined(CONFIG_BOOT_RUNFROMFLASH) || defined(CONFIG_PAGING)
|
||||
.Ldatainit:
|
||||
.long _eronly /* Where .data defaults are stored in FLASH */
|
||||
.long _sdata /* Where .data needs to reside in SDRAM */
|
||||
.long _edata
|
||||
#endif
|
||||
.size .Lvstart, .-.Lvstart
|
||||
|
||||
/* Data section variables */
|
||||
|
||||
/* This global variable is unsigned long g_heapbase and is
|
||||
* exported from here only because of its coupling to .Linitparms
|
||||
* above.
|
||||
*/
|
||||
|
||||
.data
|
||||
.align 4
|
||||
.globl g_heapbase
|
||||
.type g_heapbase, object
|
||||
g_heapbase:
|
||||
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE
|
||||
.size g_heapbase, .-g_heapbase
|
||||
.end
|
||||
|
|
@ -1,146 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_initialstate.c
|
||||
*
|
||||
* Copyright (C) 2007-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
|
||||
* 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 <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_initial_state
|
||||
*
|
||||
* Description:
|
||||
* A new thread is being started and a new TCB
|
||||
* has been created. This function is called to initialize
|
||||
* the processor specific portions of the new TCB.
|
||||
*
|
||||
* This function must setup the intial architecture registers
|
||||
* and/or stack so that execution will begin at tcb->start
|
||||
* on the next context switch.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_initial_state(_TCB *tcb)
|
||||
{
|
||||
struct xcptcontext *xcp = &tcb->xcp;
|
||||
uint32_t cpsr;
|
||||
|
||||
/* Initialize the initial exception register context structure */
|
||||
|
||||
memset(xcp, 0, sizeof(struct xcptcontext));
|
||||
|
||||
/* Save the initial stack pointer */
|
||||
|
||||
xcp->regs[REG_SP] = (uint32_t)tcb->adj_stack_ptr;
|
||||
|
||||
/* Save the task entry point */
|
||||
|
||||
xcp->regs[REG_PC] = (uint32_t)tcb->start;
|
||||
|
||||
/* If this task is running PIC, then set the PIC base register to the
|
||||
* address of the allocated D-Space region.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_PIC
|
||||
if (tcb->dspace != NULL)
|
||||
{
|
||||
/* Set the PIC base register (probably R10) to the address of the
|
||||
* alloacated D-Space region.
|
||||
*/
|
||||
|
||||
xcp->regs[REG_PIC] = (uint32_t)tcb->dspace->region;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Set supervisor- or user-mode, depending on how NuttX is configured and
|
||||
* what kind of thread is being started. Disable FIQs in any event
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_NUTTX_KERNEL
|
||||
if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_KERNEL)
|
||||
{
|
||||
/* It is a kernel thread.. set supervisor mode */
|
||||
|
||||
cpsr = SVC_MODE | PSR_F_BIT;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* It is a normal task or a pthread. Set user mode */
|
||||
|
||||
cpsr = USR_MODE | PSR_F_BIT;
|
||||
}
|
||||
#else
|
||||
/* If the kernel build is not selected, then all threads run in
|
||||
* supervisor-mode.
|
||||
*/
|
||||
|
||||
cpsr = SVC_MODE | PSR_F_BIT;
|
||||
#endif
|
||||
|
||||
/* Enable or disable interrupts, based on user configuration */
|
||||
|
||||
# ifdef CONFIG_SUPPRESS_INTERRUPTS
|
||||
cpsr |= PSR_I_BIT;
|
||||
# endif
|
||||
|
||||
xcp->regs[REG_CPSR] = cpsr;
|
||||
}
|
||||
|
|
@ -1,167 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_nommuhead.S
|
||||
*
|
||||
* Copyright (C) 2007, 2009-2010, 2012 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Macros
|
||||
****************************************************************************/
|
||||
|
||||
/* This macro will modify r0, r1, r2 and r14 */
|
||||
|
||||
#ifdef CONFIG_DEBUG
|
||||
.macro showprogress, code
|
||||
mov r0, #\code
|
||||
bl up_lowputc
|
||||
.endm
|
||||
#else
|
||||
.macro showprogress, code
|
||||
.endm
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* OS Entry Point
|
||||
****************************************************************************/
|
||||
|
||||
/* We assume the bootloader has already initialized most of the h/w for
|
||||
* us and that only leaves us having to do some os specific things
|
||||
* below.
|
||||
*/
|
||||
.text
|
||||
.global __start
|
||||
.type __start, #function
|
||||
__start:
|
||||
|
||||
/* First, setup initial processor mode */
|
||||
|
||||
mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT )
|
||||
msr cpsr, r0
|
||||
|
||||
showprogress 'A'
|
||||
|
||||
/* Setup system stack (and get the BSS range) */
|
||||
|
||||
adr r0, LC0
|
||||
ldmia r0, {r4, r5, sp}
|
||||
|
||||
/* Clear system BSS section */
|
||||
|
||||
mov r0, #0
|
||||
1: cmp r4, r5
|
||||
strcc r0, [r4], #4
|
||||
bcc 1b
|
||||
|
||||
showprogress 'B'
|
||||
|
||||
/* Copy system .data sections to new home in RAM. */
|
||||
|
||||
#ifdef CONFIG_BOOT_RUNFROMFLASH
|
||||
|
||||
adr r3, LC2
|
||||
ldmia r3, {r0, r1, r2}
|
||||
|
||||
1: ldmia r0!, {r3 - r10}
|
||||
stmia r1!, {r3 - r10}
|
||||
cmp r1, r2
|
||||
blt 1b
|
||||
|
||||
#endif
|
||||
|
||||
/* Perform early serial initialization */
|
||||
|
||||
mov fp, #0
|
||||
#ifdef USE_EARLYSERIALINIT
|
||||
bl up_earlyserialinit
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_DEBUG
|
||||
mov r0, #'C'
|
||||
bl up_putc
|
||||
mov r0, #'\n'
|
||||
bl up_putc
|
||||
#endif
|
||||
/* Initialize onboard LEDs */
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
bl up_ledinit
|
||||
#endif
|
||||
|
||||
/* Then jump to OS entry */
|
||||
|
||||
b os_start
|
||||
|
||||
/* Variables:
|
||||
* _sbss is the start of the BSS region (see ld.script)
|
||||
* _ebss is the end of the BSS regsion (see ld.script)
|
||||
* The idle task stack starts at the end of BSS and is
|
||||
* of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues
|
||||
* from there until the end of memory. See g_heapbase
|
||||
* below.
|
||||
*/
|
||||
|
||||
LC0: .long _sbss
|
||||
.long _ebss
|
||||
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
|
||||
|
||||
#ifdef CONFIG_BOOT_RUNFROMFLASH
|
||||
LC2: .long _eronly /* Where .data defaults are stored in FLASH */
|
||||
.long _sdata /* Where .data needs to reside in SDRAM */
|
||||
.long _edata
|
||||
#endif
|
||||
.size __start, .-__start
|
||||
|
||||
/* This global variable is unsigned long g_heapbase and is
|
||||
* exported from here only because of its coupling to LCO
|
||||
* above.
|
||||
*/
|
||||
|
||||
.data
|
||||
.align 4
|
||||
.globl g_heapbase
|
||||
.type g_heapbase, object
|
||||
g_heapbase:
|
||||
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE
|
||||
.size g_heapbase, .-g_heapbase
|
||||
|
||||
.end
|
||||
|
|
@ -1,96 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_pginitialize.c
|
||||
* Initialize the MMU for on-demand paging support.
|
||||
*
|
||||
* 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 <debug.h>
|
||||
|
||||
#include <nuttx/sched.h>
|
||||
#include <nuttx/page.h>
|
||||
|
||||
#include "up_internal.h"
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_pginitialize()
|
||||
*
|
||||
* Description:
|
||||
* Initialize the MMU for on-demand paging support..
|
||||
*
|
||||
* Input Parameters:
|
||||
* None.
|
||||
*
|
||||
* Returned Value:
|
||||
* None. This function will crash if any errors are detected during MMU
|
||||
* initialization
|
||||
*
|
||||
* Assumptions:
|
||||
* - Called early in the platform initialization sequence so that no special
|
||||
* concurrency protection is required.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_pginitialize(void)
|
||||
{
|
||||
/* None needed at present. This file is just retained in case the need
|
||||
* arises in the future. Nothing calls up_pginitialize() now. If needed,
|
||||
* if should be called early in up_boot.c to assure that all paging is
|
||||
* ready.
|
||||
*/
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
|
@ -1,154 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/src/up_prefetchabort.c
|
||||
*
|
||||
* Copyright (C) 2007-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 <stdint.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#ifdef CONFIG_PAGING
|
||||
# include <nuttx/page.h>
|
||||
#endif
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
/* Output debug info if stack dump is selected -- even if
|
||||
* debug is not selected.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
# undef lldbg
|
||||
# define lldbg lib_lowprintf
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_prefetchabort
|
||||
*
|
||||
* Description;
|
||||
* This is the prefetch abort exception handler. The ARM prefetch abort
|
||||
* exception occurs when a memory fault is detected during an an
|
||||
* instruction fetch.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_prefetchabort(uint32_t *regs)
|
||||
{
|
||||
#ifdef CONFIG_PAGING
|
||||
uint32_t *savestate;
|
||||
|
||||
/* Save the saved processor context in current_regs where it can be accessed
|
||||
* for register dumps and possibly context switching.
|
||||
*/
|
||||
|
||||
savestate = (uint32_t*)current_regs;
|
||||
#endif
|
||||
current_regs = regs;
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
/* Get the (virtual) address of instruction that caused the prefetch abort.
|
||||
* When the exception occurred, this address was provided in the lr register
|
||||
* and this value was saved in the context save area as the PC at the
|
||||
* REG_R15 index.
|
||||
*
|
||||
* Check to see if this miss address is within the configured range of
|
||||
* virtual addresses.
|
||||
*/
|
||||
|
||||
pglldbg("VADDR: %08x VBASE: %08x VEND: %08x\n",
|
||||
regs[REG_PC], PG_PAGED_VBASE, PG_PAGED_VEND);
|
||||
|
||||
if (regs[REG_R15] >= PG_PAGED_VBASE && regs[REG_R15] < PG_PAGED_VEND)
|
||||
{
|
||||
/* Save the offending PC as the fault address in the TCB of the currently
|
||||
* executing task. This value is, of course, already known in regs[REG_R15],
|
||||
* but saving it in this location will allow common paging logic for both
|
||||
* prefetch and data aborts.
|
||||
*/
|
||||
|
||||
FAR _TCB *tcb = (FAR _TCB *)g_readytorun.head;
|
||||
tcb->xcp.far = regs[REG_R15];
|
||||
|
||||
/* Call pg_miss() to schedule the page fill. A consequences of this
|
||||
* call are:
|
||||
*
|
||||
* (1) The currently executing task will be blocked and saved on
|
||||
* on the g_waitingforfill task list.
|
||||
* (2) An interrupt-level context switch will occur so that when
|
||||
* this function returns, it will return to a different task,
|
||||
* most likely the page fill worker thread.
|
||||
* (3) The page fill worker task has been signalled and should
|
||||
* execute immediately when we return from this exception.
|
||||
*/
|
||||
|
||||
pg_miss();
|
||||
|
||||
/* Restore the previous value of current_regs. NULL would indicate that
|
||||
* we are no longer in an interrupt handler. It will be non-NULL if we
|
||||
* are returning from a nested interrupt.
|
||||
*/
|
||||
|
||||
current_regs = savestate;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
lldbg("Prefetch abort. PC: %08x\n", regs[REG_PC]);
|
||||
PANIC(OSERR_ERREXCEPTION);
|
||||
}
|
||||
}
|
|
@ -1,132 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_releasepending.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <sched.h>
|
||||
#include <debug.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_release_pending
|
||||
*
|
||||
* Description:
|
||||
* Release and ready-to-run tasks that have
|
||||
* collected in the pending task list. This can call a
|
||||
* context switch if a new task is placed at the head of
|
||||
* the ready to run list.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_release_pending(void)
|
||||
{
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
|
||||
slldbg("From TCB=%p\n", rtcb);
|
||||
|
||||
/* Merge the g_pendingtasks list into the g_readytorun task list */
|
||||
|
||||
/* sched_lock(); */
|
||||
if (sched_mergepending())
|
||||
{
|
||||
/* The currently active task has changed! We will need to
|
||||
* switch contexts. First check if we are operating in
|
||||
* interrupt context:
|
||||
*/
|
||||
|
||||
if (current_regs)
|
||||
{
|
||||
/* Yes, then we have to do things differently.
|
||||
* Just copy the current_regs into the OLD rtcb.
|
||||
*/
|
||||
|
||||
up_savestate(rtcb->xcp.regs);
|
||||
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
slldbg("New Active Task TCB=%p\n", rtcb);
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_restorestate(rtcb->xcp.regs);
|
||||
}
|
||||
|
||||
/* Copy the exception context into the TCB of the task that
|
||||
* was currently active. if up_saveusercontext returns a non-zero
|
||||
* value, then this is really the previously running task
|
||||
* restarting!
|
||||
*/
|
||||
|
||||
else if (!up_saveusercontext(rtcb->xcp.regs))
|
||||
{
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
slldbg("New Active Task TCB=%p\n", rtcb);
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_fullcontextrestore(rtcb->xcp.regs);
|
||||
}
|
||||
}
|
||||
}
|
|
@ -1,187 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_reprioritizertr.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <sched.h>
|
||||
#include <debug.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_reprioritize_rtr
|
||||
*
|
||||
* Description:
|
||||
* Called when the priority of a running or
|
||||
* ready-to-run task changes and the reprioritization will
|
||||
* cause a context switch. Two cases:
|
||||
*
|
||||
* 1) The priority of the currently running task drops and the next
|
||||
* task in the ready to run list has priority.
|
||||
* 2) An idle, ready to run task's priority has been raised above the
|
||||
* the priority of the current, running task and it now has the
|
||||
* priority.
|
||||
*
|
||||
* Inputs:
|
||||
* tcb: The TCB of the task that has been reprioritized
|
||||
* priority: The new task priority
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
|
||||
{
|
||||
/* Verify that the caller is sane */
|
||||
|
||||
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
|
||||
tcb->task_state > LAST_READY_TO_RUN_STATE
|
||||
#if SCHED_PRIORITY_MIN > 0
|
||||
|| priority < SCHED_PRIORITY_MIN
|
||||
#endif
|
||||
#if SCHED_PRIORITY_MAX < UINT8_MAX
|
||||
|| priority > SCHED_PRIORITY_MAX
|
||||
#endif
|
||||
)
|
||||
{
|
||||
PANIC(OSERR_BADREPRIORITIZESTATE);
|
||||
}
|
||||
else
|
||||
{
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
bool switch_needed;
|
||||
|
||||
slldbg("TCB=%p PRI=%d\n", tcb, priority);
|
||||
|
||||
/* Remove the tcb task from the ready-to-run list.
|
||||
* sched_removereadytorun will return true if we just
|
||||
* remove the head of the ready to run list.
|
||||
*/
|
||||
|
||||
switch_needed = sched_removereadytorun(tcb);
|
||||
|
||||
/* Setup up the new task priority */
|
||||
|
||||
tcb->sched_priority = (uint8_t)priority;
|
||||
|
||||
/* Return the task to the specified blocked task list.
|
||||
* sched_addreadytorun will return true if the task was
|
||||
* added to the new list. We will need to perform a context
|
||||
* switch only if the EXCLUSIVE or of the two calls is non-zero
|
||||
* (i.e., one and only one the calls changes the head of the
|
||||
* ready-to-run list).
|
||||
*/
|
||||
|
||||
switch_needed ^= sched_addreadytorun(tcb);
|
||||
|
||||
/* Now, perform the context switch if one is needed */
|
||||
|
||||
if (switch_needed)
|
||||
{
|
||||
/* If we are going to do a context switch, then now is the right
|
||||
* time to add any pending tasks back into the ready-to-run list.
|
||||
* task list now
|
||||
*/
|
||||
|
||||
if (g_pendingtasks.head)
|
||||
{
|
||||
sched_mergepending();
|
||||
}
|
||||
|
||||
/* Are we in an interrupt handler? */
|
||||
|
||||
if (current_regs)
|
||||
{
|
||||
/* Yes, then we have to do things differently.
|
||||
* Just copy the current_regs into the OLD rtcb.
|
||||
*/
|
||||
|
||||
up_savestate(rtcb->xcp.regs);
|
||||
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
slldbg("New Active Task TCB=%p\n", rtcb);
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_restorestate(rtcb->xcp.regs);
|
||||
}
|
||||
|
||||
/* Copy the exception context into the TCB at the (old) head of the
|
||||
* g_readytorun Task list. if up_saveusercontext returns a non-zero
|
||||
* value, then this is really the previously running task restarting!
|
||||
*/
|
||||
|
||||
else if (!up_saveusercontext(rtcb->xcp.regs))
|
||||
{
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
slldbg("New Active Task TCB=%p\n", rtcb);
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_fullcontextrestore(rtcb->xcp.regs);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
|
@ -1,119 +0,0 @@
|
|||
/**************************************************************************
|
||||
* arch/arm/src/arm/up_saveusercontext.S
|
||||
*
|
||||
* Copyright (C) 2007, 2009 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/irq.h>
|
||||
#include "up_internal.h"
|
||||
|
||||
/**************************************************************************
|
||||
* Private Definitions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Types
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Function Prototypes
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Global Variables
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Variables
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Functions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Public Functions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Name: up_saveusercontext
|
||||
**************************************************************************/
|
||||
|
||||
.text
|
||||
.globl up_saveusercontext
|
||||
.type up_saveusercontext, function
|
||||
up_saveusercontext:
|
||||
/* On entry, a1 (r0) holds address of struct xcptcontext.
|
||||
* Offset to the user region.
|
||||
*/
|
||||
|
||||
/* Make sure that the return value will be non-zero (the
|
||||
* value of the other volatile registers don't matter --
|
||||
* r1-r3, ip). This function is called throught the
|
||||
* noraml C calling conventions and the values of these
|
||||
* registers cannot be assumed at the point of setjmp
|
||||
* return.
|
||||
*/
|
||||
|
||||
mov ip, #1
|
||||
str ip, [r0, #(4*REG_R0)]
|
||||
|
||||
/* Save the volatile registers (plus r12 which really
|
||||
* doesn't need to be saved)
|
||||
*/
|
||||
|
||||
add r1, r0, #(4*REG_R4)
|
||||
stmia r1, {r4-r14}
|
||||
|
||||
/* Save the current cpsr */
|
||||
|
||||
mrs r2, cpsr /* R3 = CPSR value */
|
||||
add r1, r0, #(4*REG_CPSR)
|
||||
str r2, [r1]
|
||||
|
||||
/* Finally save the return address as the PC so that we
|
||||
* return to the exit from this function.
|
||||
*/
|
||||
|
||||
add r1, r0, #(4*REG_PC)
|
||||
str lr, [r1]
|
||||
|
||||
/* Return 0 */
|
||||
|
||||
mov r0, #0 /* Return value == 0 */
|
||||
mov pc, lr /* Return */
|
||||
.size up_saveusercontext, . - up_saveusercontext
|
||||
|
|
@ -1,204 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_schedulesigaction.c
|
||||
*
|
||||
* Copyright (C) 2007-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 <stdint.h>
|
||||
#include <sched.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#ifndef CONFIG_DISABLE_SIGNALS
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_schedule_sigaction
|
||||
*
|
||||
* Description:
|
||||
* This function is called by the OS when one or more
|
||||
* signal handling actions have been queued for execution.
|
||||
* The architecture specific code must configure things so
|
||||
* that the 'igdeliver' callback is executed on the thread
|
||||
* specified by 'tcb' as soon as possible.
|
||||
*
|
||||
* This function may be called from interrupt handling logic.
|
||||
*
|
||||
* This operation should not cause the task to be unblocked
|
||||
* nor should it cause any immediate execution of sigdeliver.
|
||||
* Typically, a few cases need to be considered:
|
||||
*
|
||||
* (1) This function may be called from an interrupt handler
|
||||
* During interrupt processing, all xcptcontext structures
|
||||
* should be valid for all tasks. That structure should
|
||||
* be modified to invoke sigdeliver() either on return
|
||||
* from (this) interrupt or on some subsequent context
|
||||
* switch to the recipient task.
|
||||
* (2) If not in an interrupt handler and the tcb is NOT
|
||||
* the currently executing task, then again just modify
|
||||
* the saved xcptcontext structure for the recipient
|
||||
* task so it will invoke sigdeliver when that task is
|
||||
* later resumed.
|
||||
* (3) If not in an interrupt handler and the tcb IS the
|
||||
* currently executing task -- just call the signal
|
||||
* handler now.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
|
||||
{
|
||||
/* Refuse to handle nested signal actions */
|
||||
|
||||
sdbg("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver);
|
||||
|
||||
if (!tcb->xcp.sigdeliver)
|
||||
{
|
||||
irqstate_t flags;
|
||||
|
||||
/* Make sure that interrupts are disabled */
|
||||
|
||||
flags = irqsave();
|
||||
|
||||
/* First, handle some special cases when the signal is
|
||||
* being delivered to the currently executing task.
|
||||
*/
|
||||
|
||||
sdbg("rtcb=0x%p current_regs=0x%p\n", g_readytorun.head, current_regs);
|
||||
|
||||
if (tcb == (_TCB*)g_readytorun.head)
|
||||
{
|
||||
/* CASE 1: We are not in an interrupt handler and
|
||||
* a task is signalling itself for some reason.
|
||||
*/
|
||||
|
||||
if (!current_regs)
|
||||
{
|
||||
/* In this case just deliver the signal now. */
|
||||
|
||||
sigdeliver(tcb);
|
||||
}
|
||||
|
||||
/* CASE 2: We are in an interrupt handler AND the
|
||||
* interrupted task is the same as the one that
|
||||
* must receive the signal, then we will have to modify
|
||||
* the return state as well as the state in the TCB.
|
||||
*
|
||||
* Hmmm... there looks like a latent bug here: The following
|
||||
* logic would fail in the strange case where we are in an
|
||||
* interrupt handler, the thread is signalling itself, but
|
||||
* a context switch to another task has occurred so that
|
||||
* current_regs does not refer to the thread at g_readytorun.head!
|
||||
*/
|
||||
|
||||
else
|
||||
{
|
||||
/* Save the return lr and cpsr and one scratch register
|
||||
* These will be restored by the signal trampoline after
|
||||
* the signals have been delivered.
|
||||
*/
|
||||
|
||||
tcb->xcp.sigdeliver = sigdeliver;
|
||||
tcb->xcp.saved_pc = current_regs[REG_PC];
|
||||
tcb->xcp.saved_cpsr = current_regs[REG_CPSR];
|
||||
|
||||
/* Then set up to vector to the trampoline with interrupts
|
||||
* disabled
|
||||
*/
|
||||
|
||||
current_regs[REG_PC] = (uint32_t)up_sigdeliver;
|
||||
current_regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
|
||||
|
||||
/* And make sure that the saved context in the TCB
|
||||
* is the same as the interrupt return context.
|
||||
*/
|
||||
|
||||
up_savestate(tcb->xcp.regs);
|
||||
}
|
||||
}
|
||||
|
||||
/* Otherwise, we are (1) signaling a task is not running
|
||||
* from an interrupt handler or (2) we are not in an
|
||||
* interrupt handler and the running task is signalling
|
||||
* some non-running task.
|
||||
*/
|
||||
|
||||
else
|
||||
{
|
||||
/* Save the return lr and cpsr and one scratch register
|
||||
* These will be restored by the signal trampoline after
|
||||
* the signals have been delivered.
|
||||
*/
|
||||
|
||||
tcb->xcp.sigdeliver = sigdeliver;
|
||||
tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
|
||||
tcb->xcp.saved_cpsr = tcb->xcp.regs[REG_CPSR];
|
||||
|
||||
/* Then set up to vector to the trampoline with interrupts
|
||||
* disabled
|
||||
*/
|
||||
|
||||
tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver;
|
||||
tcb->xcp.regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
|
||||
}
|
||||
|
||||
irqrestore(flags);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* !CONFIG_DISABLE_SIGNALS */
|
|
@ -1,139 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_sigdeliver.c
|
||||
*
|
||||
* Copyright (C) 2007-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 <stdint.h>
|
||||
#include <sched.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#ifndef CONFIG_DISABLE_SIGNALS
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_sigdeliver
|
||||
*
|
||||
* Description:
|
||||
* This is the a signal handling trampoline. When a signal action was
|
||||
* posted. The task context was mucked with and forced to branch to this
|
||||
* location with interrupts disabled.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_sigdeliver(void)
|
||||
{
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
uint32_t regs[XCPTCONTEXT_REGS];
|
||||
sig_deliver_t sigdeliver;
|
||||
|
||||
/* Save the errno. This must be preserved throughout the signal handling
|
||||
* so that the user code final gets the correct errno value (probably
|
||||
* EINTR).
|
||||
*/
|
||||
|
||||
int saved_errno = rtcb->pterrno;
|
||||
|
||||
up_ledon(LED_SIGNAL);
|
||||
|
||||
sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n",
|
||||
rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head);
|
||||
ASSERT(rtcb->xcp.sigdeliver != NULL);
|
||||
|
||||
/* Save the real return state on the stack. */
|
||||
|
||||
up_copystate(regs, rtcb->xcp.regs);
|
||||
regs[REG_PC] = rtcb->xcp.saved_pc;
|
||||
regs[REG_CPSR] = rtcb->xcp.saved_cpsr;
|
||||
|
||||
/* Get a local copy of the sigdeliver function pointer. we do this so that
|
||||
* we can nullify the sigdeliver function pointer in the TCB and accept
|
||||
* more signal deliveries while processing the current pending signals.
|
||||
*/
|
||||
|
||||
sigdeliver = rtcb->xcp.sigdeliver;
|
||||
rtcb->xcp.sigdeliver = NULL;
|
||||
|
||||
/* Then restore the task interrupt state */
|
||||
|
||||
irqrestore(regs[REG_CPSR]);
|
||||
|
||||
/* Deliver the signals */
|
||||
|
||||
sigdeliver(rtcb);
|
||||
|
||||
/* Output any debug messages BEFORE restoring errno (because they may
|
||||
* alter errno), then disable interrupts again and restore the original
|
||||
* errno that is needed by the user logic (it is probably EINTR).
|
||||
*/
|
||||
|
||||
sdbg("Resuming\n");
|
||||
(void)irqsave();
|
||||
rtcb->pterrno = saved_errno;
|
||||
|
||||
/* Then restore the correct state for this thread of execution. */
|
||||
|
||||
up_ledoff(LED_SIGNAL);
|
||||
up_fullcontextrestore(regs);
|
||||
}
|
||||
|
||||
#endif /* !CONFIG_DISABLE_SIGNALS */
|
||||
|
|
@ -1,96 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_syscall.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <stdint.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Output debug info if stack dump is selected -- even if
|
||||
* debug is not selected.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
# undef lldbg
|
||||
# define lldbg lib_lowprintf
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* vectors
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_syscall
|
||||
*
|
||||
* Description:
|
||||
* SWI interrupts will vection here with insn=the SWI
|
||||
* instruction and xcp=the interrupt context
|
||||
*
|
||||
* The handler may get the SWI number be de-referencing
|
||||
* the return address saved in the xcp and decoding
|
||||
* the SWI instruction
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_syscall(uint32_t *regs)
|
||||
{
|
||||
lldbg("Syscall from 0x%x\n", regs[REG_PC]);
|
||||
current_regs = regs;
|
||||
PANIC(OSERR_ERREXCEPTION);
|
||||
}
|
|
@ -1,159 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_unblocktask.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <sched.h>
|
||||
#include <debug.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "clock_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_unblock_task
|
||||
*
|
||||
* Description:
|
||||
* A task is currently in an inactive task list
|
||||
* but has been prepped to execute. Move the TCB to the
|
||||
* ready-to-run list, restore its context, and start execution.
|
||||
*
|
||||
* Inputs:
|
||||
* tcb: Refers to the tcb to be unblocked. This tcb is
|
||||
* in one of the waiting tasks lists. It must be moved to
|
||||
* the ready-to-run list and, if it is the highest priority
|
||||
* ready to run taks, executed.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_unblock_task(_TCB *tcb)
|
||||
{
|
||||
/* Verify that the context switch can be performed */
|
||||
|
||||
if ((tcb->task_state < FIRST_BLOCKED_STATE) ||
|
||||
(tcb->task_state > LAST_BLOCKED_STATE))
|
||||
{
|
||||
PANIC(OSERR_BADUNBLOCKSTATE);
|
||||
}
|
||||
else
|
||||
{
|
||||
_TCB *rtcb = (_TCB*)g_readytorun.head;
|
||||
|
||||
/* Remove the task from the blocked task list */
|
||||
|
||||
sched_removeblocked(tcb);
|
||||
|
||||
/* Reset its timeslice. This is only meaningful for round
|
||||
* robin tasks but it doesn't here to do it for everything
|
||||
*/
|
||||
|
||||
#if CONFIG_RR_INTERVAL > 0
|
||||
tcb->timeslice = CONFIG_RR_INTERVAL / MSEC_PER_TICK;
|
||||
#endif
|
||||
|
||||
/* Add the task in the correct location in the prioritized
|
||||
* g_readytorun task list
|
||||
*/
|
||||
|
||||
if (sched_addreadytorun(tcb))
|
||||
{
|
||||
/* The currently active task has changed! We need to do
|
||||
* a context switch to the new task.
|
||||
*
|
||||
* Are we in an interrupt handler?
|
||||
*/
|
||||
|
||||
if (current_regs)
|
||||
{
|
||||
/* Yes, then we have to do things differently.
|
||||
* Just copy the current_regs into the OLD rtcb.
|
||||
*/
|
||||
|
||||
up_savestate(rtcb->xcp.regs);
|
||||
|
||||
/* Restore the exception context of the rtcb at the (new) head
|
||||
* of the g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_restorestate(rtcb->xcp.regs);
|
||||
}
|
||||
|
||||
/* We are not in an interrupt handler. Copy the user C context
|
||||
* into the TCB of the task that was previously active. if
|
||||
* up_saveusercontext returns a non-zero value, then this is really the
|
||||
* previously running task restarting!
|
||||
*/
|
||||
|
||||
else if (!up_saveusercontext(rtcb->xcp.regs))
|
||||
{
|
||||
/* Restore the exception context of the new task that is ready to
|
||||
* run (probably tcb). This is the new rtcb at the head of the
|
||||
* g_readytorun task list.
|
||||
*/
|
||||
|
||||
rtcb = (_TCB*)g_readytorun.head;
|
||||
|
||||
/* Then switch contexts */
|
||||
|
||||
up_fullcontextrestore(rtcb->xcp.regs);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
|
@ -1,81 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_undefinedinsn.c
|
||||
*
|
||||
* Copyright (C) 2007-2009 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 <stdint.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Output debug info if stack dump is selected -- even if
|
||||
* debug is not selected.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ARCH_STACKDUMP
|
||||
# undef lldbg
|
||||
# define lldbg lib_lowprintf
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_undefinedinsn
|
||||
****************************************************************************/
|
||||
|
||||
void up_undefinedinsn(uint32_t *regs)
|
||||
{
|
||||
lldbg("Undefined instruction at 0x%x\n", regs[REG_PC]);
|
||||
current_regs = regs;
|
||||
PANIC(OSERR_UNDEFINEDINSN);
|
||||
}
|
|
@ -1,121 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_va2pte.c
|
||||
* Utility to map a virtual address to a L2 page table entry.
|
||||
*
|
||||
* 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 <stdint.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/sched.h>
|
||||
#include <nuttx/page.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "pg_macros.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
#ifdef CONFIG_PAGING
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_va2pte()
|
||||
*
|
||||
* Description:
|
||||
* Convert a virtual address within the paged text region into a pointer to
|
||||
* the corresponding page table entry.
|
||||
*
|
||||
* Input Parameters:
|
||||
* vaddr - The virtual address within the paged text region.
|
||||
*
|
||||
* Returned Value:
|
||||
* A pointer to the corresponding page table entry.
|
||||
*
|
||||
* Assumptions:
|
||||
* - This function is called from the normal tasking context (but with
|
||||
* interrupts disabled). The implementation must take whatever actions
|
||||
* are necessary to assure that the operation is safe within this
|
||||
* context.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
uint32_t *up_va2pte(uintptr_t vaddr)
|
||||
{
|
||||
uint32_t L1;
|
||||
uint32_t *L2;
|
||||
unsigned int ndx;
|
||||
|
||||
/* The virtual address is expected to lie in the paged text region */
|
||||
|
||||
DEBUGASSERT(vaddr >= PG_PAGED_VBASE && vaddr < PG_PAGED_VEND);
|
||||
|
||||
/* Get the L1 table entry associated with this virtual address */
|
||||
|
||||
L1 = *(uint32_t*)PG_POOL_VA2L1VADDR(vaddr);
|
||||
|
||||
/* Get the address of the L2 page table from the L1 entry */
|
||||
|
||||
L2 = (uint32_t*)PG_POOL_L12VPTABLE(L1);
|
||||
|
||||
/* Get the index into the L2 page table. Each L1 entry maps
|
||||
* 256 x 4Kb or 1024 x 1Kb pages.
|
||||
*/
|
||||
|
||||
ndx = (vaddr & 0x000fffff) >> PAGESHIFT;
|
||||
|
||||
/* Return true if this virtual address is mapped. */
|
||||
|
||||
return &L2[ndx];
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PAGING */
|
|
@ -1,83 +0,0 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/src/up_vectoraddrexceptn.S
|
||||
*
|
||||
* Copyright (C) 2008-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 <nuttx/irq.h>
|
||||
#include "up_arch.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Global Data
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Assembly Macros
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
.text
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
.text
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_vectoraddrexcption
|
||||
*
|
||||
* Description:
|
||||
* Shouldn't happen. This exception handler is in a separate file from other
|
||||
* vector handlers because some processors (e.g., lpc2148) do not support the
|
||||
* the Address Exception vector.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectoraddrexcptn
|
||||
.type up_vectoraddrexcptn, %function
|
||||
up_vectoraddrexcptn:
|
||||
b up_vectoraddrexcptn
|
||||
.size up_vectoraddrexcptn, . - up_vectoraddrexcptn
|
||||
.end
|
|
@ -1,446 +0,0 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/arm/up_vectors.S
|
||||
*
|
||||
* Copyright (C) 2007-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 <nuttx/irq.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Global Data
|
||||
************************************************************************************/
|
||||
|
||||
.data
|
||||
g_irqtmp:
|
||||
.word 0 /* Saved lr */
|
||||
.word 0 /* Saved spsr */
|
||||
g_undeftmp:
|
||||
.word 0 /* Saved lr */
|
||||
.word 0 /* Saved spsr */
|
||||
g_aborttmp:
|
||||
.word 0 /* Saved lr */
|
||||
.word 0 /* Saved spsr */
|
||||
|
||||
/************************************************************************************
|
||||
* Assembly Macros
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
.text
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
.text
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_vectorirq
|
||||
*
|
||||
* Description:
|
||||
* Interrupt excetpion. Entered in IRQ mode with spsr = SVC CPSR, lr = SVC PC
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectorirq
|
||||
.type up_vectorirq, %function
|
||||
up_vectorirq:
|
||||
/* On entry, we are in IRQ mode. We are free to use
|
||||
* the IRQ mode r13 and r14.
|
||||
*/
|
||||
|
||||
ldr r13, .Lirqtmp
|
||||
sub lr, lr, #4
|
||||
str lr, [r13] @ save lr_IRQ
|
||||
mrs lr, spsr
|
||||
str lr, [r13, #4] @ save spsr_IRQ
|
||||
|
||||
/* Then switch back to SVC mode */
|
||||
|
||||
bic lr, lr, #MODE_MASK /* Keep F and T bits */
|
||||
orr lr, lr, #(SVC_MODE | PSR_I_BIT)
|
||||
msr cpsr_c, lr /* Switch to SVC mode */
|
||||
|
||||
/* Create a context structure. First set aside a stack frame
|
||||
* and store r0-r12 into the frame.
|
||||
*/
|
||||
|
||||
sub sp, sp, #XCPTCONTEXT_SIZE
|
||||
stmia sp, {r0-r12} /* Save the SVC mode regs */
|
||||
|
||||
/* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
|
||||
|
||||
add r1, sp, #XCPTCONTEXT_SIZE
|
||||
mov r2, r14
|
||||
|
||||
/* Get the values for r15(pc) and CPSR in r3 and r4 */
|
||||
|
||||
ldr r0, .Lirqtmp /* Points to temp storage */
|
||||
ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
|
||||
|
||||
add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
|
||||
stmia r0, {r1-r4}
|
||||
|
||||
/* Then call the IRQ handler with interrupts disabled. */
|
||||
|
||||
mov fp, #0 /* Init frame pointer */
|
||||
mov r0, sp /* Get r0=xcp */
|
||||
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
ldr sp, .Lirqstackbase /* SP = interrupt stack base */
|
||||
str r0, [sp] /* Save the user stack pointer */
|
||||
bl up_decodeirq /* Call the handler */
|
||||
ldr sp, [sp] /* Restore the user stack pointer */
|
||||
#else
|
||||
bl up_decodeirq /* Call the handler */
|
||||
#endif
|
||||
|
||||
/* Restore the CPSR, SVC modr registers and return */
|
||||
.Lnoirqset:
|
||||
ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
|
||||
msr spsr, r0
|
||||
ldmia sp, {r0-r15}^ /* Return */
|
||||
|
||||
.Lirqtmp:
|
||||
.word g_irqtmp
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
.Lirqstackbase:
|
||||
.word up_stackbase
|
||||
#endif
|
||||
.size up_vectorirq, . - up_vectorirq
|
||||
.align 5
|
||||
|
||||
/************************************************************************************
|
||||
* Function: up_vectorswi
|
||||
*
|
||||
* Description:
|
||||
* SWI interrupt. We enter the SWI in SVC mode.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectorswi
|
||||
.type up_vectorswi, %function
|
||||
up_vectorswi:
|
||||
|
||||
/* Create a context structure. First set aside a stack frame
|
||||
* and store r0-r12 into the frame.
|
||||
*/
|
||||
|
||||
sub sp, sp, #XCPTCONTEXT_SIZE
|
||||
stmia sp, {r0-r12} /* Save the SVC mode regs */
|
||||
|
||||
/* Get the correct values of r13(sp), r14(lr), r15(pc)
|
||||
* and CPSR in r1-r4 */
|
||||
|
||||
add r1, sp, #XCPTCONTEXT_SIZE
|
||||
mov r2, r14 /* R14 is altered on return from SWI */
|
||||
mov r3, r14 /* Save r14 as the PC as well */
|
||||
mrs r4, spsr /* Get the saved CPSR */
|
||||
|
||||
add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
|
||||
stmia r0, {r1-r4}
|
||||
|
||||
/* Then call the SWI handler with interrupts disabled.
|
||||
* void up_syscall(struct xcptcontext *xcp)
|
||||
*/
|
||||
|
||||
mov fp, #0 /* Init frame pointer */
|
||||
mov r0, sp /* Get r0=xcp */
|
||||
bl up_syscall /* Call the handler */
|
||||
|
||||
/* Restore the CPSR, SVC modr registers and return */
|
||||
|
||||
ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
|
||||
msr spsr, r0
|
||||
ldmia sp, {r0-r15}^ /* Return */
|
||||
.size up_vectorswi, . - up_vectorswi
|
||||
|
||||
.align 5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_vectordata
|
||||
*
|
||||
* Description:
|
||||
* This is the data abort exception dispatcher. The ARM data abort exception occurs
|
||||
* when a memory fault is detected during a data transfer. This handler saves the
|
||||
* current processor state and gives control to data abort handler. This function
|
||||
* is entered in ABORT mode with spsr = SVC CPSR, lr = SVC PC
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectordata
|
||||
.type up_vectordata, %function
|
||||
up_vectordata:
|
||||
/* On entry we are free to use the ABORT mode registers
|
||||
* r13 and r14
|
||||
*/
|
||||
|
||||
ldr r13, .Ldaborttmp /* Points to temp storage */
|
||||
sub lr, lr, #8 /* Fixup return */
|
||||
str lr, [r13] /* Save in temp storage */
|
||||
mrs lr, spsr /* Get SPSR */
|
||||
str lr, [r13, #4] /* Save in temp storage */
|
||||
|
||||
/* Then switch back to SVC mode */
|
||||
|
||||
bic lr, lr, #MODE_MASK /* Keep F and T bits */
|
||||
orr lr, lr, #(SVC_MODE | PSR_I_BIT)
|
||||
msr cpsr_c, lr /* Switch to SVC mode */
|
||||
|
||||
/* Create a context structure. First set aside a stack frame
|
||||
* and store r0-r12 into the frame.
|
||||
*/
|
||||
|
||||
sub sp, sp, #XCPTCONTEXT_SIZE
|
||||
stmia sp, {r0-r12} /* Save the SVC mode regs */
|
||||
|
||||
/* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
|
||||
|
||||
add r1, sp, #XCPTCONTEXT_SIZE
|
||||
mov r2, r14
|
||||
|
||||
/* Get the values for r15(pc) and CPSR in r3 and r4 */
|
||||
|
||||
ldr r0, .Ldaborttmp /* Points to temp storage */
|
||||
ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
|
||||
|
||||
add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
|
||||
stmia r0, {r1-r4}
|
||||
|
||||
/* Then call the data abort handler with interrupts disabled.
|
||||
* void up_dataabort(struct xcptcontext *xcp)
|
||||
*/
|
||||
|
||||
mov fp, #0 /* Init frame pointer */
|
||||
mov r0, sp /* Get r0=xcp */
|
||||
#ifdef CONFIG_PAGING
|
||||
mrc p15, 0, r2, c5, c0, 0 /* Get r2=FSR */
|
||||
mrc p15, 0, r1, c6, c0, 0 /* Get R1=FAR */
|
||||
#endif
|
||||
bl up_dataabort /* Call the handler */
|
||||
|
||||
/* Restore the CPSR, SVC modr registers and return */
|
||||
|
||||
ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
|
||||
msr spsr_cxsf, r0
|
||||
ldmia sp, {r0-r15}^ /* Return */
|
||||
|
||||
.Ldaborttmp:
|
||||
.word g_aborttmp
|
||||
.size up_vectordata, . - up_vectordata
|
||||
|
||||
.align 5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_vectorprefetch
|
||||
*
|
||||
* Description:
|
||||
* This is the prefetch abort exception dispatcher. The ARM prefetch abort exception
|
||||
* occurs when a memory fault is detected during an an instruction fetch. This
|
||||
* handler saves the current processor state and gives control to prefetch abort
|
||||
* handler. This function is entered in ABT mode with spsr = SVC CPSR, lr = SVC PC.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectorprefetch
|
||||
.type up_vectorprefetch, %function
|
||||
up_vectorprefetch:
|
||||
/* On entry we are free to use the ABORT mode registers
|
||||
* r13 and r14
|
||||
*/
|
||||
|
||||
ldr r13, .Lpaborttmp /* Points to temp storage */
|
||||
sub lr, lr, #4 /* Fixup return */
|
||||
str lr, [r13] /* Save in temp storage */
|
||||
mrs lr, spsr /* Get SPSR */
|
||||
str lr, [r13, #4] /* Save in temp storage */
|
||||
|
||||
/* Then switch back to SVC mode */
|
||||
|
||||
bic lr, lr, #MODE_MASK /* Keep F and T bits */
|
||||
orr lr, lr, #(SVC_MODE | PSR_I_BIT)
|
||||
msr cpsr_c, lr /* Switch to SVC mode */
|
||||
|
||||
/* Create a context structure. First set aside a stack frame
|
||||
* and store r0-r12 into the frame.
|
||||
*/
|
||||
|
||||
sub sp, sp, #XCPTCONTEXT_SIZE
|
||||
stmia sp, {r0-r12} /* Save the SVC mode regs */
|
||||
|
||||
/* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
|
||||
|
||||
add r1, sp, #XCPTCONTEXT_SIZE
|
||||
mov r2, r14
|
||||
|
||||
/* Get the values for r15(pc) and CPSR in r3 and r4 */
|
||||
|
||||
ldr r0, .Lpaborttmp /* Points to temp storage */
|
||||
ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
|
||||
|
||||
add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
|
||||
stmia r0, {r1-r4}
|
||||
|
||||
/* Then call the prefetch abort handler with interrupts disabled.
|
||||
* void up_prefetchabort(struct xcptcontext *xcp)
|
||||
*/
|
||||
|
||||
mov fp, #0 /* Init frame pointer */
|
||||
mov r0, sp /* Get r0=xcp */
|
||||
bl up_prefetchabort /* Call the handler */
|
||||
|
||||
/* Restore the CPSR, SVC modr registers and return */
|
||||
|
||||
ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
|
||||
msr spsr_cxsf, r0
|
||||
ldmia sp, {r0-r15}^ /* Return */
|
||||
|
||||
.Lpaborttmp:
|
||||
.word g_aborttmp
|
||||
.size up_vectorprefetch, . - up_vectorprefetch
|
||||
|
||||
.align 5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_vectorundefinsn
|
||||
*
|
||||
* Description:
|
||||
* Undefined instruction entry exception. Entered in UND mode, spsr = SVC CPSR,
|
||||
* lr = SVC PC
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectorundefinsn
|
||||
.type up_vectorundefinsn, %function
|
||||
up_vectorundefinsn:
|
||||
/* On entry we are free to use the UND mode registers
|
||||
* r13 and r14
|
||||
*/
|
||||
|
||||
ldr r13, .Lundeftmp /* Points to temp storage */
|
||||
str lr, [r13] /* Save in temp storage */
|
||||
mrs lr, spsr /* Get SPSR */
|
||||
str lr, [r13, #4] /* Save in temp storage */
|
||||
|
||||
/* Then switch back to SVC mode */
|
||||
|
||||
bic lr, lr, #MODE_MASK /* Keep F and T bits */
|
||||
orr lr, lr, #(SVC_MODE | PSR_I_BIT)
|
||||
msr cpsr_c, lr /* Switch to SVC mode */
|
||||
|
||||
/* Create a context structure. First set aside a stack frame
|
||||
* and store r0-r12 into the frame.
|
||||
*/
|
||||
|
||||
sub sp, sp, #XCPTCONTEXT_SIZE
|
||||
stmia sp, {r0-r12} /* Save the SVC mode regs */
|
||||
|
||||
/* Get the correct values of r13(sp) and r14(lr) in r1 and r2 */
|
||||
|
||||
add r1, sp, #XCPTCONTEXT_SIZE
|
||||
mov r2, r14
|
||||
|
||||
/* Get the values for r15(pc) and CPSR in r3 and r4 */
|
||||
|
||||
ldr r0, .Lundeftmp /* Points to temp storage */
|
||||
ldmia r0, {r3, r4} /* Recover r1=lr_IRQ, r2=spsr_IRQ */
|
||||
|
||||
add r0, sp, #(4*REG_SP) /* Offset to pc, cpsr storage */
|
||||
stmia r0, {r1-r4}
|
||||
|
||||
/* Then call the undef insn handler with interrupts disabled.
|
||||
* void up_undefinedinsn(struct xcptcontext *xcp)
|
||||
*/
|
||||
|
||||
mov fp, #0 /* Init frame pointer */
|
||||
mov r0, sp /* Get r0=xcp */
|
||||
bl up_undefinedinsn /* Call the handler */
|
||||
|
||||
/* Restore the CPSR, SVC modr registers and return */
|
||||
|
||||
ldr r0, [sp, #(4*REG_CPSR)] /* Setup the SVC mode SPSR */
|
||||
msr spsr_cxsf, r0
|
||||
ldmia sp, {r0-r15}^ /* Return */
|
||||
|
||||
.Lundeftmp:
|
||||
.word g_undeftmp
|
||||
.size up_vectorundefinsn, . - up_vectorundefinsn
|
||||
|
||||
.align 5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_vectorfiq
|
||||
*
|
||||
* Description:
|
||||
* Shouldn't happen
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
.globl up_vectorfiq
|
||||
.type up_vectorfiq, %function
|
||||
up_vectorfiq:
|
||||
subs pc, lr, #4
|
||||
.size up_vectorfiq, . - up_vectorfiq
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_interruptstack/g_userstack
|
||||
************************************************************************************/
|
||||
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
.bss
|
||||
.align 4
|
||||
.globl g_userstack
|
||||
.type g_userstack, object
|
||||
up_interruptstack:
|
||||
.skip ((CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4)
|
||||
g_userstack:
|
||||
up_stackbase:
|
||||
.skip 4
|
||||
.size g_userstack, 4
|
||||
.size up_interruptstack, (CONFIG_ARCH_INTERRUPTSTACK & ~3)
|
||||
#endif
|
||||
.end
|
|
@ -1,103 +0,0 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/arm/up_vectortab.S
|
||||
*
|
||||
* Copyright (C) 2007, 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>
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Global Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Assembly Macros
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: _vector_start
|
||||
*
|
||||
* Description:
|
||||
* Vector initialization block
|
||||
****************************************************************************/
|
||||
|
||||
.globl _vector_start
|
||||
|
||||
/* These will be relocated to VECTOR_BASE. */
|
||||
|
||||
_vector_start:
|
||||
ldr pc, .Lresethandler /* 0x00: Reset */
|
||||
ldr pc, .Lundefinedhandler /* 0x04: Undefined instruction */
|
||||
ldr pc, .Lswihandler /* 0x08: Software interrupt */
|
||||
ldr pc, .Lprefetchaborthandler /* 0x0c: Prefetch abort */
|
||||
ldr pc, .Ldataaborthandler /* 0x10: Data abort */
|
||||
ldr pc, .Laddrexcptnhandler /* 0x14: Address exception */
|
||||
ldr pc, .Lirqhandler /* 0x18: IRQ */
|
||||
ldr pc, .Lfiqhandler /* 0x1c: FIQ */
|
||||
|
||||
.globl __start
|
||||
.globl up_vectorundefinsn
|
||||
.globl up_vectorswi
|
||||
.globl up_vectorprefetch
|
||||
.globl up_vectordata
|
||||
.globl up_vectoraddrexcptn
|
||||
.globl up_vectorirq
|
||||
.globl up_vectorfiq
|
||||
|
||||
.Lresethandler:
|
||||
.long __start
|
||||
.Lundefinedhandler:
|
||||
.long up_vectorundefinsn
|
||||
.Lswihandler:
|
||||
.long up_vectorswi
|
||||
.Lprefetchaborthandler:
|
||||
.long up_vectorprefetch
|
||||
.Ldataaborthandler:
|
||||
.long up_vectordata
|
||||
.Laddrexcptnhandler:
|
||||
.long up_vectoraddrexcptn
|
||||
.Lirqhandler:
|
||||
.long up_vectorirq
|
||||
.Lfiqhandler:
|
||||
.long up_vectorfiq
|
||||
|
||||
.globl _vector_end
|
||||
_vector_end:
|
||||
.end
|
Loading…
Reference in New Issue