summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/arch/arm/src/sama5/Kconfig8
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h23
-rw-r--r--nuttx/arch/arm/src/sama5/sam_boot.c2
-rw-r--r--nuttx/arch/arm/src/sama5/sam_nand.c113
-rw-r--r--nuttx/arch/arm/src/sama5/sam_pmecc.c2
-rw-r--r--nuttx/configs/sama5d3x-ek/Kconfig62
-rw-r--r--nuttx/configs/sama5d3x-ek/README.txt48
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_at24.c8
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_at25.c8
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_nandflash.c79
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_nsh.c23
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_usbmsc.c4
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h77
-rw-r--r--nuttx/include/sys/mount.h8
15 files changed, 356 insertions, 111 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 1620997b2..ef7b7326e 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6104,3 +6104,5 @@
Ken Pettit (2013-11-23)
* tools/mkctags.sh: A script for creating ctags from Ken Pettit
(2013-11-23)
+ * configs/sama5d3x-ek/src/sam_nand.c: Add support for auto-mounting
+ NAND MTD block or NXFFS devices (2013-11-25).
diff --git a/nuttx/arch/arm/src/sama5/Kconfig b/nuttx/arch/arm/src/sama5/Kconfig
index 7817f64f8..a9444325e 100644
--- a/nuttx/arch/arm/src/sama5/Kconfig
+++ b/nuttx/arch/arm/src/sama5/Kconfig
@@ -3046,7 +3046,7 @@ endchoice # CS0 Memory Type
choice
prompt "NAND ECC type"
default SAMA5_EBICS0_ECCNONE
- depends on SAMA5_EBICS0_NAND
+ depends on SAMA5_EBICS0_NAND
config SAMA5_EBICS0_ECCNONE
bool "No ECC"
@@ -3129,7 +3129,7 @@ endchoice # CS1 Memory Type
choice
prompt "NAND ECC type"
default SAMA5_EBICS1_ECCNONE
- depends on SAMA5_EBICS1_NAND
+ depends on SAMA5_EBICS1_NAND
config SAMA5_EBICS1_ECCNONE
bool "No ECC"
@@ -3212,7 +3212,7 @@ endchoice # CS2 Memory Type
choice
prompt "NAND ECC type"
default SAMA5_EBICS2_ECCNONE
- depends on SAMA5_EBICS2_NAND
+ depends on SAMA5_EBICS2_NAND
config SAMA5_EBICS2_ECCNONE
bool "No ECC"
@@ -3295,7 +3295,7 @@ endchoice # CS3 Memory Type
choice
prompt "NAND ECC type"
default SAMA5_EBICS3_ECCNONE
- depends on SAMA5_EBICS3_NAND
+ depends on SAMA5_EBICS3_NAND
config SAMA5_EBICS3_ECCNONE
bool "No ECC"
diff --git a/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h b/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
index 80c353791..ec680516f 100644
--- a/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
+++ b/nuttx/arch/arm/src/sama5/chip/sama5d3x_memorymap.h
@@ -263,25 +263,46 @@
#define SAM_AXIMX_MMUFLAGS MMU_IOFLAGS
#define SAM_DAP_MMUFLAGS MMU_IOFLAGS
+/* SDRAM is a special case because it requires non-cached access of its
+ * initial configuration, then caached access thereafter.
+ */
+
#define SAM_DDRCS_MMUFLAGS MMU_MEMFLAGS
-#if defined(CONFIG_SAMA5_EBICS0_SRAM) || defined(CONFIG_SAMA5_EBICS0_PSRAM)
+/* The external memory regions may support all access if they host SRAM,
+ * PSRAM, or SDRAM. NAND memory requires write access for NAND control and
+ * so should be uncached.
+ */
+
+#if defined(CONFIG_SAMA5_EBICS0_SRAM) || defined(CONFIG_SAMA5_EBICS0_PSRAM) || \
+ defined(CONFIG_SAMA5_EBICS0_NAND)
# define SAM_EBICS0_MMUFLAGS MMU_MEMFLAGS
+#elif defined(CONFIG_SAMA5_EBICS0_NAND)
+# define SAM_EBICS0_MMUFLAGS MMU_IOFLAGS
#else
# define SAM_EBICS0_MMUFLAGS MMU_ROMFLAGS
#endif
+
#if defined(CONFIG_SAMA5_EBICS1_SRAM) || defined(CONFIG_SAMA5_EBICS1_PSRAM)
# define SAM_EBICS1_MMUFLAGS MMU_MEMFLAGS
+#elif defined(CONFIG_SAMA5_EBICS1_NAND)
+# define SAM_EBICS2_MMUFLAGS MMU_IOFLAGS
#else
# define SAM_EBICS1_MMUFLAGS MMU_ROMFLAGS
#endif
+
#if defined(CONFIG_SAMA5_EBICS2_SRAM) || defined(CONFIG_SAMA5_EBICS2_PSRAM)
# define SAM_EBICS2_MMUFLAGS MMU_MEMFLAGS
+#elif defined(CONFIG_SAMA5_EBICS2_NAND)
+# define SAM_EBICS2_MMUFLAGS MMU_IOFLAGS
#else
# define SAM_EBICS2_MMUFLAGS MMU_ROMFLAGS
#endif
+
#if defined(CONFIG_SAMA5_EBICS3_SRAM) || defined(CONFIG_SAMA5_EBICS3_PSRAM)
# define SAM_EBICS3_MMUFLAGS MMU_MEMFLAGS
+#elif defined(CONFIG_SAMA5_EBICS3_NAND)
+# define SAM_EBICS3_MMUFLAGS MMU_IOFLAGS
#else
# define SAM_EBICS3_MMUFLAGS MMU_ROMFLAGS
#endif
diff --git a/nuttx/arch/arm/src/sama5/sam_boot.c b/nuttx/arch/arm/src/sama5/sam_boot.c
index cedddefeb..2351e26da 100644
--- a/nuttx/arch/arm/src/sama5/sam_boot.c
+++ b/nuttx/arch/arm/src/sama5/sam_boot.c
@@ -235,7 +235,7 @@ static const struct section_mapping_s section_mapping[] =
SAM_EBICS3_MMUFLAGS, SAM_EBICS3_NSECTIONS
},
#endif
-#ifdef CONFIG_SAMA5_NFCCR
+#ifdef CONFIG_SAMA5_HAVE_NAND
{ SAM_NFCCR_PSECTION, SAM_NFCCR_VSECTION,
SAM_NFCCR_MMUFLAGS, SAM_NFCCR_NSECTIONS
},
diff --git a/nuttx/arch/arm/src/sama5/sam_nand.c b/nuttx/arch/arm/src/sama5/sam_nand.c
index 89fcd4cb9..07933477a 100644
--- a/nuttx/arch/arm/src/sama5/sam_nand.c
+++ b/nuttx/arch/arm/src/sama5/sam_nand.c
@@ -359,7 +359,7 @@ static void nand_cmdsend(struct sam_nandcs_s *priv, uint32_t cmd,
/* Wait until host controller is not busy. */
- while ((nand_getreg(NFCCMD_BASE + NFCADDR_CMD_NFCCMD) & 0x8000000) != 0);
+ while ((nand_getreg(NFCCMD_BASE + NFCADDR_CMD_NFCCMD) & 0x08000000) != 0);
nand_setup_cmddone(priv);
/* Send the command plus the ADDR_CYCLE */
@@ -604,11 +604,9 @@ static void nand_nfc_configure(struct sam_nandcs_s *priv, uint8_t mode,
regval = NFCADDR_CMD_DATADIS;
}
- if (((mode & HSMC_ALE_COL_EN) == HSMC_ALE_COL_EN) ||
- ((mode & HSMC_ALE_ROW_EN) == HSMC_ALE_ROW_EN))
+ if (((mode & HSMC_ALE_COL_EN) != 0) || ((mode & HSMC_ALE_ROW_EN) != 0))
{
- bool rowonly = (((mode & HSMC_ALE_COL_EN) == 0) &&
- ((mode & HSMC_ALE_ROW_EN) == HSMC_ALE_ROW_EN));
+ bool rowonly = ((mode & HSMC_ALE_COL_EN) == 0);
nand_translate_address(priv, coladdr, rowaddr, &acycle0, &acycle1234, rowonly);
acycle = nand_get_acycle(ncycles);
}
@@ -643,7 +641,7 @@ static void nand_wait_cmddone(struct sam_nandcs_s *priv)
irqstate_t flags;
int ret;
- /* Wait for the XFRDONE interrupt to occur */
+ /* Wait for the CMDDONE interrupt to occur */
flags = irqsave();
while (!g_nand.cmddone)
@@ -655,6 +653,8 @@ static void nand_wait_cmddone(struct sam_nandcs_s *priv)
}
}
+ /* Disable further CMDDONE interrupts */
+
g_nand.cmddone = false;
nand_putreg(SAM_HSMC_IDR, HSMC_NFCINT_CMDDONE);
irqrestore(flags);
@@ -689,7 +689,7 @@ static void nand_setup_cmddone(struct sam_nandcs_s *priv)
/* Enable the CMDDONE interrupt */
- nand_putreg(SAM_HSMC_IDR, HSMC_NFCINT_CMDDONE);
+ nand_putreg(SAM_HSMC_IER, HSMC_NFCINT_CMDDONE);
irqrestore(flags);
}
@@ -724,6 +724,8 @@ static void nand_wait_xfrdone(struct sam_nandcs_s *priv)
}
}
+ /* Disable further XFRDONE interrupts */
+
g_nand.xfrdone = false;
nand_putreg(SAM_HSMC_IDR, HSMC_NFCINT_XFRDONE);
irqrestore(flags);
@@ -758,7 +760,7 @@ static void nand_setup_xfrdone(struct sam_nandcs_s *priv)
/* Enable the XFRDONE interrupt */
- nand_putreg(SAM_HSMC_IDR, HSMC_NFCINT_XFRDONE);
+ nand_putreg(SAM_HSMC_IER, HSMC_NFCINT_XFRDONE);
irqrestore(flags);
}
@@ -793,6 +795,8 @@ static void nand_wait_rbedge(struct sam_nandcs_s *priv)
}
}
+ /* Disable further RBEDGE interrupts */
+
g_nand.rbedge = false;
nand_putreg(SAM_HSMC_IDR, HSMC_NFCINT_RBEDGE0);
irqrestore(flags);
@@ -827,7 +831,7 @@ static void nand_setup_rbedge(struct sam_nandcs_s *priv)
/* Enable the EBEDGE0 interrupt */
- nand_putreg(SAM_HSMC_IDR, HSMC_NFCINT_RBEDGE0);
+ nand_putreg(SAM_HSMC_IER, HSMC_NFCINT_RBEDGE0);
irqrestore(flags);
}
@@ -1714,6 +1718,8 @@ 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);
+
/* Get page and spare sizes */
pagesize = nandmodel_getpagesize(&priv->raw.model);
@@ -1765,7 +1771,6 @@ static int nand_writepage_noecc(struct sam_nandcs_s *priv, off_t block,
/* Calculate physical address of the page */
rowaddr = block * nandmodel_pagesperblock(&priv->raw.model) + page;
- fvdbg("Block %d Page %d\n", block, page);
/* Handle the case where we use NFC SRAM */
@@ -2448,51 +2453,7 @@ struct mtd_dev_s *sam_nand_initialize(int cs)
sem_init(&priv->waitsem, 0, 0);
- /* Initialize the NAND hardware */
- /* Perform board-specific SMC intialization for this CS */
-
- ret = board_nandflash_config(cs);
- if (ret < 0)
- {
- fdbg("ERROR: board_nandflash_config failed for CS%d: %d\n",
- cs, ret);
- return NULL;
- }
-
- /* Reset the NAND FLASH part */
-
- nand_reset(priv);
-
- /* Probe the NAND part. On success, an MTD interface that wraps
- * our raw NAND interface is returned.
- */
-
- mtd = nand_initialize(&priv->raw);
- if (!mtd)
- {
- fdbg("ERROR: CS%d nand_initialize failed %d\n", cs);
- return NULL;
- }
-
- /* Allocate a DMA channel for NAND transfers
- * REVISIT: Need DMA channel setup.
- */
-
- if (nandmodel_getbuswidth(&priv->raw.model) == 16)
- {
- priv->dma = sam_dmachannel(1, DMA_FLAGS16);
- }
- else
- {
- priv->dma = sam_dmachannel(1, DMA_FLAGS8);
- }
-
- if (!priv->dma)
- {
- fdbg("ERROR: Failed to allocate the DMA channel for CS%d\n", cs);
- }
-
- /* Enable the NAND FLASH controller */
+ /* Perform one-time, global NFC/PMECC initialization */
if (!g_nand.initialized)
{
@@ -2537,6 +2498,48 @@ struct mtd_dev_s *sam_nand_initialize(int cs)
g_nand.initialized = true;
}
+ /* Initialize the NAND hardware for this CS */
+ /* Perform board-specific SMC intialization for this CS */
+
+ ret = board_nandflash_config(cs);
+ if (ret < 0)
+ {
+ fdbg("ERROR: board_nandflash_config failed for CS%d: %d\n",
+ cs, ret);
+ return NULL;
+ }
+
+ /* Reset the NAND FLASH part */
+
+ nand_reset(priv);
+
+ /* Probe the NAND part. On success, an MTD interface that wraps
+ * our raw NAND interface is returned.
+ */
+
+ mtd = nand_initialize(&priv->raw);
+ if (!mtd)
+ {
+ fdbg("ERROR: CS%d nand_initialize failed %d\n", cs);
+ return NULL;
+ }
+
+ /* Allocate a DMA channel for NAND transfers */
+
+ if (nandmodel_getbuswidth(&priv->raw.model) == 16)
+ {
+ priv->dma = sam_dmachannel(1, DMA_FLAGS16);
+ }
+ else
+ {
+ priv->dma = sam_dmachannel(1, DMA_FLAGS8);
+ }
+
+ if (!priv->dma)
+ {
+ fdbg("ERROR: Failed to allocate the DMA channel for CS%d\n", cs);
+ }
+
/* Return the MTD wrapper interface as the MTD device */
return mtd;
diff --git a/nuttx/arch/arm/src/sama5/sam_pmecc.c b/nuttx/arch/arm/src/sama5/sam_pmecc.c
index 4b23493e1..f08c9b3d7 100644
--- a/nuttx/arch/arm/src/sama5/sam_pmecc.c
+++ b/nuttx/arch/arm/src/sama5/sam_pmecc.c
@@ -702,7 +702,7 @@ static uint32_t pmecc_correctionalgo(uint32_t isr, uint32_t data)
}
#define HSMC_PAGESIZE \
- ((1 << ((nand_getreg(SAM_HSMC_PMECCFG) & HSMC_PMECCFG_PAGESIZE_MASK) >> \
+ (1 << ((nand_getreg(SAM_HSMC_PMECCFG) & HSMC_PMECCFG_PAGESIZE_MASK) >> \
HSMC_PMECCFG_PAGESIZE_SHIFT))
while (sector < (uint32_t)HSMC_PAGESIZE && isr != 0)
diff --git a/nuttx/configs/sama5d3x-ek/Kconfig b/nuttx/configs/sama5d3x-ek/Kconfig
index 8a110979d..ca8e9042b 100644
--- a/nuttx/configs/sama5d3x-ek/Kconfig
+++ b/nuttx/configs/sama5d3x-ek/Kconfig
@@ -42,13 +42,43 @@ config SAMA5_NOR_START
option: If SAMA5_NOR_START is defined, then it will not wait but
will, instead, immediately start the program in NOR FLASH.
-config SAMA5_TSD_DEVMINOR
- int "Touchscreen device minor"
- default 0
- depends on SAMA5_TSD
+config SAMA5_NAND_AUTOMOUNT
+ bool "NAND FLASH auto-mount"
+ default n
+ depends on NSH_ARCHINIT && SAMA5_EBICS3_NAND
---help---
- This touchscreen will be register as /dev/inputN where the value of
- N is provided by this configuration setting.
+ Automatically initialize the NAND FLASH driver when NSH starts.
+
+choice
+ prompt "NAND FLASH configuration"
+ default SAMA5_NAND_NXFFS
+ depends on SAMA5_NAND_AUTOMOUNT
+
+config SAMA5_NAND_FTL
+ bool "Create NAND FLASH block driver"
+ ---help---
+ Create the MTD driver for the NAND and "wrap" the NAND as a standard
+ block driver that could then, for example, be mounted using FAT or
+ any other file system. Any file system may be used, but there will
+ be no wear-leveling.
+
+ NOTE: This options is not currently recommended. There is not now
+ NuttX file system that can handle the NAND back blocks or performs
+ wear-leveling other than NXFFS and NXFFS does not use a block driver
+ but, rather, operates directly upon the NAND MTD device.
+
+config SAMA5_NAND_NXFFS
+ bool "Create NAND FLASH NXFFS file system"
+ depends on FS_NXFFS
+ ---help---
+ Create the MTD driver for the NAND and mount the NAND device as
+ a wear-leveling, NuttX FLASH file system (NXFFS). The downside of
+ NXFFS is that it can be very slow.
+
+ NOTE: NXFFS is recommended because (1) it can handle the NAND back
+ blocks and (1) performs wear-leveling.
+
+endchoice # NAND FLASH configuration
config SAMA5_AT25_AUTOMOUNT
bool "AT25 serial FLASH auto-mount"
@@ -65,7 +95,7 @@ choice
config SAMA5_AT25_FTL
bool "Create AT25 Serial FLASH block driver"
---help---
- Create the MTD driver for the AT25 and "wrap" the AT25 is a standard
+ Create the MTD driver for the AT25 and "wrap" the AT25 as a standard
block driver that could then, for example, be mounted using FAT or
any other file system. Any file system may be used, but there will
be no wear-leveling.
@@ -74,7 +104,7 @@ config SAMA5_AT25_NXFFS
bool "Create AT25 serial FLASH NXFFS file system"
depends on FS_NXFFS
---help---
- Create the MTD driver for the AT25 and and mount the AT25 device as
+ Create the MTD driver for the AT25 and mount the AT25 device as
a wear-leveling, NuttX FLASH file system (NXFFS). The downside of
NXFFS is that it can be very slow.
@@ -106,7 +136,7 @@ choice
config SAMA5_AT24_FTL
bool "Create AT24 block driver"
---help---
- Create the MTD driver for the AT24 and "wrap" the AT24 is a standard
+ Create the MTD driver for the AT24 and "wrap" the AT24 as a standard
block driver that could then, for example, be mounted using FAT or
any other file system. Any file system may be used, but there will
be no wear-leveling.
@@ -115,12 +145,20 @@ config SAMA5_AT24_NXFFS
bool "Create AT24 NXFFS file system"
depends on FS_NXFFS
---help---
- Create the MTD driver for the AT24 and and mount the AT24 device as
+ Create the MTD driver for the AT24 and mount the AT24 device as
a wear-leveling, NuttX FLASH file system (NXFFS). The downside of
NXFFS is that it can be very slow.
endchoice # AT24 serial EPPROM configuration
+config SAMA5_TSD_DEVMINOR
+ int "Touchscreen device minor"
+ default 0
+ depends on SAMA5_TSD
+ ---help---
+ This touchscreen will be register as /dev/inputN where the value of
+ N is provided by this configuration setting.
+
config SAMA5D3X_EK_CHANNEL
int "PWM channel number"
default 0 if SAMA5_PWM_CHAN0
@@ -133,8 +171,6 @@ config SAMA5D3X_EK_CHANNEL
Selects the PWM channel number that will be used to perform the PWM
test. See apps/examples/pwm.
-endif
-
if AUDIO_I2SCHAR && (SAMA5_SSC0 || SAMA5_SSC1)
if SAMA5_SSC0 && SAMA5_SSC1
@@ -172,4 +208,6 @@ config SAMA5D3X_EK_I2SCHAR_MINOR
device. The driver will be registered at /dev/is2charN where N is
the value provided by this setting.
+endif # AUDIO_I2SCHAR && (SAMA5_SSC0 || SAMA5_SSC1)
+
endif # ARCH_BOARD_SAMA5D3X_EK
diff --git a/nuttx/configs/sama5d3x-ek/README.txt b/nuttx/configs/sama5d3x-ek/README.txt
index 8596fb370..8c5516cb1 100644
--- a/nuttx/configs/sama5d3x-ek/README.txt
+++ b/nuttx/configs/sama5d3x-ek/README.txt
@@ -640,6 +640,48 @@ USB Ports
---- ----------- -------------------------------------------------------
PD28 OVCUR_USB Combined overrcurrent indication from port A and B
+NAND Support
+============
+ NAND Support can be added to the the NSH configuration by modifying the
+ NuttX configuration file as follows:
+
+ System Type -> SAMA5 Peripheal support
+ CONFIG_SAMA5_DMAC1=y : Use DMA1 for memory-to-memory DMA
+ CONFIG_SAMA5_HSMC=y : Make sure that the SMC is enabled
+
+ Drivers -> Memory Technology Device (MTD) Support
+ CONFIG_MTD=y : Enable MTD support
+ CONFIG_MTD_NAND=y : Enable NAND support
+ CONFIG_MTD_NAND_BLOCKCHECK=y : Enable bad block checking support
+ CONFIG_MTD_NAND_HWECC=y : Use H/W ECC calculation
+
+ Defaults for all other NAND settings should be okay
+
+ System Type -> External Memory Configuration
+ CONFIG_SAMA5_EBICS3=y : Enable External CS3 memory
+ CONFIG_SAMA5_EBICS3_NAND=y : Select NAND memory type
+ CONFIG_SAMA5_EBICS3_SIZE=8388608 : Use this size
+ CONFIG_SAMA5_EBICS3_PMECC=y : Use H/W ECC calculation
+ CONFIG_SAMA5_PMECC_EMBEDDEDALGO=n : Use the software PMECC algorithm
+ CONFIG_SAMA5_PMECC_GALOIS_ROMTABLES=y : use the ROM Galois tables
+
+ Defaults for ROM page table addresses should be okay
+
+ File Systems:
+ CONFIG_FS_NXFFS=y : Enable the NXFFS file system
+
+ Defaults for all other NXFFS settings should be okay
+
+ Board Selection
+ CONFIG_SAMA5_NAND_AUTOMOUNT=y : Enable FS support on NAND
+ CONFIG_SAMA5_NAND_NXFFS=y : Use the NXFFS file system
+
+ Other file systems are not recommended because only NXFFS can handle
+ bad blocks and only NXFFS performs wear-leveling.
+
+ Application Configuration -> NSH Library
+ CONFIG_NSH_ARCHINIT=y : Use architecture-specific initialization
+
AT24 Serial EEPROM
==================
@@ -2881,9 +2923,5 @@ To-Do List
do with the camera. NuttX needs something liek V4L to provide the
definition for what a camera driver is supposed to do.
-11) NAND. There is no NAND support. A NAND driver is a complex thing
- because it must support not only basic NAND access but also bad block
- detection, sparing and ECC. Lots of work!
-
-12) GMAC has only been tested on a 10/100Base-T network. I don't have a
+11) GMAC has only been tested on a 10/100Base-T network. I don't have a
1000Base-T network to support additional testing.
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_at24.c b/nuttx/configs/sama5d3x-ek/src/sam_at24.c
index e935672ca..7efe93f6a 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_at24.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_at24.c
@@ -81,14 +81,14 @@
****************************************************************************/
/****************************************************************************
- * Name: sam_at24_initialize
+ * Name: sam_at24_automount
*
* Description:
* Initialize and configure the AT24 serial EEPROM
*
****************************************************************************/
-int sam_at24_initialize(int minor)
+int sam_at24_automount(int minor)
{
FAR struct i2c_dev_s *i2c;
FAR struct mtd_dev_s *mtd;
@@ -127,7 +127,7 @@ int sam_at24_initialize(int minor)
ret = ftl_initialize(AT24_MINOR, mtd);
if (ret < 0)
{
- fdbg("ERROR: Initialize the FTL layer\n");
+ fdbg("ERROR: Failed to initialize the FTL layer: %d\n", ret);
return ret;
}
@@ -138,7 +138,7 @@ int sam_at24_initialize(int minor)
ret = nxffs_initialize(mtd);
if (ret < 0)
{
- fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ fdbg("ERROR: NXFFS initialization failed: %d\n", ret);
return ret;
}
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_at25.c b/nuttx/configs/sama5d3x-ek/src/sam_at25.c
index 4ecef3cf1..2be9a3bb1 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_at25.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_at25.c
@@ -64,14 +64,14 @@
****************************************************************************/
/****************************************************************************
- * Name: sam_at25_initialize
+ * Name: sam_at25_automount
*
* Description:
* Initialize and configure the AT25 serial FLASH
*
****************************************************************************/
-int sam_at25_initialize(int minor)
+int sam_at25_automount(int minor)
{
FAR struct spi_dev_s *spi;
FAR struct mtd_dev_s *mtd;
@@ -106,7 +106,7 @@ int sam_at25_initialize(int minor)
ret = ftl_initialize(AT25_MINOR, mtd);
if (ret < 0)
{
- fdbg("ERROR: Initialize the FTL layer\n");
+ fdbg("ERROR: Failed to initialize the FTL layer: %d\n", ret);
return ret;
}
@@ -116,7 +116,7 @@ int sam_at25_initialize(int minor)
ret = nxffs_initialize(mtd);
if (ret < 0)
{
- fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ fdbg("ERROR: NXFFS initialization failed: %d\n", ret);
return ret;
}
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_nandflash.c b/nuttx/configs/sama5d3x-ek/src/sam_nandflash.c
index 8ad48ccc5..7c3680e21 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_nandflash.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_nandflash.c
@@ -46,8 +46,15 @@
#include <nuttx/config.h>
+#include <sys/mount.h>
+#include <stdbool.h>
+#include <stdint.h>
+#include <errno.h>
#include <debug.h>
+#include <nuttx/mtd/mtd.h>
+#include <nuttx/fs/nxffs.h>
+
#include "up_arch.h"
#include "sam_periphclks.h"
#include "sam_nand.h"
@@ -55,7 +62,7 @@
#include "sama5d3x-ek.h"
-#ifdef CONFIG_SAMA5_BOOT_CS3FLASH
+#ifdef CONFIG_SAMA5_EBICS3_NAND
/****************************************************************************
* Pre-processor Definitions
@@ -73,7 +80,7 @@
* Name: board_nandflash_config
*
* Description:
- * If CONFIG_SAMA5_BOOT_CS3FLASH is defined, then NAND FLASH support is
+ * If CONFIG_SAMA5_EBICS3_NAND is defined, then NAND FLASH support is
* enabled. This function provides the board-specific implementation of
* the logic to reprogram the SMC to support NAND FLASH on the specified
* CS.
@@ -137,4 +144,70 @@ int board_nandflash_config(int cs)
return -ENODEV;
}
-#endif /* CONFIG_SAMA5_BOOT_CS3FLASH */
+/****************************************************************************
+ * Name: sam_nand_automount
+ *
+ * Description:
+ * Initialize and configure the NAND on CS3
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_NAND
+int sam_nand_automount(int minor)
+{
+ FAR struct mtd_dev_s *mtd;
+ static bool initialized = false;
+ int ret;
+
+ /* Have we already initialized? */
+
+ if (!initialized)
+ {
+ /* Create and initialize an NAND MATD device */
+
+ mtd = sam_nand_initialize(HSMC_CS3);
+ if (!mtd)
+ {
+ fdbg("ERROR: Failed to create the NAND driver on CS%d\n", HSMC_CS3);
+ return -ENODEV;
+ }
+
+#if defined(CONFIG_SAMA5_NAND_FTL)
+ /* Use the FTL layer to wrap the MTD driver as a block driver */
+
+ ret = ftl_initialize(NAND_MINOR, mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to initialize the FTL layer: %d\n", ret);
+ return ret;
+ }
+
+#elif defined(CONFIG_SAMA5_NAND_NXFFS)
+ /* Initialize to provide NXFFS on the MTD interface */
+
+ ret = nxffs_initialize(mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: NXFFS initialization failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Mount the file system at /mnt/nand */
+
+ ret = mount(NULL, "/mnt/nand", "nxffs", 0, NULL);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno);
+ return ret;
+ }
+#endif
+ /* Now we are intialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+#endif
+
+#endif /* CONFIG_SAMA5_EBICS3_NAND */
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_nsh.c b/nuttx/configs/sama5d3x-ek/src/sam_nsh.c
index 27c72158a..dc62c193e 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_nsh.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_nsh.c
@@ -86,18 +86,29 @@
int nsh_archinitialize(void)
{
-#if defined(HAVE_AT25) || defined(HAVE_AT24) || defined(HAVE_HSMCI) || \
- defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR)
+#if defined(HAVE_NAND) || defined(HAVE_AT25) || defined(HAVE_AT24) || \
+ defined(HAVE_HSMCI) || defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR)
int ret;
#endif
+#ifdef HAVE_NAND
+ /* Initialize the NAND driver */
+
+ ret = sam_nand_automount(NAND_MINOR);
+ if (ret < 0)
+ {
+ message("ERROR: sam_nand_automount failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
#ifdef HAVE_AT25
/* Initialize the AT25 driver */
- ret = sam_at25_initialize(AT25_MINOR);
+ ret = sam_at25_automount(AT25_MINOR);
if (ret < 0)
{
- message("ERROR: sam_at25_initialize failed: %d\n", ret);
+ message("ERROR: sam_at25_automount failed: %d\n", ret);
return ret;
}
#endif
@@ -105,10 +116,10 @@ int nsh_archinitialize(void)
#ifdef HAVE_AT24
/* Initialize the AT24 driver */
- ret = sam_at24_initialize(AT24_MINOR);
+ ret = sam_at24_automount(AT24_MINOR);
if (ret < 0)
{
- message("ERROR: sam_at24_initialize failed: %d\n", ret);
+ message("ERROR: sam_at24_automount failed: %d\n", ret);
return ret;
}
#endif
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_usbmsc.c b/nuttx/configs/sama5d3x-ek/src/sam_usbmsc.c
index b303e6d87..a386bda49 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_usbmsc.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_usbmsc.c
@@ -110,10 +110,10 @@ int usbmsc_archinitialize(void)
/* Initialize the AT25 MTD driver */
#ifdef HAVE_AT25
- int ret = sam_at25_initialize(AT25_MINOR);
+ int ret = sam_at25_automount(AT25_MINOR);
if (ret < 0)
{
- message("ERROR: sam_at25_initialize failed: %d\n", ret);
+ message("ERROR: sam_at25_automount failed: %d\n", ret);
}
return ret;
diff --git a/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h b/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
index 99b097aa6..f0cff264e 100644
--- a/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
+++ b/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
@@ -58,6 +58,7 @@
#define HAVE_HSMCI 1
#define HAVE_AT24 1
#define HAVE_AT25 1
+#define HAVE_NAND 1
#define HAVE_USBHOST 1
#define HAVE_USBDEV 1
#define HAVE_USBMONITOR 1
@@ -84,6 +85,39 @@
# undef HAVE_HSMCI
#endif
+/* NAND FLASH */
+/* Can't support the NAND device if NAND flash is not configured on EBI CS3 */
+
+#ifndef CONFIG_SAMA5_EBICS3_NAND
+# undef HAVE_NAND
+#endif
+
+/* Can't support NAND features if mountpoints are disabled or if we were not
+ * asked to mount the NAND part
+ */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_SAMA5_NAND_AUTOMOUNT)
+# undef HAVE_NAND
+#endif
+
+/* If we are going to mount the NAND, then they user must also have told
+ * us what to do with it by setting one of these.
+ */
+
+#ifndef CONFIG_FS_NXFFS
+# undef CONFIG_SAMA5_NAND_NXFFS
+#endif
+
+#if !defined(CONFIG_SAMA5_NAND_FTL) && !defined(CONFIG_SAMA5_NAND_NXFFS)
+# undef HAVE_NAND
+#endif
+
+#if defined(CONFIG_SAMA5_NAND_FTL) && defined(CONFIG_SAMA5_NAND_NXFFS)
+# warning Both CONFIG_SAMA5_NAND_FTL and CONFIG_SAMA5_NAND_NXFFS are set
+# warning Ignoring CONFIG_SAMA5_NAND_NXFFS
+# undef CONFIG_SAMA5_NAND_NXFFS
+#endif
+
/* AT25 Serial FLASH */
/* Can't support the AT25 device if it SPI0 or AT25 support are not enabled */
@@ -167,15 +201,28 @@
# undef CONFIG_SAMA5_AT24_NXFFS
#endif
-/* Assign minor device numbers. We will also use MINOR number 0 for the AT25.
- * It should appear as /dev/mtdblock0
+/* Assign minor device numbers. For example, if we also use MINOR number 0
+ * for the AT25, it should appear as /dev/mtdblock0
*/
+#define _NAND_MINOR 0
+
+#ifdef HAVE_NAND
+# define NAND_MINOR _NAND_MINOR
+# define _AT25_MINOR (_NAND_MINOR+1)
+#else
+# define _AT25_MINOR _NAND_MINOR
+#endif
+
#ifdef HAVE_AT25
-# define AT25_MINOR 0
-# define AT24_MINOR 1
+# define AT25_MINOR _AT25_MINOR
+# define _AT24_MINOR (_AT25_MINOR+1)
#else
-# define AT24_MINOR 0
+# define _AT24_MINOR _AT25_MINOR
+#endif
+
+#ifdef HAVE_AT24
+# define AT24_MINOR _AT24_MINOR
#endif
/* MMC/SD minor numbers: The NSH device minor extended is extened to support
@@ -549,7 +596,19 @@ void sam_sdram_config(void);
#endif
/****************************************************************************
- * Name: sam_at25_initialize
+ * Name: sam_nand_automount
+ *
+ * Description:
+ * Initialize and configure the NAND on CS3
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_NAND
+int sam_nand_automount(int minor);
+#endif
+
+/****************************************************************************
+ * Name: sam_at25_automount
*
* Description:
* Initialize and configure the AT25 serial FLASH
@@ -557,11 +616,11 @@ void sam_sdram_config(void);
****************************************************************************/
#ifdef HAVE_AT25
-int sam_at25_initialize(int minor);
+int sam_at25_automount(int minor);
#endif
/****************************************************************************
- * Name: sam_at24_initialize
+ * Name: sam_at24_automount
*
* Description:
* Initialize and configure the AT24 serial EEPROM
@@ -569,7 +628,7 @@ int sam_at25_initialize(int minor);
****************************************************************************/
#ifdef HAVE_AT24
-int sam_at24_initialize(int minor);
+int sam_at24_automount(int minor);
#endif
/****************************************************************************
diff --git a/nuttx/include/sys/mount.h b/nuttx/include/sys/mount.h
index 194dec8cc..4553618b4 100644
--- a/nuttx/include/sys/mount.h
+++ b/nuttx/include/sys/mount.h
@@ -64,10 +64,10 @@ extern "C" {
#define EXTERN extern
#endif
-EXTERN int mount(const char *source, const char *target,
- const char *filesystemtype, unsigned long mountflags,
- const void *data);
-EXTERN int umount(const char *target);
+int mount(const char *source, const char *target,
+ const char *filesystemtype, unsigned long mountflags,
+ const void *data);
+int umount(const char *target);
#undef EXTERN
#if defined(__cplusplus)