summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/fs/nxffs/Kconfig30
-rw-r--r--nuttx/fs/nxffs/nxffs.h110
-rw-r--r--nuttx/fs/nxffs/nxffs_block.c12
-rw-r--r--nuttx/fs/nxffs/nxffs_cache.c7
-rw-r--r--nuttx/fs/nxffs/nxffs_initialize.c40
-rw-r--r--nuttx/fs/nxffs/nxffs_pack.c37
-rw-r--r--nuttx/fs/nxffs/nxffs_reformat.c91
-rw-r--r--nuttx/fs/nxffs/nxffs_unlink.c6
-rw-r--r--nuttx/fs/nxffs/nxffs_write.c66
-rw-r--r--nuttx/include/nuttx/fs/nxffs.h15
10 files changed, 302 insertions, 112 deletions
diff --git a/nuttx/fs/nxffs/Kconfig b/nuttx/fs/nxffs/Kconfig
index dc05c93df..e9528c8ab 100644
--- a/nuttx/fs/nxffs/Kconfig
+++ b/nuttx/fs/nxffs/Kconfig
@@ -14,6 +14,36 @@ config FS_NXFFS
if FS_NXFFS
+config NXFFS_SCAN_VOLUME
+ bool "Scan volume"
+ default n
+ ---help---
+ Scan the media for bad blocks on start-up. If too many bad or
+ unformatted blocks are found, then re-format the volume. Otherwise,
+ the volume will be reformatted only if no NXFFS file system is
+ found.
+
+ Why might you want to do this? If too many bad blocks accumulate
+ over time, then attempting to reformat my be the only way to
+ recover. And what if you power down the device while formatting
+ the FLASH so that you have only a partially formatted device?
+ Scanning the volume can get you out of these situations.
+
+ The down side is that scanning the volume can adversely affect
+ your start-up time. An option is to just erase the FLASH and
+ reboot in these cases. That can be done with
+ apps/system/flash_eraseall.
+
+config NXFFS_REFORMAT_THRESH
+ int "Reformat percentage"
+ default 20
+ range 0 100
+ depends on NXFFS_SCAN_VOLUME
+ ---help---
+ This defines the threshold for re-formatting. Is less than this
+ percentage of good blocks are found, then the volume is re-
+ formatted.
+
config NXFFS_PREALLOCATED
bool "Single, preallocated volume"
default y
diff --git a/nuttx/fs/nxffs/nxffs.h b/nuttx/fs/nxffs/nxffs.h
index 38a27da38..9b7bdc4ce 100644
--- a/nuttx/fs/nxffs/nxffs.h
+++ b/nuttx/fs/nxffs/nxffs.h
@@ -374,7 +374,7 @@ extern struct nxffs_volume_s g_volume;
*
****************************************************************************/
-extern int nxffs_limits(FAR struct nxffs_volume_s *volume);
+int nxffs_limits(FAR struct nxffs_volume_s *volume);
/****************************************************************************
* Name: nxffs_rdle16
@@ -392,7 +392,7 @@ extern int nxffs_limits(FAR struct nxffs_volume_s *volume);
*
****************************************************************************/
-extern uint16_t nxffs_rdle16(FAR const uint8_t *val);
+uint16_t nxffs_rdle16(FAR const uint8_t *val);
/****************************************************************************
* Name: nxffs_wrle16
@@ -411,7 +411,7 @@ extern uint16_t nxffs_rdle16(FAR const uint8_t *val);
*
****************************************************************************/
-extern void nxffs_wrle16(uint8_t *dest, uint16_t val);
+void nxffs_wrle16(uint8_t *dest, uint16_t val);
/****************************************************************************
* Name: nxffs_rdle32
@@ -429,7 +429,7 @@ extern void nxffs_wrle16(uint8_t *dest, uint16_t val);
*
****************************************************************************/
-extern uint32_t nxffs_rdle32(FAR const uint8_t *val);
+uint32_t nxffs_rdle32(FAR const uint8_t *val);
/****************************************************************************
* Name: nxffs_wrle32
@@ -448,7 +448,7 @@ extern uint32_t nxffs_rdle32(FAR const uint8_t *val);
*
****************************************************************************/
-extern void nxffs_wrle32(uint8_t *dest, uint32_t val);
+void nxffs_wrle32(uint8_t *dest, uint32_t val);
/****************************************************************************
* Name: nxffs_erased
@@ -467,7 +467,7 @@ extern void nxffs_wrle32(uint8_t *dest, uint32_t val);
*
****************************************************************************/
-extern size_t nxffs_erased(FAR const uint8_t *buffer, size_t buflen);
+size_t nxffs_erased(FAR const uint8_t *buffer, size_t buflen);
/****************************************************************************
* Name: nxffs_rdcache
@@ -487,7 +487,7 @@ extern size_t nxffs_erased(FAR const uint8_t *buffer, size_t buflen);
*
****************************************************************************/
-extern int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block);
+int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block);
/****************************************************************************
* Name: nxffs_wrcache
@@ -505,7 +505,7 @@ extern int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block);
*
****************************************************************************/
-extern int nxffs_wrcache(FAR struct nxffs_volume_s *volume);
+int nxffs_wrcache(FAR struct nxffs_volume_s *volume);
/****************************************************************************
* Name: nxffs_ioseek
@@ -524,7 +524,7 @@ extern int nxffs_wrcache(FAR struct nxffs_volume_s *volume);
*
****************************************************************************/
-extern void nxffs_ioseek(FAR struct nxffs_volume_s *volume, off_t offset);
+void nxffs_ioseek(FAR struct nxffs_volume_s *volume, off_t offset);
/****************************************************************************
* Name: nxffs_iotell
@@ -542,7 +542,7 @@ extern void nxffs_ioseek(FAR struct nxffs_volume_s *volume, off_t offset);
*
****************************************************************************/
-extern off_t nxffs_iotell(FAR struct nxffs_volume_s *volume);
+off_t nxffs_iotell(FAR struct nxffs_volume_s *volume);
/****************************************************************************
* Name: nxffs_getc
@@ -566,7 +566,7 @@ extern off_t nxffs_iotell(FAR struct nxffs_volume_s *volume);
*
****************************************************************************/
-extern int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve);
+int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve);
/****************************************************************************
* Name: nxffs_freeentry
@@ -590,7 +590,7 @@ extern int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve);
*
****************************************************************************/
-extern void nxffs_freeentry(FAR struct nxffs_entry_s *entry);
+void nxffs_freeentry(FAR struct nxffs_entry_s *entry);
/****************************************************************************
* Name: nxffs_nextentry
@@ -612,8 +612,8 @@ extern void nxffs_freeentry(FAR struct nxffs_entry_s *entry);
*
****************************************************************************/
-extern int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR struct nxffs_entry_s *entry);
+int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
+ FAR struct nxffs_entry_s *entry);
/****************************************************************************
* Name: nxffs_findinode
@@ -636,9 +636,8 @@ extern int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
*
****************************************************************************/
-extern int nxffs_findinode(FAR struct nxffs_volume_s *volume,
- FAR const char *name,
- FAR struct nxffs_entry_s *entry);
+int nxffs_findinode(FAR struct nxffs_volume_s *volume, FAR const char *name,
+ FAR struct nxffs_entry_s *entry);
/****************************************************************************
* Name: nxffs_inodeend
@@ -664,8 +663,8 @@ extern int nxffs_findinode(FAR struct nxffs_volume_s *volume,
*
****************************************************************************/
-extern off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry);
+off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
+ FAR struct nxffs_entry_s *entry);
/****************************************************************************
* Name: nxffs_verifyblock
@@ -680,14 +679,19 @@ extern off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
* block - The (logical) block number to load and verify.
*
* Returned Values:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure.
+ * OK (zero( is returned on success. Otherwise, a negated errno value is
+ * returned indicating the nature of the failure:
+ *
+ * -EIO is returned if we failed to read the block. If we are using
+ * NAND memory, then this probably means that the block has
+ * uncorrectable bit errors.
+ * -ENOENT is returned if the block is a bad block.
*
* Defined in nxffs_block.c
*
****************************************************************************/
-extern int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block);
+int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block);
/****************************************************************************
* Name: nxffs_validblock
@@ -709,7 +713,7 @@ extern int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block);
*
****************************************************************************/
-extern int nxffs_validblock(struct nxffs_volume_s *volume, off_t *block);
+int nxffs_validblock(struct nxffs_volume_s *volume, off_t *block);
/****************************************************************************
* Name: nxffs_blockstats
@@ -732,8 +736,8 @@ extern int nxffs_validblock(struct nxffs_volume_s *volume, off_t *block);
*
****************************************************************************/
-extern int nxffs_blockstats(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_blkstats_s *stats);
+int nxffs_blockstats(FAR struct nxffs_volume_s *volume,
+ FAR struct nxffs_blkstats_s *stats);
/****************************************************************************
* Name: nxffs_reformat
@@ -754,7 +758,27 @@ extern int nxffs_blockstats(FAR struct nxffs_volume_s *volume,
*
****************************************************************************/
-extern int nxffs_reformat(FAR struct nxffs_volume_s *volume);
+int nxffs_reformat(FAR struct nxffs_volume_s *volume);
+
+/****************************************************************************
+ * Name: nxffs_blkinit
+ *
+ * Description:
+ * Initialize an NXFFS block to the erased state with the specified block
+ * status.
+ *
+ * Input Parameters:
+ * volume - Describes the NXFFS volume (needed for the blocksize).
+ * blkptr - Pointer to the logic block to initialize.
+ * state - Either BLOCK_STATE_GOOD or BLOCK_STATE_BAD.
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void nxffs_blkinit(FAR struct nxffs_volume_s *volume, FAR uint8_t *blkptr,
+ uint8_t state);
/****************************************************************************
* Name: nxffs_findofile
@@ -776,8 +800,8 @@ extern int nxffs_reformat(FAR struct nxffs_volume_s *volume);
*
****************************************************************************/
-extern FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volume,
- FAR const char *name);
+FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volume,
+ FAR const char *name);
/****************************************************************************
* Name: nxffs_findwriter
@@ -797,7 +821,7 @@ extern FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volu
*
****************************************************************************/
-extern FAR struct nxffs_wrfile_s *nxffs_findwriter(FAR struct nxffs_volume_s *volume);
+FAR struct nxffs_wrfile_s *nxffs_findwriter(FAR struct nxffs_volume_s *volume);
/****************************************************************************
* Name: nxffs_wrinode
@@ -823,8 +847,8 @@ extern FAR struct nxffs_wrfile_s *nxffs_findwriter(FAR struct nxffs_volume_s *vo
*
****************************************************************************/
-extern int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry);
+int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
+ FAR struct nxffs_entry_s *entry);
/****************************************************************************
* Name: nxffs_updateinode
@@ -843,8 +867,8 @@ extern int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
*
****************************************************************************/
-extern int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry);
+int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
+ FAR struct nxffs_entry_s *entry);
/****************************************************************************
* Name: nxffs_wrreserve
@@ -884,7 +908,7 @@ extern int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
*
****************************************************************************/
-extern int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
+int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
/****************************************************************************
* Name: nxffs_wrverify
@@ -928,7 +952,7 @@ extern int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
*
****************************************************************************/
-extern int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size);
+int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size);
/****************************************************************************
* Name: nxffs_wrblkhdr
@@ -950,8 +974,8 @@ extern int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size);
*
****************************************************************************/
-extern int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile);
+int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
+ FAR struct nxffs_wrfile_s *wrfile);
/****************************************************************************
* Name: nxffs_nextblock
@@ -972,8 +996,8 @@ extern int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
*
****************************************************************************/
-extern int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR struct nxffs_blkentry_s *blkentry);
+int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
+ FAR struct nxffs_blkentry_s *blkentry);
/****************************************************************************
* Name: nxffs_rdblkhdr
@@ -995,8 +1019,8 @@ extern int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
*
****************************************************************************/
-extern int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR uint16_t *datlen);
+int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
+ FAR uint16_t *datlen);
/****************************************************************************
* Name: nxffs_rminode
@@ -1015,7 +1039,7 @@ extern int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
*
****************************************************************************/
-extern int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name);
+int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name);
/****************************************************************************
* Name: nxffs_pack
@@ -1033,7 +1057,7 @@ extern int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name
*
****************************************************************************/
-extern int nxffs_pack(FAR struct nxffs_volume_s *volume);
+int nxffs_pack(FAR struct nxffs_volume_s *volume);
/****************************************************************************
* Standard mountpoint operation methods
diff --git a/nuttx/fs/nxffs/nxffs_block.c b/nuttx/fs/nxffs/nxffs_block.c
index ace656ff2..1a6a13adb 100644
--- a/nuttx/fs/nxffs/nxffs_block.c
+++ b/nuttx/fs/nxffs/nxffs_block.c
@@ -83,9 +83,13 @@
* block - The (logical) block number to load and verify.
*
* Returned Values:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. -ENOENT is returned
- * if the block is a bad block.
+ * OK (zero( is returned on success. Otherwise, a negated errno value is
+ * returned indicating the nature of the failure:
+ *
+ * -EIO is returned if we failed to read the block. If we are using
+ * NAND memory, then this probably means that the block has
+ * uncorrectable bit errors.
+ * -ENOENT is returned if the block is a bad block.
*
****************************************************************************/
@@ -102,7 +106,7 @@ int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block)
/* Perhaps we are at the end of the media */
fdbg("ERROR: Failed to read data into cache: %d\n", ret);
- return ret;
+ return -EIO;
}
/* Check if the block has a magic number (meaning that it is not
diff --git a/nuttx/fs/nxffs/nxffs_cache.c b/nuttx/fs/nxffs/nxffs_cache.c
index 71f31f892..b5a1749db 100644
--- a/nuttx/fs/nxffs/nxffs_cache.c
+++ b/nuttx/fs/nxffs/nxffs_cache.c
@@ -246,8 +246,13 @@ int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve)
ret = nxffs_verifyblock(volume, volume->ioblock);
if (ret < 0 && ret != -ENOENT)
{
+ /* A read error occurred. This probably means that we are
+ * using NAND memory this block has an uncorrectable bit error.
+ * Ignore the error (after complaining) and try the next
+ * block.
+ */
+
fdbg("ERROR: Failed to read valid data into cache: %d\n", ret);
- return ret;
}
}
while (ret != OK);
diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c
index 5c40b7e96..084f3254e 100644
--- a/nuttx/fs/nxffs/nxffs_initialize.c
+++ b/nuttx/fs/nxffs/nxffs_initialize.c
@@ -157,7 +157,9 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
{
FAR struct nxffs_volume_s *volume;
struct nxffs_blkstats_s stats;
+#ifdef CONFIG_NXFFS_SCAN_VOLUME
off_t threshold;
+#endif
int ret;
/* If CONFIG_NXFFS_PREALLOCATED is defined, then this is the single, pre-
@@ -230,6 +232,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
volume->nblocks = volume->geo.neraseblocks * volume->blkper;
DEBUGASSERT((off_t)volume->blkper * volume->geo.blocksize == volume->geo.erasesize);
+#ifdef CONFIG_NXFFS_SCAN_VOLUME
/* Check if there is a valid NXFFS file system on the flash */
ret = nxffs_blockstats(volume, &stats);
@@ -243,7 +246,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
* blocks is high, then reformat the FLASH.
*/
- threshold = stats.nblocks / 5;
+ threshold = (stats.nblocks * CONFIG_NXFFS_REFORMAT_THRESH) / 100;
if (stats.ngood < threshold || stats.nunformat > threshold)
{
/* Reformat the volume */
@@ -266,6 +269,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
}
#endif
}
+#endif /* CONFIG_NXFFS_SCAN_VOLUME */
/* Get the file system limits */
@@ -275,6 +279,37 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
return OK;
}
+ /* We may need to format the volume. Try that before giving up. */
+
+ fdbg("WARNING: Failed to calculate file system limits: %d\n", -ret);
+ ret = nxffs_reformat(volume);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to reformat the volume: %d\n", -ret);
+ goto errout_with_buffer;
+ }
+
+ /* Get statistics on the re-formatted volume */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
+ ret = nxffs_blockstats(volume, &stats);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to collect block statistics: %d\n", -ret);
+ goto errout_with_buffer;
+ }
+#endif
+
+ /* Now try to get the file system limits again */
+
+ ret = nxffs_limits(volume);
+ if (ret == OK)
+ {
+ return OK;
+ }
+
+ /* Now give up */
+
fdbg("ERROR: Failed to calculate file system limits: %d\n", -ret);
errout_with_buffer:
@@ -382,6 +417,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
offset = nxffs_inodeend(volume, &entry);
nxffs_freeentry(&entry);
}
+
fvdbg("Last inode before offset %d\n", offset);
}
@@ -412,6 +448,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
volume->inoffset = volume->froffset;
fvdbg("No inodes, inoffset: %d\n", volume->inoffset);
}
+
return OK;
}
@@ -444,6 +481,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
volume->inoffset = offset;
fvdbg("First inode at offset %d\n", volume->inoffset);
}
+
return OK;
}
}
diff --git a/nuttx/fs/nxffs/nxffs_pack.c b/nuttx/fs/nxffs/nxffs_pack.c
index afbb55307..d6e31896e 100644
--- a/nuttx/fs/nxffs/nxffs_pack.c
+++ b/nuttx/fs/nxffs/nxffs_pack.c
@@ -1409,20 +1409,39 @@ start_pack:
eblock < volume->geo.neraseblocks;
eblock++)
{
- /* Read the erase block into the pack buffer. We need to do this even
- * if we are overwriting the entire block so that we skip over
- * previously marked bad blocks.
- */
+ /* Get the starting block number of the erase block */
pack.block0 = eblock * volume->blkper;
- ret = MTD_BREAD(volume->mtd, pack.block0, volume->blkper, volume->pack);
- if (ret < 0)
+
+ /* Read the entire erase block into the pack buffer, one-block-at-a-
+ * time. We need to do this even if we are overwriting the entire
+ * block so that (1) we skip over previously marked bad blocks, and
+ * (2) we can handle individual block read failures.
+ *
+ * For most FLASH, a read failure indicates a fatal hardware failure.
+ * But for NAND FLASH, the read failure probably indicates a block
+ * with uncorrectable bit errors.
+ */
+
+ /* Pack each I/O block */
+
+ for (i = 0, block = pack.block0, pack.iobuffer = volume->pack;
+ i < volume->blkper;
+ i++, block++, pack.iobuffer += volume->geo.blocksize)
{
- fdbg("ERROR: Failed to read erase block %d: %d\n", eblock, -ret);
- goto errout_with_pack;
+ /* Read the next block in the erase block */
+
+ ret = MTD_BREAD(volume->mtd, block, 1, pack.iobuffer);
+ if (ret < 0)
+ {
+ /* Force a the block to be an NXFFS bad block */
+
+ fdbg("ERROR: Failed to read block %d: %d\n", block, ret);
+ nxffs_blkinit(volume, pack.iobuffer, BLOCK_STATE_BAD);
+ }
}
- /* Pack each I/O block */
+ /* Now ack each I/O block */
for (i = 0, block = pack.block0, pack.iobuffer = volume->pack;
i < volume->blkper;
diff --git a/nuttx/fs/nxffs/nxffs_reformat.c b/nuttx/fs/nxffs/nxffs_reformat.c
index 294414d40..fd33dd3b2 100644
--- a/nuttx/fs/nxffs/nxffs_reformat.c
+++ b/nuttx/fs/nxffs/nxffs_reformat.c
@@ -92,14 +92,11 @@ static int nxffs_format(FAR struct nxffs_volume_s *volume)
/* Create an image of one properly formatted erase sector */
- memset(volume->pack, CONFIG_NXFFS_ERASEDSTATE, volume->geo.erasesize);
for (blkptr = volume->pack, i = 0;
i < volume->blkper;
blkptr += volume->geo.blocksize, i++)
{
- FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr;
- memcpy(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE);
- blkhdr->state = BLOCK_STATE_GOOD;
+ nxffs_blkinit(volume, blkptr, BLOCK_STATE_GOOD);
}
/* Erase and format each erase block */
@@ -149,7 +146,8 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume)
{
FAR uint8_t *blkptr; /* Pointer to next block data */
off_t eblock; /* Erase block number */
- off_t lblock; /* Logical block number */
+ off_t lblock; /* Logical block number of the erase block */
+ off_t block; /* Working block number */
ssize_t nxfrd; /* Number of blocks transferred */
bool good; /* TRUE: block is good */
bool modified; /* TRUE: The erase block has been modified */
@@ -159,31 +157,50 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume)
for (eblock = 0; eblock < volume->geo.neraseblocks; eblock++)
{
- /* Read the entire erase block */
+ /* Get the logical block number of the erase block */
lblock = eblock * volume->blkper;
- nxfrd = MTD_BREAD(volume->mtd, lblock, volume->blkper, volume->pack);
- if (nxfrd != volume->blkper)
- {
- fdbg("ERROR: Read erase block %d failed: %d\n", lblock, nxfrd);
- return -EIO;
- }
- /* Process each logical block */
+ /* Read the entire erase block into memory, processing each block one-
+ * at-a-time. We could read the entire erase block at once. That
+ * would be more efficient. However, for the case of NAND FLASH, each
+ * individual block can fail independently due to uncorrectable bit
+ * errors in that block.
+ */
modified = false;
- for (blkptr = volume->pack, i = 0;
+ for (i = 0, block = lblock, blkptr = volume->pack;
i < volume->blkper;
- blkptr += volume->geo.blocksize, i++)
+ i++, block++, blkptr += volume->geo.blocksize)
{
FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr;
- /* Check block header */
+ /* Read the next block in the erase block */
- good = true;
- if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0 ||
- blkhdr->state != BLOCK_STATE_GOOD)
+ good = true;
+ nxfrd = MTD_BREAD(volume->mtd, block, i, blkptr);
+ if (nxfrd < 0)
{
+ /* Failed to read the block. This should never happen with
+ * most FLASH. However, for NAND this probably means that we
+ * read a block with uncorrectable bit errors.
+ */
+
+ fdbg("ERROR: Failed to read block %d: %d\n",
+ block, (int)nxfrd);
+
+ good = false;
+ }
+
+ /* Check the block header */
+
+ else if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0 ||
+ blkhdr->state != BLOCK_STATE_GOOD)
+ {
+ /* The block is not formated with the NXFFS magic bytes or else
+ * the block is specifically marked bad.
+ */
+
good = false;
}
@@ -196,15 +213,14 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume)
good = (blocksize == erasesize);
}
- /* If the block is bad, attempt to re-write the block header indicating
- * a bad block (of course, if the block has failed, this may not be
- * possible, depending upon failure modes.
+ /* If the block is bad, attempt to re-write the block header
+ * indicating a bad block (of course, if the block has failed,
+ * this may not be possible, depending upon failure modes.
*/
if (!good)
{
- memcpy(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE);
- blkhdr->state = BLOCK_STATE_BAD;
+ nxffs_blkinit(volume, blkptr, BLOCK_STATE_BAD);
modified = true;
}
}
@@ -269,3 +285,30 @@ int nxffs_reformat(FAR struct nxffs_volume_s *volume)
return ret;
}
+
+/****************************************************************************
+ * Name: nxffs_blkinit
+ *
+ * Description:
+ * Initialize an NXFFS block to the erased state with the specified block
+ * status.
+ *
+ * Input Parameters:
+ * volume - Describes the NXFFS volume (needed for the blocksize).
+ * blkptr - Pointer to the logic block to initialize.
+ * state - Either BLOCK_STATE_GOOD or BLOCK_STATE_BAD.
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void nxffs_blkinit(FAR struct nxffs_volume_s *volume, FAR uint8_t *blkptr,
+ uint8_t state)
+{
+ FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr;
+
+ memset(blkptr, CONFIG_NXFFS_ERASEDSTATE, volume->geo.blocksize);
+ memcpy(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE);
+ blkhdr->state = state;
+} \ No newline at end of file
diff --git a/nuttx/fs/nxffs/nxffs_unlink.c b/nuttx/fs/nxffs/nxffs_unlink.c
index 6970d67a0..65838846d 100644
--- a/nuttx/fs/nxffs/nxffs_unlink.c
+++ b/nuttx/fs/nxffs/nxffs_unlink.c
@@ -127,7 +127,8 @@ int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name)
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("ERROR: Failed to read data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to read block %d into cache: %d\n",
+ volume->ioblock, ret);
goto errout_with_entry;
}
@@ -141,7 +142,8 @@ int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name)
ret = nxffs_wrcache(volume);
if (ret < 0)
{
- fdbg("ERROR: Failed to read data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to write block %d: %d\n",
+ volume->ioblock, ret);
}
errout_with_entry:
diff --git a/nuttx/fs/nxffs/nxffs_write.c b/nuttx/fs/nxffs/nxffs_write.c
index 0b1e27ccd..29f972697 100644
--- a/nuttx/fs/nxffs/nxffs_write.c
+++ b/nuttx/fs/nxffs/nxffs_write.c
@@ -705,52 +705,64 @@ int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size)
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("ERROR: Failed to read block %d: %d\n", volume->ioblock, -ret);
- return ret;
+ /* Ignore the error... just skip to the next block. This should
+ * never happen with normal FLASH, but could occur with NAND if
+ * the block has uncorrectable bit errors.
+ */
+
+ fdbg("ERROR: Failed to read block %d: %d\n",
+ volume->ioblock, -ret);
}
/* Search to the very end of this block if we have to */
- iooffset = volume->iooffset;
- nerased = 0;
-
- for (i = volume->iooffset; i < volume->geo.blocksize; i++)
+ else
{
- /* Is this byte erased? */
+ iooffset = volume->iooffset;
+ nerased = 0;
- if (volume->cache[i] == CONFIG_NXFFS_ERASEDSTATE)
+ for (i = volume->iooffset; i < volume->geo.blocksize; i++)
{
- /* Yes.. increment the count of contiguous, erased bytes */
+ /* Is this byte erased? */
- nerased++;
+ if (volume->cache[i] == CONFIG_NXFFS_ERASEDSTATE)
+ {
+ /* Yes.. increment the count of contiguous, erased bytes */
- /* Is the whole header memory erased? */
+ nerased++;
- if (nerased >= size)
- {
- /* Yes.. this this is where we will put the object */
+ /* Is the whole header memory erased? */
- off_t offset = volume->ioblock * volume->geo.blocksize + iooffset;
+ if (nerased >= size)
+ {
+ /* Yes.. this this is where we will put the object */
- /* Update the free flash offset and return success */
+ off_t offset =
+ volume->ioblock * volume->geo.blocksize + iooffset;
- volume->froffset = offset + size;
- return OK;
+ /* Update the free flash offset and return success */
+
+ volume->froffset = offset + size;
+ return OK;
+ }
}
- }
- /* This byte is not erased! (It should be unless the block is bad) */
+ /* This byte is not erased! (It should be unless the block is
+ * bad)
+ */
- else
- {
- nerased = 0;
- iooffset = i + 1;
+ else
+ {
+ nerased = 0;
+ iooffset = i + 1;
+ }
}
}
- /* If we get here, then we have looked at every byte in the block
- * and did not find any sequence of erased bytes long enough to hold
- * the object. Skip to the next, valid block.
+ /* If we get here, then either (1) this block is not read-able, or
+ * (2) we have looked at every byte in the block and did not find
+ * any sequence of erased bytes long enough to hold the object.
+ * Skip to the next, valid block.
*/
volume->ioblock++;
diff --git a/nuttx/include/nuttx/fs/nxffs.h b/nuttx/include/nuttx/fs/nxffs.h
index 79c5b1d94..60c3af1e9 100644
--- a/nuttx/include/nuttx/fs/nxffs.h
+++ b/nuttx/include/nuttx/fs/nxffs.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/fs/nxffs.h
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -94,6 +94,19 @@
#undef CONFIG_NXFSS_PREALLOCATED
#define CONFIG_NXFSS_PREALLOCATED 1
+/* If we were asked to scan the volume, then a re-formatting threshold must
+ * also be provided.
+ */
+
+#ifdef CONFIG_NXFFS_SCAN_VOLUME
+# ifndef CONFIG_NXFFS_REFORMAT_THRESH
+# define CONFIG_NXFFS_REFORMAT_THRESH 20
+# endif
+# if CONFIG_NXFFS_REFORMAT_THRESH < 0 || CONFIG_NXFFS_REFORMAT_THRESH > 100
+# error CONFIG_NXFFS_REFORMAT_THRESH is not a valid percentage
+# endif
+#endif
+
/****************************************************************************
* Public Function Prototypes
****************************************************************************/