summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-04-30 12:37:34 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-04-30 12:37:34 -0600
commit8241609e9edbab8443fb4a3f278bfc7a924c05b1 (patch)
tree403f6fa2723bd5fda9cbf9cff50ae040714cad45 /nuttx/drivers
parent0a925b25adf3c6aa533f0ddbff298ad3d6fb344b (diff)
downloadpx4-nuttx-8241609e9edbab8443fb4a3f278bfc7a924c05b1.tar.gz
px4-nuttx-8241609e9edbab8443fb4a3f278bfc7a924c05b1.tar.bz2
px4-nuttx-8241609e9edbab8443fb4a3f278bfc7a924c05b1.zip
Add MTD partition support plus fix some typos in comments
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/mtd/Kconfig25
-rw-r--r--nuttx/drivers/mtd/Make.defs4
-rw-r--r--nuttx/drivers/mtd/mtd_partition.c419
-rw-r--r--nuttx/drivers/mtd/skeleton.c10
4 files changed, 453 insertions, 5 deletions
diff --git a/nuttx/drivers/mtd/Kconfig b/nuttx/drivers/mtd/Kconfig
index 1449a7125..99aea5813 100644
--- a/nuttx/drivers/mtd/Kconfig
+++ b/nuttx/drivers/mtd/Kconfig
@@ -2,10 +2,35 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
+config MTD_PARTITION
+ bool "Support MTD partitions"
+ default n
+ ---help---
+ MTD partitions are build as MTD drivers that manage a sub-region
+ of the FLASH memory. The contain the original FLASH MTD driver and
+ simply manage all accesses to assure that (1) FLASH accesses are
+ always offset to the beginning of the partition, and (2) that FLASH
+ accesses do not extend outside of the partition.
+
+ A FLASH device may be broken up into several partitions managed,
+ each managed by a separate MTD driver. The MTD parition interface
+ is described in:
+
+ include/nuttx/mtd.h
+ FAR struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd, off_t offset, off_t nblocks);
+
+ Each call to mtd_partition() will create a new MTD driver instance
+ managing the sub-region of flash beginning at 'offset' (in blocks)
+ and of size 'nblocks' on the device specified by 'mtd'.
+
config MTD_AT24XX
bool "I2C-based AT24XX eeprom"
default n
select I2C
+ ---help---
+ Build support for I2C-based at24cxx EEPROM(at24c32, at24c64,
+ at24c128, at24c256)
if MTD_AT24XX
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index 350d055f6..fd16fd405 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -41,6 +41,10 @@ ifeq ($(CONFIG_MTD),y)
CSRCS += at45db.c flash_eraseall.c ftl.c m25px.c rammtd.c ramtron.c
+ifeq ($(CONFIG_MTD_PARTITION),y)
+CSRCS += mtd_partition.c
+endif
+
ifeq ($(CONFIG_MTD_AT24XX),y)
CSRCS += at24xx.c
endif
diff --git a/nuttx/drivers/mtd/mtd_partition.c b/nuttx/drivers/mtd/mtd_partition.c
new file mode 100644
index 000000000..cc0b8c4df
--- /dev/null
+++ b/nuttx/drivers/mtd/mtd_partition.c
@@ -0,0 +1,419 @@
+/****************************************************************************
+ * drivers/child/skeleton.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor 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 <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/fs/ioctl.h>
+#include <nuttx/mtd.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* This type represents the state of the 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 mtd_partition_s.
+ */
+
+struct mtd_partition_s
+{
+ /* This structure must reside at the beginning so that we can simply cast
+ * from struct mtd_dev_s * to struct mtd_partition_s *
+ */
+
+ struct mtd_dev_s child; /* The "child" MTD vtable that manages the
+ * sub-region */
+ /* Other implementation specific data may follow here */
+
+ FAR struct mtd_dev_s *parent; /* The "parent" MTD driver that manages the
+ * entire FLASH */
+ off_t offset; /* Offset to the first sector of the managed
+ * sub-region */
+ off_t neraseblocks; /* The number of erase blocks in the managed
+ * sub-region */
+ off_t blocksize; /* The size of one read/write block */
+ uint16_t blkpererase; /* Number of R/W blocks in one erase block */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* MTD driver methods */
+
+static int part_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
+static ssize_t part_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR uint8_t *buf);
+static ssize_t part_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
+ FAR const uint8_t *buf);
+static ssize_t part_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR uint8_t *buffer);
+static int part_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: part_erase
+ *
+ * Description:
+ * Erase several blocks, each of the size previously reported.
+ *
+ ****************************************************************************/
+
+static int part_erase(FAR struct mtd_dev_s *dev, off_t startblock,
+ size_t nblocks)
+{
+ FAR struct mtd_partition_s *priv = (FAR struct mtd_partition_s *)dev;
+ off_t partsize;
+
+ DEBUGASSERT(priv);
+
+ /* Make sure that erase would not extend past the end of the partition */
+
+ partsize = priv->neraseblocks * priv->blkpererase;
+ if ((startblock + nblocks) > partsize)
+ {
+ fdbg("ERROR: Read beyond the end of the partition\n");
+ return -ENXIO;
+ }
+
+ /* Just add the partition offset to the requested offset and let the
+ * underlying MTD driver perform the erase.
+ */
+
+ return priv->parent->erase(priv->parent, startblock + priv->offset,
+ nblocks);
+}
+
+/****************************************************************************
+ * Name: part_bread
+ *
+ * Description:
+ * Read the specified number of blocks into the user provided buffer.
+ *
+ ****************************************************************************/
+
+static ssize_t part_bread(FAR struct mtd_dev_s *dev, off_t startblock,
+ size_t nblocks, FAR uint8_t *buf)
+{
+ FAR struct mtd_partition_s *priv = (FAR struct mtd_partition_s *)dev;
+ off_t partsize;
+
+ DEBUGASSERT(priv && (buf || nblocks == 0));
+
+ /* Make sure that read would not extend past the end of the partition */
+
+ partsize = priv->neraseblocks * priv->blkpererase;
+ if ((startblock + nblocks) > partsize)
+ {
+ fdbg("ERROR: Read beyond the end of the partition\n");
+ return -ENXIO;
+ }
+
+ /* Just add the partition offset to the requested offset and let the
+ * underlying MTD driver perform the read.
+ */
+
+ return priv->parent->bread(priv->parent, startblock + priv->offset,
+ nblocks, buf);
+}
+
+/****************************************************************************
+ * Name: part_bwrite
+ *
+ * Description:
+ * Write the specified number of blocks from the user provided buffer.
+ *
+ ****************************************************************************/
+
+static ssize_t part_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
+ size_t nblocks, FAR const uint8_t *buf)
+{
+ FAR struct mtd_partition_s *priv = (FAR struct mtd_partition_s *)dev;
+ off_t partsize;
+
+ DEBUGASSERT(priv && (buf || nblocks == 0));
+
+ /* Make sure that write would not extend past the end of the partition */
+
+ partsize = priv->neraseblocks * priv->blkpererase;
+ if ((startblock + nblocks) > partsize)
+ {
+ fdbg("ERROR: Write beyond the end of the partition\n");
+ return -ENXIO;
+ }
+
+ /* Just add the partition offset to the requested offset and let the
+ * underlying MTD driver perform the write.
+ */
+
+ return priv->parent->bwrite(priv->parent, startblock + priv->offset,
+ nblocks, buf);
+}
+
+/****************************************************************************
+ * Name: part_read
+ *
+ * Description:
+ * Read the specified number of bytes to the user provided buffer.
+ *
+ ****************************************************************************/
+
+static ssize_t part_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR uint8_t *buffer)
+{
+ FAR struct mtd_partition_s *priv = (FAR struct mtd_partition_s *)dev;
+ off_t erasesize;
+ off_t readend;
+ off_t newoffset;
+
+ DEBUGASSERT(priv && (buffer || nbytes == 0));
+
+ /* Does the underlying MTD device support the read method? */
+
+ if (priv->parent->read)
+ {
+ /* Make sure that read would not extend past the end of the partition */
+
+ erasesize = priv->blocksize * priv->blkpererase;
+ readend = (offset + nbytes + erasesize - 1) / erasesize;
+
+ if (readend > priv->neraseblocks)
+ {
+ fdbg("ERROR: Read beyond the end of the partition\n");
+ return -ENXIO;
+ }
+
+ /* Just add the partition offset to the requested offset and let the
+ * underlying MTD driver perform the read.
+ */
+
+ newoffset = offset + priv->offset * priv->blocksize;
+ return priv->parent->read(priv->parent, newoffset, nbytes, buffer);
+ }
+
+ /* The underlying MTD driver does not support the read() method */
+
+ return -ENOSYS;
+}
+
+/****************************************************************************
+ * Name: part_ioctl
+ ****************************************************************************/
+
+static int part_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
+{
+ FAR struct mtd_partition_s *priv = (FAR struct mtd_partition_s *)dev;
+ int ret = -EINVAL; /* Assume good command with bad parameters */
+
+ DEBUGASSERT(priv);
+
+ switch (cmd)
+ {
+ case MTDIOC_GEOMETRY:
+ {
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)arg;
+ if (geo)
+ {
+ /* Populate the geometry structure with information needed to know
+ * the capacity and how to access the device.
+ */
+
+ geo->blocksize = priv->blocksize;
+ geo->erasesize = priv->blocksize * priv->blkpererase;
+ geo->neraseblocks = priv->neraseblocks;
+ ret = OK;
+ }
+ }
+ break;
+
+ case MTDIOC_XIPBASE:
+ {
+ FAR void **ppv = (FAR void**)arg;
+ unsigned long base;
+
+ if (ppv)
+ {
+ /* Get hte XIP base of the entire FLASH */
+
+ ret = priv->parent->ioctl(priv->parent, MTDIOC_XIPBASE,
+ (unsigned long)((uintptr_t)&base));
+ if (ret == OK)
+ {
+ /* Add the offset of this partion to the XIP base and
+ * return the sum to the caller.
+ */
+
+ *ppv = (FAR void *)(base + priv->offset * priv->blocksize);
+ }
+ }
+ }
+ break;
+
+ case MTDIOC_BULKERASE:
+ {
+ /* Erase the entire partition */
+
+ ret = priv->parent->erase(priv->parent, priv->offset,
+ priv->neraseblocks * priv->blkpererase);
+ }
+ break;
+
+ default:
+ ret = -ENOTTY; /* Bad command */
+ break;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mtd_partition
+ *
+ * Description:
+ * Give an instance of an MTD driver, create a flash partition, ie.,
+ * another MTD driver instance that only operates with a sub-region of
+ * FLASH media. That sub-region is defined by a sector offsetset and a
+ * sector count (where the size of a sector is provided the by parent MTD
+ * driver).
+ *
+ ****************************************************************************/
+
+FAR struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd, off_t offset,
+ off_t nblocks)
+{
+ FAR struct mtd_partition_s *part;
+ FAR struct mtd_geometry_s geo;
+ unsigned int blkpererase;
+ off_t erasestart;
+ off_t eraseend;
+ off_t devblocks;
+ int ret;
+
+ DEBUGASSERT(mtd);
+
+ /* Get the geometry of the FLASH device */
+
+ ret = mtd->ioctl(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo));
+ if (ret < 0)
+ {
+ fdbg("ERROR: mtd->ioctl failed: %d\n", ret);
+ return NULL;
+ }
+
+ /* Get the number of blocks per erase. There must be an even number of
+ * blocks in one erase blocks.
+ */
+
+ blkpererase = geo.erasesize / geo.blocksize;
+ DEBUGASSERT(blkpererase * geo.blocksize == geo.erasesize);
+
+ /* Adjust the offset and size if necessary so that they are multiples of
+ * the erase block size (making sure that we do not go outside of the
+ * requested sub-region). NOTE that eraseend is the first erase block
+ * beyond the sub-region.
+ */
+
+ erasestart = (offset + blkpererase - 1) / blkpererase;
+ eraseend = (offset + nblocks) / blkpererase;
+
+ if (erasestart >= eraseend)
+ {
+ fdbg("ERROR: sub-region too small\n");
+ return NULL;
+ }
+
+ /* Verify that the sub-region is valid for this geometry */
+
+ devblocks = blkpererase * geo.neraseblocks;
+ if (eraseend > devblocks)
+ {
+ fdbg("ERROR: sub-region too big\n");
+ return NULL;
+ }
+
+ /* Allocate a partition device structure */
+
+ part = (FAR struct mtd_partition_s *)malloc(sizeof(struct mtd_partition_s));
+ if (!part)
+ {
+ fdbg("ERROR: Failed to allocate memory for the partition device\n");
+ return NULL;
+ }
+
+ /* Initialize the partition device structure */
+
+ part->child.erase = part_erase;
+ part->child.bread = part_bread;
+ part->child.bwrite = part_bwrite;
+ part->child.read = mtd->read ? part_read : NULL;
+ part->child.ioctl = part_ioctl;
+
+ part->parent = mtd;
+ part->offset = erasestart * blkpererase;
+ part->neraseblocks = eraseend - erasestart;
+ part->blocksize = geo.blocksize;
+ part->blkpererase = blkpererase;
+
+ /* Return the implementation-specific state structure as the MTD device */
+
+ return &part->child;
+}
+
diff --git a/nuttx/drivers/mtd/skeleton.c b/nuttx/drivers/mtd/skeleton.c
index 15ddac1ef..d3b0937bf 100644
--- a/nuttx/drivers/mtd/skeleton.c
+++ b/nuttx/drivers/mtd/skeleton.c
@@ -109,7 +109,7 @@ static int skel_erase(FAR struct mtd_dev_s *dev, off_t startblock,
{
FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
- /* The interface definition assumes that all erase blocks ar the same size.
+ /* The interface definition assumes that all erase blocks are the same size.
* If that is not true for this particular device, then transform the
* start block and nblocks as necessary.
*/
@@ -132,7 +132,7 @@ static ssize_t skel_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nb
{
FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
- /* The interface definition assumes that all read/write blocks ar the same size.
+ /* 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
* start block and nblocks as necessary.
*/
@@ -157,7 +157,7 @@ static ssize_t skel_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
{
FAR struct skel_dev_s *priv = (FAR struct skel_dev_s *)dev;
- /* The interface definition assumes that all read/write blocks ar the same size.
+ /* 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
* start block and nblocks as necessary.
*/
@@ -190,7 +190,7 @@ static ssize_t skel_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
* instance.
*/
- /* The interface definition assumes that all read/write blocks ar the same size.
+ /* 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
* start block and nblocks as necessary.
*/
@@ -218,7 +218,7 @@ static int skel_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)arg;
if (geo)
{
- /* Populate the geometry structure with information need to know
+ /* Populate the geometry structure with information needed to know
* the capacity and how to access the device.
*
* NOTE: that the device is treated as though it where just an array