summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-07-27 09:27:37 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-07-27 09:27:37 -0600
commit14abdf844c33ace2a8616acaddb6babee58bcaac (patch)
treef7626e23796710352143f837fb312008e247535f
parent94180157df88ff16132699cae16ef22c91cda5a3 (diff)
downloadpx4-nuttx-14abdf844c33ace2a8616acaddb6babee58bcaac.tar.gz
px4-nuttx-14abdf844c33ace2a8616acaddb6babee58bcaac.tar.bz2
px4-nuttx-14abdf844c33ace2a8616acaddb6babee58bcaac.zip
SAMA5 page table is cached; need to flush the cache each time that the page table is updated
-rwxr-xr-xnuttx/arch/arm/src/armv7-a/arm_cache.S663
-rw-r--r--nuttx/arch/arm/src/armv7-a/cache.h73
-rw-r--r--nuttx/arch/arm/src/armv7-a/cp15.h7
-rw-r--r--nuttx/arch/arm/src/sama5/sam_boot.c9
-rw-r--r--nuttx/sched/os_start.c4
5 files changed, 394 insertions, 362 deletions
diff --git a/nuttx/arch/arm/src/armv7-a/arm_cache.S b/nuttx/arch/arm/src/armv7-a/arm_cache.S
index 2b6b93a56..79b3703e7 100755
--- a/nuttx/arch/arm/src/armv7-a/arm_cache.S
+++ b/nuttx/arch/arm/src/armv7-a/arm_cache.S
@@ -1,318 +1,345 @@
-/****************************************************************************
- * arch/arm/src/armv7-a/arm_cache.S
- *
- * Copyright (C) 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * References:
- *
- * "Cortex-A5™ MPCore, Technical Reference Manual", Revision: r0p1,
- * Copyright © 2010 ARM. All rights reserved. ARM DDI 0434B (ID101810)
- * "ARM® Architecture Reference Manual, ARMv7-A and ARMv7-R edition",
- * Copyright © 1996-1998, 2000, 2004-2012 ARM. All rights reserved. ARM
- * DDI 0406C.b (ID072512)
- *
- * Portions of this file derive from Atmel sample code for the SAMA5D3 Cortex-A5
- * which also has a modified BSD-style license:
- *
- * Copyright (c) 2012, Atmel Corporation
- * All rights reserved.
- *
- * 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 Atmel nor the names of the 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.
- *
- ****************************************************************************/
-
-/* cp15_cache Cache Operations
- *
- * Usage
- *
- * They are performed as MCR instructions and only operate on a level 1 cache
- * associated with ARM v7 processor.
- *
- * The supported operations are:
- *
- * 1. Any of these operations can be applied to any data cache or any
- * unified cache.
- * 2. Invalidate by MVA. Performs an invalidate of a data or unified cache
- * line
- * based on the address it contains.
- * 3. Invalidate by set/way. Performs an invalidate of a data or unified
- * cache line based on its location in the cache hierarchy.
- * 4. Clean by MVA. Performs a clean of a data or unified cache line based
- * on the address it contains.
- * 5. Clean by set/way. Performs a clean of a data or unified cache line
- * based on its location in the cache hierarchy.
- * 6. Clean and Invalidate by MVA. Performs a clean and invalidate of a
- * data or unified cache line based on the address it contains.
- * 7. Clean and Invalidate by set/way. Performs a clean and invalidate of
- * a data or unified cache line based on its location in the cache
- * hierarchy.
- *
- * NOTE: Many of these operations are implemented as assembly language
- * macros or as C inline functions in the file cache.h. The larger functions
- * are implemented here as C-callable functions.
- */
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
- .file "arm_cache.S"
-
-/****************************************************************************
- * Preprocessor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Symbols
- ****************************************************************************/
-
- .globl cp15_coherent_dcache_for_dma
- .globl cp15_invalidate_dcache_for_dma
- .globl cp15_clean_dcache_for_dma
- .globl cp15_flush_dcache_for_dma
- .globl cp15_flush_kern_dcache_for_dma
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
- .text
-
-/****************************************************************************
- * Name: cp15_coherent_dcache_for_dma
- *
- * Description:
- * Ensure that the I and D caches are coherent within specified region.
- * This is typically used when code has been written to a memory region,
- * and will be executed.
- *
- * Input Parameters:
- * start - virtual start address of region
- * end - virtual end address of region
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
- .globl cp15_coherent_dcache_for_dma
- .type cp15_coherent_dcache_for_dma, function
-
-cp15_coherent_dcache_for_dma:
-
- mrc p15, 0, r3, c0, c0, 1
- lsr r3, r3, #16
- and r3, r3, #0xf
- mov r2, #4
- mov r2, r2, lsl r3
-
- sub r3, r2, #1
- bic r12, r0, r3
-1:
- mcr p15, 0, r12, c7, c11, 1
- add r12, r12, r2
- cmp r12, r1
- blo 1b
- dsb
-
- mrc p15, 0, r3, c0, c0, 1
- and r3, r3, #0xf
- mov r2, #4
- mov r2, r2, lsl r3
-
- sub r3, r2, #1
- bic r12, r0, r3
-2:
- mcr p15, 0, r12, c7, c5, 1
- add r12, r12, r2
- cmp r12, r1
- blo 2b
- mov r0, #0
- mcr p15, 0, r0, c7, c1, 6
- mcr p15, 0, r0, c7, c5, 6
- dsb
- isb
- bx lr
- .size cp15_coherent_dcache_for_dma, . - cp15_coherent_dcache_for_dma
-
-/****************************************************************************
- * Name: cp15_invalidate_dcache_for_dma
- *
- * Description:
- * Invalidate the data cache within the specified region; we will be
- * performing a DMA operation in this region and we want to purge old data
- * in the cache.
- *
- * Input Parameters:
- * start - virtual start address of region
- * end - virtual end address of region
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
- .globl cp15_invalidate_dcache_for_dma
- .type cp15_invalidate_dcache_for_dma, function
-
-cp15_invalidate_dcache_for_dma:
-
- mrc p15, 0, r3, c0, c0, 1
- lsr r3, r3, #16
- and r3, r3, #0xf
- mov r2, #4
- mov r2, r2, lsl r3
-
- sub r3, r2, #1
- tst r0, r3
- bic r0, r0, r3
-
- mcrne p15, 0, r0, c7, c14, 1
-
- tst r1, r3
- bic r1, r1, r3
- mcrne p15, 0, r1, c7, c14, 1
-3:
- mcr p15, 0, r0, c7, c6, 1
- add r0, r0, r2
- cmp r0, r1
- blo 3b
- dsb
- bx lr
- .size cp15_coherent_dcache_for_dma, . - cp15_coherent_dcache_for_dma
-
-/****************************************************************************
- * Name: cp15_clean_dcache_for_dma
- *
- * Description:
- * Clean the data cache within the specified region
- *
- * Input Parameters:
- * start - virtual start address of region
- * end - virtual end address of region
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
- .globl cp15_clean_dcache_for_dma
- .type cp15_clean_dcache_for_dma, function
-
-cp15_clean_dcache_for_dma:
- mrc p15, 0, r3, c0, c0, 1
- lsr r3, r3, #16
- and r3, r3, #0xf
- mov r2, #4
- mov r2, r2, lsl r3
-
- sub r3, r2, #1
- bic r0, r0, r3
-4:
- mcr p15, 0, r0, c7, c10, 1
- add r0, r0, r2
- cmp r0, r1
- blo 4b
- dsb
- bx lr
- .size cp15_clean_dcache_for_dma, . - cp15_clean_dcache_for_dma
-
-/****************************************************************************
- * Name: cp15_flush_dcache_for_dma
- *
- * Description:
- * Flush the data cache within the specified region
- *
- * Input Parameters:
- * start - virtual start address of region
- * end - virtual end address of region
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
- .globl cp15_flush_dcache_for_dma
- .type cp15_flush_dcache_for_dma, function
-
-cp15_flush_dcache_for_dma:
- mrc p15, 0, r3, c0, c0, 1
- lsr r3, r3, #16
- and r3, r3, #0xf
- mov r2, #4
- mov r2, r2, lsl r3
- sub r3, r2, #1
- bic r0, r0, r3
-5:
- mcr p15, 0, r0, c7, c14, 1
- add r0, r0, r2
- cmp r0, r1
- blo 5b
- dsb
- bx lr
- .size cp15_flush_dcache_for_dma, . - cp15_flush_dcache_for_dma
-
-/****************************************************************************
- * Name: cp15_flush_kern_dcache_for_dma
- *
- * Description:
- * Ensure that the data held in the page kaddr is written back to the page
- * in question.
- *
- * Input Parameters:
- * start - virtual start address of region
- * end - virtual end address of region
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
- .globl cp15_flush_kern_dcache_for_dma
- .type cp15_flush_kern_dcache_for_dma, function
-
-cp15_flush_kern_dcache_for_dma:
- mrc p15, 0, r3, c0, c0, 1
- lsr r3, r3, #16
- and r3, r3, #0xf
- mov r2, #4
- mov r2, r2, lsl r3
-
- add r1, r0, r1
- sub r3, r2, #1
- bic r0, r0, r3
-
- mcr p15, 0, r0, c7, c14, 1
- add r0, r0, r2
- cmp r0, r1
- blo 1b
- dsb
- bx lr
- .size cp15_flush_kern_dcache_for_dma, . - cp15_flush_kern_dcache_for_dma
- .end
+/****************************************************************************
+ * arch/arm/src/armv7-a/arm_cache.S
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References:
+ *
+ * "Cortex-A5™ MPCore, Technical Reference Manual", Revision: r0p1,
+ * Copyright © 2010 ARM. All rights reserved. ARM DDI 0434B (ID101810)
+ * "ARM® Architecture Reference Manual, ARMv7-A and ARMv7-R edition",
+ * Copyright © 1996-1998, 2000, 2004-2012 ARM. All rights reserved. ARM
+ * DDI 0406C.b (ID072512)
+ *
+ * Portions of this file derive from Atmel sample code for the SAMA5D3 Cortex-A5
+ * which also has a modified BSD-style license:
+ *
+ * Copyright (c) 2012, Atmel Corporation
+ * All rights reserved.
+ *
+ * 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 Atmel nor the names of the 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.
+ *
+ ****************************************************************************/
+
+/* cp15_cache Cache Operations
+ *
+ * Usage
+ *
+ * They are performed as MCR instructions and only operate on a level 1 cache
+ * associated with ARM v7 processor.
+ *
+ * The supported operations are:
+ *
+ * 1. Any of these operations can be applied to any data cache or any
+ * unified cache.
+ * 2. Invalidate by MVA. Performs an invalidate of a data or unified cache
+ * line
+ * based on the address it contains.
+ * 3. Invalidate by set/way. Performs an invalidate of a data or unified
+ * cache line based on its location in the cache hierarchy.
+ * 4. Clean by MVA. Performs a clean of a data or unified cache line based
+ * on the address it contains.
+ * 5. Clean by set/way. Performs a clean of a data or unified cache line
+ * based on its location in the cache hierarchy.
+ * 6. Clean and Invalidate by MVA. Performs a clean and invalidate of a
+ * data or unified cache line based on the address it contains.
+ * 7. Clean and Invalidate by set/way. Performs a clean and invalidate of
+ * a data or unified cache line based on its location in the cache
+ * hierarchy.
+ *
+ * NOTE: Many of these operations are implemented as assembly language
+ * macros or as C inline functions in the file cache.h. The larger functions
+ * are implemented here as C-callable functions.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include "cp15.h"
+
+ .file "arm_cache.S"
+
+/****************************************************************************
+ * Preprocessor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Symbols
+ ****************************************************************************/
+
+ .globl cp15_coherent_dcache_for_dma
+ .globl cp15_invalidate_dcache_for_dma
+ .globl cp15_clean_dcache_for_dma
+ .globl cp15_flush_dcache_for_dma
+ .globl cp15_flush_kern_dcache_for_dma
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+ .text
+
+/****************************************************************************
+ * Name: cp15_coherent_dcache_for_dma
+ *
+ * Description:
+ * Ensure that the I and D caches are coherent within specified region
+ * by cleaning the D cache (i.e., flushing the D cache contents to memory
+ * and invalidating the I cache. This is typically used when code has been
+ * written to a memory region, and will be executed.
+ *
+ * Input Parameters:
+ * start - virtual start address of region
+ * end - virtual end address of region
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+ .globl cp15_coherent_dcache_for_dma
+ .type cp15_coherent_dcache_for_dma, function
+
+cp15_coherent_dcache_for_dma:
+ mrc CP15_TR(r3) /* Read the Cache Type Register */
+ lsr r3, r3, #16 /* Isolate the DMinLine field */
+ and r3, r3, #0xf
+ mov r2, #4
+ mov r2, r2, lsl r3 /* Get the cache line size in bytes */
+
+ sub r3, r2, #1 /* R3=Cache line size mask */
+ bic r12, r0, r3 /* R12=aligned start address */
+
+ /* Loop, flushing each D cache line to memory */
+1:
+ mcr CP15_DCCMVAU(r12) /* Clean data or unified cache line by VA to PoU */
+ add r12, r12, r2 /* R12=Next cache line */
+ cmp r12, r1 /* Loop until all cache lines have been cleaned */
+ blo 1b
+
+ dsb
+
+ mrc CP15_TR(r3) /* Read the Cache Type Register */
+ and r3, r3, #0xf /* Isolate the IminLine field */
+ mov r2, #4
+ mov r2, r2, lsl r3 /* Get the cache line size in bytes */
+
+ sub r3, r2, #1 /* R3=Cache line size mask */
+ bic r12, r0, r3 /* R12=aligned start address */
+
+ /* Loop, invalidating each I cache line to memory */
+2:
+ mcr CP15_ICIMVAU(r12) /* Invalidate instruction cache by VA to PoU */
+ add r12, r12, r2 /* R12=Next cache line */
+ cmp r12, r1 /* Loop until all cache lines have been invalidated */
+ blo 2b
+
+ mov r0, #0
+ mcr CP15_BPIALLIS(r0) /* Invalidate entire branch predictor array Inner Shareable */
+ mcr CP15_BPIALL(r0) /* Invalidate entire branch predictor array Inner Shareable */
+
+ dsb
+ isb
+ bx lr
+ .size cp15_coherent_dcache_for_dma, . - cp15_coherent_dcache_for_dma
+
+/****************************************************************************
+ * Name: cp15_invalidate_dcache_for_dma
+ *
+ * Description:
+ * Invalidate the data cache within the specified region; we will be
+ * performing a DMA operation in this region and we want to purge old data
+ * in the cache.
+ *
+ * Input Parameters:
+ * start - virtual start address of region
+ * end - virtual end address of region
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+ .globl cp15_invalidate_dcache_for_dma
+ .type cp15_invalidate_dcache_for_dma, function
+
+cp15_invalidate_dcache_for_dma:
+
+ mrc CP15_TR(r3) /* Read the Cache Type Register */
+ lsr r3, r3, #16 /* Isolate the DMinLine field */
+ and r3, r3, #0xf
+ mov r2, #4
+ mov r2, r2, lsl r3 /* Get the cache line size in bytes */
+
+ sub r3, r2, #1 /* R3=Cache line size mask */
+ tst r0, r3
+ bic r0, r0, r3 /* R0=aligned start address */
+
+ mcrne CP15_DCCIMVAC(r0) /* Clean and invalidate data cache line by VA to PoC */
+
+ tst r1, r3
+ bic r1, r1, r3 /* R0=aligned end address */
+ mcrne CP15_DCCIMVAC(r1) /* Clean and invalidate data cache line by VA to PoC */
+
+ /* Loop, invalidating each D cache line */
+3:
+ mcr CP15_DCIMVAC(r0) /* Invalidate data cache line by VA to PoC */
+ add r0, r0, r2 /* R12=Next cache line */
+ cmp r0, r1 /* Loop until all cache lines have been invalidate */
+ blo 3b
+
+ dsb
+ bx lr
+ .size cp15_coherent_dcache_for_dma, . - cp15_coherent_dcache_for_dma
+
+/****************************************************************************
+ * Name: cp15_clean_dcache_for_dma
+ *
+ * Description:
+ * Clean the data cache within the specified region by flushing the
+ * contents of the data cache to memory.
+ *
+ * Input Parameters:
+ * start - virtual start address of region
+ * end - virtual end address of region
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+ .globl cp15_clean_dcache_for_dma
+ .type cp15_clean_dcache_for_dma, function
+
+cp15_clean_dcache_for_dma:
+
+ mrc CP15_TR(r3) /* Read the Cache Type Register */
+ lsr r3, r3, #16 /* Isolate the DMinLine field */
+ and r3, r3, #0xf
+ mov r2, #4
+ mov r2, r2, lsl r3 /* Get the cache line size in bytes */
+
+ sub r3, r2, #1 /* R3=Cache line size mask */
+ bic r12, r0, r3 /* R12=aligned start address */
+
+ /* Loop, cleaning each cache line by writing its contents to memory */
+
+4:
+ mcr CP15_DCCMVAC(r0) /* Clean data cache line to PoC by VA */
+ add r0, r0, r2 /* R12=Next cache line */
+ cmp r0, r1 /* Loop until all cache lines have been cleaned */
+ blo 4b
+
+ dsb
+ bx lr
+ .size cp15_clean_dcache_for_dma, . - cp15_clean_dcache_for_dma
+
+/****************************************************************************
+ * Name: cp15_flush_dcache_for_dma
+ *
+ * Description:
+ * Flush the data cache within the specified region by cleaning and
+ * invalidating the the D cache.
+ *
+ * Input Parameters:
+ * start - virtual start address of region
+ * end - virtual end address of region
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+ .globl cp15_flush_dcache_for_dma
+ .type cp15_flush_dcache_for_dma, function
+
+cp15_flush_dcache_for_dma:
+
+ mrc CP15_TR(r3) /* Read the Cache Type Register */
+ lsr r3, r3, #16 /* Isolate the DMinLine field */
+ and r3, r3, #0xf
+ mov r2, #4
+ mov r2, r2, lsl r3 /* Get the cache line size in bytes */
+
+ sub r3, r2, #1 /* R3=Cache line size mask */
+ bic r12, r0, r3 /* R12=aligned start address */
+
+ /* Loop, cleaning and invaliding each D cache line in the address range */
+
+5:
+ mcrne CP15_DCCIMVAC(r0) /* Clean and invalidate data cache line by VA to PoC */
+ add r0, r0, r2 /* R12=Next cache line */
+ cmp r0, r1 /* Loop until all cache lines have been cleaned */
+ blo 5b
+
+ dsb
+ bx lr
+ .size cp15_flush_dcache_for_dma, . - cp15_flush_dcache_for_dma
+
+/****************************************************************************
+ * Name: cp15_flush_kern_dcache_for_dma
+ *
+ * Description:
+ * Ensure that the data held in the page kaddr is written back to the page
+ * in question.
+ *
+ * Input Parameters:
+ * start - virtual start address of region
+ * end - virtual end address of region
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+ .globl cp15_flush_kern_dcache_for_dma
+ .type cp15_flush_kern_dcache_for_dma, function
+
+cp15_flush_kern_dcache_for_dma:
+
+ mrc CP15_TR(r3) /* Read the Cache Type Register */
+ lsr r3, r3, #16 /* Isolate the DMinLine field */
+ and r3, r3, #0xf
+ mov r2, #4
+ mov r2, r2, lsl r3 /* Get the cache line size in bytes */
+
+ add r1, r0, r1
+ sub r3, r2, #1 /* R3=Cache line size mask */
+ bic r0, r0, r3 /* R0=aligned start address */
+
+ mcrne CP15_DCCIMVAC(r0) /* Clean and invalidate data cache line by VA to PoC */
+ add r0, r0, r2 /* R12=Next cache line */
+ cmp r0, r1 /* Loop until all cache lines have been cleaned */
+ blo 1b /* Merge with loop flushing each D cache line to memory */
+
+ dsb
+ bx lr
+ .size cp15_flush_kern_dcache_for_dma, . - cp15_flush_kern_dcache_for_dma
+ .end
diff --git a/nuttx/arch/arm/src/armv7-a/cache.h b/nuttx/arch/arm/src/armv7-a/cache.h
index b5a121001..76982153d 100644
--- a/nuttx/arch/arm/src/armv7-a/cache.h
+++ b/nuttx/arch/arm/src/armv7-a/cache.h
@@ -179,7 +179,7 @@
.macro cp15_invalidate_icache_inner_sharable, tmp
mov \tmp, #0
- mrc p15, 0, \tmp, c7, c1, 0
+ mrc p15, 0, \tmp, c7, c1, 0 /* ICIALLUIS */
.endm
/************************************************************************************
@@ -198,7 +198,7 @@
.macro cp15_invalidate_btb_inner_sharable, tmp
mov \tmp, #0
- mrc p15, 0, \tmp, c7, c1, 6
+ mrc p15, 0, \tmp, c7, c1, 6 /* BPIALLIS */
.endm
/************************************************************************************
@@ -217,7 +217,7 @@
.macro cp15_invalidate_icache, tmp
mov \tmp, #0
- mrc p15, 0, \tmp, c7, c5, 0
+ mrc p15, 0, \tmp, c7, c5, 0 /* ICIALLU */
.endm
/************************************************************************************
@@ -235,7 +235,7 @@
************************************************************************************/
.macro cp15_invalidate_icache_bymva, va
- mrc p15, 0, \va, c7, c5, 1
+ mrc p15, 0, \va, c7, c5, 1 /* ICIMVAU */
.endm
/************************************************************************************
@@ -254,7 +254,7 @@
.macro cp15_flush_btb, tmp
mov \tmp, #0
- mrc p15, 0, \tmp, c7, c5, 6
+ mrc p15, 0, \tmp, c7, c5, 6 /* BPIALL */
.endm
/************************************************************************************
@@ -273,7 +273,7 @@
.macro cp15_flush_btb_bymva, tmp
mov \tmp, #0
- mrc p15, 0, \tmp, c7, c5, 7
+ mrc p15, 0, \tmp, c7, c5, 7 /* BPIMVA */
.endm
/************************************************************************************
@@ -291,7 +291,7 @@
************************************************************************************/
.macro cp15_invalidate_dcacheline_bymva, va
- mrc p15, 0, \va, c7, c6, 1
+ mrc p15, 0, \va, c7, c6, 1 /* DCIMVAC */
.endm
/************************************************************************************
@@ -309,7 +309,7 @@
************************************************************************************/
.macro cp15_invalidate_dcacheline_bysetway, setway
- mrc p15, 0, \setway, c7, c6, 2
+ mrc p15, 0, \setway, c7, c6, 2 /* DCISW */
.endm
/************************************************************************************
@@ -327,7 +327,7 @@
************************************************************************************/
.macro cp15_clean_dcache_bymva, va
- mrc p15, 0, \va, c7, c10, 1
+ mrc p15, 0, \va, c7, c10, 1 /* DCCMVAC */
.endm
/************************************************************************************
@@ -345,11 +345,11 @@
************************************************************************************/
.macro cp15_clean_dcache_bysetway, setway
- mrc p15, 0, \setway, c7, c10, 2
+ mrc p15, 0, \setway, c7, c10, 2 /* DCCSW */
.endm
/************************************************************************************
- * Name: cp15_clean_dcache_bymva
+ * Name: cp15_clean_ucache_bymva
*
* Description:
* Clean unified cache line by MVA
@@ -362,8 +362,8 @@
*
************************************************************************************/
- .macro cp15_clean_dcache_bymva, setway
- mrc p15, 0, \setway, c7, c11, 1
+ .macro cp15_clean_ucache_bymva, setway
+ mrc p15, 0, \setway, c7, c11, 1 /* DCCMVAU */
.endm
/************************************************************************************
@@ -381,7 +381,7 @@
************************************************************************************/
.macro cp15_cleaninvalidate_dcacheline_bymva, va
- mrc p15, 0, \va, c7, c14, 1
+ mrc p15, 0, \va, c7, c14, 1 /* DCCIMVAC */
.endm
/************************************************************************************
@@ -399,7 +399,7 @@
************************************************************************************/
.macro cp15_cleaninvalidate_dcacheline, setway
- mrc p15, 0, \setway, c7, c14, 2
+ mrc p15, 0, \setway, c7, c14, 2 /* DCCISW */
.endm
#endif /* __ASSEMBLY__ */
@@ -429,7 +429,7 @@ static inline void cp15_invalidate_icache_inner_sharable(void)
__asm__ __volatile__
(
"\tmov r0, #0\n"
- "\tmcr p15, 0, r0, c7, c1, 0\n"
+ "\tmcr p15, 0, r0, c7, c1, 0\n" /* ICIALLUIS */
:
:
: "r0", "memory"
@@ -455,7 +455,7 @@ static inline void cp15_invalidate_btb_inner_sharable(void)
__asm__ __volatile__
(
"\tmov r0, #0\n"
- "\tmcr p15, 0, r0, c7, c1, 6\n"
+ "\tmcr p15, 0, r0, c7, c1, 6\n" /* BPIALLIS */
:
:
: "r0", "memory"
@@ -481,7 +481,7 @@ static inline void cp15_invalidate_icache(void)
__asm__ __volatile__
(
"\tmov r0, #0\n"
- "\tmcr p15, 0, r0, c7, c5, 0\n"
+ "\tmcr p15, 0, r0, c7, c5, 0\n" /* ICIALLU */
:
:
: "r0", "memory"
@@ -506,7 +506,7 @@ static inline void cp15_invalidate_icache_bymva(unsigned int va)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c5, 1\n"
+ "\tmcr p15, 0, %0, c7, c5, 1\n" /* ICIMVAU */
:
: "r" (va)
: "memory"
@@ -532,7 +532,7 @@ static inline void cp15_flush_btb(void)
__asm__ __volatile__
(
"\tmov r0, #0\n"
- "\tmcr p15, 0, r0, c7, c5, 6\n"
+ "\tmcr p15, 0, r0, c7, c5, 6\n" /* BPIALL */
:
:
: "r0", "memory"
@@ -558,7 +558,7 @@ static inline void cp15_flush_btb_bymva(void)
__asm__ __volatile__
(
"\tmov r0, #0\n"
- "\tmcr p15, 0, r0, c7, c5, 7\n"
+ "\tmcr p15, 0, r0, c7, c5, 7\n" /* BPIMVA */
:
:
: "r0", "memory"
@@ -585,7 +585,7 @@ static inline void cp15_invalidate_dcacheline_bymva(unsigned int va)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c6, 1\n"
+ "\tmcr p15, 0, %0, c7, c6, 1\n" /* DCIMVAC */
:
: "r" (va)
: "memory"
@@ -612,7 +612,7 @@ static inline void cp15_invalidate_dcacheline_bysetway(unsigned int setway)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c6, 2\n"
+ "\tmcr p15, 0, %0, c7, c6, 2\n" /* DCISW */
:
: "r" (setway)
: "memory"
@@ -639,7 +639,7 @@ static inline void cp15_clean_dcache_bymva(unsigned int va)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c10, 1\n"
+ "\tmcr p15, 0, %0, c7, c10, 1\n" /* DCCMVAC */
:
: "r" (va)
: "memory"
@@ -664,7 +664,7 @@ static inline void cp15_clean_dcache_bysetway(unsigned int setway)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c10, 2\n"
+ "\tmcr p15, 0, %0, c7, c10, 2\n" /* DCCSW */
:
: "r" (setway)
: "memory"
@@ -672,7 +672,7 @@ static inline void cp15_clean_dcache_bysetway(unsigned int setway)
}
/************************************************************************************
- * Name: cp15_clean_dcache_bymva
+ * Name: cp15_clean_ucache_bymva
*
* Description:
* Clean unified cache line by MVA
@@ -685,11 +685,11 @@ static inline void cp15_clean_dcache_bysetway(unsigned int setway)
*
************************************************************************************/
-static inline void cp15_clean_dcache_bymva(unsigned int setway)
+static inline void cp15_clean_ucache_bymva(unsigned int setway)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c11, 1\n"
+ "\tmcr p15, 0, %0, c7, c11, 1\n" /* DCCMVAU */
:
: "r" (setway)
: "memory"
@@ -714,7 +714,7 @@ static inline void cp15_cleaninvalidate_dcacheline_bymva(unsigned int va)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, r0, c7, c14, 1\n"
+ "\tmcr p15, 0, r0, c7, c14, 1\n" /* DCCIMVAC */
:
: "r" (va)
: "memory"
@@ -739,7 +739,7 @@ static inline void cp15_cleaninvalidate_dcacheline(unsigned int setway)
{
__asm__ __volatile__
(
- "\tmcr p15, 0, %0, c7, c14, 2\n"
+ "\tmcr p15, 0, %0, c7, c14, 2\n" /* DCCISW */
:
: "r" (setway)
: "memory"
@@ -768,9 +768,10 @@ extern "C" {
* Name: cp15_coherent_dcache_for_dma
*
* Description:
- * Ensure that the I and D caches are coherent within specified region.
- * This is typically used when code has been written to a memory region,
- * and will be executed.
+ * Ensure that the I and D caches are coherent within specified region
+ * by cleaning the D cache (i.e., flushing the D cache contents to memory
+ * and invalidating the I cache. This is typically used when code has been
+ * written to a memory region, and will be executed.
*
* Input Parameters:
* start - virtual start address of region
@@ -806,7 +807,8 @@ void cp15_invalidate_dcache_for_dma(uintptr_t start, uintptr_t end);
* Name: cp15_clean_dcache_for_dma
*
* Description:
- * Clean the data cache within the specified region
+ * Clean the data cache within the specified region by flushing the
+ * contents of the data cache to memory.
*
* Input Parameters:
* start - virtual start address of region
@@ -823,7 +825,8 @@ void cp15_clean_dcache_for_dma(uintptr_t start, uintptr_t end);
* Name: cp15_flush_dcache_for_dma
*
* Description:
- * Flush the data cache within the specified region
+ * Flush the data cache within the specified region by cleaning and
+ * invalidating the the D cache.
*
* Input Parameters:
* start - virtual start address of region
diff --git a/nuttx/arch/arm/src/armv7-a/cp15.h b/nuttx/arch/arm/src/armv7-a/cp15.h
index 9c8bf91f1..31d58ead8 100644
--- a/nuttx/arch/arm/src/armv7-a/cp15.h
+++ b/nuttx/arch/arm/src/armv7-a/cp15.h
@@ -196,11 +196,4 @@
#define CP15_CBADDR(r) _CP15(4, r, c15, c0, 0) /* Configuration Base Address Register */
#define CP15_TLBHITMAP(r) _CP15(5, r, c15, c0, 0) /* TLB access and attributes */
-/* System control register descriptions.
- *
- * To be provided
- *
- * Reference: Cortex-A5™ MPCore, Technical Reference Manual, Paragraph 4.3.
- */
-
#endif /* __ARCH_ARM_SRC_ARMV7_A_CP15_H */
diff --git a/nuttx/arch/arm/src/sama5/sam_boot.c b/nuttx/arch/arm/src/sama5/sam_boot.c
index 6f7324671..d353d25ac 100644
--- a/nuttx/arch/arm/src/sama5/sam_boot.c
+++ b/nuttx/arch/arm/src/sama5/sam_boot.c
@@ -51,6 +51,7 @@
#include "chip.h"
#include "arm.h"
#include "mmu.h"
+#include "cache.h"
#include "fpu.h"
#include "up_internal.h"
#include "up_arch.h"
@@ -500,6 +501,14 @@ void up_boot(void)
sam_vectormapping();
+
+ /* The SRAM address hold the the page table is probably buffered. Make sure
+ * that the modified contents of the page table are flushed into physical
+ * memory.
+ */
+
+ cp15_clean_dcache_for_dma(VECTOR_L2_VBASE, VECTOR_L2_VBASE + PGTABLE_SIZE);
+
#endif /* CONFIG_ARCH_ROMPGTABLE */
/* Setup up vector block. _vector_start and _vector_end are exported from
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 100c736b2..84c61044b 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -271,8 +271,8 @@ void os_start(void)
/* Assign the process ID of ZERO to the idle task */
- g_pidhash[ PIDHASH(0)].tcb = &g_idletcb.cmn;
- g_pidhash[ PIDHASH(0)].pid = 0;
+ g_pidhash[PIDHASH(0)].tcb = &g_idletcb.cmn;
+ g_pidhash[PIDHASH(0)].pid = 0;
/* Initialize the IDLE task TCB *******************************************/
/* Initialize a TCB for this thread of execution. NOTE: The default