summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-12-01 18:22:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-12-01 18:22:33 -0600
commit88795ce92903f7a1f95081add5e640ad4192d05e (patch)
tree063ca61c4e3bf6d874b64e434befd583b3856343
parent352e09485686fbe166b894a8459a5b4d9b5750b9 (diff)
downloadpx4-nuttx-88795ce92903f7a1f95081add5e640ad4192d05e.tar.gz
px4-nuttx-88795ce92903f7a1f95081add5e640ad4192d05e.tar.bz2
px4-nuttx-88795ce92903f7a1f95081add5e640ad4192d05e.zip
NXFFS: First of many changes for NAND. NAND reports read errors on ECC failures. NXFFS can't just give up in these cases and must treat read failures like bad blocks
-rw-r--r--nuttx/ChangeLog7
-rw-r--r--nuttx/fs/nxffs/nxffs_block.c4
-rw-r--r--nuttx/fs/nxffs/nxffs_blockstats.c64
-rw-r--r--nuttx/fs/nxffs/nxffs_cache.c13
-rw-r--r--nuttx/fs/nxffs/nxffs_initialize.c23
-rw-r--r--nuttx/fs/nxffs/nxffs_inode.c24
-rw-r--r--nuttx/fs/nxffs/nxffs_ioctl.c4
-rw-r--r--nuttx/fs/nxffs/nxffs_open.c60
-rw-r--r--nuttx/fs/nxffs/nxffs_pack.c39
-rw-r--r--nuttx/fs/nxffs/nxffs_read.c27
-rw-r--r--nuttx/fs/nxffs/nxffs_reformat.c15
-rw-r--r--nuttx/fs/nxffs/nxffs_unlink.c8
-rw-r--r--nuttx/fs/nxffs/nxffs_write.c40
13 files changed, 177 insertions, 151 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 6fa69a82b..9f15e1314 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6139,4 +6139,11 @@
* configs/viewtool-stm32f107/src/stm32_buttons.c and stm32_leds.c:
Add support for LEDs an buttons on the ViewTools STM32F107 board
(2013-11-30).
+ * fs/nxffs/nxffs_initialize.c: First of probably several changes for
+ NAND FLASH. NAND can report read errors because of bad ECC. Logic
+ in NXFFS must account for it and not just throw in th towel every
+ time a read fails (2013-11-30).
+ * drivers/mtd/mtd_nand* and arch/arm/src/sama5/sam_nand.c: NAND
+ accesses now work (at least with software ECC and now DMA). Still
+ lots of testing to be done (2013-11-30).
diff --git a/nuttx/fs/nxffs/nxffs_block.c b/nuttx/fs/nxffs/nxffs_block.c
index 4cc2ac263..ace656ff2 100644
--- a/nuttx/fs/nxffs/nxffs_block.c
+++ b/nuttx/fs/nxffs/nxffs_block.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_block.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -101,7 +101,7 @@ int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block)
{
/* Perhaps we are at the end of the media */
- fvdbg("Failed to read data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to read data into cache: %d\n", ret);
return ret;
}
diff --git a/nuttx/fs/nxffs/nxffs_blockstats.c b/nuttx/fs/nxffs/nxffs_blockstats.c
index 89188a353..785dcea8d 100644
--- a/nuttx/fs/nxffs/nxffs_blockstats.c
+++ b/nuttx/fs/nxffs/nxffs_blockstats.c
@@ -91,62 +91,76 @@
int nxffs_blockstats(FAR struct nxffs_volume_s *volume,
FAR struct nxffs_blkstats_s *stats)
{
- FAR uint8_t *bptr; /* Pointer to next block data */
- off_t ioblock; /* I/O block number */
- int lblock; /* Logical block index */
+ FAR struct nxffs_block_s *blkhdr; /* Pointer to FLASH block header */
+ off_t ioblock; /* I/O block number */
int ret;
/* Process each erase block */
memset(stats, 0, sizeof(struct nxffs_blkstats_s));
- for (ioblock = 0; ioblock < volume->nblocks; ioblock += volume->blkper)
+ for (ioblock = 0; ioblock < volume->nblocks; ioblock++)
{
- /* Read the full erase block */
+ /* Increment the total count of blocks examined */
- ret = MTD_BREAD(volume->mtd, ioblock, volume->blkper, volume->pack);
- if (ret < volume->blkper)
+ stats->nblocks++;
+
+ /* Read each logical block, one at a time. We could read all of the
+ * blocks in the erase block into volume->pack at once. But this would
+ * be a problem for NAND which may generate read errors due to bad ECC
+ * on individual blocks.
+ */
+
+ ret = MTD_BREAD(volume->mtd, ioblock, 1, volume->pack);
+ if (ret < 1)
{
- /* This should not happen at all on most FLASH. A bad read will
- * happen normally with a NAND device that has uncorrectable blocks.
- * So, just for NAND, we keep the count of unreadable blocks.
+ /* This should not happen at all on most kinds of FLASH. But a
+ * bad read will happen normally with a NAND device that has
+ * uncorrectable blocks. So, just for NAND, we keep the count
+ * of unreadable blocks.
*/
- fdbg("Failed to read erase block %d: %d\n",
- ioblock / volume->blkper, ret);
+ fdbg("ERROR: Failed to read block %d: %d\n", ioblock, ret);
- /* Declare all blocks in the eraseblock as bad */
+ /* Increment the count of un-readable blocks */
- stats->nblocks += volume->blkper;
- stats->nbadread += volume->blkper;
- continue;
+ stats->nbadread++;
}
-
- /* Process each logical block */
-
- for (bptr = volume->pack, lblock = 0;
- lblock < volume->blkper;
- bptr += volume->geo.blocksize, lblock++)
+ else
{
- FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)bptr;
+ /* We read the block successfully, now check for errors tagged
+ * in the NXFFS data.
+ */
+
+ blkhdr = (FAR struct nxffs_block_s*)volume->pack;
/* Collect statistics */
+ /* Check if this is a block that should be recognized by NXFFS */
- stats->nblocks++;
if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0)
{
+ /* Nope.. block must not be formatted */
+
stats->nunformat++;
}
else if (blkhdr->state == BLOCK_STATE_BAD)
{
+ /* The block is marked as bad */
+
stats->nbad++;
}
else if (blkhdr->state == BLOCK_STATE_GOOD)
{
- stats-> ngood++;
+ /* The block is marked as good */
+
+ stats-> ngood++;
}
else
{
+ /* The good/bad mark is not recognized. Let's call this
+ * corrupt (vs. unformatted).
+ */
+
stats->ncorrupt++;
}
}
diff --git a/nuttx/fs/nxffs/nxffs_cache.c b/nuttx/fs/nxffs/nxffs_cache.c
index 2f328aac7..71f31f892 100644
--- a/nuttx/fs/nxffs/nxffs_cache.c
+++ b/nuttx/fs/nxffs/nxffs_cache.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_cache.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -98,7 +98,7 @@ int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block)
nxfrd = MTD_BREAD(volume->mtd, block, 1, volume->cache);
if (nxfrd != 1)
{
- fvdbg("Read block %d failed: %d\n", block, nxfrd);
+ fdbg("ERROR: Read block %d failed: %d\n", block, nxfrd);
return -EIO;
}
@@ -106,6 +106,7 @@ int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block)
volume->cblock = block;
}
+
return OK;
}
@@ -132,7 +133,7 @@ int nxffs_wrcache(FAR struct nxffs_volume_s *volume)
nxfrd = MTD_BWRITE(volume->mtd, volume->cblock, 1, volume->cache);
if (nxfrd != 1)
{
- fdbg("Write block %d failed: %d\n", volume->cblock, nxfrd);
+ fdbg("ERROR: Write block %d failed: %d\n", volume->cblock, nxfrd);
return -EIO;
}
@@ -202,7 +203,7 @@ off_t nxffs_iotell(FAR struct nxffs_volume_s *volume)
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno indicating the
* nature of the failure.
- *
+ *
****************************************************************************/
int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve)
@@ -231,7 +232,7 @@ int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve)
/* Set up the seek to the data just after the header in the
* next block.
*/
-
+
volume->ioblock = nextblock;
volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
}
@@ -245,7 +246,7 @@ int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve)
ret = nxffs_verifyblock(volume, volume->ioblock);
if (ret < 0 && ret != -ENOENT)
{
- fvdbg("Failed to read valid data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to read valid data into cache: %d\n", ret);
return ret;
}
}
diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c
index 8cf2edcdb..390b03bcd 100644
--- a/nuttx/fs/nxffs/nxffs_initialize.c
+++ b/nuttx/fs/nxffs/nxffs_initialize.c
@@ -195,7 +195,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&volume->geo));
if (ret < 0)
{
- fdbg("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", -ret);
+ fdbg("ERROR: MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", -ret);
goto errout_with_volume;
}
@@ -204,7 +204,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
volume->cache = (FAR uint8_t *)kmalloc(volume->geo.blocksize);
if (!volume->cache)
{
- fdbg("Failed to allocate an erase block buffer\n");
+ fdbg("ERROR: Failed to allocate an erase block buffer\n");
ret = -ENOMEM;
goto errout_with_volume;
}
@@ -217,7 +217,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
volume->pack = (FAR uint8_t *)kmalloc(volume->geo.erasesize);
if (!volume->pack)
{
- fdbg("Failed to allocate an I/O block buffer\n");
+ fdbg("ERROR: Failed to allocate an I/O block buffer\n");
ret = -ENOMEM;
goto errout_with_cache;
}
@@ -235,7 +235,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
ret = nxffs_blockstats(volume, &stats);
if (ret < 0)
{
- fdbg("Failed to collect block statistics: %d\n", -ret);
+ fdbg("ERROR: Failed to collect block statistics: %d\n", -ret);
goto errout_with_buffer;
}
@@ -251,7 +251,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
ret = nxffs_reformat(volume);
if (ret < 0)
{
- fdbg("Failed to reformat the volume: %d\n", -ret);
+ fdbg("ERROR: Failed to reformat the volume: %d\n", -ret);
goto errout_with_buffer;
}
@@ -261,7 +261,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
ret = nxffs_blockstats(volume, &stats);
if (ret < 0)
{
- fdbg("Failed to collect block statistics: %d\n", -ret);
+ fdbg("ERROR: Failed to collect block statistics: %d\n", -ret);
goto errout_with_buffer;
}
#endif
@@ -274,7 +274,8 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
{
return OK;
}
- fdbg("Failed to calculate file system limits: %d\n", -ret);
+
+ fdbg("ERROR: Failed to calculate file system limits: %d\n", -ret);
errout_with_buffer:
kfree(volume->pack);
@@ -327,7 +328,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
ret = nxffs_validblock(volume, &block);
if (ret < 0)
{
- fdbg("Failed to find a valid block: %d\n", -ret);
+ fdbg("ERROR: Failed to find a valid block: %d\n", -ret);
return ret;
}
@@ -345,7 +346,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
if (ret != -ENOENT)
{
- fdbg("nxffs_nextentry failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_nextentry failed: %d\n", -ret);
return ret;
}
@@ -379,7 +380,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
/* Discard the entry and guess the next offset. */
offset = nxffs_inodeend(volume, &entry);
- nxffs_freeentry(&entry);
+ nxffs_freeentry(&entry);
}
fvdbg("Last inode before offset %d\n", offset);
}
@@ -416,7 +417,7 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume)
// No? Then it is some other failure that we do not know how to handle
- fdbg("nxffs_getc failed: %d\n", -ch);
+ fdbg("ERROR: nxffs_getc failed: %d\n", -ch);
return ch;
}
diff --git a/nuttx/fs/nxffs/nxffs_inode.c b/nuttx/fs/nxffs/nxffs_inode.c
index bf21eafcd..287dcae33 100644
--- a/nuttx/fs/nxffs/nxffs_inode.c
+++ b/nuttx/fs/nxffs/nxffs_inode.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_inode.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -85,7 +85,7 @@
* Zero on success. Otherwise, a negated errno value is returned
* indicating the nature of the failure.
*
- * On return, the
+ * On return, the
*
****************************************************************************/
@@ -117,7 +117,7 @@ static int nxffs_rdentry(FAR struct nxffs_volume_s *volume, off_t offset,
ret = -ENOENT;
goto errout_no_offset;
}
-
+
/* Copy the packed header into the user-friendly buffer */
entry->hoffset = offset;
@@ -139,11 +139,11 @@ static int nxffs_rdentry(FAR struct nxffs_volume_s *volume, off_t offset,
entry->name = (FAR char *)kmalloc(namlen + 1);
if (!entry->name)
{
- fdbg("Failed to allocate name, namlen: %d\n", namlen);
+ fdbg("ERROR: Failed to allocate name, namlen: %d\n", namlen);
ret = -ENOMEM;
goto errout_no_offset;
}
-
+
/* Seek to the expected location of the name in FLASH */
nxffs_ioseek(volume, entry->noffset);
@@ -151,11 +151,11 @@ static int nxffs_rdentry(FAR struct nxffs_volume_s *volume, off_t offset,
/* Make sure that the block is in memory (the name may not be in the
* same block as the inode header.
*/
-
+
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("nxffsx_rdcache failed: %d\n", -ret);
+ fdbg("ERROR: nxffsx_rdcache failed: %d\n", -ret);
goto errout_with_name;
}
@@ -255,7 +255,7 @@ void nxffs_freeentry(FAR struct nxffs_entry_s *entry)
* offset - The FLASH memory offset to begin searching.
* entry - A pointer to memory provided by the caller in which to return
* the inode description.
- *
+ *
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno is returned
* that indicates the nature of the failure.
@@ -275,7 +275,7 @@ int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
nxffs_ioseek(volume, offset);
/* Then begin searching */
-
+
nerased = 0;
nmagic = 0;
for (;;)
@@ -285,7 +285,7 @@ int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
ch = nxffs_getc(volume, SIZEOF_NXFFS_INODE_HDR - nmagic);
if (ch < 0)
{
- fvdbg("nxffs_getc failed: %d\n", -ch);
+ fdbg("ERROR: nxffs_getc failed: %d\n", -ch);
return ch;
}
@@ -340,7 +340,7 @@ int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
* indicate the beginning of an NXFFS inode.
*/
- else
+ else
{
/* The the FLASH offset where we found the matching magic number */
@@ -498,5 +498,3 @@ off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
DEBUGASSERT(entry->noffset);
return entry->noffset + strlen(entry->name);
}
-
-
diff --git a/nuttx/fs/nxffs/nxffs_ioctl.c b/nuttx/fs/nxffs/nxffs_ioctl.c
index a6d85bf4e..853c46fab 100644
--- a/nuttx/fs/nxffs/nxffs_ioctl.c
+++ b/nuttx/fs/nxffs/nxffs_ioctl.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_ioctl.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -104,7 +104,7 @@ int nxffs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
if (ret != OK)
{
ret = -errno;
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
goto errout;
}
diff --git a/nuttx/fs/nxffs/nxffs_open.c b/nuttx/fs/nxffs/nxffs_open.c
index 4e5fe3cae..31b5dad32 100644
--- a/nuttx/fs/nxffs/nxffs_open.c
+++ b/nuttx/fs/nxffs/nxffs_open.c
@@ -189,6 +189,7 @@ static inline int nxffs_nampos(FAR struct nxffs_volume_s *volume,
wrfile->ofile.entry.noffset = nxffs_iotell(volume);
}
+
return ret;
}
@@ -242,7 +243,7 @@ static inline int nxffs_hdrerased(FAR struct nxffs_volume_s *volume,
int ret;
/* Find a valid location to save the inode header */
-
+
ret = nxffs_wrverify(volume, SIZEOF_NXFFS_INODE_HDR);
if (ret == OK)
{
@@ -250,6 +251,7 @@ static inline int nxffs_hdrerased(FAR struct nxffs_volume_s *volume,
wrfile->ofile.entry.hoffset = nxffs_iotell(volume);
}
+
return ret;
}
@@ -304,7 +306,7 @@ static inline int nxffs_namerased(FAR struct nxffs_volume_s *volume,
int ret;
/* Find a valid location to save the inode name */
-
+
ret = nxffs_wrverify(volume, namlen);
if (ret == OK)
{
@@ -312,6 +314,7 @@ static inline int nxffs_namerased(FAR struct nxffs_volume_s *volume,
wrfile->ofile.entry.noffset = nxffs_iotell(volume);
}
+
return ret;
}
@@ -332,7 +335,7 @@ static inline int nxffs_namerased(FAR struct nxffs_volume_s *volume,
*
* Input Parameters:
* volume - Describes the NXFFS volume
- * entry - Describes the entry to be written.
+ * entry - Describes the entry to be written.
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
@@ -354,7 +357,7 @@ static inline int nxffs_wrname(FAR struct nxffs_volume_s *volume,
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("Failed to read inode name block %d: %d\n",
+ fdbg("ERROR: Failed to read inode name block %d: %d\n",
volume->ioblock, -ret);
return ret;
}
@@ -365,7 +368,7 @@ static inline int nxffs_wrname(FAR struct nxffs_volume_s *volume,
ret = nxffs_wrcache(volume);
if (ret < 0)
{
- fdbg("Failed to write inode header block %d: %d\n",
+ fdbg("ERROR: Failed to write inode header block %d: %d\n",
volume->ioblock, -ret);
}
@@ -400,7 +403,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
ret = sem_wait(&volume->wrsem);
if (ret != OK)
{
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
ret = -errno;
goto errout;
}
@@ -413,7 +416,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
ret = sem_wait(&volume->exclsem);
if (ret != OK)
{
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
ret = -errno;
goto errout_with_wrsem;
}
@@ -462,7 +465,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
* until the new file is successfully written.
*/
- truncate = true;
+ truncate = true;
}
/* The file exists and we were not asked to truncate (and recreate) it.
@@ -567,7 +570,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
if (ret != -ENOSPC || packed)
{
- fdbg("Failed to find inode header memory: %d\n", -ret);
+ fdbg("ERROR: Failed to find inode header memory: %d\n", -ret);
goto errout_with_name;
}
@@ -578,19 +581,19 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
ret = nxffs_pack(volume);
if (ret < 0)
{
- fdbg("Failed to pack the volume: %d\n", -ret);
+ fdbg("ERROR: Failed to pack the volume: %d\n", -ret);
goto errout_with_name;
}
-
+
/* After packing the volume, froffset will be updated to point to the
* new free flash region. Try again.
*/
-
+
packed = true;
}
/* Loop until the inode name is configured or until a failure occurs.
- * Note that nothing is written to FLASH.
+ * Note that nothing is written to FLASH.
*/
for (;;)
@@ -614,7 +617,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
ret = nxffs_wrname(volume, &wrfile->ofile.entry, namlen);
if (ret < 0)
{
- fdbg("Failed to write the inode name: %d\n", -ret);
+ fdbg("ERROR: Failed to write the inode name: %d\n", -ret);
goto errout_with_name;
}
@@ -633,7 +636,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
if (ret != -ENOSPC || packed)
{
- fdbg("Failed to find inode name memory: %d\n", -ret);
+ fdbg("ERROR: Failed to find inode name memory: %d\n", -ret);
goto errout_with_name;
}
@@ -644,14 +647,14 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
ret = nxffs_pack(volume);
if (ret < 0)
{
- fdbg("Failed to pack the volume: %d\n", -ret);
+ fdbg("ERROR: Failed to pack the volume: %d\n", -ret);
goto errout_with_name;
}
-
+
/* After packing the volume, froffset will be updated to point to the
* new free flash region. Try again.
*/
-
+
packed = true;
}
@@ -707,7 +710,7 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
ret = sem_wait(&volume->exclsem);
if (ret != OK)
{
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
ret = -errno;
goto errout;
}
@@ -742,11 +745,11 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
else
{
/* Not already open.. create a new open structure */
-
+
ofile = (FAR struct nxffs_ofile_s *)kzalloc(sizeof(struct nxffs_ofile_s));
if (!ofile)
{
- fdbg("ofile allocation failed\n");
+ fdbg("ERROR: ofile allocation failed\n");
ret = -ENOMEM;
goto errout_with_exclsem;
}
@@ -840,7 +843,7 @@ static inline void nxffs_freeofile(FAR struct nxffs_volume_s *volume,
/* Release the open file entry */
nxffs_freeentry(&ofile->entry);
-
+
/* Then free the open file container (unless this the pre-alloated
* write-only open file container)
*/
@@ -883,7 +886,7 @@ static inline int nxffs_wrclose(FAR struct nxffs_volume_s *volume,
ret = nxffs_wrblkhdr(volume, wrfile);
if (ret < 0)
{
- fdbg("Failed to write the final block of the file: %d\n", -ret);
+ fdbg("ERROR: Failed to write the final block of the file: %d\n", -ret);
goto errout;
}
}
@@ -902,7 +905,7 @@ static inline int nxffs_wrclose(FAR struct nxffs_volume_s *volume,
ret = nxffs_rminode(volume, wrfile->ofile.entry.name);
if (ret < 0)
{
- fdbg("nxffs_rminode failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_rminode failed: %d\n", -ret);
goto errout;
}
}
@@ -1055,6 +1058,7 @@ int nxffs_open(FAR struct file *filep, FAR const char *relpath,
{
filep->f_priv = ofile;
}
+
return ret;
}
@@ -1153,7 +1157,7 @@ int nxffs_close(FAR struct file *filep)
if (ret != OK)
{
ret = -errno;
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
goto errout;
}
@@ -1234,7 +1238,7 @@ int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("Failed to read inode header block %d: %d\n",
+ fdbg("ERROR: Failed to read inode header block %d: %d\n",
volume->ioblock, -ret);
goto errout;
}
@@ -1273,7 +1277,7 @@ int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
ret = nxffs_wrcache(volume);
if (ret < 0)
{
- fdbg("Failed to write inode header block %d: %d\n",
+ fdbg("ERROR: Failed to write inode header block %d: %d\n",
volume->ioblock, -ret);
}
@@ -1317,6 +1321,6 @@ int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
ofile->entry.noffset = entry->noffset;
ofile->entry.doffset = entry->doffset;
}
+
return OK;
}
-
diff --git a/nuttx/fs/nxffs/nxffs_pack.c b/nuttx/fs/nxffs/nxffs_pack.c
index 3d53c0584..afbb55307 100644
--- a/nuttx/fs/nxffs/nxffs_pack.c
+++ b/nuttx/fs/nxffs/nxffs_pack.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_pack.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -335,7 +335,7 @@ static inline int nxffs_startpos(FAR struct nxffs_volume_s *volume,
ret = nxffs_nextblock(volume, offset, &blkentry);
if (ret < 0)
{
- fdbg("Failed to find next data block: %d\n", -ret);
+ fdbg("ERROR: Failed to find next data block: %d\n", -ret);
return ret;
}
@@ -425,8 +425,9 @@ static int nxffs_srcsetup(FAR struct nxffs_volume_s *volume,
int ret = nxffs_rdblkhdr(volume, offset, &pack->src.blklen);
if (ret < 0)
{
- fdbg("Failed to verify the data block header: %d\n", -ret);
+ fdbg("ERROR: Failed to verify the data block header: %d\n", -ret);
}
+
return ret;
}
@@ -709,7 +710,7 @@ static int nxffs_wrinodehdr(FAR struct nxffs_volume_s *volume,
ret = nxffs_updateinode(volume, &pack->dest.entry);
if (ret < 0)
{
- fdbg("Failed to update inode info: %s\n", -ret);
+ fdbg("ERROR: Failed to update inode info: %s\n", -ret);
}
}
@@ -852,7 +853,7 @@ static int nxffs_endsrcblock(FAR struct nxffs_volume_s *volume,
ret = nxffs_nextblock(volume, offset, &blkentry);
if (ret < 0)
{
- fdbg("Failed to find next data block: %d\n", -ret);
+ fdbg("ERROR: Failed to find next data block: %d\n", -ret);
return ret;
}
@@ -896,7 +897,7 @@ static inline int nxffs_packblock(FAR struct nxffs_volume_s *volume,
ret = nxffs_srcsetup(volume, pack, pack->src.entry.doffset);
if (ret < 0)
{
- fdbg("Failed to configure the src stream: %d\n", -ret);
+ fdbg("ERROR: Failed to configure the src stream: %d\n", -ret);
return ret;
}
}
@@ -922,7 +923,7 @@ static inline int nxffs_packblock(FAR struct nxffs_volume_s *volume,
}
else
{
- fdbg("Failed to configure the dest stream: %d\n", -ret);
+ fdbg("ERROR: Failed to configure the dest stream: %d\n", -ret);
return ret;
}
}
@@ -997,7 +998,7 @@ static inline int nxffs_packblock(FAR struct nxffs_volume_s *volume,
return OK;
}
-
+
/* Configure the destination stream */
ret = nxffs_destsetup(volume, pack);
@@ -1014,7 +1015,7 @@ static inline int nxffs_packblock(FAR struct nxffs_volume_s *volume,
}
else
{
- fdbg("Failed to configure the dest stream: %d\n", -ret);
+ fdbg("ERROR: Failed to configure the dest stream: %d\n", -ret);
return ret;
}
}
@@ -1149,7 +1150,7 @@ static inline int nxffs_packwriter(FAR struct nxffs_volume_s *volume,
ret = nxffs_srcsetup(volume, pack, pack->src.entry.doffset);
if (ret < 0)
{
- fdbg("Failed to configure the src stream: %d\n", -ret);
+ fdbg("ERROR: Failed to configure the src stream: %d\n", -ret);
return ret;
}
}
@@ -1175,7 +1176,7 @@ static inline int nxffs_packwriter(FAR struct nxffs_volume_s *volume,
}
else
{
- fdbg("Failed to configure the dest stream: %d\n", -ret);
+ fdbg("ERROR: Failed to configure the dest stream: %d\n", -ret);
return ret;
}
}
@@ -1287,7 +1288,7 @@ int nxffs_pack(FAR struct nxffs_volume_s *volume)
{
/* Offset zero is only returned if no valid blocks were found on the
* FLASH media or if there are no valid inode entries on the FLASH after
- * the first valid block. There are two possibilities: (1) there
+ * the first valid block. There are two possibilities: (1) there
* really is nothing on the FLASH, or (2) there is a file being written
* to the FLASH now.
*/
@@ -1383,14 +1384,14 @@ int nxffs_pack(FAR struct nxffs_volume_s *volume)
}
else
{
- fvdbg("Failed to find a packing position: %d\n", -ret);
+ fdbg("ERROR: Failed to find a packing position: %d\n", -ret);
return ret;
}
}
/* Otherwise, begin pack at this src/dest block combination. Initialize
* ioblock and iooffset with the position of the first inode header. In
- * this case, the FLASH offset to the first inode header is return in
+ * this case, the FLASH offset to the first inode header is return in
* iooffset.
*/
@@ -1417,7 +1418,7 @@ start_pack:
ret = MTD_BREAD(volume->mtd, pack.block0, volume->blkper, volume->pack);
if (ret < 0)
{
- fdbg("Failed to read erase block %d: %d\n", eblock, -ret);
+ fdbg("ERROR: Failed to read erase block %d: %d\n", eblock, -ret);
goto errout_with_pack;
}
@@ -1483,7 +1484,7 @@ start_pack:
{
/* Otherwise, something really bad happened */
- fdbg("Failed to pack into block %d: %d\n",
+ fdbg("ERROR: Failed to pack into block %d: %d\n",
block, ret);
goto errout_with_pack;
}
@@ -1515,7 +1516,7 @@ start_pack:
{
/* Otherwise, something really bad happened */
- fdbg("Failed to pack into block %d: %d\n",
+ fdbg("ERROR: Failed to pack into block %d: %d\n",
block, ret);
goto errout_with_pack;
}
@@ -1549,7 +1550,7 @@ start_pack:
ret = MTD_ERASE(volume->mtd, eblock, 1);
if (ret < 0)
{
- fdbg("Failed to erase block %d [%d]: %d\n",
+ fdbg("ERROR: Failed to erase block %d [%d]: %d\n",
eblock, pack.block0, -ret);
goto errout_with_pack;
}
@@ -1559,7 +1560,7 @@ start_pack:
ret = MTD_BWRITE(volume->mtd, pack.block0, volume->blkper, volume->pack);
if (ret < 0)
{
- fdbg("Failed to write erase block %d [%]: %d\n",
+ fdbg("ERROR: Failed to write erase block %d [%]: %d\n",
eblock, pack.block0, -ret);
goto errout_with_pack;
}
diff --git a/nuttx/fs/nxffs/nxffs_read.c b/nuttx/fs/nxffs/nxffs_read.c
index 315b41e88..406d27dd3 100644
--- a/nuttx/fs/nxffs/nxffs_read.c
+++ b/nuttx/fs/nxffs/nxffs_read.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_read.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -118,10 +118,10 @@ static ssize_t nxffs_rdseek(FAR struct nxffs_volume_s *volume,
ret = nxffs_nextblock(volume, offset, blkentry);
if (ret < 0)
{
- fdbg("nxffs_nextblock failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_nextblock failed: %d\n", -ret);
return ret;
}
-
+
/* Get the range of data offsets for this data block */
datstart = datend;
@@ -185,7 +185,7 @@ ssize_t nxffs_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
if (ret != OK)
{
ret = -errno;
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
goto errout;
}
@@ -217,7 +217,7 @@ ssize_t nxffs_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
ret = nxffs_rdseek(volume, &ofile->entry, filep->f_pos, &blkentry);
if (ret < 0)
{
- fdbg("nxffs_rdseek failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_rdseek failed: %d\n", -ret);
ret = -EACCES;
goto errout_with_semaphore;
}
@@ -263,7 +263,7 @@ errout:
* Input Parameters:
* volume - Describes the NXFFS volume.
* datlen - A memory location to return the data block length.
- *
+ *
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno is returned
* that indicates the nature of the failure.
@@ -290,7 +290,7 @@ int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
}
/* Then begin searching */
-
+
nerased = 0;
nmagic = 0;
@@ -301,7 +301,7 @@ int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
ch = nxffs_getc(volume, SIZEOF_NXFFS_DATA_HDR - nmagic);
if (ch < 0)
{
- fvdbg("nxffs_getc failed: %d\n", -ch);
+ fdbg("ERROR: nxffs_getc failed: %d\n", -ch);
return ch;
}
@@ -357,7 +357,7 @@ int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
* indicate the beginning of an NXFFS data block.
*/
- else
+ else
{
/* The offset to the header must be 4 bytes before the current
* FLASH seek location.
@@ -424,7 +424,7 @@ int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fvdbg("Failed to read data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to read data into cache: %d\n", ret);
return ret;
}
@@ -448,7 +448,7 @@ int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
fdbg("Data length=%d is unreasonable at offset=%d\n", dlen, doffset);
return -EIO;
}
-
+
/* Extract the expected CRC and calculate the CRC of the data block */
ecrc = nxffs_rdle32(blkhdr.crc);
@@ -459,7 +459,7 @@ int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
if (crc != ecrc)
{
- fdbg("CRC failure\n");
+ fdbg("ERROR: CRC failure\n");
return -EIO;
}
@@ -468,6 +468,3 @@ int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
*datlen = dlen;
return OK;
}
-
-
-
diff --git a/nuttx/fs/nxffs/nxffs_reformat.c b/nuttx/fs/nxffs/nxffs_reformat.c
index 3453b387d..294414d40 100644
--- a/nuttx/fs/nxffs/nxffs_reformat.c
+++ b/nuttx/fs/nxffs/nxffs_reformat.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_reformat.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -111,7 +111,7 @@ static int nxffs_format(FAR struct nxffs_volume_s *volume)
ret = MTD_ERASE(volume->mtd, eblock, 1);
if (ret < 0)
{
- fdbg("Erase block %d failed: %d\n", eblock, ret);
+ fdbg("ERROR: Erase block %d failed: %d\n", eblock, ret);
return ret;
}
@@ -121,7 +121,7 @@ static int nxffs_format(FAR struct nxffs_volume_s *volume)
nxfrd = MTD_BWRITE(volume->mtd, lblock, volume->blkper, volume->pack);
if (nxfrd != volume->blkper)
{
- fdbg("Write erase block %d failed: %d\n", lblock, nxfrd);
+ fdbg("ERROR: Write erase block %d failed: %d\n", lblock, nxfrd);
return -EIO;
}
}
@@ -165,7 +165,7 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume)
nxfrd = MTD_BREAD(volume->mtd, lblock, volume->blkper, volume->pack);
if (nxfrd != volume->blkper)
{
- fdbg("Read erase block %d failed: %d\n", lblock, nxfrd);
+ fdbg("ERROR: Read erase block %d failed: %d\n", lblock, nxfrd);
return -EIO;
}
@@ -216,7 +216,7 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume)
nxfrd = MTD_BWRITE(volume->mtd, lblock, volume->blkper, volume->pack);
if (nxfrd != volume->blkper)
{
- fdbg("Write erase block %d failed: %d\n", lblock, nxfrd);
+ fdbg("ERROR: Write erase block %d failed: %d\n", lblock, nxfrd);
return -EIO;
}
}
@@ -255,7 +255,7 @@ int nxffs_reformat(FAR struct nxffs_volume_s *volume)
ret = nxffs_format(volume);
if (ret < 0)
{
- fdbg("Failed to reformat the volume: %d\n", -ret);
+ fdbg("ERROR: Failed to reformat the volume: %d\n", -ret);
return ret;
}
@@ -264,7 +264,8 @@ int nxffs_reformat(FAR struct nxffs_volume_s *volume)
ret = nxffs_badblocks(volume);
if (ret < 0)
{
- fdbg("Bad block check failed: %d\n", -ret);
+ fdbg("ERROR: Bad block check failed: %d\n", -ret);
}
+
return ret;
}
diff --git a/nuttx/fs/nxffs/nxffs_unlink.c b/nuttx/fs/nxffs/nxffs_unlink.c
index 36bc50796..6970d67a0 100644
--- a/nuttx/fs/nxffs/nxffs_unlink.c
+++ b/nuttx/fs/nxffs/nxffs_unlink.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_unlink.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -127,7 +127,7 @@ int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name)
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("Failed to read data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to read data into cache: %d\n", ret);
goto errout_with_entry;
}
@@ -141,7 +141,7 @@ int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name)
ret = nxffs_wrcache(volume);
if (ret < 0)
{
- fdbg("Failed to read data into cache: %d\n", ret);
+ fdbg("ERROR: Failed to read data into cache: %d\n", ret);
}
errout_with_entry:
@@ -180,7 +180,7 @@ int nxffs_unlink(FAR struct inode *mountpt, FAR const char *relpath)
/* Then remove the NXFFS inode */
ret = nxffs_rminode(volume, relpath);
-
+
sem_post(&volume->exclsem);
errout:
return ret;
diff --git a/nuttx/fs/nxffs/nxffs_write.c b/nuttx/fs/nxffs/nxffs_write.c
index 3a95e82a7..0b1e27ccd 100644
--- a/nuttx/fs/nxffs/nxffs_write.c
+++ b/nuttx/fs/nxffs/nxffs_write.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/nxffs/nxffs_write.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References: Linux/Documentation/filesystems/romfs.txt
@@ -60,7 +60,7 @@
/****************************************************************************
* Public Types
****************************************************************************/
-
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -128,6 +128,7 @@ static inline int nxffs_hdrpos(FAR struct nxffs_volume_s *volume,
wrfile->doffset = nxffs_iotell(volume);
}
+
return ret;
}
@@ -181,7 +182,7 @@ static inline int nxffs_hdrerased(FAR struct nxffs_volume_s *volume,
int ret;
/* Find a valid location to save the inode header */
-
+
ret = nxffs_wrverify(volume, SIZEOF_NXFFS_DATA_HDR + size);
if (ret == OK)
{
@@ -189,6 +190,7 @@ static inline int nxffs_hdrerased(FAR struct nxffs_volume_s *volume,
wrfile->doffset = nxffs_iotell(volume);
}
+
return ret;
}
@@ -253,7 +255,7 @@ static inline int nxffs_wralloc(FAR struct nxffs_volume_s *volume,
if (ret != -ENOSPC || packed)
{
- fdbg("Failed to find inode header memory: %d\n", -ret);
+ fdbg("ERROR: Failed to find inode header memory: %d\n", -ret);
return -ENOSPC;
}
@@ -264,7 +266,7 @@ static inline int nxffs_wralloc(FAR struct nxffs_volume_s *volume,
ret = nxffs_pack(volume);
if (ret < 0)
{
- fdbg("Failed to pack the volume: %d\n", -ret);
+ fdbg("ERROR: Failed to pack the volume: %d\n", -ret);
return ret;
}
@@ -323,10 +325,11 @@ static inline int nxffs_reverify(FAR struct nxffs_volume_s *volume,
if (crc != wrfile->crc)
{
- fdbg("CRC failure\n");
+ fdbg("ERROR: CRC failure\n");
return -EIO;
}
}
+
return OK;
}
@@ -396,13 +399,13 @@ static inline ssize_t nxffs_wrappend(FAR struct nxffs_volume_s *volume,
/* And write the partial write block to FLASH -- unless the data
* block is full. In that case, the block will be written below.
*/
-
+
if (nbytesleft > 0)
{
ret = nxffs_wrcache(volume);
if (ret < 0)
{
- fdbg("nxffs_wrcache failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_wrcache failed: %d\n", -ret);
return ret;
}
}
@@ -417,7 +420,7 @@ static inline ssize_t nxffs_wrappend(FAR struct nxffs_volume_s *volume,
ret = nxffs_wrblkhdr(volume, wrfile);
if (ret < 0)
{
- fdbg("nxffs_wrblkdhr failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_wrblkdhr failed: %d\n", -ret);
return ret;
}
}
@@ -472,7 +475,7 @@ ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer, size_t bufle
if (ret != OK)
{
ret = -errno;
- fdbg("sem_wait failed: %d\n", ret);
+ fdbg("ERROR: sem_wait failed: %d\n", ret);
goto errout;
}
@@ -503,7 +506,7 @@ ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer, size_t bufle
ret = nxffs_wralloc(volume, wrfile, remaining);
if (ret < 0)
{
- fdbg("Failed to allocate a data block: %d\n", -ret);
+ fdbg("ERROR: Failed to allocate a data block: %d\n", -ret);
goto errout_with_semaphore;
}
}
@@ -517,7 +520,7 @@ ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer, size_t bufle
ret = nxffs_reverify(volume, wrfile);
if (ret < 0)
{
- fdbg("Failed to verify FLASH data block: %d\n", -ret);
+ fdbg("ERROR: Failed to verify FLASH data block: %d\n", -ret);
goto errout_with_semaphore;
}
@@ -528,12 +531,12 @@ ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer, size_t bufle
nwritten = nxffs_wrappend(volume, wrfile, &buffer[total], remaining);
if (nwritten < 0)
{
- fdbg("Failed to append to FLASH to a data block: %d\n", -ret);
+ fdbg("ERROR: Failed to append to FLASH to a data block: %d\n", -ret);
goto errout_with_semaphore;
}
/* Decrement the number of bytes remaining to be written */
-
+
total += nwritten;
}
@@ -615,7 +618,7 @@ int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size)
/* We will need to skip to the next block. But first, check if we are
* already at the final block.
*/
-
+
if (volume->ioblock + 1 >= volume->nblocks)
{
/* Return -ENOSPC to indicate that the volume is full */
@@ -698,11 +701,11 @@ int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size)
while (volume->ioblock < volume->nblocks)
{
/* Make sure that the block is in memory */
-
+
ret = nxffs_rdcache(volume, volume->ioblock);
if (ret < 0)
{
- fdbg("Failed to read block %d: %d\n", volume->ioblock, -ret);
+ fdbg("ERROR: Failed to read block %d: %d\n", volume->ioblock, -ret);
return ret;
}
@@ -812,7 +815,7 @@ int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
ret = nxffs_wrcache(volume);
if (ret < 0)
{
- fdbg("nxffs_wrcache failed: %d\n", -ret);
+ fdbg("ERROR: nxffs_wrcache failed: %d\n", -ret);
goto errout;
}
@@ -850,4 +853,3 @@ errout:
wrfile->datlen = 0;
return ret;
}
-