summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-03 12:52:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-03 12:52:33 -0600
commit1092e4b16395d945517b9bcbc2c48828fbe9303c (patch)
treee2171ab3f21ae1e0610903694901c776a7e1a1d8 /nuttx/drivers
parent2567deb0338a774086231fbb778b639c10398cc1 (diff)
downloadpx4-nuttx-1092e4b16395d945517b9bcbc2c48828fbe9303c.tar.gz
px4-nuttx-1092e4b16395d945517b9bcbc2c48828fbe9303c.tar.bz2
px4-nuttx-1092e4b16395d945517b9bcbc2c48828fbe9303c.zip
Rearchitecting of some MTD, partition, SMART interfaces, and FLASH drivers to: Better use the byte write capbility when available and to use smaller erase sectors for the erase sector size when available).
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/mtd/Kconfig27
-rw-r--r--nuttx/drivers/mtd/m25px.c330
-rw-r--r--nuttx/drivers/mtd/mtd_partition.c11
-rw-r--r--nuttx/drivers/mtd/rammtd.c55
-rw-r--r--nuttx/drivers/mtd/smart.c313
5 files changed, 391 insertions, 345 deletions
diff --git a/nuttx/drivers/mtd/Kconfig b/nuttx/drivers/mtd/Kconfig
index 310f494d8..4754fbeb7 100644
--- a/nuttx/drivers/mtd/Kconfig
+++ b/nuttx/drivers/mtd/Kconfig
@@ -64,13 +64,6 @@ config RAMMTD_FLASHSIM
RAMMTD_FLASHSIM will add some extra logic to improve the level of
FLASH simulation.
-config RAMMTD_SMART
- bool "SMART block driver support in the RAM MTD driver"
- default n
- ---help---
- Builds in additional ioctl and interface code to support the
- SMART block driver / filesystem.
-
endif
config MTD_AT24XX
@@ -139,30 +132,14 @@ config M25P_MEMORY_TYPE
---help---
The memory type for M25 "P" series is 0x20, but the driver also supports "F" series
devices, such as the EON EN25F80 part which adds a 4K sector erase capability. The
- ID for "F" series parts from EON is 0x31.
-
-config M25P_SUBSECTOR_ERASE
- bool "Sub-Sector Erase"
- default n
- ---help---
- Some devices (such as the EON EN25F80) support a smaller erase block
- size (4K vs 64K). This option enables support for sub-sector erase.
- The SMART file system can take advantage of this option if it is enabled.
-
-config M25P_BYTEWRITE
- bool "Enable ByteWrite ioctl support"
- default n
- ---help---
- The M25P series of devices allow writing to a page with less than a full-page
- size of data. In this case, only the written bytes are updated without affecting
- the other bytes in the page. The SMART FS requires this option for proper operation.
+ memory type for "F" series parts from EON is 0x31. The 4K sector erase size will
+ automatically be enabled when filessytems that can use it are enabled, such as SMART.
endif
config MTD_SMART
bool "Sector Mapped Allocation for Really Tiny (SMART) Flash support"
default y
- select M25P_BYTEWRITE
---help---
The MP25x series of Flash devices are typically very small and have a very large
erase block size. This causes issues with the standard Flash Translation Layer
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index bfe21a7dd..17f7a0672 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -3,7 +3,7 @@
* Driver for SPI-based M25P1 (128Kbit), M25P64 (32Mbit), M25P64 (64Mbit), and
* M25P128 (128Mbit) FLASH (and compatible).
*
- * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -114,6 +114,7 @@
#define M25P_EN25F80_PAGE_SHIFT 8 /* Page size 1 << 8 = 256 */
#define M25P_EN25F80_NPAGES 4096
#define M25P_EN25F80_SUBSECT_SHIFT 12 /* Sub-Sector size 1 << 12 = 4,096 */
+#define M25P_EN25F80_NSUBSECTORS 256
/* M25P32 capacity is 4,194,304 bytes:
* (64 sectors) * (65,536 bytes per sector)
@@ -203,7 +204,7 @@ struct m25p_dev_s
uint8_t pageshift; /* 8 */
uint16_t nsectors; /* 128 or 64 */
uint32_t npages; /* 32,768 or 65,536 */
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
+#ifdef CONFIG_MTD_SMART
uint8_t subsectorshift; /* 0, 12 or 13 (4K or 8K) */
#endif
};
@@ -219,13 +220,10 @@ static inline void m25p_unlock(FAR struct spi_dev_s *dev);
static inline int m25p_readid(struct m25p_dev_s *priv);
static void m25p_waitwritecomplete(struct m25p_dev_s *priv);
static void m25p_writeenable(struct m25p_dev_s *priv);
-static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t offset);
+static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t offset, uint8_t type);
static inline int m25p_bulkerase(struct m25p_dev_s *priv);
static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *buffer,
off_t offset);
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
-static inline void m25p_subsectorerase(struct m25p_dev_s *priv, off_t offset);
-#endif
/* MTD driver methods */
@@ -236,6 +234,10 @@ static ssize_t m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
size_t nblocks, FAR const uint8_t *buf);
static ssize_t m25p_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 m25p_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR const uint8_t *buffer);
+#endif
static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/************************************************************************************
@@ -320,7 +322,7 @@ static inline int m25p_readid(struct m25p_dev_s *priv)
{
/* Okay.. is it a FLASH capacity that we understand? */
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
+#ifdef CONFIG_MTD_SMART
priv->subsectorshift = 0;
#endif
@@ -338,11 +340,11 @@ static inline int m25p_readid(struct m25p_dev_s *priv)
{
/* Save the FLASH geometry */
- priv->sectorshift = M25P_EN25F80_SECTOR_SHIFT;
- priv->nsectors = M25P_EN25F80_NSECTORS;
priv->pageshift = M25P_EN25F80_PAGE_SHIFT;
priv->npages = M25P_EN25F80_NPAGES;
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
+ priv->sectorshift = M25P_EN25F80_SECTOR_SHIFT;
+ priv->nsectors = M25P_EN25F80_NSECTORS;
+#ifdef CONFIG_MTD_SMART
priv->subsectorshift = M25P_EN25F80_SUBSECT_SHIFT;
#endif
return OK;
@@ -480,9 +482,20 @@ static void m25p_writeenable(struct m25p_dev_s *priv)
* Name: m25p_sectorerase
************************************************************************************/
-static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector)
+static void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector, uint8_t type)
{
- off_t offset = sector << priv->sectorshift;
+ off_t offset;
+
+#ifdef CONFIG_MTD_SMART
+ if (priv->subsectorshift > 0)
+ {
+ offset = sector << priv->subsectorshift;
+ }
+ else
+#endif
+ {
+ offset = sector << priv->sectorshift;
+ }
fvdbg("sector: %08lx\n", (long)sector);
@@ -502,55 +515,11 @@ static inline void m25p_sectorerase(struct m25p_dev_s *priv, off_t sector)
SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
- /* Send the "Sector Erase (SE)" instruction */
-
- (void)SPI_SEND(priv->dev, M25P_SE);
-
- /* Send the sector offset high byte first. For all of the supported
- * parts, the sector number is completely contained in the first byte
- * and the values used in the following two bytes don't really matter.
- */
-
- (void)SPI_SEND(priv->dev, (offset >> 16) & 0xff);
- (void)SPI_SEND(priv->dev, (offset >> 8) & 0xff);
- (void)SPI_SEND(priv->dev, offset & 0xff);
-
- /* Deselect the FLASH */
-
- SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
- fvdbg("Erased\n");
-}
-
-/************************************************************************************
- * Name: m25p_subsectorerase
- ************************************************************************************/
-
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
-static inline void m25p_subsectorerase(struct m25p_dev_s *priv, off_t subsector)
-{
- off_t offset = subsector << priv->subsectorshift;
-
- fvdbg("subsector: %9lx\n", (long)subsector);
-
- /* Wait for any preceding write to complete. We could simplify things by
- * perform this wait at the end of each write operation (rather than at
- * the beginning of ALL operations), but have the wait first will slightly
- * improve performance.
+ /* Send the "Sector Erase (SE)" or Sub-Sector Erase (SSE) instruction
+ * that was passed in as the erase type.
*/
- m25p_waitwritecomplete(priv);
-
- /* Send write enable instruction */
-
- m25p_writeenable(priv);
-
- /* Select this FLASH part */
-
- SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
-
- /* Send the "Sub-Sector Erase (SSE)" instruction */
-
- (void)SPI_SEND(priv->dev, M25P_SSE);
+ (void)SPI_SEND(priv->dev, type);
/* Send the sector offset high byte first. For all of the supported
* parts, the sector number is completely contained in the first byte
@@ -566,7 +535,6 @@ static inline void m25p_subsectorerase(struct m25p_dev_s *priv, off_t subsector)
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
fvdbg("Erased\n");
}
-#endif
/************************************************************************************
* Name: m25p_bulkerase
@@ -654,7 +622,7 @@ static inline void m25p_pagewrite(struct m25p_dev_s *priv, FAR const uint8_t *bu
* Name: m25p_bytewrite
************************************************************************************/
-#ifdef CONFIG_M25P_BYTEWRITE
+#ifdef CONFIG_MTD_BYTE_WRITE
static inline void m25p_bytewrite(struct m25p_dev_s *priv, FAR const uint8_t *buffer,
off_t offset, uint16_t count)
{
@@ -711,13 +679,55 @@ static int m25p_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblock
/* Lock access to the SPI bus until we complete the erase */
m25p_lock(priv->dev);
- while (blocksleft-- > 0)
+ while (blocksleft > 0)
{
- /* Erase each sector */
+#ifdef CONFIG_MTD_SMART
+ size_t sectorboundry;
+ size_t blkper;
+
+ /* If we have a smaller erase size, then we will find as many full
+ * sector erase blocks as possible to speed up the process instead of
+ * erasing everything in smaller chunks.
+ */
+
+ if (priv->subsectorshift > 0)
+ {
+ blkper = 1 << (priv->sectorshift - priv->subsectorshift);
+ sectorboundry = (startblock + blkper - 1) / blkper;
+ sectorboundry *= blkper;
- m25p_sectorerase(priv, startblock);
+ /* If we are on a sector boundry and have at least a full sector
+ * of blocks left to erase, then we can do a full sector erase.
+ */
+
+ if (startblock == sectorboundry && blocksleft >= blkper)
+ {
+ /* Do a full sector erase */
+
+ m25p_sectorerase(priv, startblock / blkper, M25P_SE);
+ startblock += blkper;
+ blocksleft -= blkper;
+ continue;
+ }
+ else
+ {
+ /* Just do a sub-sector erase */
+
+ m25p_sectorerase(priv, startblock, M25P_SSE);
+ startblock++;
+ blocksleft--;
+ continue;
+ }
+ }
+#endif
+
+ /* Not using sub-sector erase. Erase each full sector */
+
+ m25p_sectorerase(priv, startblock, M25P_SE);
startblock++;
+ blocksleft--;
}
+
m25p_unlock(priv->dev);
return (int)nblocks;
}
@@ -741,6 +751,7 @@ static ssize_t m25p_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nb
{
return nbytes >> priv->pageshift;
}
+
return (int)nbytes;
}
@@ -766,8 +777,8 @@ static ssize_t m25p_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
buffer += pagesize;
startblock++;
}
- m25p_unlock(priv->dev);
+ m25p_unlock(priv->dev);
return nblocks;
}
@@ -818,6 +829,78 @@ static ssize_t m25p_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
}
/************************************************************************************
+ * Name: m25p_write
+ ************************************************************************************/
+
+#ifdef CONFIG_MTD_BYTE_WRITE
+static ssize_t m25p_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
+ FAR const uint8_t *buffer)
+{
+ FAR struct m25p_dev_s *priv = (FAR struct m25p_dev_s *)dev;
+ int startpage;
+ int endpage;
+ int count;
+ int index;
+ int pagesize;
+ int bytestowrite;
+
+ fvdbg("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes);
+
+ /* We must test if the offset + count crosses one or more pages
+ * and perform individual writes. The devices can only write in
+ * page increments.
+ */
+
+ startpage = offset / (1 << priv->pageshift);
+ endpage = (offset + nbytes) / (1 << priv->pageshift);
+
+ if (startpage == endpage)
+ {
+ /* All bytes within one programmable page. Just do the write. */
+
+ m25p_bytewrite(priv, buffer, offset, nbytes);
+ }
+ else
+ {
+ /* Write the 1st partial-page */
+
+ count = nbytes;
+ pagesize = (1 << priv->pageshift);
+ bytestowrite = pagesize - (offset & (pagesize-1));
+ m25p_bytewrite(priv, buffer, offset, bytestowrite);
+
+ /* Update offset and count */
+
+ offset += bytestowrite;
+ count -= bytestowrite;
+ index = bytestowrite;
+
+ /* Write full pages */
+
+ while (count >= pagesize)
+ {
+ m25p_bytewrite(priv, &buffer[index], offset, pagesize);
+
+ /* Update offset and count */
+
+ offset += pagesize;
+ count -= pagesize;
+ index += pagesize;
+ }
+
+ /* Now write any partial page at the end */
+
+ if (count > 0)
+ {
+ m25p_bytewrite(priv, &buffer[index], offset, count);
+ }
+ }
+
+ return nbytes;
+}
+#endif /* CONFIG_MTD_BYTE_WRITE */
+
+/************************************************************************************
* Name: m25p_ioctl
************************************************************************************/
@@ -844,15 +927,22 @@ static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
* appear so.
*/
- geo->blocksize = (1 << priv->pageshift);
- geo->erasesize = (1 << priv->sectorshift);
- geo->neraseblocks = priv->nsectors;
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
- geo->subsectorsize = (1 << priv->subsectorshift);
- geo->nsubsectors = priv->nsectors * (1 << (priv->sectorshift -
- priv->subsectorshift));
+ geo->blocksize = (1 << priv->pageshift);
+#ifdef CONFIG_MTD_SMART
+ if (priv->subsectorshift > 0)
+ {
+ geo->erasesize = (1 << priv->subsectorshift);
+ geo->neraseblocks = priv->nsectors * (1 << (priv->sectorshift -
+ priv->subsectorshift));
+ }
+ else
#endif
- ret = OK;
+ {
+ geo->erasesize = (1 << priv->sectorshift);
+ geo->neraseblocks = priv->nsectors;
+ }
+
+ ret = OK;
fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
geo->blocksize, geo->erasesize, geo->neraseblocks);
@@ -870,97 +960,6 @@ static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
}
break;
-#ifdef CONFIG_FS_SMARTFS
- case MTDIOC_GETCAPS:
- {
- ret = 0;
-#ifdef CONFIG_M25P_BYTEWRITE
- ret |= MTDIOC_CAPS_BYTEWRITE;
-#endif
-
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
- ret |= MTDIOC_CAPS_SECTERASE;
-#endif
- break;
- }
-#endif /* CONFIG_FS_SMARTFS */
-
-#ifdef CONFIG_M25P_SUBSECTOR_ERASE
- case MTDIOC_SECTERASE:
- {
- m25p_subsectorerase(priv, (off_t) arg);
- ret = OK;
- break;
- }
-#endif
-
-#ifdef CONFIG_M25P_BYTEWRITE
- case MTDIOC_BYTEWRITE:
- {
- struct mtd_byte_write_s *bytewrite = (struct mtd_byte_write_s *) arg;
- int startpage;
- int endpage;
- int count;
- int index;
- int pagesize;
- int bytestowrite;
- size_t offset;
-
- /* We must test if the offset + count crosses one or more pages
- * and perform individual writes. The devices can only write in
- * page increments.
- */
-
- startpage = bytewrite->offset / (1 << priv->pageshift);
- endpage = (bytewrite->offset + bytewrite->count) / (1 << priv->pageshift);
-
- if (startpage == endpage)
- {
- m25p_bytewrite(priv, bytewrite->buffer, bytewrite->offset,
- bytewrite->count);
- }
- else
- {
- /* Write the 1st partial-page */
-
- count = bytewrite->count;
- pagesize = (1 << priv->pageshift);
- offset = bytewrite->offset;
- bytestowrite = pagesize - (bytewrite->offset & (pagesize-1));
- m25p_bytewrite(priv, bytewrite->buffer, offset, bytestowrite);
-
- /* Update offset and count */
-
- offset += bytestowrite;
- count -= bytestowrite;
- index = bytestowrite;
-
- /* Write full pages */
-
- while (count >= pagesize)
- {
- m25p_bytewrite(priv, &bytewrite->buffer[index], offset, pagesize);
-
- /* Update offset and count */
-
- offset += pagesize;
- count -= pagesize;
- index += pagesize;
- }
-
- /* Now write any partial page at the end */
-
- if (count > 0)
- {
- m25p_bytewrite(priv, &bytewrite->buffer[index], offset, count);
- }
- }
-
- ret = OK;
- break;
- }
-#endif
-
case MTDIOC_XIPBASE:
default:
ret = -ENOTTY; /* Bad command */
@@ -1010,6 +1009,9 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
priv->mtd.bread = m25p_bread;
priv->mtd.bwrite = m25p_bwrite;
priv->mtd.read = m25p_read;
+#ifdef CONFIG_MTD_BYTE_WRITE
+ priv->mtd.write = m25p_write;
+#endif
priv->mtd.ioctl = m25p_ioctl;
priv->dev = dev;
diff --git a/nuttx/drivers/mtd/mtd_partition.c b/nuttx/drivers/mtd/mtd_partition.c
index 1bff0af9c..699a2fa5a 100644
--- a/nuttx/drivers/mtd/mtd_partition.c
+++ b/nuttx/drivers/mtd/mtd_partition.c
@@ -137,7 +137,7 @@ static bool part_bytecheck(FAR struct mtd_partition_s *priv, off_t byoff)
erasesize = priv->blocksize * priv->blkpererase;
readend = (byoff + erasesize - 1) / erasesize;
- return readend < priv->neraseblocks;
+ return readend <= priv->neraseblocks;
}
/****************************************************************************
@@ -410,6 +410,12 @@ static int part_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
* sector count (where the size of a sector is provided the by parent MTD
* driver).
*
+ * NOTE: Since there may be a number of MTD partition drivers operating on
+ * the same, underlying FLASH driver, that FLASH driver must be capable
+ * of enforcing mutually exclusive access to the FLASH device. Without
+ * partitions, that mutual exclusion would be provided by the file system
+ * above the FLASH driver.
+ *
****************************************************************************/
FAR struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd, off_t firstblock,
@@ -483,6 +489,9 @@ FAR struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd, off_t firstblock,
part->child.bwrite = part_bwrite;
part->child.read = mtd->read ? part_read : NULL;
part->child.ioctl = part_ioctl;
+#ifdef CONFIG_MTD_BYTE_WRITE
+ part->child.write = mtd->write ? part_write : NULL;
+#endif
part->parent = mtd;
part->firstblock = erasestart * blkpererase;
diff --git a/nuttx/drivers/mtd/rammtd.c b/nuttx/drivers/mtd/rammtd.c
index 461cd7d99..137f91f73 100644
--- a/nuttx/drivers/mtd/rammtd.c
+++ b/nuttx/drivers/mtd/rammtd.c
@@ -228,7 +228,7 @@ static int ram_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks
* Name: ram_readbytes
****************************************************************************/
-#ifdef CONFIG_RAMMTD_SMART
+#ifdef CONFIG_MTD_SMART
static ssize_t ram_read_bytes(FAR struct mtd_dev_s *dev, off_t offset,
size_t nbytes, FAR uint8_t *buf)
{
@@ -329,6 +329,34 @@ static ssize_t ram_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
}
/****************************************************************************
+ * Name: ram_bytewrite
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_BYTE_WRITE
+static ssize_t ram_bytewrite(FAR struct mtd_dev_s *dev, off_t offset,
+ size_t nbytes, FAR const uint8_t *buf)
+{
+ FAR struct ram_dev_s *priv = (FAR struct ram_dev_s *)dev;
+ off_t maxaddr;
+
+ DEBUGASSERT(dev && buf);
+
+ /* Don't let the write exceed the size of the ram buffer */
+
+ maxaddr = priv->nblocks * CONFIG_RAMMTD_ERASESIZE;
+ if (offset + nbytes > maxaddr)
+ {
+ return 0;
+ }
+
+ /* Then write the data to RAM */
+
+ ram_write(&priv->start[offset], buf, nbytes);
+ return nbytes;
+}
+#endif
+
+/****************************************************************************
* Name: ram_ioctl
****************************************************************************/
@@ -380,24 +408,6 @@ static int ram_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
}
break;
-#ifdef CONFIG_RAMMTD_SMART
- case MTDIOC_GETCAPS:
- {
- ret = MTDIOC_CAPS_BYTEWRITE;
- break;
- }
-
- case MTDIOC_BYTEWRITE:
- {
- struct mtd_byte_write_s *bytewrite = (struct mtd_byte_write_s *) arg;
-
- ram_write(&priv->start[bytewrite->offset], bytewrite->buffer,
- bytewrite->count);
- ret = OK;
- break;
- }
-#endif
-
default:
ret = -ENOTTY; /* Bad command */
break;
@@ -454,9 +464,14 @@ FAR struct mtd_dev_s *rammtd_initialize(FAR uint8_t *start, size_t size)
priv->mtd.bwrite = ram_bwrite;
priv->mtd.ioctl = ram_ioctl;
priv->mtd.erase = ram_erase;
+#ifdef CONFIG_MTD_BYTE_WRITE
+ priv->mtd.write = ram_bytewrite;
+#endif
-#ifdef CONFIG_RAMMTD_SMART
+#ifdef CONFIG_MTD_SMART
priv->mtd.read = ram_read_bytes;
+#else
+ priv->mtd.read = NULL;
#endif
priv->start = start;
diff --git a/nuttx/drivers/mtd/smart.c b/nuttx/drivers/mtd/smart.c
index 9de557b5f..35a367e5b 100644
--- a/nuttx/drivers/mtd/smart.c
+++ b/nuttx/drivers/mtd/smart.c
@@ -97,7 +97,7 @@
#define SMART_FMT_VERSION 1
-#define SMART_FIRST_ALLOC_SECTOR 16 /* First logical sector number we will
+#define SMART_FIRST_ALLOC_SECTOR 12 /* First logical sector number we will
* use for assignment of requested Alloc
* sectors. All enries below this are
* reserved (some for root dir entries,
@@ -134,6 +134,7 @@ struct smart_struct_s
FAR uint8_t *releasecount; /* Count of released sectors per erase block */
FAR uint8_t *freecount; /* Count of free sectors per erase block */
FAR char *rwbuffer; /* Our sector read/write buffer */
+ const FAR char *partname; /* Optional partition name */
uint8_t formatversion; /* Format version on the device */
uint8_t formatstatus; /* Indicates the status of the device format */
uint8_t namesize; /* Length of filenames on this device */
@@ -471,49 +472,21 @@ static int smart_setsectorsize(struct smart_struct_s *dev, uint16_t size)
{
uint32_t erasesize;
uint32_t totalsectors;
- int ret;
- /* Check if the device supports sub-sector erase regions. If it does, then
- * use the sub-sector erase size instead of the larger erase size to
- * provide finer granularity.
- */
+ /* Validate the size isn't zero so we don't divide by zero below */
-#ifdef CONFIG_MTD_SUBSECTOR_ERASE
- ret = MTD_IOCTL(dev->mtd, MTDIOC_GETCAPS, 0);
- if (ret >= 0)
+ if (size == 0)
{
- /* The block device supports the GETCAPS ioctl. Now check if sub-sector
- * erase is supported.
- */
-
- if (!(ret & MTDIOC_CAPS_SECTERASE))
- {
- /* Ensure the subsector size is zero */
- dev->geo.subsectorsize = 0;
- dev->geo.nsubsectors = 0;
- }
+ size = CONFIG_MTD_SMART_SECTOR_SIZE;
}
- /* Now calculate the variables */
-
- if (dev->geo.subsectorsize != 0)
- {
- /* Use the sub-sector erase size */
-
- erasesize = dev->geo.subsectorsize;
- dev->neraseblocks = dev->geo.nsubsectors;
- }
- else
-#endif /* CONFIG_MTD_SUBSECTOR_ERASE */
- {
- erasesize = dev->geo.erasesize;
- dev->neraseblocks = dev->geo.neraseblocks;
- }
+ erasesize = dev->geo.erasesize;
+ dev->neraseblocks = dev->geo.neraseblocks;
/* Most FLASH devices have erase size of 64K, but geo.erasesize is only
* 16 bits, so it will be zero
*/
-
+
if (erasesize == 0)
{
erasesize = 65536;
@@ -569,6 +542,74 @@ static int smart_setsectorsize(struct smart_struct_s *dev, uint16_t size)
}
/****************************************************************************
+ * Name: smart_bytewrite
+ *
+ * Description: Writes a non-page size count of bytes to the underlying
+ * MTD device. If the MTD driver supports a direct impl of
+ * write, then it uses it, otherwise it does a read-modify-write
+ * and depends on the architecture of the flash to only program
+ * bits that acutally changed.
+ *
+ ****************************************************************************/
+
+static ssize_t smart_bytewrite(struct smart_struct_s *dev, size_t offset,
+ int nbytes, const uint8_t *buffer)
+{
+ ssize_t ret;
+
+#ifdef CONFIG_MTD_BYTE_WRITE
+ /* Check if the underlying MTD device supports write */
+
+ if (dev->mtd->write != NULL)
+ {
+ /* Use the MTD's write method to write individual bytes */
+
+ ret = dev->mtd->write(dev->mtd, offset, nbytes, buffer);
+ }
+ else
+#endif
+ {
+ /* Perform block-based read-modify-write */
+
+ uint16_t startblock;
+ uint16_t nblocks;
+
+ /* First calculate the start block and number of blocks affected */
+
+ startblock = offset / dev->geo.blocksize;
+ nblocks = (nbytes + dev->geo.blocksize-1) / dev->geo.blocksize;
+ DEBUGASSERT(nblocks <= dev->mtdBlksPerSector);
+
+ /* Do a block read */
+
+ ret = MTD_BREAD(dev->mtd, startblock, nblocks, (uint8_t *) dev->rwbuffer);
+ if (ret < 0)
+ {
+ fdbg("Error %d reading from device\n", -ret);
+ goto errout;
+ }
+
+ /* Modify the data */
+
+ memcpy(&dev->rwbuffer[offset - startblock * dev->geo.blocksize], buffer, nbytes);
+
+ /* Write the data back to the device */
+
+ ret = MTD_BWRITE(dev->mtd, startblock, nblocks, (uint8_t *) dev->rwbuffer);
+ if (ret < 0)
+ {
+ fdbg("Error %d writing to device\n", -ret);
+ goto errout;
+ }
+ }
+
+ ret = nbytes;
+
+errout:
+ return ret;
+}
+
+/****************************************************************************
* Name: smart_scan
*
* Description: Performs a scan of the MTD device searching for format
@@ -581,17 +622,17 @@ static int smart_scan(struct smart_struct_s *dev)
{
int sector;
int ret;
- int x;
+ int offset;
uint16_t totalsectors;
uint16_t sectorsize;
uint16_t logicalsector;
uint16_t seq1;
uint16_t seq2;
- char devname[18];
size_t readaddress;
struct smart_sect_header_s header;
- struct mtd_byte_write_s bytewrite;
#ifdef CONFIG_SMARTFS_MULTI_ROOT_DIRS
+ int x;
+ char devname[22];
struct smart_multiroot_device_s *rootdirdev;
#endif
@@ -675,7 +716,7 @@ static int smart_scan(struct smart_struct_s *dev)
}
#endif
- /* Test if this sector has been commited */
+ /* Test if this sector has been committed */
if ((header.status & SMART_STATUS_COMMITTED) ==
(CONFIG_SMARTFS_ERASEDSTATE & SMART_STATUS_COMMITTED))
@@ -763,7 +804,16 @@ static int smart_scan(struct smart_struct_s *dev)
for (x = 1; x < dev->rootdirentries; x++)
{
- snprintf(devname, 18, "/dev/smart%dd%d", dev->minor, x + 1);
+ if (dev->partname != NULL)
+ {
+ snprintf(dev->rwbuffer, sizeof(devname), "/dev/smart%d%s%d",
+ dev->minor, dev->partname, x+1);
+ }
+ else
+ {
+ snprintf(devname, sizeof(devname), "/dev/smart%dd%d", dev->minor,
+ x + 1);
+ }
/* Inode private data is a reference to a struct containing
* the SMART device structure and the root directory number.
@@ -792,9 +842,9 @@ static int smart_scan(struct smart_struct_s *dev)
/* Test for duplicate logical sectors on the device */
- if (dev->sMap[logicalsector] != -1)
+ if (dev->sMap[logicalsector] != 0xFFFF)
{
- /* TODO: Uh-oh, we found more than 1 physical sector claiming to be
+ /* Uh-oh, we found more than 1 physical sector claiming to be
* the * same logical sector. Use the sequence number information
* to resolve who wins.
*/
@@ -853,10 +903,13 @@ static int smart_scan(struct smart_struct_s *dev)
#else
header.status |= SMART_STATUS_RELEASED;
#endif
- bytewrite.offset = readaddress + offsetof(struct smart_sect_header_s, status);
- bytewrite.count = 1;
- bytewrite.buffer = &header.status;
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
+ offset = readaddress + offsetof(struct smart_sect_header_s, status);
+ ret = smart_bytewrite(dev, offset, 1, &header.status);
+ if (ret < 0)
+ {
+ fdbg("Error %d releasing duplicate sector\n", -ret);
+ goto err_out;
+ }
}
/* Update the logical to physical sector map */
@@ -886,9 +939,11 @@ err_out:
#ifdef CONFIG_SMARTFS_MULTI_ROOT_DIRS
static inline int smart_getformat(struct smart_struct_s *dev,
- struct smart_format_s *fmt, uint8_t rootdirnum)
+ struct smart_format_s *fmt,
+ uint8_t rootdirnum)
#else
-static inline int smart_getformat(struct smart_struct_s *dev, struct smart_format_s *fmt)
+static inline int smart_getformat(struct smart_struct_s *dev,
+ struct smart_format_s *fmt)
#endif
{
int ret;
@@ -914,8 +969,6 @@ static inline int smart_getformat(struct smart_struct_s *dev, struct smart_forma
}
}
- /* TODO: Determine if the underlying MTD device supports bytewrite */
-
/* Now fill in the structure */
if (dev->formatstatus == SMART_FMT_STAT_FORMATTED)
@@ -978,7 +1031,7 @@ static inline int smart_llformat(struct smart_struct_s *dev, unsigned long arg)
/* Erase the MTD device */
ret = MTD_IOCTL(dev->mtd, MTDIOC_BULKERASE, 0);
- if (ret != OK)
+ if (ret < 0)
{
return ret;
}
@@ -1180,8 +1233,9 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
bool collect = TRUE;
int x;
int ret;
+ size_t offset;
struct smart_sect_header_s *header;
- struct mtd_byte_write_s bytewrite;
+ uint8_t newstatus;
while (collect)
{
@@ -1196,8 +1250,6 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
{
releasedsectors += dev->releasecount[x];
if (dev->releasecount[x] > releasemax)
-// if (dev->releasecount[x] > releasemax &&
-// dev->freecount[x] < (dev->sectorsPerBlk >> 1))
{
releasemax = dev->releasecount[x];
collectblock = x;
@@ -1205,7 +1257,8 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
}
/* Test if the released sectors count is greater than the
- * free sectors. If it is, then we will do garbage collection */
+ * free sectors. If it is, then we will do garbage collection.
+ */
if (releasedsectors > dev->freesectors)
collect = TRUE;
@@ -1238,7 +1291,8 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
/* Perform collection on block with the most released sectors.
* First mark the block as having no free sectors so we don't
- * try to move sectors into the block we are trying to erase. */
+ * try to move sectors into the block we are trying to erase.
+ */
dev->freecount[collectblock] = 0;
@@ -1267,7 +1321,8 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
(CONFIG_SMARTFS_ERASEDSTATE & SMART_STATUS_RELEASED)))
{
/* This sector doesn't have live data (free or released).
- * just continue to the next sector and don't move it. */
+ * just continue to the next sector and don't move it.
+ */
continue;
}
@@ -1304,27 +1359,35 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
/* Commit the sector */
- bytewrite.offset = newsector * dev->mtdBlksPerSector * dev->geo.blocksize +
+ offset = newsector * dev->mtdBlksPerSector * dev->geo.blocksize +
offsetof(struct smart_sect_header_s, status);
#if CONFIG_SMARTFS_ERASEDSTATE == 0xFF
- header->status &= ~SMART_STATUS_COMMITTED;
+ newstatus = header->status & ~SMART_STATUS_COMMITTED;
#else
- header->status |= SMART_STATUS_COMMITTED;
+ newstatus = header->status | SMART_STATUS_COMMITTED;
#endif
- bytewrite.count = 1;
- bytewrite.buffer = &header->status;
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
+ ret = smart_bytewrite(dev, offset, 1, &newstatus);
+ if (ret < 0)
+ {
+ fdbg("Error %d committing new sector %d\n" -ret, newsector);
+ goto errout;
+ }
/* Release the old physical sector */
#if CONFIG_SMARTFS_ERASEDSTATE == 0xFF
- header->status &= ~SMART_STATUS_RELEASED;
+ newstatus = header->status & ~SMART_STATUS_RELEASED;
#else
- header->status |= SMART_STATUS_RELEASED;
+ newstatus = header->status | SMART_STATUS_RELEASED;
#endif
- bytewrite.offset = x * dev->mtdBlksPerSector * dev->geo.blocksize +
+ offset = x * dev->mtdBlksPerSector * dev->geo.blocksize +
offsetof(struct smart_sect_header_s, status);
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
+ ret = smart_bytewrite(dev, offset, 1, &newstatus);
+ if (ret < 0)
+ {
+ fdbg("Error %d releasing old sector %d\n" -ret, x);
+ goto errout;
+ }
/* Update the variables */
@@ -1334,17 +1397,7 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
/* Now erase the erase block */
-#ifdef CONFIG_MTD_SUBSECTOR_ERASE
- if (dev->geo.subsectorsize != 0)
- {
- /* Perform a sub-sector erase */
- MTD_IOCTL(dev->mtd, MTDIOC_SECTERASE, collectblock);
- }
- else
-#endif
- {
- MTD_ERASE(dev->mtd, collectblock, 1);
- }
+ MTD_ERASE(dev->mtd, collectblock, 1);
dev->freesectors += dev->releasecount[collectblock];
dev->freecount[collectblock] = dev->sectorsPerBlk;
@@ -1357,18 +1410,19 @@ static int smart_garbagecollect(struct smart_struct_s *dev)
/* Set the sector size in the 1st header */
uint8_t sectsize = dev->sectorsize >> 7;
- header = (struct smart_sect_header_s *) dev->rwbuffer;
#if ( CONFIG_SMARTFS_ERASEDSTATE == 0xFF )
- header->status = (uint8_t) ~SMART_STATUS_SIZEBITS | sectsize;
+ newstatus = (uint8_t) ~SMART_STATUS_SIZEBITS | sectsize;
#else
- header->status = (uint8_t) sectsize;
+ newstatus = (uint8_t) sectsize;
#endif
/* Write the sector size to the device */
- bytewrite.offset = offsetof(struct smart_sect_header_s, status);
- bytewrite.count = 1;
- bytewrite.buffer = &header->status;
- MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
+ offset = offsetof(struct smart_sect_header_s, status);
+ ret = smart_bytewrite(dev, offset, 1, &newstatus);
+ if (ret < 0)
+ {
+ fdbg("Error %d setting sector 0 size\n", -ret);
+ }
}
/* Update the block aging information in the format signature sector */
@@ -1402,15 +1456,15 @@ errout:
#ifdef CONFIG_FS_WRITABLE
static inline int smart_writesector(struct smart_struct_s *dev, unsigned long arg)
{
- int ret;
- uint16_t x;
- bool needsrelocate = FALSE;
- uint16_t mtdblock;
- uint16_t physsector;
- struct smart_read_write_s *req;
- struct smart_sect_header_s *header;
- struct mtd_byte_write_s bytewrite;
- uint8_t byte;
+ int ret;
+ uint16_t x;
+ bool needsrelocate = FALSE;
+ uint16_t mtdblock;
+ uint16_t physsector;
+ struct smart_read_write_s *req;
+ struct smart_sect_header_s *header;
+ size_t offset;
+ uint8_t byte;
fvdbg("Entry\n");
req = (struct smart_read_write_s *) arg;
@@ -1515,16 +1569,14 @@ static inline int smart_writesector(struct smart_struct_s *dev, unsigned long ar
/* Commit the new physical sector */
#if CONFIG_SMARTFS_ERASEDSTATE == 0xFF
- header->status &= ~SMART_STATUS_COMMITTED;
+ byte = header->status & ~SMART_STATUS_COMMITTED;
#else
- header->status |= SMART_STATUS_COMMITTED;
+ byte = header->status | SMART_STATUS_COMMITTED;
#endif
- bytewrite.offset = physsector * dev->mtdBlksPerSector *
- dev->geo.blocksize + offsetof(struct smart_sect_header_s, status);
- bytewrite.count = 1;
- bytewrite.buffer = (uint8_t *) &header->status;
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
- if (ret != OK)
+ offset = physsector * dev->mtdBlksPerSector * dev->geo.blocksize +
+ offsetof(struct smart_sect_header_s, status);
+ ret = smart_bytewrite(dev, offset, 1, &byte);
+ if (ret != 1)
{
fvdbg("Error committing physical sector %d\n", physsector);
ret = -EIO;
@@ -1534,13 +1586,13 @@ static inline int smart_writesector(struct smart_struct_s *dev, unsigned long ar
/* Release the old physical sector */
#if CONFIG_SMARTFS_ERASEDSTATE == 0xFF
- header->status &= ~SMART_STATUS_RELEASED;
+ byte = header->status & ~SMART_STATUS_RELEASED;
#else
- header->status |= SMART_STATUS_RELEASED;
+ byte = header->status | SMART_STATUS_RELEASED;
#endif
- bytewrite.offset = mtdblock * dev->geo.blocksize +
+ offset = mtdblock * dev->geo.blocksize +
offsetof(struct smart_sect_header_s, status);
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
+ ret = smart_bytewrite(dev, offset, 1, &byte);
/* Update releasecount for released sector and freecount for the
* newly allocated physical sector. */
@@ -1564,11 +1616,9 @@ static inline int smart_writesector(struct smart_struct_s *dev, unsigned long ar
/* Not relocated. Just write the portion of the sector that needs
* to be written. */
- bytewrite.offset = mtdblock * dev->geo.blocksize +
+ offset = mtdblock * dev->geo.blocksize +
sizeof(struct smart_sect_header_s) + req->offset;
- bytewrite.count = req->count;
- bytewrite.buffer = req->buffer;
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
+ ret = smart_bytewrite(dev, offset, req->count, req->buffer);
}
ret = OK;
@@ -1743,9 +1793,8 @@ static inline int smart_allocsector(struct smart_struct_s *dev, unsigned long re
* rescan and try again to "self heal" in case of a
* bug in our code? */
- fdbg("Couldn't find free sector when I expected too\n");
-
- /* Unlock the mutex if we add one */
+ fdbg("No free logical sector numbers! Free sectors = %d\n",
+ dev->freesectors);
return -EIO;
}
@@ -1827,7 +1876,7 @@ static inline int smart_freesector(struct smart_struct_s *dev, unsigned long
uint16_t physsector;
uint16_t block;
struct smart_sect_header_s header;
- struct mtd_byte_write_s bytewrite;
+ size_t offset;
/* Check if the logical sector is within bounds */
@@ -1875,11 +1924,9 @@ static inline int smart_freesector(struct smart_struct_s *dev, unsigned long
/* Write the status back to the device */
- bytewrite.offset = readaddr + offsetof(struct smart_sect_header_s, status);
- bytewrite.count = 1;
- bytewrite.buffer = &header.status;
- ret = MTD_IOCTL(dev->mtd, MTDIOC_BYTEWRITE, (unsigned long) &bytewrite);
- if (ret != OK)
+ offset = readaddr + offsetof(struct smart_sect_header_s, status);
+ ret = smart_bytewrite(dev, offset, 1, &header.status);
+ if (ret != 1)
{
fdbg("Error updating physicl sector %d status\n", physsector);
goto errout;
@@ -1900,15 +1947,7 @@ static inline int smart_freesector(struct smart_struct_s *dev, unsigned long
{
/* Erase the block */
-#ifdef CONFIG_MTD_SUBSECTOR_ERASE
- if (dev->geo.subsectorsize != 0)
- {
- /* Perform a sub-sector erase */
- MTD_IOCTL(dev->mtd, MTDIOC_SECTERASE, block);
- }
- else
-#endif
- MTD_ERASE(dev->mtd, block, 1);
+ MTD_ERASE(dev->mtd, block, 1);
dev->freesectors += dev->releasecount[block];
dev->releasecount[block] = 0;
@@ -2050,7 +2089,7 @@ ok_out:
*
****************************************************************************/
-int smart_initialize(int minor, FAR struct mtd_dev_s *mtd)
+int smart_initialize(int minor, FAR struct mtd_dev_s *mtd, const char *partname)
{
struct smart_struct_s *dev;
int ret = -ENOMEM;
@@ -2084,10 +2123,6 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd)
/* Set these to zero in case the device doesn't support them */
-#ifdef CONFIG_MTD_SUBSECTOR_ERASE
- dev->geo.subsectorsize= 0;
- dev->geo.nsubsectors = 0;
-#endif
ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&dev->geo));
if (ret < 0)
{
@@ -2123,6 +2158,7 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd)
dev->formatstatus = SMART_FMT_STAT_UNKNOWN;
dev->namesize = CONFIG_SMARTFS_MAXNAMLEN;
+ dev->partname = partname;
#ifdef CONFIG_SMARTFS_MULTI_ROOT_DIRS
dev->minor = minor;
#endif
@@ -2130,7 +2166,10 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd)
/* Create a MTD block device name */
#ifdef CONFIG_SMARTFS_MULTI_ROOT_DIRS
- snprintf(dev->rwbuffer, 18, "/dev/smart%dd1", minor);
+ if (partname != NULL)
+ snprintf(dev->rwbuffer, 18, "/dev/smart%d%sd1", minor, partname);
+ else
+ snprintf(dev->rwbuffer, 18, "/dev/smart%dd1", minor);
/* Inode private data is a reference to a struct containing
* the SMART device structure and the root directory number.
@@ -2154,7 +2193,10 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd)
ret = register_blockdriver(dev->rwbuffer, &g_bops, 0, rootdirdev);
#else
- snprintf(dev->rwbuffer, 18, "/dev/smart%d", minor);
+ if (partname != NULL)
+ snprintf(dev->rwbuffer, 18, "/dev/smart%d%s", minor, partname);
+ else
+ snprintf(dev->rwbuffer, 18, "/dev/smart%d", minor);
/* Inode private data is a reference to the SMART device structure */
@@ -2167,6 +2209,7 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd)
kfree(dev->sMap);
kfree(dev->rwbuffer);
kfree(dev);
+ goto errout;
}
/* Do a scan of the device */