summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-11-25 18:38:03 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-11-25 18:38:03 -0600
commit4bc7f8fa5225545788aadd84a8524d8f40d8295e (patch)
tree342711b9c2db093ce17f0150e1070ad32cada67c
parentf48dc8de50efe2da526ac38bf09cf956909375a6 (diff)
downloadpx4-nuttx-4bc7f8fa5225545788aadd84a8524d8f40d8295e.tar.gz
px4-nuttx-4bc7f8fa5225545788aadd84a8524d8f40d8295e.tar.bz2
px4-nuttx-4bc7f8fa5225545788aadd84a8524d8f40d8295e.zip
SAMA5 NAND: Changes made durint testing (still does not work)
-rw-r--r--nuttx/arch/arm/src/sama5/Kconfig13
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sam_hsmc.h37
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h12
-rw-r--r--nuttx/arch/arm/src/sama5/sam_nand.c110
4 files changed, 122 insertions, 50 deletions
diff --git a/nuttx/arch/arm/src/sama5/Kconfig b/nuttx/arch/arm/src/sama5/Kconfig
index a9444325e..3db70b5e5 100644
--- a/nuttx/arch/arm/src/sama5/Kconfig
+++ b/nuttx/arch/arm/src/sama5/Kconfig
@@ -788,8 +788,11 @@ endchoice # Base layer color format
endif # SAMA5_LCDC_HCR
config SAMA5_LCDC_REGDEBUG
- bool "Low level register debug"
+ bool "Register-Level Debug"
+ default n
depends on DEBUG
+ ---help---
+ Enable very low-level register access debug. Depends on DEBUG.
endmenu # LCDC configuration
endif # SAMA5_LCDC
@@ -3420,6 +3423,14 @@ config SAMA5_PMECC_GALOIS_CUSTOM
by any NuttX logic.
endif # SAMA5_HAVE_PMECC
+
+config SAMA5_NAND_REGDEBUG
+ bool "Register-Level NAND Debug"
+ default n
+ depends on DEBUG
+ ---help---
+ Enable very low-level register access debug. Depends on DEBUG.
+
endif # SAMA5_HAVE_NAND
endmenu # External Memory Configuration
diff --git a/nuttx/arch/arm/src/sama5/chip/sam_hsmc.h b/nuttx/arch/arm/src/sama5/chip/sam_hsmc.h
index 792217e0f..d7ea2837b 100644
--- a/nuttx/arch/arm/src/sama5/chip/sam_hsmc.h
+++ b/nuttx/arch/arm/src/sama5/chip/sam_hsmc.h
@@ -339,15 +339,12 @@
/* HSMC NFC Interrupt Mask Register */
#define HSMC_SR_SMCSTS (1 << 0) /* Bit 0: NAND Flash Controller Status (SR only) */
-
#define HSMC_NFCINT_RB_RISE (1 << 4) /* Bit 4: Ready Busy Rising Edge Detection Interrupt */
#define HSMC_NFCINT_RB_FALL (1 << 5) /* Bit 5: Ready Busy Falling Edge Detection Interrupt */
-
#define HSMC_SR_NFCBUSY (1 << 8) /* Bit 8: NFC Busy (SR only) */
#define HSMC_SR_NFCWR (1 << 11) /* Bit 11: NFC Write/Read Operation (SR only) */
#define HSMC_SR_NFCSID_SHIFT (12) /* Bits 12-14: NFC Chip Select ID (SR only) */
#define HSMC_SR_NFCSID_MASK (7 << HSMC_SR_NFCSID_SHIFT)
-
#define HSMC_NFCINT_XFRDONE (1 << 16) /* Bit 16: Transfer Done Interrupt */
#define HSMC_NFCINT_CMDDONE (1 << 17) /* Bit 17: Command Done Interrupt */
#define HSMC_NFCINT_DTOE (1 << 20) /* Bit 20: Data Timeout Error Interrupt Enable */
@@ -356,7 +353,7 @@
#define HSMC_NFCINT_NFCASE (1 << 23) /* Bit 23: NFC Access Size Error Interrupt */
#define HSMC_NFCINT_RBEDGE0 (1 << 24) /* Bit 24: Ready/Busy Line 0 Interrupt */
-#define HSMC_NFCINT_ALL (0x01f300030)
+#define HSMC_NFCINT_ALL (0x01f30030)
/* HSMC NFC Address Cycle Zero Register */
@@ -597,22 +594,24 @@
#define NFCADDR_CMD_VCMD2 (1 << 18) /* Bit 18:Valid Cycle 2 Command */
#define NFCADDR_CMD_ACYCLE_SHIFT (19) /* Bits 19-21: Number of Address required for command */
#define NFCADDR_CMD_ACYCLE_MASK (7 << NFCADDR_CMD_ACYCLE_SHIFT)
-# define NFCADDR_CMD_ACYCLE_NONE (0 << NFCADDR_CMD_ACYCLE_SHIFT) /* No address cycle */
-# define NFCADDR_CMD_ACYCLE_ONE (1 << NFCADDR_CMD_ACYCLE_SHIFT) /* One address cycle */
-# define NFCADDR_CMD_ACYCLE_TWO (2 << NFCADDR_CMD_ACYCLE_SHIFT) /* Two address cycles */
-# define NFCADDR_CMD_ACYCLE_THREE (3 << NFCADDR_CMD_ACYCLE_SHIFT) /* Three address cycles */
-# define NFCADDR_CMD_ACYCLE_FOUR (4 << NFCADDR_CMD_ACYCLE_SHIFT) /* Four address cycles */
-# define NFCADDR_CMD_ACYCLE_FIVE (5 << NFCADDR_CMD_ACYCLE_SHIFT) /* Five address cycles */
+# define NFCADDR_CMD_ACYCLE(n) ((uint32_t)(n) << NFCADDR_CMD_ACYCLE_SHIFT) /* n address cycles, n=0-5 */
+# define NFCADDR_CMD_ACYCLE_NONE (0 << NFCADDR_CMD_ACYCLE_SHIFT) /* No address cycle */
+# define NFCADDR_CMD_ACYCLE_ONE (1 << NFCADDR_CMD_ACYCLE_SHIFT) /* One address cycle */
+# define NFCADDR_CMD_ACYCLE_TWO (2 << NFCADDR_CMD_ACYCLE_SHIFT) /* Two address cycles */
+# define NFCADDR_CMD_ACYCLE_THREE (3 << NFCADDR_CMD_ACYCLE_SHIFT) /* Three address cycles */
+# define NFCADDR_CMD_ACYCLE_FOUR (4 << NFCADDR_CMD_ACYCLE_SHIFT) /* Four address cycles */
+# define NFCADDR_CMD_ACYCLE_FIVE (5 << NFCADDR_CMD_ACYCLE_SHIFT) /* Five address cycles */
#define NFCADDR_CMD_CSID_SHIFT (22) /* Bits 22-24: Chip Select Identifier */
-#define NFCADDR_CMD_CSID_MASK (7 << NFCADDR_CMD_CSID_SHIFT) /* Bits 22-24: Chip Select Identifier */
-# define NFCADDR_CMD_CSID_0 (0 << NFCADDR_CMD_CSID_SHIFT) /* CS0 */
-# define NFCADDR_CMD_CSID_1 (1 << NFCADDR_CMD_CSID_SHIFT) /* CS1 */
-# define NFCADDR_CMD_CSID_2 (2 << NFCADDR_CMD_CSID_SHIFT) /* CS2 */
-# define NFCADDR_CMD_CSID_3 (3 << NFCADDR_CMD_CSID_SHIFT) /* CS3 */
-# define NFCADDR_CMD_CSID_4 (4 << NFCADDR_CMD_CSID_SHIFT) /* CS4 */
-# define NFCADDR_CMD_CSID_5 (5 << NFCADDR_CMD_CSID_SHIFT) /* CS5 */
-# define NFCADDR_CMD_CSID_6 (6 << NFCADDR_CMD_CSID_SHIFT) /* CS6 */
-# define NFCADDR_CMD_CSID_7 (7 << NFCADDR_CMD_CSID_SHIFT) /* CS7 */
+#define NFCADDR_CMD_CSID_MASK (7 << NFCADDR_CMD_CSID_SHIFT)
+# define NFCADDR_CMD_CSID(n) ((uint32_t)(n) << NFCADDR_CMD_CSID_SHIFT) /* CSn, n=0-7 */
+# define NFCADDR_CMD_CSID_0 (0 << NFCADDR_CMD_CSID_SHIFT) /* CS0 */
+# define NFCADDR_CMD_CSID_1 (1 << NFCADDR_CMD_CSID_SHIFT) /* CS1 */
+# define NFCADDR_CMD_CSID_2 (2 << NFCADDR_CMD_CSID_SHIFT) /* CS2 */
+# define NFCADDR_CMD_CSID_3 (3 << NFCADDR_CMD_CSID_SHIFT) /* CS3 */
+# define NFCADDR_CMD_CSID_4 (4 << NFCADDR_CMD_CSID_SHIFT) /* CS4 */
+# define NFCADDR_CMD_CSID_5 (5 << NFCADDR_CMD_CSID_SHIFT) /* CS5 */
+# define NFCADDR_CMD_CSID_6 (6 << NFCADDR_CMD_CSID_SHIFT) /* CS6 */
+# define NFCADDR_CMD_CSID_7 (7 << NFCADDR_CMD_CSID_SHIFT) /* CS7 */
#define NFCADDR_CMD_DATAEN (1 << 25) /* Bit 25: 1=NFC Data Enable */
#define NFCADDR_CMD_DATADIS (0 << 25) /* Bit 25: 0=NFC Data disable */
#define NFCADDR_CMD_NFCRD (0 << 26) /* Bit 26: 0=NFC Read Enable */
diff --git a/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h b/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
index ec680516f..c626a5875 100644
--- a/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
+++ b/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
@@ -254,7 +254,6 @@
#define SAM_BOOTMEM_MMUFLAGS MMU_ROMFLAGS
#define SAM_ROM_MMUFLAGS MMU_ROMFLAGS
-#define SAM_NFCSRAM_MMUFLAGS MMU_IOFLAGS
#define SAM_ISRAM_MMUFLAGS MMU_MEMFLAGS
#define SAM_SMD_MMUFLAGS MMU_MEMFLAGS
#define SAM_UDPHSRAM_MMUFLAGS MMU_IOFLAGS
@@ -263,6 +262,17 @@
#define SAM_AXIMX_MMUFLAGS MMU_IOFLAGS
#define SAM_DAP_MMUFLAGS MMU_IOFLAGS
+/* If the NFC is not being used, the NFC SRAM can be used as general purpose
+ * SRAM (cached). If the NFC is used, then the NFC SRAM should be treated
+ * as an I/O devices (uncached).
+ */
+
+#ifdef CONFIG_SAMA5_HAVE_NAND
+# define SAM_NFCSRAM_MMUFLAGS MMU_IOFLAGS
+#else
+# define SAM_NFCSRAM_MMUFLAGS MMU_MEMFLAGS
+#endif
+
/* SDRAM is a special case because it requires non-cached access of its
* initial configuration, then caached access thereafter.
*/
diff --git a/nuttx/arch/arm/src/sama5/sam_nand.c b/nuttx/arch/arm/src/sama5/sam_nand.c
index 8a5a73f54..71b7fae10 100644
--- a/nuttx/arch/arm/src/sama5/sam_nand.c
+++ b/nuttx/arch/arm/src/sama5/sam_nand.c
@@ -615,7 +615,7 @@ static void nand_nfc_configure(struct sam_nandcs_s *priv, uint8_t mode,
acycle = NFCADDR_CMD_ACYCLE_NONE;
}
- cmd = (rw | regval | NFCADDR_CMD_CSID_3 | acycle |
+ cmd = (rw | regval | NFCADDR_CMD_CSID(priv->cs) | acycle |
(((mode & HSMC_CLE_VCMD2_EN) == HSMC_CLE_VCMD2_EN) ? NFCADDR_CMD_VCMD2 : 0) |
(cmd1 << NFCADDR_CMD_CMD1_SHIFT) | (cmd2 << NFCADDR_CMD_CMD2_SHIFT));
@@ -860,13 +860,17 @@ static void nand_setup_rbedge(struct sam_nandcs_s *priv)
static int hsmc_interrupt(int irq, void *context)
{
- uint32_t status = nand_getreg(SAM_HSMC_SR);
+ uint32_t sr = nand_getreg(SAM_HSMC_SR);
+ uint32_t imr = nand_getreg(SAM_HSMC_IMR);
+ uint32_t pending = sr & imr;
+
+ fllvdbg("sr=%08x imr=%08x pending=%08x\n", sr, imr, pending);
/* When set to one, this XFRDONE indicates that the NFC has terminated
* the data transfer. This flag is reset after the status read.
*/
- if ((status & HSMC_NFCINT_XFRDONE) != 0)
+ if ((pending & HSMC_NFCINT_XFRDONE) != 0)
{
g_nand.xfrdone = true;
sem_post(&g_nand.waitsem);
@@ -876,7 +880,7 @@ static int hsmc_interrupt(int irq, void *context)
* the Command. This flag is reset after the status read.
*/
- if ((status & HSMC_NFCINT_CMDDONE) != 0)
+ if ((pending & HSMC_NFCINT_CMDDONE) != 0)
{
g_nand.cmddone = true;
sem_post(&g_nand.waitsem);
@@ -888,7 +892,7 @@ static int hsmc_interrupt(int irq, void *context)
* reset after the status read.
*/
- if ((status & HSMC_NFCINT_RBEDGE0) != 0)
+ if ((pending & HSMC_NFCINT_RBEDGE0) != 0)
{
g_nand.rbedge = true;
sem_post(&g_nand.waitsem);
@@ -1179,7 +1183,7 @@ static int nand_smc_read16(uintptr_t src, uint8_t *dest, size_t buflen)
}
/****************************************************************************
- * Name: nand_write
+ * Name: nand_read
*
* Description:
* Read data from NAND using the appropriate method
@@ -1271,8 +1275,9 @@ static int nand_read_pmecc(struct sam_nandcs_s *priv, off_t block,
uint32_t regval;
uint16_t pagesize;
uint16_t sparesize;
+ int ret;
- fvdbg("Block %d Page %d\n", block, page);
+ fvdbg("block=%d page=%d data=%p\n", (int)block, page, data);
DEBUGASSERT(priv && data);
/* Get page and spare sizes */
@@ -1349,7 +1354,12 @@ static int nand_read_pmecc(struct sam_nandcs_s *priv, off_t block,
nand_putreg(SAM_HSMC_PMECCFG, regval);
regval = nand_getreg(SAM_HSMC_PMECCEADDR);
- nand_read(priv, true, (uint8_t *)data, pagesize + (regval + 1));
+ ret = nand_read(priv, true, (uint8_t *)data, pagesize + (regval + 1));
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_read for data region failed: %d\n", ret);
+ return ret;
+ }
/* Wait until the kernel of the PMECC is not busy */
@@ -1544,8 +1554,9 @@ static int nand_readpage_noecc(struct sam_nandcs_s *priv, off_t block,
uint16_t sparesize;
off_t rowaddr;
off_t coladdr;
+ int ret;
- fvdbg("Block %d Page %d\n", (int)block, page);
+ fvdbg("block=%d page=%d data=%p spare=%p\n", (int)block, page, data, spare);
DEBUGASSERT(priv && (data || spare));
/* Get page and spare sizes */
@@ -1605,14 +1616,24 @@ static int nand_readpage_noecc(struct sam_nandcs_s *priv, off_t block,
if (data)
{
- nand_read(priv, true, (uint8_t *)data, pagesize);
+ ret = nand_read(priv, true, (uint8_t *)data, pagesize);
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_read for data region failed: %d\n", ret);
+ return ret;
+ }
}
/* Read the spare are is so requested */
if (spare)
{
- nand_read(priv, true, (uint8_t *)spare, sparesize);
+ ret = nand_read(priv, true, (uint8_t *)spare, sparesize);
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_read for spare region failed: %d\n", ret);
+ return ret;
+ }
}
return OK;
@@ -1647,18 +1668,22 @@ static int nand_readpage_pmecc(struct sam_nandcs_s *priv, off_t block,
DEBUGASSERT(priv && data);
- /* Get exclusive access to the PMECC */
+ /* Make sure that we have exclusive access to the PMECC and that the PMECC
+ * is properly configured for this CS.
+ */
- nand_lock();
- sparesize = nandmodel_getsparesize(&priv->raw.model);
+ pmecc_lock();
+ pmecc_configure(priv, 0, false);
/* Start by reading the spare data */
+ sparesize = nandmodel_getsparesize(&priv->raw.model);
+
ret = nand_read_pmecc(priv, block, page, data);
if (ret < 0)
{
fdbg("ERROR: Failed to read page\n");
- return ret;
+ goto errout;
}
regval = nand_getreg(SAM_HSMC_PMECCISR);
@@ -1688,17 +1713,18 @@ static int nand_readpage_pmecc(struct sam_nandcs_s *priv, off_t block,
ret = pmecc_correction(regval, (uintptr_t)data);
if (ret < 0)
{
- fdbg("ERROR: Block %d page %d Unrecoverable data\n", block, page);
+ fdbg("ERROR: block=%d page=%d Unrecoverable data\n", block, page);
}
- /* Disable the HSMC */
+ /* Disable auto mode */
+errout:
regval = nand_getreg(SAM_HSMC_PMECCFG);
regval &= ~HSMC_PMECCFG_AUTO_MASK;
nand_putreg(SAM_HSMC_PMECCFG, regval);
nand_putreg(SAM_HSMC_PMECCTRL, HSMC_PMECCTRL_DISABLE);
- nand_unlock();
+ pmecc_unlock();
return ret;
}
#endif /* CONFIG_SAMA5_HAVE_PMECC */
@@ -1731,7 +1757,7 @@ static int nand_writepage_noecc(struct sam_nandcs_s *priv, off_t block,
off_t rowaddr;
int ret = OK;
- fvdbg("Block %d Page %d\n", block, page);
+ fvdbg("block=%d page=%d data=%p spare=%p\n", (int)block, page, data, spare);
/* Get page and spare sizes */
@@ -1789,11 +1815,21 @@ static int nand_writepage_noecc(struct sam_nandcs_s *priv, off_t block,
if (data)
{
- nand_write(priv, true, (uint8_t *)data, pagesize, 0);
+ ret = nand_write(priv, true, (uint8_t *)data, pagesize, 0);
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_write for data region failed: %d\n", ret);
+ return ret;
+ }
if (spare)
{
- nand_write(priv, true, (uint8_t *)spare, sparesize, pagesize);
+ ret = nand_write(priv, true, (uint8_t *)spare, sparesize, pagesize);
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_write for data region failed: %d\n", ret);
+ return ret;
+ }
}
}
@@ -1832,7 +1868,7 @@ static int nand_writepage_noecc(struct sam_nandcs_s *priv, off_t block,
ret = nand_write(priv, false, (uint8_t *)spare, sparesize, 0);
if (ret < 0)
{
- fdbg("ERROR: Failed writing data area\n");
+ fdbg("ERROR: nand_write for spare region failed: %d\n", ret);
ret = -EPERM;
}
@@ -1879,11 +1915,14 @@ static int nand_writepage_pmecc(struct sam_nandcs_s *priv, off_t block,
int i;
int ret = 0;
- fvdbg("Block %d Page %d\n", block, page);
+ fvdbg("block=%d page=%d data=%p\n", (int)block, page, data);
- /* Get exclusive access to the PMECC */
+ /* Make sure that we have exclusive access to the PMECC and that the PMECC
+ * is properly configured for this CS.
+ */
- nand_lock();
+ pmecc_lock();
+ pmecc_configure(priv, 0, false);
/* Calculate the start page address */
@@ -1899,7 +1938,12 @@ static int nand_writepage_pmecc(struct sam_nandcs_s *priv, off_t block,
if (data)
{
- nand_write(priv, true, (uint8_t *)data, pagesize, 0);
+ ret = nand_write(priv, true, (uint8_t *)data, pagesize, 0);
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_write for data region failed: %d\n", ret);
+ goto errout;
+ }
}
/* Get the number of sectors per page */
@@ -2000,7 +2044,14 @@ static int nand_writepage_pmecc(struct sam_nandcs_s *priv, off_t block,
}
}
- nand_write(priv, false, (uint8_t *)(uint8_t *)g_nand.ecctab, sectornumber * eccpersector, 0);
+ ret = nand_write(priv, false, (uint8_t *)(uint8_t *)g_nand.ecctab,
+ sectornumber * eccpersector, 0);
+ if (ret < 0)
+ {
+ fdbg("ERROR: nand_write for spare region failed: %d\n", ret);
+ goto errout;
+ }
+
nand_nfc_configure(priv, HSMC_CLE_WRITE_EN, COMMAND_WRITE_2, 0, 0, 0);
nand_wait_ready(priv);
@@ -2014,8 +2065,9 @@ static int nand_writepage_pmecc(struct sam_nandcs_s *priv, off_t block,
/* Disable the PMECC */
+errout:
nand_putreg(SAM_HSMC_PMECCTRL, HSMC_PMECCTRL_DISABLE);
- nand_unlock();
+ pmecc_unlock();
return ret;
}
#endif /* CONFIG_SAMA5_HAVE_PMECC */
@@ -2069,7 +2121,7 @@ static int nand_eraseblock(struct nand_raw_s *raw, off_t block)
DEBUGASSERT(priv);
- fvdbg("Block %d\n", (int)block);
+ fvdbg("block=%d\n", (int)block);
/* Get exclusvie access to the HSMC hardware.
* REVISIT: The scope of this exclusivity is just NAND.