summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-07-26 18:47:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-07-26 18:47:33 -0600
commit256dbae49296be51ff732eb88992dfb6ea9fbf0b (patch)
tree5e9fe17a706e3a6861e73a701095e09438203d75
parenta97b61396ffbfa3ba5d8993797ef3b5c9aa4847b (diff)
downloadpx4-nuttx-256dbae49296be51ff732eb88992dfb6ea9fbf0b.tar.gz
px4-nuttx-256dbae49296be51ff732eb88992dfb6ea9fbf0b.tar.bz2
px4-nuttx-256dbae49296be51ff732eb88992dfb6ea9fbf0b.zip
Change naming from cp_XYZ_cache() to arch_XYP_cache() so that all cache operations will pick up L2 support if it is enabled
-rw-r--r--nuttx/arch/arm/src/sama5/sam_adc.c2
-rw-r--r--nuttx/arch/arm/src/sama5/sam_dmac.c8
-rwxr-xr-xnuttx/arch/arm/src/sama5/sam_ehci.c42
-rw-r--r--nuttx/arch/arm/src/sama5/sam_emaca.c26
-rw-r--r--nuttx/arch/arm/src/sama5/sam_emacb.c28
-rw-r--r--nuttx/arch/arm/src/sama5/sam_gmac.c26
-rw-r--r--nuttx/arch/arm/src/sama5/sam_irq.c4
-rw-r--r--nuttx/arch/arm/src/sama5/sam_nand.c4
-rw-r--r--nuttx/arch/arm/src/sama5/sam_ohci.c46
-rw-r--r--nuttx/arch/arm/src/sama5/sam_ssc.c4
-rw-r--r--nuttx/arch/arm/src/sama5/sam_udphs.c6
-rw-r--r--nuttx/arch/arm/src/sama5/sam_xdmac.c8
-rw-r--r--nuttx/configs/sama5d3x-ek/src/nor_main.c4
-rw-r--r--nuttx/configs/sama5d4-ek/src/dram_main.c6
14 files changed, 107 insertions, 107 deletions
diff --git a/nuttx/arch/arm/src/sama5/sam_adc.c b/nuttx/arch/arm/src/sama5/sam_adc.c
index 111259de5..a2b2b460e 100644
--- a/nuttx/arch/arm/src/sama5/sam_adc.c
+++ b/nuttx/arch/arm/src/sama5/sam_adc.c
@@ -652,7 +652,7 @@ static void sam_adc_dmadone(void *arg)
* newly DMAed data from RAM.
*/
- cp15_invalidate_dcache((uintptr_t)buffer,
+ arch_invalidate_dcache((uintptr_t)buffer,
(uintptr_t)buffer + SAMA5_ADC_SAMPLES * sizeof(uint16_t));
/* Process each sample */
diff --git a/nuttx/arch/arm/src/sama5/sam_dmac.c b/nuttx/arch/arm/src/sama5/sam_dmac.c
index 675b0f88d..3b0234d44 100644
--- a/nuttx/arch/arm/src/sama5/sam_dmac.c
+++ b/nuttx/arch/arm/src/sama5/sam_dmac.c
@@ -1440,7 +1440,7 @@ sam_allocdesc(struct sam_dmach_s *dmach, struct dma_linklist_s *prev,
* that hardware will be accessing the descriptor via DMA.
*/
- cp15_clean_dcache((uintptr_t)desc,
+ arch_clean_dcache((uintptr_t)desc,
(uintptr_t)desc + sizeof(struct dma_linklist_s));
break;
}
@@ -1764,7 +1764,7 @@ static void sam_dmaterminate(struct sam_dmach_s *dmach, int result)
if (dmach->rx)
{
- cp15_invalidate_dcache(dmach->rxaddr, dmach->rxaddr + dmach->rxsize);
+ arch_invalidate_dcache(dmach->rxaddr, dmach->rxaddr + dmach->rxsize);
}
/* Perform the DMA complete callback */
@@ -2197,7 +2197,7 @@ int sam_dmatxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
/* Clean caches associated with the DMA memory */
- cp15_clean_dcache(maddr, maddr + nbytes);
+ arch_clean_dcache(maddr, maddr + nbytes);
return ret;
}
@@ -2278,7 +2278,7 @@ int sam_dmarxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
/* Clean caches associated with the DMA memory */
- cp15_clean_dcache(maddr, maddr + nbytes);
+ arch_clean_dcache(maddr, maddr + nbytes);
return ret;
}
diff --git a/nuttx/arch/arm/src/sama5/sam_ehci.c b/nuttx/arch/arm/src/sama5/sam_ehci.c
index 5f608cf78..6e552b9cf 100755
--- a/nuttx/arch/arm/src/sama5/sam_ehci.c
+++ b/nuttx/arch/arm/src/sama5/sam_ehci.c
@@ -1118,7 +1118,7 @@ static int sam_qtd_invalidate(struct sam_qtd_s *qtd, uint32_t **bp, void *arg)
* memory over the specified address range.
*/
- cp15_invalidate_dcache((uintptr_t)&qtd->hw,
+ arch_invalidate_dcache((uintptr_t)&qtd->hw,
(uintptr_t)&qtd->hw + sizeof(struct ehci_qtd_s));
return OK;
}
@@ -1137,7 +1137,7 @@ static int sam_qh_invalidate(struct sam_qh_s *qh)
{
/* Invalidate the QH first so that we reload the qTD list head */
- cp15_invalidate_dcache((uintptr_t)&qh->hw,
+ arch_invalidate_dcache((uintptr_t)&qh->hw,
(uintptr_t)&qh->hw + sizeof(struct ehci_qh_s));
/* Then invalidate all of the qTD entries in the queue */
@@ -1163,12 +1163,12 @@ static int sam_qtd_flush(struct sam_qtd_s *qtd, uint32_t **bp, void *arg)
*/
#if 0 /* Didn't behave as expected */
- cp15_flush_dcache((uintptr_t)&qtd->hw,
+ arch_flush_dcache((uintptr_t)&qtd->hw,
(uintptr_t)&qtd->hw + sizeof(struct ehci_qtd_s));
#else
- cp15_clean_dcache((uintptr_t)&qtd->hw,
+ arch_clean_dcache((uintptr_t)&qtd->hw,
(uintptr_t)&qtd->hw + sizeof(struct ehci_qtd_s));
- cp15_invalidate_dcache((uintptr_t)&qtd->hw,
+ arch_invalidate_dcache((uintptr_t)&qtd->hw,
(uintptr_t)&qtd->hw + sizeof(struct ehci_qtd_s));
#endif
@@ -1191,12 +1191,12 @@ static int sam_qh_flush(struct sam_qh_s *qh)
*/
#if 0 /* Didn't behave as expected */
- cp15_flush_dcache((uintptr_t)&qh->hw,
+ arch_flush_dcache((uintptr_t)&qh->hw,
(uintptr_t)&qh->hw + sizeof(struct ehci_qh_s));
#else
- cp15_clean_dcache((uintptr_t)&qh->hw,
+ arch_clean_dcache((uintptr_t)&qh->hw,
(uintptr_t)&qh->hw + sizeof(struct ehci_qh_s));
- cp15_invalidate_dcache((uintptr_t)&qh->hw,
+ arch_invalidate_dcache((uintptr_t)&qh->hw,
(uintptr_t)&qh->hw + sizeof(struct ehci_qh_s));
#endif
@@ -1407,7 +1407,7 @@ static void sam_qh_enqueue(struct sam_qh_s *qhead, struct sam_qh_s *qh)
physaddr = (uintptr_t)sam_physramaddr((uintptr_t)qh);
qhead->hw.hlp = sam_swap32(physaddr | QH_HLP_TYP_QH);
- cp15_clean_dcache((uintptr_t)&qhead->hw,
+ arch_clean_dcache((uintptr_t)&qhead->hw,
(uintptr_t)&qhead->hw + sizeof(struct ehci_qh_s));
}
@@ -1545,10 +1545,10 @@ static int sam_qtd_addbpl(struct sam_qtd_s *qtd, const void *buffer, size_t bufl
*/
#if 0 /* Didn't behave as expected */
- cp15_flush_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
+ arch_flush_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
#else
- cp15_clean_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
- cp15_invalidate_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
+ arch_clean_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
+ arch_invalidate_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
#endif
/* Loop, adding the aligned physical addresses of the buffer to the buffer page
@@ -2096,7 +2096,7 @@ static ssize_t sam_async_transfer(struct sam_rhport_s *rhport,
* invalid in this memory region.
*/
- cp15_invalidate_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
+ arch_invalidate_dcache((uintptr_t)buffer, (uintptr_t)buffer + buflen);
}
#endif
@@ -2331,7 +2331,7 @@ static int sam_qtd_ioccheck(struct sam_qtd_s *qtd, uint32_t **bp, void *arg)
/* Make sure we reload the QH from memory */
- cp15_invalidate_dcache((uintptr_t)&qtd->hw,
+ arch_invalidate_dcache((uintptr_t)&qtd->hw,
(uintptr_t)&qtd->hw + sizeof(struct ehci_qtd_s));
sam_qtd_print(qtd);
@@ -2382,7 +2382,7 @@ static int sam_qh_ioccheck(struct sam_qh_s *qh, uint32_t **bp, void *arg)
/* Make sure we reload the QH from memory */
- cp15_invalidate_dcache((uintptr_t)&qh->hw,
+ arch_invalidate_dcache((uintptr_t)&qh->hw,
(uintptr_t)&qh->hw + sizeof(struct ehci_qh_s));
sam_qh_print(qh);
@@ -2436,7 +2436,7 @@ static int sam_qh_ioccheck(struct sam_qh_s *qh, uint32_t **bp, void *arg)
*/
**bp = qh->hw.hlp;
- cp15_clean_dcache((uintptr_t)*bp, (uintptr_t)*bp + sizeof(uint32_t));
+ arch_clean_dcache((uintptr_t)*bp, (uintptr_t)*bp + sizeof(uint32_t));
/* Check for errors, update the data toggle */
@@ -2536,7 +2536,7 @@ static inline void sam_ioc_bottomhalf(void)
/* Check the Asynchronous Queue */
/* Make sure that the head of the asynchronous queue is invalidated */
- cp15_invalidate_dcache((uintptr_t)&g_asynchead.hw,
+ arch_invalidate_dcache((uintptr_t)&g_asynchead.hw,
(uintptr_t)&g_asynchead.hw + sizeof(struct ehci_qh_s));
/* Set the back pointer to the forward qTD pointer of the asynchronous
@@ -2562,7 +2562,7 @@ static inline void sam_ioc_bottomhalf(void)
/* Check the Interrupt Queue */
/* Make sure that the head of the interrupt queue is invalidated */
- cp15_invalidate_dcache((uintptr_t)&g_intrhead.hw,
+ arch_invalidate_dcache((uintptr_t)&g_intrhead.hw,
(uintptr_t)&g_intrhead.hw + sizeof(struct ehci_qh_s));
/* Set the back pointer to the forward qTD pointer of the asynchronous
@@ -4294,7 +4294,7 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
g_asynchead.hw.overlay.token = sam_swap32(QH_TOKEN_HALTED);
g_asynchead.fqp = sam_swap32(QTD_NQP_T);
- cp15_clean_dcache((uintptr_t)&g_asynchead.hw,
+ arch_clean_dcache((uintptr_t)&g_asynchead.hw,
(uintptr_t)&g_asynchead.hw + sizeof(struct ehci_qh_s));
/* Set the Current Asynchronous List Address. */
@@ -4325,9 +4325,9 @@ FAR struct usbhost_connection_s *sam_ehci_initialize(int controller)
/* Set the Periodic Frame List Base Address. */
- cp15_clean_dcache((uintptr_t)&g_intrhead.hw,
+ arch_clean_dcache((uintptr_t)&g_intrhead.hw,
(uintptr_t)&g_intrhead.hw + sizeof(struct ehci_qh_s));
- cp15_clean_dcache((uintptr_t)g_framelist,
+ arch_clean_dcache((uintptr_t)g_framelist,
(uintptr_t)g_framelist + FRAME_LIST_SIZE * sizeof(uint32_t));
physaddr = sam_physramaddr((uintptr_t)g_framelist);
diff --git a/nuttx/arch/arm/src/sama5/sam_emaca.c b/nuttx/arch/arm/src/sama5/sam_emaca.c
index e4149c131..9a9d46d84 100644
--- a/nuttx/arch/arm/src/sama5/sam_emaca.c
+++ b/nuttx/arch/arm/src/sama5/sam_emaca.c
@@ -738,7 +738,7 @@ static int sam_transmit(struct sam_emac_s *priv)
virtaddr = sam_virtramaddr(txdesc->addr);
memcpy((void *)virtaddr, dev->d_buf, dev->d_len);
- cp15_clean_dcache((uint32_t)virtaddr, (uint32_t)virtaddr + dev->d_len);
+ arch_clean_dcache((uint32_t)virtaddr, (uint32_t)virtaddr + dev->d_len);
}
/* Update TX descriptor status. */
@@ -752,7 +752,7 @@ static int sam_transmit(struct sam_emac_s *priv)
/* Update the descriptor status and flush the updated value to RAM */
txdesc->status = status;
- cp15_clean_dcache((uint32_t)txdesc,
+ arch_clean_dcache((uint32_t)txdesc,
(uint32_t)txdesc + sizeof(struct emac_txdesc_s));
/* Increment the head index */
@@ -939,7 +939,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Invalidate the RX descriptor to force re-fetching from RAM */
- cp15_invalidate_dcache((uintptr_t)rxdesc,
+ arch_invalidate_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc + sizeof(struct emac_rxdesc_s));
nllvdbg("rxndx: %d\n", rxndx);
@@ -963,7 +963,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1008,7 +1008,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1038,7 +1038,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
physaddr = (uintptr_t)(rxdesc->addr & EMACRXD_ADDR_MASK);
src = (const uint8_t *)sam_virtramaddr(physaddr);
- cp15_invalidate_dcache((uintptr_t)src, (uintptr_t)src + copylen);
+ arch_invalidate_dcache((uintptr_t)src, (uintptr_t)src + copylen);
/* And do the copy */
@@ -1068,7 +1068,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1108,7 +1108,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1121,7 +1121,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Invalidate the RX descriptor to force re-fetching from RAM */
- cp15_invalidate_dcache((uintptr_t)rxdesc,
+ arch_invalidate_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc + sizeof(struct emac_rxdesc_s));
}
@@ -1252,7 +1252,7 @@ static void sam_txdone(struct sam_emac_s *priv)
/* Yes.. check the next buffer at the tail of the list */
txdesc = &priv->txdesc[priv->txtail];
- cp15_invalidate_dcache((uintptr_t)txdesc,
+ arch_invalidate_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct emac_txdesc_s));
/* Is this TX descriptor still in use? */
@@ -1272,7 +1272,7 @@ static void sam_txdone(struct sam_emac_s *priv)
sam_physramaddr((uintptr_t)txdesc) != sam_getreg(priv, SAM_EMAC_TBQP))
{
txdesc->status = (uint32_t)EMACTXD_STA_USED;
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct emac_txdesc_s));
}
else
@@ -2620,7 +2620,7 @@ static void sam_txreset(struct sam_emac_s *priv)
/* Flush the entire TX descriptor table to RAM */
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc +
CONFIG_SAMA5_EMAC_NTXBUFFERS * sizeof(struct emac_txdesc_s));
@@ -2684,7 +2684,7 @@ static void sam_rxreset(struct sam_emac_s *priv)
/* Flush the entire RX descriptor table to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
CONFIG_SAMA5_EMAC_NRXBUFFERS * sizeof(struct emac_rxdesc_s));
diff --git a/nuttx/arch/arm/src/sama5/sam_emacb.c b/nuttx/arch/arm/src/sama5/sam_emacb.c
index fb06788c5..04808a2ff 100644
--- a/nuttx/arch/arm/src/sama5/sam_emacb.c
+++ b/nuttx/arch/arm/src/sama5/sam_emacb.c
@@ -1060,7 +1060,7 @@ static int sam_transmit(struct sam_emac_s *priv)
virtaddr = sam_virtramaddr(txdesc->addr);
memcpy((void *)virtaddr, dev->d_buf, dev->d_len);
- cp15_clean_dcache((uint32_t)virtaddr, (uint32_t)virtaddr + dev->d_len);
+ arch_clean_dcache((uint32_t)virtaddr, (uint32_t)virtaddr + dev->d_len);
}
/* Update TX descriptor status. */
@@ -1074,7 +1074,7 @@ static int sam_transmit(struct sam_emac_s *priv)
/* Update the descriptor status and flush the updated value to RAM */
txdesc->status = status;
- cp15_clean_dcache((uint32_t)txdesc,
+ arch_clean_dcache((uint32_t)txdesc,
(uint32_t)txdesc + sizeof(struct emac_txdesc_s));
/* Increment the head index */
@@ -1261,7 +1261,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Invalidate the RX descriptor to force re-fetching from RAM */
- cp15_invalidate_dcache((uintptr_t)rxdesc,
+ arch_invalidate_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc + sizeof(struct emac_rxdesc_s));
nllvdbg("rxndx: %d\n", rxndx);
@@ -1284,7 +1284,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1329,7 +1329,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1359,7 +1359,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
physaddr = (uintptr_t)(rxdesc->addr & EMACRXD_ADDR_MASK);
src = (const uint8_t *)sam_virtramaddr(physaddr);
- cp15_invalidate_dcache((uintptr_t)src, (uintptr_t)src + copylen);
+ arch_invalidate_dcache((uintptr_t)src, (uintptr_t)src + copylen);
/* And do the copy */
@@ -1389,7 +1389,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1429,7 +1429,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct emac_rxdesc_s));
@@ -1442,7 +1442,7 @@ static int sam_recvframe(struct sam_emac_s *priv)
/* Invalidate the RX descriptor to force re-fetching from RAM */
- cp15_invalidate_dcache((uintptr_t)rxdesc,
+ arch_invalidate_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc + sizeof(struct emac_rxdesc_s));
}
@@ -1576,7 +1576,7 @@ static void sam_txdone(struct sam_emac_s *priv)
/* Yes.. check the next buffer at the tail of the list */
txdesc = &priv->txdesc[priv->txtail];
- cp15_invalidate_dcache((uintptr_t)txdesc,
+ arch_invalidate_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct emac_txdesc_s));
/* Is this TX descriptor still in use? */
@@ -1609,7 +1609,7 @@ static void sam_txdone(struct sam_emac_s *priv)
sam_physramaddr((uintptr_t)txdesc) != sam_getreg(priv, SAM_EMAC_TBQB_OFFSET))
{
txdesc->status = (uint32_t)EMACTXD_STA_USED;
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct emac_txdesc_s));
}
else
@@ -1627,7 +1627,7 @@ static void sam_txdone(struct sam_emac_s *priv)
/* Make sure that the USED bit is set */
txdesc->status = (uint32_t)EMACTXD_STA_USED;
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct emac_txdesc_s));
#endif
@@ -3175,7 +3175,7 @@ static void sam_txreset(struct sam_emac_s *priv)
/* Flush the entire TX descriptor table to RAM */
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc +
priv->attr->ntxbuffers * sizeof(struct emac_txdesc_s));
@@ -3239,7 +3239,7 @@ static void sam_rxreset(struct sam_emac_s *priv)
/* Flush the entire RX descriptor table to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
priv->attr->nrxbuffers * sizeof(struct emac_rxdesc_s));
diff --git a/nuttx/arch/arm/src/sama5/sam_gmac.c b/nuttx/arch/arm/src/sama5/sam_gmac.c
index 8e2e4f8f1..4444f69a5 100644
--- a/nuttx/arch/arm/src/sama5/sam_gmac.c
+++ b/nuttx/arch/arm/src/sama5/sam_gmac.c
@@ -670,7 +670,7 @@ static int sam_transmit(struct sam_gmac_s *priv)
virtaddr = sam_virtramaddr(txdesc->addr);
memcpy((void *)virtaddr, dev->d_buf, dev->d_len);
- cp15_clean_dcache((uint32_t)virtaddr, (uint32_t)virtaddr + dev->d_len);
+ arch_clean_dcache((uint32_t)virtaddr, (uint32_t)virtaddr + dev->d_len);
}
/* Update TX descriptor status. */
@@ -684,7 +684,7 @@ static int sam_transmit(struct sam_gmac_s *priv)
/* Update the descriptor status and flush the updated value to RAM */
txdesc->status = status;
- cp15_clean_dcache((uint32_t)txdesc,
+ arch_clean_dcache((uint32_t)txdesc,
(uint32_t)txdesc + sizeof(struct gmac_txdesc_s));
/* Increment the head index */
@@ -871,7 +871,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
/* Invalidate the RX descriptor to force re-fetching from RAM */
- cp15_invalidate_dcache((uintptr_t)rxdesc,
+ arch_invalidate_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc + sizeof(struct gmac_rxdesc_s));
nllvdbg("rxndx: %d\n", rxndx);
@@ -895,7 +895,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct gmac_rxdesc_s));
@@ -940,7 +940,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct gmac_rxdesc_s));
@@ -970,7 +970,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
physaddr = (uintptr_t)(rxdesc->addr & GMACRXD_ADDR_MASK);
src = (const uint8_t *)sam_virtramaddr(physaddr);
- cp15_invalidate_dcache((uintptr_t)src, (uintptr_t)src + copylen);
+ arch_invalidate_dcache((uintptr_t)src, (uintptr_t)src + copylen);
/* And do the copy */
@@ -1000,7 +1000,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct gmac_rxdesc_s));
@@ -1038,7 +1038,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
/* Flush the modified RX descriptor to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
sizeof(struct gmac_rxdesc_s));
@@ -1051,7 +1051,7 @@ static int sam_recvframe(struct sam_gmac_s *priv)
/* Invalidate the RX descriptor to force re-fetching from RAM */
- cp15_invalidate_dcache((uintptr_t)rxdesc,
+ arch_invalidate_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc + sizeof(struct gmac_rxdesc_s));
}
@@ -1182,7 +1182,7 @@ static void sam_txdone(struct sam_gmac_s *priv)
/* Yes.. check the next buffer at the tail of the list */
txdesc = &priv->txdesc[priv->txtail];
- cp15_invalidate_dcache((uintptr_t)txdesc,
+ arch_invalidate_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct gmac_txdesc_s));
/* Is this TX descriptor still in use? */
@@ -1201,7 +1201,7 @@ static void sam_txdone(struct sam_gmac_s *priv)
sam_physramaddr((uintptr_t)txdesc) != sam_getreg(priv, SAM_GMAC_TBQB))
{
txdesc->status = (uint32_t)GMACTXD_STA_USED;
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc + sizeof(struct gmac_txdesc_s));
}
else
@@ -2674,7 +2674,7 @@ static void sam_txreset(struct sam_gmac_s *priv)
/* Flush the entire TX descriptor table to RAM */
- cp15_clean_dcache((uintptr_t)txdesc,
+ arch_clean_dcache((uintptr_t)txdesc,
(uintptr_t)txdesc +
CONFIG_SAMA5_GMAC_NTXBUFFERS * sizeof(struct gmac_txdesc_s));
@@ -2738,7 +2738,7 @@ static void sam_rxreset(struct sam_gmac_s *priv)
/* Flush the entire RX descriptor table to RAM */
- cp15_clean_dcache((uintptr_t)rxdesc,
+ arch_clean_dcache((uintptr_t)rxdesc,
(uintptr_t)rxdesc +
CONFIG_SAMA5_GMAC_NRXBUFFERS * sizeof(struct gmac_rxdesc_s));
diff --git a/nuttx/arch/arm/src/sama5/sam_irq.c b/nuttx/arch/arm/src/sama5/sam_irq.c
index dc7dfce56..f81617e8c 100644
--- a/nuttx/arch/arm/src/sama5/sam_irq.c
+++ b/nuttx/arch/arm/src/sama5/sam_irq.c
@@ -531,8 +531,8 @@ void up_irqinitialize(void)
/* Make sure that there is no trace of any previous mapping */
vectorsize = sam_vectorsize();
- cp15_invalidate_icache();
- cp15_invalidate_dcache(0, vectorsize);
+ arch_invalidate_icache();
+ arch_invalidate_dcache(0, vectorsize);
mmu_invalidate_region(0, vectorsize);
#if 0 /* Disabled on reset */
diff --git a/nuttx/arch/arm/src/sama5/sam_nand.c b/nuttx/arch/arm/src/sama5/sam_nand.c
index 2f53aa98a..3cd533852 100644
--- a/nuttx/arch/arm/src/sama5/sam_nand.c
+++ b/nuttx/arch/arm/src/sama5/sam_nand.c
@@ -1305,7 +1305,7 @@ static int nand_dma_read(struct sam_nandcs_s *priv,
* that memory will be re-cached after the DMA completes).
*/
- cp15_invalidate_dcache(vdest, vdest + nbytes);
+ arch_invalidate_dcache(vdest, vdest + nbytes);
/* DMA will need physical addresses. */
@@ -1390,7 +1390,7 @@ static int nand_dma_write(struct sam_nandcs_s *priv,
* the data to be transferred lies in physical memory
*/
- cp15_clean_dcache(vsrc, vsrc + nbytes);
+ arch_clean_dcache(vsrc, vsrc + nbytes);
/* DMA will need physical addresses. */
diff --git a/nuttx/arch/arm/src/sama5/sam_ohci.c b/nuttx/arch/arm/src/sama5/sam_ohci.c
index 74eba1df4..4f5b47f36 100644
--- a/nuttx/arch/arm/src/sama5/sam_ohci.c
+++ b/nuttx/arch/arm/src/sama5/sam_ohci.c
@@ -792,7 +792,7 @@ static inline int sam_addbulked(struct sam_ed_s *ed)
/* Add the new bulk ED to the head of the bulk list */
ed->hw.nexted = sam_getreg(SAM_USBHOST_BULKHEADED);
- cp15_clean_dcache((uintptr_t)ed, (uintptr_t)ed + sizeof(struct ohci_ed_s));
+ arch_clean_dcache((uintptr_t)ed, (uintptr_t)ed + sizeof(struct ohci_ed_s));
physed = sam_physramaddr((uintptr_t)ed);
sam_putreg((uint32_t)physed, SAM_USBHOST_BULKHEADED);
@@ -866,7 +866,7 @@ static inline int sam_rembulked(struct sam_ed_s *ed)
*/
prev->hw.nexted = ed->hw.nexted;
- cp15_clean_dcache((uintptr_t)prev,
+ arch_clean_dcache((uintptr_t)prev,
(uintptr_t)prev + sizeof(struct sam_ed_s));
}
}
@@ -955,7 +955,7 @@ static void sam_setinttab(uint32_t value, unsigned int interval, unsigned int of
/* Make sure that the modified table value is flushed to RAM */
inttbl = (uintptr_t)g_hcca.inttbl;
- cp15_clean_dcache(inttbl, inttbl + sizeof(uint32_t)*HCCA_INTTBL_WSIZE);
+ arch_clean_dcache(inttbl, inttbl + sizeof(uint32_t)*HCCA_INTTBL_WSIZE);
}
#endif
@@ -1058,7 +1058,7 @@ static inline int sam_addinted(const FAR struct usbhost_epdesc_s *epdesc,
*/
ed->hw.nexted = physhead;
- cp15_clean_dcache((uintptr_t)ed, (uintptr_t)ed + sizeof(struct ohci_ed_s));
+ arch_clean_dcache((uintptr_t)ed, (uintptr_t)ed + sizeof(struct ohci_ed_s));
physed = sam_physramaddr((uintptr_t)ed);
sam_setinttab((uint32_t)physed, interval, offset);
@@ -1295,7 +1295,7 @@ static int sam_enqueuetd(struct sam_rhport_s *rhport, struct sam_ed_s *ed,
/* Skip processing of this ED while we modify the TD list. */
ed->hw.ctrl |= ED_CONTROL_K;
- cp15_clean_dcache((uintptr_t)ed,
+ arch_clean_dcache((uintptr_t)ed,
(uintptr_t)ed + sizeof(struct ohci_ed_s));
/* Get the tail ED for this root hub port */
@@ -1335,19 +1335,19 @@ static int sam_enqueuetd(struct sam_rhport_s *rhport, struct sam_ed_s *ed,
if (buffer && buflen > 0)
{
- cp15_clean_dcache((uintptr_t)buffer,
+ arch_clean_dcache((uintptr_t)buffer,
(uintptr_t)buffer + buflen);
}
- cp15_clean_dcache((uintptr_t)tdtail,
+ arch_clean_dcache((uintptr_t)tdtail,
(uintptr_t)tdtail + sizeof(struct ohci_gtd_s));
- cp15_clean_dcache((uintptr_t)td,
+ arch_clean_dcache((uintptr_t)td,
(uintptr_t)td + sizeof(struct ohci_gtd_s));
/* Resume processing of this ED */
ed->hw.ctrl &= ~ED_CONTROL_K;
- cp15_clean_dcache((uintptr_t)ed,
+ arch_clean_dcache((uintptr_t)ed,
(uintptr_t)ed + sizeof(struct ohci_ed_s));
ret = OK;
}
@@ -1445,9 +1445,9 @@ static int sam_ep0enqueue(struct sam_rhport_s *rhport)
/* Flush the affected control ED and tail TD to RAM */
- cp15_clean_dcache((uintptr_t)edctrl,
+ arch_clean_dcache((uintptr_t)edctrl,
(uintptr_t)edctrl + sizeof(struct ohci_ed_s));
- cp15_clean_dcache((uintptr_t)tdtail,
+ arch_clean_dcache((uintptr_t)tdtail,
(uintptr_t)tdtail + sizeof(struct ohci_gtd_s));
/* ControlListEnable. This bit is set to (re-)enable the processing of the
@@ -1528,7 +1528,7 @@ static void sam_ep0dequeue(struct sam_rhport_s *rhport)
/* Flush the modified ED to RAM */
- cp15_clean_dcache((uintptr_t)preved,
+ arch_clean_dcache((uintptr_t)preved,
(uintptr_t)preved + sizeof(struct ohci_ed_s));
}
else
@@ -1885,10 +1885,10 @@ static void sam_wdh_bottomhalf(void)
/* Invalidate D-cache to force re-reading of the Done Head */
#if 0 /* Apparently insufficient */
- cp15_invalidate_dcache((uintptr_t)&g_hcca.donehead,
+ arch_invalidate_dcache((uintptr_t)&g_hcca.donehead,
(uintptr_t)&g_hcca.donehead + sizeof(uint32_t));
#else
- cp15_invalidate_dcache((uintptr_t)&g_hcca,
+ arch_invalidate_dcache((uintptr_t)&g_hcca,
(uintptr_t)&g_hcca + sizeof(struct ohci_hcca_s));
#endif
@@ -1906,7 +1906,7 @@ static void sam_wdh_bottomhalf(void)
* reloaded from memory.
*/
- cp15_invalidate_dcache((uintptr_t)td,
+ arch_invalidate_dcache((uintptr_t)td,
(uintptr_t)td + sizeof( struct ohci_gtd_s));
/* Get the ED in which this TD was enqueued */
@@ -1923,7 +1923,7 @@ static void sam_wdh_bottomhalf(void)
* memory.
*/
- cp15_invalidate_dcache((uintptr_t)ed,
+ arch_invalidate_dcache((uintptr_t)ed,
(uintptr_t)ed + sizeof( struct ohci_ed_s));
/* Save the condition code from the (single) TD status/control
@@ -2279,7 +2279,7 @@ static int sam_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
/* Flush the modified control ED to RAM */
- cp15_clean_dcache((uintptr_t)edctrl,
+ arch_clean_dcache((uintptr_t)edctrl,
(uintptr_t)edctrl + sizeof(struct ohci_ed_s));
sam_givesem(&g_ohci.exclsem);
@@ -2451,9 +2451,9 @@ static int sam_epalloc(FAR struct usbhost_driver_s *drvr,
/* Make sure these settings are flushed to RAM */
- cp15_clean_dcache((uintptr_t)ed,
+ arch_clean_dcache((uintptr_t)ed,
(uintptr_t)ed + sizeof(struct ohci_ed_s));
- cp15_clean_dcache((uintptr_t)td,
+ arch_clean_dcache((uintptr_t)td,
(uintptr_t)td + sizeof(struct ohci_gtd_s));
/* Now add the endpoint descriptor to the appropriate list */
@@ -2819,7 +2819,7 @@ static int sam_ctrlin(FAR struct usbhost_driver_s *drvr,
*/
sam_givesem(&g_ohci.exclsem);
- cp15_invalidate_dcache((uintptr_t)buffer, (uintptr_t)buffer + len);
+ arch_invalidate_dcache((uintptr_t)buffer, (uintptr_t)buffer + len);
return ret;
}
@@ -3007,7 +3007,7 @@ static int sam_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
/* Invalidate the D cache to force the ED to be reloaded from RAM */
- cp15_invalidate_dcache((uintptr_t)ed,
+ arch_invalidate_dcache((uintptr_t)ed,
(uintptr_t)ed + sizeof(struct ohci_ed_s));
/* Check the TD completion status bits */
@@ -3020,7 +3020,7 @@ static int sam_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
if (in)
{
- cp15_invalidate_dcache((uintptr_t)buffer,
+ arch_invalidate_dcache((uintptr_t)buffer,
(uintptr_t)buffer + buflen);
}
@@ -3196,7 +3196,7 @@ FAR struct usbhost_connection_s *sam_ohci_initialize(int controller)
memset((void*)&g_hcca, 0, sizeof(struct ohci_hcca_s));
- cp15_clean_dcache((uint32_t)&g_hcca,
+ arch_clean_dcache((uint32_t)&g_hcca,
(uint32_t)&g_hcca + sizeof(struct ohci_hcca_s));
/* Initialize user-configurable EDs */
diff --git a/nuttx/arch/arm/src/sama5/sam_ssc.c b/nuttx/arch/arm/src/sama5/sam_ssc.c
index 56c16064b..ca7917438 100644
--- a/nuttx/arch/arm/src/sama5/sam_ssc.c
+++ b/nuttx/arch/arm/src/sama5/sam_ssc.c
@@ -1214,7 +1214,7 @@ static int ssc_rxdma_setup(struct sam_ssc_s *priv)
* DMA buffer after starting the DMA transfer.
*/
- cp15_invalidate_dcache((uintptr_t)apb->samp,
+ arch_invalidate_dcache((uintptr_t)apb->samp,
(uintptr_t)apb->samp + apb->nmaxbytes);
}
@@ -1623,7 +1623,7 @@ static int ssc_txdma_setup(struct sam_ssc_s *priv)
* before starting the DMA.
*/
- cp15_clean_dcache((uintptr_t)apb->samp,
+ arch_clean_dcache((uintptr_t)apb->samp,
(uintptr_t)apb->samp + apb->nbytes);
}
diff --git a/nuttx/arch/arm/src/sama5/sam_udphs.c b/nuttx/arch/arm/src/sama5/sam_udphs.c
index ffef30b48..ca16b9e8a 100644
--- a/nuttx/arch/arm/src/sama5/sam_udphs.c
+++ b/nuttx/arch/arm/src/sama5/sam_udphs.c
@@ -908,7 +908,7 @@ static void sam_dma_single(uint8_t epno, struct sam_req_s *privreq,
/* Flush the contents of the DMA buffer to RAM */
buffer = (uintptr_t)&privreq->req.buf[privreq->req.xfrd];
- cp15_clean_dcache(buffer, buffer + privreq->inflight);
+ arch_clean_dcache(buffer, buffer + privreq->inflight);
/* Set up the DMA */
@@ -2412,7 +2412,7 @@ static void sam_dma_interrupt(struct sam_usbdev_s *priv, int epno)
DEBUGASSERT(USB_ISEPOUT(privep->ep.eplog));
buf = &privreq->req.buf[privreq->req.xfrd];
- cp15_invalidate_dcache((uintptr_t)buf, (uintptr_t)buf + xfrsize);
+ arch_invalidate_dcache((uintptr_t)buf, (uintptr_t)buf + xfrsize);
/* Complete this transfer, return the request to the class
* implementation, and try to start the next, queue read request.
@@ -2468,7 +2468,7 @@ static void sam_dma_interrupt(struct sam_usbdev_s *priv, int epno)
*/
buf = &privreq->req.buf[privreq->req.xfrd];
- cp15_invalidate_dcache((uintptr_t)buf, (uintptr_t)buf + xfrsize);
+ arch_invalidate_dcache((uintptr_t)buf, (uintptr_t)buf + xfrsize);
/* Complete this transfer, return the request to the class
* implementation, and try to start the next, queue read request.
diff --git a/nuttx/arch/arm/src/sama5/sam_xdmac.c b/nuttx/arch/arm/src/sama5/sam_xdmac.c
index c59e7bdb9..6e4ca9ed4 100644
--- a/nuttx/arch/arm/src/sama5/sam_xdmac.c
+++ b/nuttx/arch/arm/src/sama5/sam_xdmac.c
@@ -1400,7 +1400,7 @@ sam_allocdesc(struct sam_xdmach_s *xdmach, struct chnext_view1_s *prev,
* that hardware will be accessing the descriptor via DMA.
*/
- cp15_clean_dcache((uintptr_t)descr,
+ arch_clean_dcache((uintptr_t)descr,
(uintptr_t)descr + sizeof(struct chnext_view1_s));
break;
}
@@ -1804,7 +1804,7 @@ static void sam_dmaterminate(struct sam_xdmach_s *xdmach, int result)
if (xdmach->rx)
{
- cp15_invalidate_dcache(xdmach->rxaddr, xdmach->rxaddr + xdmach->rxsize);
+ arch_invalidate_dcache(xdmach->rxaddr, xdmach->rxaddr + xdmach->rxsize);
}
/* Perform the DMA complete callback */
@@ -2243,7 +2243,7 @@ int sam_dmatxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
/* Clean caches associated with the DMA memory */
- cp15_clean_dcache(maddr, maddr + nbytes);
+ arch_clean_dcache(maddr, maddr + nbytes);
return ret;
}
@@ -2324,7 +2324,7 @@ int sam_dmarxsetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
/* Clean caches associated with the DMA memory */
- cp15_clean_dcache(maddr, maddr + nbytes);
+ arch_clean_dcache(maddr, maddr + nbytes);
return ret;
}
diff --git a/nuttx/configs/sama5d3x-ek/src/nor_main.c b/nuttx/configs/sama5d3x-ek/src/nor_main.c
index 063ba1d1f..a50f85411 100644
--- a/nuttx/configs/sama5d3x-ek/src/nor_main.c
+++ b/nuttx/configs/sama5d3x-ek/src/nor_main.c
@@ -187,8 +187,8 @@ int nor_main(int argc, char *argv)
/* Invalidate caches and TLBs */
- cp15_invalidate_icache();
- cp15_invalidate_dcache_all();
+ arch_invalidate_icache();
+ arch_invalidate_dcache_all();
cp15_invalidate_tlbs();
/* Then jump into NOR flash */
diff --git a/nuttx/configs/sama5d4-ek/src/dram_main.c b/nuttx/configs/sama5d4-ek/src/dram_main.c
index 1fa34d920..4f2868094 100644
--- a/nuttx/configs/sama5d4-ek/src/dram_main.c
+++ b/nuttx/configs/sama5d4-ek/src/dram_main.c
@@ -134,7 +134,7 @@ int dram_main(int argc, char *argv)
* we disable caching.
*/
- cp15_clean_dcache((uintptr_t)SAM_DDRCS_VSECTION,
+ arch_clean_dcache((uintptr_t)SAM_DDRCS_VSECTION,
(uintptr_t)(SAM_DDRCS_VSECTION + CONFIG_SAMA5_DDRCS_SIZE));
/* Interrupts must be disabled through the following. In this configuration,
@@ -155,8 +155,8 @@ int dram_main(int argc, char *argv)
/* Invalidate caches and TLBs */
- cp15_invalidate_icache();
- cp15_invalidate_dcache_all();
+ arch_invalidate_icache();
+ arch_invalidate_dcache_all();
cp15_invalidate_tlbs();
/* Then jump into NOR flash */