summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-11-17 08:56:30 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-11-17 08:56:30 -0600
commitc871a0b7e2edcfb6957ed431e5ad84f43a28aa3d (patch)
tree9bfe8106a59847a8fd0c4f99ec4c8cbfc9d78590 /nuttx
parent8cd61239af2a935ec08fb0e5dd55152d7824505e (diff)
downloadpx4-nuttx-c871a0b7e2edcfb6957ed431e5ad84f43a28aa3d.tar.gz
px4-nuttx-c871a0b7e2edcfb6957ed431e5ad84f43a28aa3d.tar.bz2
px4-nuttx-c871a0b7e2edcfb6957ed431e5ad84f43a28aa3d.zip
Continuing NAND integration
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/arch/arm/src/sama5/sam_nand.c56
-rw-r--r--nuttx/drivers/mtd/Make.defs2
-rwxr-xr-xnuttx/drivers/mtd/mtd_nand.c42
-rw-r--r--nuttx/drivers/mtd/mtd_nandmodel.c245
-rwxr-xr-xnuttx/drivers/mtd/mtd_rawnand.c115
-rw-r--r--nuttx/include/nuttx/mtd/nand.h24
-rw-r--r--nuttx/include/nuttx/mtd/nand_model.h63
-rw-r--r--nuttx/include/nuttx/mtd/nand_raw.h165
9 files changed, 379 insertions, 335 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 13d95bb90..fc411dfaf 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6077,4 +6077,6 @@
(2013-11-16).
* drivers/mtd/mtd_nandmodel.c: More NAND support (same story).
(2013-11-16).
+ * drivers/mtd/mtd_rawnand.c and include/nuttx/mtd/nand_raw.h: More
+ NAND support (2013-11-17).
diff --git a/nuttx/arch/arm/src/sama5/sam_nand.c b/nuttx/arch/arm/src/sama5/sam_nand.c
index 03b8b8d18..d62741b89 100644
--- a/nuttx/arch/arm/src/sama5/sam_nand.c
+++ b/nuttx/arch/arm/src/sama5/sam_nand.c
@@ -53,11 +53,13 @@
#include <stdint.h>
#include <string.h>
#include <errno.h>
+#include <assert.h>
#include <debug.h>
#include <nuttx/fs/ioctl.h>
#include <nuttx/mtd/mtd.h>
#include <nuttx/mtd/nand.h>
+#include <nuttx/mtd/nand_raw.h>
#include <nuttx/mtd/nand_model.h>
#include <arch/board/board.h>
@@ -73,18 +75,15 @@
****************************************************************************/
/* This type represents the state of the raw NAND MTD device. The struct
- * mtd_dev_s must appear at the beginning of the definition so that you can
- * freely cast between pointers to struct mtd_dev_s and struct nand_raw_s.
+ * nand_raw_s must appear at the beginning of the definition so that you can
+ * freely cast between pointers to struct mtd_dev_s, struct nand_raw_s, and
+ * struct sam_rawnand_s.
*/
-struct nand_raw_s
+struct sam_rawnand_s
{
- struct mtd_dev_s mtd; /* Externally visible part of the driver */
+ struct nand_raw_s raw; /* Externally visible part of the driver */
uint8_t cs; /* Chip select number (0..3) */
- struct nand_model_s model; /* The NAND model */
- uintptr_t cmdaddr; /* NAND command address base */
- uintptr_t addraddr; /* NAND address address base */
- uintptr_t dataaddr; /* NAND data address */
};
/****************************************************************************
@@ -110,16 +109,16 @@ static int nand_ioctl(struct mtd_dev_s *dev, int cmd,
*/
#ifdef CONFIG_SAMA5_EBICS0_NAND
-static struct nand_raw_s g_cs0nand;
+static struct sam_rawnand_s g_cs0nand;
#endif
#ifdef CONFIG_SAMA5_EBICS1_NAND
-static struct nand_raw_s g_cs1nand;
+static struct sam_rawnand_s g_cs1nand;
#endif
#ifdef CONFIG_SAMA5_EBICS2_NAND
-static struct nand_raw_s g_cs2nand;
+static struct sam_rawnand_s g_cs2nand;
#endif
#ifdef CONFIG_SAMA5_EBICS3_NAND
-static struct nand_raw_s g_cs3nand;
+static struct sam_rawnand_s g_cs3nand;
#endif
/****************************************************************************
@@ -137,7 +136,7 @@ static struct nand_raw_s g_cs3nand;
static int nand_erase(struct mtd_dev_s *dev, off_t startblock,
size_t nblocks)
{
- struct nand_raw_s *priv = (struct nand_raw_s *)dev;
+ struct sam_rawnand_s *priv = (struct sam_rawnand_s *)dev;
/* The interface definition assumes that all erase blocks are the same size.
* If that is not true for this particular device, then transform the
@@ -161,7 +160,7 @@ static int nand_erase(struct mtd_dev_s *dev, off_t startblock,
static ssize_t nand_bread(struct mtd_dev_s *dev, off_t startblock,
size_t nblocks, uint8_t *buf)
{
- struct nand_raw_s *priv = (struct nand_raw_s *)dev;
+ struct sam_rawnand_s *priv = (struct sam_rawnand_s *)dev;
/* The interface definition assumes that all read/write blocks are the same size.
* If that is not true for this particular device, then transform the
@@ -187,7 +186,7 @@ static ssize_t nand_bread(struct mtd_dev_s *dev, off_t startblock,
static ssize_t nand_bwrite(struct mtd_dev_s *dev, off_t startblock,
size_t nblocks, const uint8_t *buf)
{
- struct nand_raw_s *priv = (struct nand_raw_s *)dev;
+ struct sam_rawnand_s *priv = (struct sam_rawnand_s *)dev;
/* The interface definition assumes that all read/write blocks are the same size.
* If that is not true for this particular device, then transform the
@@ -208,7 +207,7 @@ static ssize_t nand_bwrite(struct mtd_dev_s *dev, off_t startblock,
static int nand_ioctl(struct mtd_dev_s *dev, int cmd, unsigned long arg)
{
- struct nand_raw_s *priv = (struct nand_raw_s *)dev;
+ struct sam_rawnand_s *priv = (struct sam_rawnand_s *)dev;
int ret = -EINVAL; /* Assume good command with bad parameters */
switch (cmd)
@@ -281,7 +280,7 @@ static int nand_ioctl(struct mtd_dev_s *dev, int cmd, unsigned long arg)
struct mtd_dev_s *sam_nand_initialize(int cs)
{
- struct nand_raw_s *priv;
+ struct sam_rawnand_s *priv;
struct mtd_s *mtd;
uintptr_t cmdaddr;
uintptr_t addraddr;
@@ -366,15 +365,15 @@ struct mtd_dev_s *sam_nand_initialize(int cs)
/* Initialize the device structure */
- memset(priv, 0, sizeof(struct nand_raw_s));
- priv->mtd.erase = nand_erase;
- priv->mtd.bread = nand_bread;
- priv->mtd.bwrite = nand_bwrite;
- priv->mtd.ioctl = nand_ioctl;
- priv->cs = cs;
- priv->cmdaddr = cmdaddr;
- priv->addraddr = addraddr;
- priv->dataaddr = dataaddr;
+ memset(priv, 0, sizeof(struct sam_rawnand_s));
+ priv->raw.mtd.erase = nand_erase;
+ priv->raw.mtd.bread = nand_bread;
+ priv->raw.mtd.bwrite = nand_bwrite;
+ priv->raw.mtd.ioctl = nand_ioctl;
+ priv->raw.cmdaddr = cmdaddr;
+ priv->raw.addraddr = addraddr;
+ priv->raw.dataaddr = dataaddr;
+ priv->cs = cs;
/* Initialize the NAND hardware */
/* Perform board-specific SMC intialization for this CS */
@@ -391,11 +390,10 @@ struct mtd_dev_s *sam_nand_initialize(int cs)
* our raw NAND interface is returned.
*/
- mtd = nand_initialize(&priv->mtd, cmdaddr, addraddr, dataaddr, &priv->model);
+ mtd = nand_initialize(&priv->raw);
if (!mtd)
{
- fdbg("ERROR: CS%d nand_initialize failed: %d at (%p, %p, %p)\n",
- cs, (FAR void *)cmdaddr, (FAR void *)addraddr, (FAR void *)dataaddr);
+ fdbg("ERROR: CS%d nand_initialize failed %d\n", cs);
return NULL;
}
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index e5e4a3e6c..1d83cf5f9 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -46,7 +46,7 @@ CSRCS += mtd_partition.c
endif
ifeq ($(CONFIG_MTD_NAND),y)
-CSRCS += mtd_nand.c mtd_onfi.c mtd_nandmodel.c mtd_modeltab.c
+CSRCS += mtd_nand.c mtd_onfi.c mtd_rawnand.c mtd_nandmodel.c mtd_modeltab.c
endif
ifeq ($(CONFIG_RAMMTD),y)
diff --git a/nuttx/drivers/mtd/mtd_nand.c b/nuttx/drivers/mtd/mtd_nand.c
index f94b0bae8..b0bf9826d 100755
--- a/nuttx/drivers/mtd/mtd_nand.c
+++ b/nuttx/drivers/mtd/mtd_nand.c
@@ -59,6 +59,7 @@
#include <nuttx/mtd/mtd.h>
#include <nuttx/mtd/nand.h>
#include <nuttx/mtd/onfi.h>
+#include <nuttx/mtd/nand_raw.h>
#include <nuttx/mtd/nand_scheme.h>
#include <nuttx/mtd/nand_model.h>
@@ -230,7 +231,7 @@ static int nand_ioctl(struct mtd_dev_s *dev, int cmd, unsigned long arg)
* Probe and initialize NAND.
*
* Input parameters:
- * raw - Raw NAND FLASH MTD interface
+ * raw - Lower-half, raw NAND FLASH interface
* cmdaddr - NAND command address base
* addraddr - NAND address address base
* dataaddr - NAND data address
@@ -243,43 +244,53 @@ static int nand_ioctl(struct mtd_dev_s *dev, int cmd, unsigned long arg)
*
****************************************************************************/
-FAR struct mtd_dev_s *nand_initialize(FAR struct mtd_dev_s *raw,
- uintptr_t cmdaddr, uintptr_t addraddr,
- uintptr_t dataaddr,
- FAR struct nand_model_s *model)
+FAR struct mtd_dev_s *nand_initialize(FAR struct nand_raw_s *raw)
{
FAR struct nand_dev_s *priv;
struct onfi_pgparam_s onfi;
- bool compatible;
- bool havemodel = false;
int ret;
fvdbg("cmdaddr=%p addraddr=%p dataaddr=%p\n",
- (FAR void *)cmdaddr, (FAR void *)addraddr, (FAR void *)dataaddr);
+ (FAR void *)raw->cmdaddr, (FAR void *)raw->addraddr,
+ (FAR void *)raw->dataaddr);
/* Check if there is NAND connected on the EBI */
- if (!onfi_ebidetect(cmdaddr, addraddr, dataaddr))
+ if (!onfi_ebidetect(raw->cmdaddr, raw->addraddr, raw->dataaddr))
{
fdbg("ERROR: No NAND device detected at: %p %p %p\n",
- (FAR void *)cmdaddr, (FAR void *)addraddr, (FAR void *)dataaddr);
+ (FAR void *)raw->cmdaddr, (FAR void *)raw->addraddr,
+ (FAR void *)raw->dataaddr);
return NULL;
}
/* Read the ONFI page parameters from the NAND device */
- ret = onfi_read(cmdaddr, addraddr, dataaddr, &onfi);
+ ret = onfi_read(raw->cmdaddr, raw->addraddr, raw->dataaddr, &onfi);
if (ret < 0)
{
- fvdbg("ERROR: Failed to get ONFI page parameters: %d\n", ret);
- compatible = false;
+ uint32_t chipid;
+
+ fvdbg("Failed to get ONFI page parameters: %d\n", ret);
+
+ /* If the ONFI model is not supported, determine the NAND
+ * model from a lookup of known FLASH parts.
+ */
+
+ chipid = nand_chipid(raw);
+ if (nandmodel_find(g_nandmodels, NAND_NMODELS, chipid,
+ &raw->model))
+ {
+ fdbg("ERROR: Could not determine NAND model\n");
+ return NULL;
+ }
}
else
{
+ FAR struct nand_model_s *model = &raw->model;
uint64_t size;
fvdbg("Found ONFI compliant NAND FLASH\n");
- compatible = true;
/* Construct the NAND model structure */
@@ -320,8 +331,6 @@ FAR struct mtd_dev_s *nand_initialize(FAR struct mtd_dev_s *raw,
break;
}
- havemodel = true;
-
/* Disable any internal, embedded ECC function */
(void)onfi_embeddedecc(&onfi, cmdaddr, addraddr, dataaddr, false);
@@ -343,7 +352,6 @@ FAR struct mtd_dev_s *nand_initialize(FAR struct mtd_dev_s *raw,
priv->mtd.bwrite = nand_bwrite;
priv->mtd.ioctl = nand_ioctl;
priv->raw = raw;
- priv->model = model;
#warning Missing logic
diff --git a/nuttx/drivers/mtd/mtd_nandmodel.c b/nuttx/drivers/mtd/mtd_nandmodel.c
index 643804fa4..bd7d898c2 100644
--- a/nuttx/drivers/mtd/mtd_nandmodel.c
+++ b/nuttx/drivers/mtd/mtd_nandmodel.c
@@ -89,8 +89,8 @@ int nandmodel_find(FAR const struct nand_model_s *modeltab, size_t size,
bool found = false;
int i;
- id2 = (uint8_t)(chipid>>8);
- id4 = (uint8_t)(chipid>>24);
+ id2 = (uint8_t)(chipid >> 8);
+ id4 = (uint8_t)(chipid >> 24);
fvdbg("NAND ID is 0x%08x\n", (int)chipid);
@@ -206,14 +206,13 @@ int nandmodel_translate(FAR const struct nand_model_s *model, off_t address,
if ((address + size) > nandmodel_getdevbytesize(model))
{
-
fvdbg("nandmodel_translate: out-of-bounds access.\n");
return -ESPIPE;
}
/* Get Nand info */
- blocksize = nandmodel_getblocksize(model);
+ blocksize = nandmodel_getbyteblocksize(model);
pagesize = nandmodel_getpagesize(model);
/* Translate address */
@@ -246,183 +245,6 @@ int nandmodel_translate(FAR const struct nand_model_s *model, off_t address,
}
/****************************************************************************
- * Name: nandmodel_getscheme
- *
- * Description:
- * Returns the spare area placement scheme used by a particular nandflash
- * model.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Spare placement scheme
- *
- ****************************************************************************/
-
-FAR const struct nand_dev_scheme_s *
-nandmodel_getscheme(FAR const struct nand_model_s *model)
-{
- return model->scheme;
-}
-
-/****************************************************************************
- * Name: nandmodel_getdevid
- *
- * Description:
- * Returns the device ID of a particular NAND FLASH model.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Device ID
- *
- ****************************************************************************/
-
-uint8_t nandmodel_getdevid(FAR const struct nand_model_s *model)
-{
- return model->devid;
-}
-
-/****************************************************************************
- * Name: nandmodel_getdevblocksize
- *
- * Description:
- * Returns the number of blocks in the entire device.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Number of blocks in the device
- *
- ****************************************************************************/
-
-off_t nandmodel_getdevblocksize(FAR const struct nand_model_s *model)
-{
- return (1024 * model->devsize) / model->blocksize;
-}
-
-/****************************************************************************
- * Name: nandmodel_getdevpagesize
- *
- * Description:
- * Returns the number of pages in the entire device.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Number of pages in the device
- *
- ****************************************************************************/
-
-size_t nandmodel_getdevpagesize(FAR const struct nand_model_s *model)
-{
- return (uint32_t)nandmodel_getdevblocksize(model) //* 8 // HACK
- * nandmodel_getblocksize(model);
-}
-
-/****************************************************************************
- * Name: nandmodel_getdevbytesize
- *
- * Description:
- * Returns the size of the whole device in bytes (this does not include
- * the size of the spare zones).
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Size of the device in bytes
- *
- ****************************************************************************/
-
-uint64_t nandmodel_getdevbytesize(FAR const struct nand_model_s *model)
-{
- return ((uint64_t)model->devsize) << 20;
-}
-
-/****************************************************************************
- * Name: nandmodel_getdevmbsize
- *
- * Description:
- * Returns the size of the whole device in Mega bytes (this does not
- * include the size of the spare zones).
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * size of the device in MB.
- *
- ****************************************************************************/
-
-uint32_t nandmodel_getdevmbsize(FAR const struct nand_model_s *model)
-{
- return ((uint32_t)model->devsize);
-}
-
-/****************************************************************************
- * Name: nandmodel_getblockpagesize
- *
- * Description:
- * Returns the number of pages in one single block of a device.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Block size in pages
- *
- ****************************************************************************/
-
-unsigned int nandmodel_getblockpagesize(FAR const struct nand_model_s *model)
-{
- return model->blocksize * 1024 / model->pagesize;
-}
-
-/****************************************************************************
- * Name: nandmodel_getblockbytesize
- *
- * Description:
- * Returns the size in bytes of one single block of a device. This does not
- * take into account the spare zones size.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Block size in bytes
- *
- ****************************************************************************/
-
-unsigned int nandmodel_getblockbytesize(FAR const struct nand_model_s *model)
-{
- return model->blocksize * 1024;
-}
-
-/****************************************************************************
- * Name: nandmodel_getpagesize
- *
- * Description:
- * Returns the size of the data area of a page in bytes.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Size of data area in bytes
- *
- ****************************************************************************/
-
-unsigned int nandmodel_getpagesize(FAR const struct nand_model_s *model)
-{
- return model->pagesize;
-}
-
-/****************************************************************************
* Name: nandmodel_getsparesize
*
* Description:
@@ -447,64 +269,3 @@ unsigned int nandmodel_getsparesize(FAR const struct nand_model_s *model)
return (model->pagesize >> 5); /* Spare size is 16/512 of data size */
}
}
-
-/****************************************************************************
- * Name: nandmodel_getbuswidth
- *
- * Description:
- * Returns the number of bits used by the data bus of a NAND FLASH device.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * data width
- *
- ****************************************************************************/
-
-unsigned int nandmodel_getbuswidth(FAR const struct nand_model_s *model)
-{
- return (model->options & NANDMODEL_DATAWIDTH16)? 16 : 8;
-}
-
-/****************************************************************************
- * Name: nandmodel_havesmallblocks
- *
- * Description:
- * Returns true if the given NAND FLASH model uses the "small blocks/pages"
- * command set; otherwise returns false.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Returns true if the given NAND FLASH model uses the "small blocks/pages"
- * command set; otherwise returns false.
- *
- ****************************************************************************/
-
-bool nandmodel_havesmallblocks(FAR const struct nand_model_s *model)
-{
- return (model->pagesize <= 512 )? 1: 0;
-}
-
-/****************************************************************************
- * Name: nandmodel_havecopyback
- *
- * Description:
- * Returns true if the device supports the copy-back operation. Otherwise
- * returns false.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Returns true if the device supports the copy-back operation. Otherwise
- * returns false.
- *
- ****************************************************************************/
-
-bool nandmodel_havecopyback(FAR const struct nand_model_s *model)
-{
- return ((model->options & NANDMODEL_COPYBACK) != 0);
-}
diff --git a/nuttx/drivers/mtd/mtd_rawnand.c b/nuttx/drivers/mtd/mtd_rawnand.c
new file mode 100755
index 000000000..92e4d82b6
--- /dev/null
+++ b/nuttx/drivers/mtd/mtd_rawnand.c
@@ -0,0 +1,115 @@
+/****************************************************************************
+ * drivers/mtd/mtd_rawnand.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This logic was based largely on Atmel sample code with modifications for
+ * better integration with NuttX. The Atmel sample code has a BSD
+ * compatibile license that requires this copyright notice:
+ *
+ * Copyright (c) 2011, 2012, Atmel Corporation
+ *
+ * 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 names NuttX nor Atmel nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/mtd/nand_config.h>
+
+#include <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/mtd/nand_raw.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nand_chipid
+ *
+ * Description:
+ * Reads and returns the identifiers of a NAND FLASH chip
+ *
+ * Input Parameters:
+ * raw - Pointer to a struct nand_raw_s instance.
+ *
+ * Returned Value:
+ * id1|(id2<<8)|(id3<<16)|(id4<<24)
+ *
+ ****************************************************************************/
+
+uint32_t nand_chipid(struct nand_raw_s *raw)
+{
+ uint8_t id[5];
+
+ DEBUGASSERT(raw);
+
+ WRITE_COMMAND8(raw, COMMAND_READID);
+ WRITE_ADDRESS8(raw, 0);
+
+ id[0] = READ_DATA8(raw);
+ id[1] = READ_DATA8(raw);
+ id[2] = READ_DATA8(raw);
+ id[3] = READ_DATA8(raw);
+ id[4] = READ_DATA8(raw);
+
+ fvdbg("Chip ID: %02x %02x %02x %02x %02x\n",
+ id[0], id[1], id[2], id[3], id[4]);
+
+ return (uint32_t)id[0] |
+ ((uint32_t)id[1] << 8) |
+ ((uint32_t)id[2] << 16) |
+ ((uint32_t)id[3] << 24);
+}
diff --git a/nuttx/include/nuttx/mtd/nand.h b/nuttx/include/nuttx/mtd/nand.h
index 4554841d9..6ac8f1445 100644
--- a/nuttx/include/nuttx/mtd/nand.h
+++ b/nuttx/include/nuttx/mtd/nand.h
@@ -52,7 +52,7 @@
#include <stdbool.h>
#include <nuttx/mtd/mtd.h>
-#include <nuttx/mtd/nand_model.h>
+#include <nuttx/mtd/nand_raw.h>
/****************************************************************************
* Pre-Processor Definitions
@@ -61,17 +61,16 @@
/****************************************************************************
* Public Types
****************************************************************************/
-
-/* This type represents the state of the NAND MTD device. The struct
- * mtd_dev_s must appear at the beginning of the definition so that you can
- * freely cast between pointers to struct mtd_dev_s and struct nand_dev_s.
+/* This type represents the state of the upper-half NAND MTD device. The
+ * struct mtd_dev_s must appear at the beginning of the definition so that
+ * you can freely cast between pointers to struct mtd_dev_s and struct
+ * nand_dev_s.
*/
struct nand_dev_s
{
struct mtd_dev_s mtd; /* Externally visible part of the driver */
- struct mtd_dev_s *raw; /* The lower-half, "raw" nand MTD driver */
- struct nand_model_s *model; /* Reference to the model (in the raw data structure) */
+ FAR struct nand_raw_s *raw; /* Retained reference to the lower half */
};
/****************************************************************************
@@ -99,12 +98,7 @@ extern "C"
* Probe and initialize NAND.
*
* Input parameters:
- * raw - Raw NAND FLASH MTD interface
- * cmdaddr - NAND command address base
- * addraddr - NAND address address base
- * dataaddr - NAND data address
- * model - A pointer to the model data (probably in the raw MTD
- * driver instance.
+ * raw - Lower-half, raw NAND FLASH interface
*
* Returned value.
* A non-NULL MTD driver intstance is returned on success. NULL is
@@ -112,9 +106,7 @@ extern "C"
*
****************************************************************************/
-FAR struct mtd_dev_s *nand_initialize(FAR struct mtd_dev_s *raw,
- uintptr_t cmdaddr, uintptr_t addraddr,
- uintptr_t dataaddr, FAR struct nand_model_s *model);
+FAR struct mtd_dev_s *nand_initialize(FAR struct nand_raw_s *raw);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/include/nuttx/mtd/nand_model.h b/nuttx/include/nuttx/mtd/nand_model.h
index 32268f44d..cca3414a1 100644
--- a/nuttx/include/nuttx/mtd/nand_model.h
+++ b/nuttx/include/nuttx/mtd/nand_model.h
@@ -174,8 +174,7 @@ int nandmodel_translate(FAR const struct nand_model_s *model, off_t address,
*
****************************************************************************/
-FAR const struct nand_dev_scheme_s *
-nandmodel_getscheme(FAR const struct nand_model_s *model);
+#define nandmodel_getscheme(m) ((m)->scheme)
/****************************************************************************
* Name: nandmodel_getdevid
@@ -191,7 +190,7 @@ nandmodel_getscheme(FAR const struct nand_model_s *model);
*
****************************************************************************/
-uint8_t nandmodel_getdevid(FAR const struct nand_model_s *model);
+#define nandmodel_getdevid(m) ((m)->devid)
/****************************************************************************
* Name: nandmodel_getdevblocksize
@@ -207,23 +206,8 @@ uint8_t nandmodel_getdevid(FAR const struct nand_model_s *model);
*
****************************************************************************/
-off_t nandmodel_getdevblocksize(FAR const struct nand_model_s *model);
-
-/****************************************************************************
- * Name: nandmodel_getdevpagesize
- *
- * Description:
- * Returns the number of pages in the entire device.
- *
- * Input Parameters:
- * model Pointer to a nand_model_s instance.
- *
- * Returned Values:
- * Number of pages in the device
- *
- ****************************************************************************/
-
-size_t nandmodel_getdevpagesize(FAR const struct nand_model_s *model);
+#define nandmodel_getdevblocksize(m) \
+ ((off_t)((m)->devsize << 10) / (m)->blocksize)
/****************************************************************************
* Name: nandmodel_getdevbytesize
@@ -240,7 +224,7 @@ size_t nandmodel_getdevpagesize(FAR const struct nand_model_s *model);
*
****************************************************************************/
-uint64_t nandmodel_getdevbytesize(FAR const struct nand_model_s *model);
+#define nandmodel_getdevbytesize(m) (((uint64_t)((m)->devsize) << 20))
/****************************************************************************
* Name: nandmodel_getdevmbsize
@@ -257,7 +241,7 @@ uint64_t nandmodel_getdevbytesize(FAR const struct nand_model_s *model);
*
****************************************************************************/
-uint32_t nandmodel_getdevmbsize(FAR const struct nand_model_s *model);
+#define nandmodel_getdevmbsize(m) ((uint32_t)((m)->devsize))
/****************************************************************************
* Name: nandmodel_getblocksize
@@ -276,7 +260,7 @@ uint32_t nandmodel_getdevmbsize(FAR const struct nand_model_s *model);
unsigned int nandmodel_getblocksize(FAR const struct nand_model_s *model);
/****************************************************************************
- * Name: nandmodel_getblockpagesize
+ * Name: nandmodel_getpageblocksize
*
* Description:
* Returns the number of pages in one single block of a device.
@@ -289,10 +273,28 @@ unsigned int nandmodel_getblocksize(FAR const struct nand_model_s *model);
*
****************************************************************************/
-unsigned int nandmodel_getblockpagesize(FAR const struct nand_model_s *model);
+#define nandmodel_getpageblocksize(m) \
+ ((uint32_t)((m)->blocksize << 10) / model->pagesize)
+
+/****************************************************************************
+ * Name: nandmodel_getdevpagesize
+ *
+ * Description:
+ * Returns the number of pages in the entire device.
+ *
+ * Input Parameters:
+ * model Pointer to a nand_model_s instance.
+ *
+ * Returned Values:
+ * Number of pages in the device
+ *
+ ****************************************************************************/
+
+#define nandmodel_getdevpagesize(m) \
+ ((uint32_t)nandmodel_getdevblocksize(m) * nandmodel_getpageblocksize(m))
/****************************************************************************
- * Name: nandmodel_getblockbytesize
+ * Name: nandmodel_getbyteblocksize
*
* Description:
* Returns the size in bytes of one single block of a device. This does not
@@ -306,7 +308,7 @@ unsigned int nandmodel_getblockpagesize(FAR const struct nand_model_s *model);
*
****************************************************************************/
-unsigned int nandmodel_getblockbytesize(FAR const struct nand_model_s *model);
+#define nandmodel_getbyteblocksize(m) ((unsigned int)(m)->blocksize << 10)
/****************************************************************************
* Name: nandmodel_getpagesize
@@ -322,7 +324,7 @@ unsigned int nandmodel_getblockbytesize(FAR const struct nand_model_s *model);
*
****************************************************************************/
-unsigned int nandmodel_getpagesize(FAR const struct nand_model_s *model);
+#define nandmodel_getpagesize(m) ((m)->pagesize)
/****************************************************************************
* Name: nandmodel_getsparesize
@@ -354,7 +356,8 @@ unsigned int nandmodel_getsparesize(FAR const struct nand_model_s *model);
*
****************************************************************************/
-unsigned int nandmodel_getbuswidth(FAR const struct nand_model_s *model);
+#define nandmodel_getbuswidth(m) \
+ (((m)->options & NANDMODEL_DATAWIDTH16) ? 16 : 8)
/****************************************************************************
* Name: nandmodel_havesmallblocks
@@ -372,7 +375,7 @@ unsigned int nandmodel_getbuswidth(FAR const struct nand_model_s *model);
*
****************************************************************************/
-bool nandmodel_havesmallblocks(FAR const struct nand_model_s *model);
+#define nandmodel_havesmallblocks(m) ((m)->pagesize <= 512)
/****************************************************************************
* Name: nandmodel_havecopyback
@@ -390,7 +393,7 @@ bool nandmodel_havesmallblocks(FAR const struct nand_model_s *model);
*
****************************************************************************/
-bool nandmodel_havecopyback(FAR const struct nand_model_s *model);
+#define nandmodel_havecopyback(m) (((m)->options & NANDMODEL_COPYBACK) != 0)
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/include/nuttx/mtd/nand_raw.h b/nuttx/include/nuttx/mtd/nand_raw.h
new file mode 100644
index 000000000..f8ff3dd9a
--- /dev/null
+++ b/nuttx/include/nuttx/mtd/nand_raw.h
@@ -0,0 +1,165 @@
+/****************************************************************************
+ * include/nuttx/mtd/nand_raw.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This logic was based largely on Atmel sample code with modifications for
+ * better integration with NuttX. The Atmel sample code has a BSD
+ * compatibile license that requires this copyright notice:
+ *
+ * Copyright (c) 2012, Atmel Corporation
+ *
+ * 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 names NuttX nor Atmel nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_MTD_NAND_RAW_H
+#define __INCLUDE_NUTTX_MTD_NAND_RAW_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#include <nuttx/mtd/mtd.h>
+#include <nuttx/mtd/nand_model.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Nand flash commands */
+
+#define COMMAND_READ_1 0x00
+#define COMMAND_READ_2 0x30
+#define COMMAND_COPYBACK_READ_1 0x00
+#define COMMAND_COPYBACK_READ_2 0x35
+#define COMMAND_COPYBACK_PROGRAM_1 0x85
+#define COMMAND_COPYBACK_PROGRAM_2 0x10
+#define COMMAND_RANDOM_OUT 0x05
+#define COMMAND_RANDOM_OUT_2 0xe0
+#define COMMAND_RANDOM_IN 0x85
+#define COMMAND_READID 0x90
+#define COMMAND_WRITE_1 0x80
+#define COMMAND_WRITE_2 0x10
+#define COMMAND_ERASE_1 0x60
+#define COMMAND_ERASE_2 0xd0
+#define COMMAND_STATUS 0x70
+#define COMMAND_RESET 0xff
+
+/* Nand flash commands (small blocks) */
+
+#define COMMAND_READ_A 0x00
+#define COMMAND_READ_C 0x50
+
+/* NAND access macros */
+
+#define WRITE_COMMAND8(raw, command) \
+ {*((volatile uint8_t *)raw->cmdaddr) = (uint8_t)command;}
+#define WRITE_COMMAND16(raw, command) \
+ {*((volatile uint16_t *)raw->cmdaddr) = (uint16_t)command;}
+#define WRITE_ADDRESS8(raw, address) \
+ {*((volatile uint8_t *)raw->addraddr) = (uint8_t)address;}
+#define WRITE_ADDRESS16(raw, address) \
+ {*((volatile uint16_t *)raw->addraddr) = (uint16_t)address;}
+#define WRITE_DATA8(raw, data) \
+ {*((volatile uint8_t *)raw->dataaddr) = (uint8_t)data;}
+#define READ_DATA8(raw) \
+ (*((volatile uint8_t *)raw->dataaddr))
+#define WRITE_DATA16(raw, data) \
+ {*((volatile uint16_t *) raw->dataaddr) = (uint16_t)data;}
+#define READ_DATA16(raw) \
+ (*((volatile uint16_t *)raw->dataaddr))
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+/* This type represents the visible portion of the lower-half, raw NAND MTD
+ * device. Rules:
+ *
+ * 1. The struct mtd_dev_s must appear at the beginning of the definition so
+ * that you can freely cast between pointers to struct mtd_dev_s and struct
+ * nand_raw_s.
+ * 2. The lower-half driver may freely append additional information after
+ * this required header information.
+ */
+
+struct nand_raw_s
+{
+ struct mtd_dev_s mtd; /* Externally visible part of the driver */
+ struct nand_model_s model; /* The NAND model storage */
+ uintptr_t cmdaddr; /* NAND command address base */
+ uintptr_t addraddr; /* NAND address address base */
+ uintptr_t dataaddr; /* NAND data address */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nand_chipid
+ *
+ * Description:
+ * Reads and returns the identifiers of a NAND FLASH chip
+ *
+ * Input Parameters:
+ * raw - Pointer to a struct nand_raw_s instance.
+ *
+ * Returned Value:
+ * id1|(id2<<8)|(id3<<16)|(id4<<24)
+ *
+ ****************************************************************************/
+
+uint32_t nand_chipid(FAR struct nand_raw_s *raw);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __INCLUDE_NUTTX_MTD_NAND_RAW_H */