summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-02 08:07:42 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-02 08:07:42 -0600
commitbb95a53a6ae12defb44b61ddff8b55011f983196 (patch)
treecc527620cdbe91522547b2d7014957525915fa65 /nuttx/drivers
parent41b50c286aaa99b848c4b21685f81ee2511f176a (diff)
downloadpx4-nuttx-bb95a53a6ae12defb44b61ddff8b55011f983196.tar.gz
px4-nuttx-bb95a53a6ae12defb44b61ddff8b55011f983196.tar.bz2
px4-nuttx-bb95a53a6ae12defb44b61ddff8b55011f983196.zip
Add support for the byte write method to MTD partition logic; Beef up the MTD partition test -- and fix resulting bugs detected
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/bch/bchlib_write.c2
-rw-r--r--nuttx/drivers/mtd/ftl.c8
-rw-r--r--nuttx/drivers/mtd/mtd_partition.c108
3 files changed, 95 insertions, 23 deletions
diff --git a/nuttx/drivers/bch/bchlib_write.c b/nuttx/drivers/bch/bchlib_write.c
index 8d7dcf26f..14f32ff7c 100644
--- a/nuttx/drivers/bch/bchlib_write.c
+++ b/nuttx/drivers/bch/bchlib_write.c
@@ -97,7 +97,7 @@ ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, size_t offset, si
return 0;
}
- /* Convert the file position into a sector number an offset. */
+ /* Convert the file position into a sector number and offset. */
sector = offset / bch->sectsize;
sectoffset = offset - sector * bch->sectsize;
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index 6cf8f0317..d3d62c655 100644
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -221,8 +221,8 @@ static ssize_t ftl_flush(FAR void *priv, FAR const uint8_t *buffer,
* alignment.
*/
- mask = dev->blkper - 1;
- alignedblock = (startblock + mask) & ~mask;
+ mask = dev->blkper - 1;
+ alignedblock = (startblock + mask) & ~mask;
/* Handle partial erase blocks before the first unaligned block */
@@ -271,7 +271,7 @@ static ssize_t ftl_flush(FAR void *priv, FAR const uint8_t *buffer,
memcpy(dev->eblock + offset, buffer, nbytes);
- /* And write the erase back to flash */
+ /* And write the erase block back to flash */
nxfrd = MTD_BWRITE(dev->mtd, rwblock, dev->blkper, dev->eblock);
if (nxfrd != dev->blkper)
@@ -333,7 +333,7 @@ static ssize_t ftl_flush(FAR void *priv, FAR const uint8_t *buffer,
{
/* Read the full erase block into the buffer */
- nxfrd = MTD_BREAD(dev->mtd, alignedblock, dev->blkper, dev->eblock);
+ nxfrd = MTD_BREAD(dev->mtd, alignedblock, dev->blkper, dev->eblock);
if (nxfrd != dev->blkper)
{
fdbg("Read erase block %d failed: %d\n", alignedblock, nxfrd);
diff --git a/nuttx/drivers/mtd/mtd_partition.c b/nuttx/drivers/mtd/mtd_partition.c
index 1dc0f79ae..1bff0af9c 100644
--- a/nuttx/drivers/mtd/mtd_partition.c
+++ b/nuttx/drivers/mtd/mtd_partition.c
@@ -46,8 +46,9 @@
#include <assert.h>
#include <debug.h>
-#include <nuttx/fs/ioctl.h>
#include <nuttx/mtd.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/fs/ioctl.h>
/****************************************************************************
* Pre-processor Definitions
@@ -95,6 +96,10 @@ static ssize_t part_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
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);
+#ifdef CONFIG_MTD_BYTE_WRITE
+static ssize_t part_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR const uint8_t *buffer);
+#endif
static int part_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/****************************************************************************
@@ -102,6 +107,40 @@ static int part_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
****************************************************************************/
/****************************************************************************
+ * Name: part_blockcheck
+ *
+ * Description:
+ * Check if the provided block offset lies within the partition
+ *
+ ****************************************************************************/
+
+static bool part_blockcheck(FAR struct mtd_partition_s *priv, off_t block)
+{
+ off_t partsize;
+
+ partsize = priv->neraseblocks * priv->blkpererase;
+ return block < partsize;
+}
+
+/****************************************************************************
+ * Name: part_bytecheck
+ *
+ * Description:
+ * Check if the provided byte offset lies within the partition
+ *
+ ****************************************************************************/
+
+static bool part_bytecheck(FAR struct mtd_partition_s *priv, off_t byoff)
+{
+ off_t erasesize;
+ off_t readend;
+
+ erasesize = priv->blocksize * priv->blkpererase;
+ readend = (byoff + erasesize - 1) / erasesize;
+ return readend < priv->neraseblocks;
+}
+
+/****************************************************************************
* Private Functions
****************************************************************************/
@@ -117,14 +156,13 @@ 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;
+ off_t eoffset;
DEBUGASSERT(priv);
/* Make sure that erase would not extend past the end of the partition */
- partsize = priv->neraseblocks * priv->blkpererase;
- if ((startblock + nblocks) > partsize)
+ if (!part_blockcheck(priv, startblock + nblocks - 1))
{
fdbg("ERROR: Read beyond the end of the partition\n");
return -ENXIO;
@@ -132,10 +170,14 @@ static int part_erase(FAR struct mtd_dev_s *dev, off_t startblock,
/* Just add the partition offset to the requested block and let the
* underlying MTD driver perform the erase.
+ *
+ * NOTE: the offset here is in units of erase blocks.
*/
- return priv->parent->erase(priv->parent, startblock + priv->firstblock,
- nblocks);
+ eoffset = priv->firstblock / priv->blkpererase;
+ DEBUGASSERT(eoffset * priv->blkpererase == priv->firstblock);
+
+ return priv->parent->erase(priv->parent, startblock + eoffset, nblocks);
}
/****************************************************************************
@@ -150,14 +192,12 @@ 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)
+ if (!part_blockcheck(priv, startblock + nblocks - 1))
{
fdbg("ERROR: Read beyond the end of the partition\n");
return -ENXIO;
@@ -183,14 +223,12 @@ 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)
+ if (!part_blockcheck(priv, startblock + nblocks - 1))
{
fdbg("ERROR: Write beyond the end of the partition\n");
return -ENXIO;
@@ -216,8 +254,6 @@ 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));
@@ -228,10 +264,7 @@ static ssize_t part_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
{
/* 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)
+ if (!part_bytecheck(priv, offset + nbytes - 1))
{
fdbg("ERROR: Read beyond the end of the partition\n");
return -ENXIO;
@@ -251,6 +284,45 @@ static ssize_t part_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
}
/****************************************************************************
+ * Name: part_write
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_BYTE_WRITE
+static ssize_t part_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR const uint8_t *buffer)
+{
+ FAR struct mtd_partition_s *priv = (FAR struct mtd_partition_s *)dev;
+ off_t newoffset;
+
+ DEBUGASSERT(priv && (buffer || nbytes == 0));
+
+ /* Does the underlying MTD device support the write method? */
+
+ if (priv->parent->write)
+ {
+ /* Make sure that write would not extend past the end of the partition */
+
+ if (!part_bytecheck(priv, offset + nbytes - 1))
+ {
+ fdbg("ERROR: Write beyond the end of the partition\n");
+ return -ENXIO;
+ }
+
+ /* Just add the partition offset to the requested block and let the
+ * underlying MTD driver perform the write.
+ */
+
+ newoffset = offset + priv->firstblock * priv->blocksize;
+ return priv->parent->write(priv->parent, newoffset, nbytes, buffer);
+ }
+
+ /* The underlying MTD driver does not support the write() method */
+
+ return -ENOSYS;
+}
+#endif
+
+/****************************************************************************
* Name: part_ioctl
****************************************************************************/