summaryrefslogtreecommitdiff
path: root/nuttx/fs/nxffs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-03 00:02:10 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-03 00:02:10 +0000
commit337053d3d948beb9523352bc7fc682b201becab2 (patch)
tree71f96f677e8a2ee3fffcc2e29fb25efc3c644f79 /nuttx/fs/nxffs
parent7270511ae42b378850af972739b448de62085b5d (diff)
downloadpx4-nuttx-337053d3d948beb9523352bc7fc682b201becab2.tar.gz
px4-nuttx-337053d3d948beb9523352bc7fc682b201becab2.tar.bz2
px4-nuttx-337053d3d948beb9523352bc7fc682b201becab2.zip
Starting NXFFS packing logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3553 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/fs/nxffs')
-rw-r--r--nuttx/fs/nxffs/nxffs.h35
-rw-r--r--nuttx/fs/nxffs/nxffs_initialize.c23
-rw-r--r--nuttx/fs/nxffs/nxffs_pack.c178
-rw-r--r--nuttx/fs/nxffs/nxffs_read.c250
4 files changed, 353 insertions, 133 deletions
diff --git a/nuttx/fs/nxffs/nxffs.h b/nuttx/fs/nxffs/nxffs.h
index 48311f3ec..51c7d7a3d 100644
--- a/nuttx/fs/nxffs/nxffs.h
+++ b/nuttx/fs/nxffs/nxffs.h
@@ -239,6 +239,15 @@ struct nxffs_entry_s
uint32_t datlen; /* Length of inode data */
};
+/* This structure describes int in-memory representation of the data block */
+
+struct nxffs_blkentry_s
+{
+ off_t hoffset; /* Offset to the block data header */
+ uint16_t datlen; /* Length of data following the header */
+ uint16_t foffset; /* Offset to start of data */
+};
+
/* This structure describes the state of one open file. This structure
* is protected by the volume semaphore.
*/
@@ -285,6 +294,7 @@ struct nxffs_volume_s
off_t cblock; /* Starting block number in cache */
FAR struct nxffs_ofile_s *ofiles; /* A singly-linked list of open files */
FAR uint8_t *cache; /* Allocated erase block */
+ FAR uint8_t *pack; /* Extra I/O block buffer to support packing */
};
/* This structure describes the state of the blocks on the NXFFS volume */
@@ -769,7 +779,6 @@ extern FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volu
* volume->froffset - Updated offset to the first free FLASH block after
* the reserved memory.
*
- *
* Defined in nxffs_write.c
*
****************************************************************************/
@@ -777,6 +786,28 @@ extern FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volu
extern int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
/****************************************************************************
+ * Name: nxffs_nextblock
+ *
+ * Description:
+ * Search for the next valid data block starting at the provided
+ * FLASH offset.
+ *
+ * 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.
+ *
+ * Defined in nxffs_read.c
+ *
+ ****************************************************************************/
+
+extern int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
+ FAR struct nxffs_blkentry_s *blkentry);
+
+/****************************************************************************
* Name: nxffs_wrverify
*
* Description:
@@ -814,6 +845,8 @@ extern int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
* position.
* volume->froffset - Updated offset to the first free FLASH block.
*
+ * Defined in nxffs_write.c
+ *
****************************************************************************/
extern int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size);
diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c
index adf1f76f7..2d1f61e4c 100644
--- a/nuttx/fs/nxffs/nxffs_initialize.c
+++ b/nuttx/fs/nxffs/nxffs_initialize.c
@@ -207,6 +207,19 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
goto errout_with_volume;
}
+ /* Pre-allocate one additional I/O block buffer to support filesystem
+ * packing. This buffer is not needed often, but is best to have pre-
+ * allocated and in-place.
+ */
+
+ volume->pack = (FAR uint8_t *)kmalloc(volume->geo.blocksize);
+ if (!volume->pack)
+ {
+ fdbg("Failed to allocate an I/O block buffer\n");
+ ret = -ENOMEM;
+ goto errout_with_cache;
+ }
+
/* Get the number of R/W blocks per erase block and the total number o
* R/W blocks
*/
@@ -221,7 +234,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
if (ret < 0)
{
fdbg("Failed to collect block statistics: %d\n", -ret);
- goto errout_with_iobuffer;
+ goto errout_with_buffer;
}
/* If the proportion of good blocks is low or the proportion of unformatted
@@ -237,7 +250,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
if (ret < 0)
{
fdbg("Failed to reformat the volume: %d\n", -ret);
- goto errout_with_iobuffer;
+ goto errout_with_buffer;
}
/* Get statistics on the re-formatted volume */
@@ -247,7 +260,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
if (ret < 0)
{
fdbg("Failed to collect block statistics: %d\n", -ret);
- goto errout_with_iobuffer;
+ goto errout_with_buffer;
}
#endif
}
@@ -261,7 +274,9 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
}
fdbg("Failed to calculate file system limits: %d\n", -ret);
-errout_with_iobuffer:
+errout_with_buffer:
+ kfree(volume->pack);
+errout_with_cache:
kfree(volume->cache);
errout_with_volume:
kfree(volume);
diff --git a/nuttx/fs/nxffs/nxffs_pack.c b/nuttx/fs/nxffs/nxffs_pack.c
index 476c5972b..b44a15736 100644
--- a/nuttx/fs/nxffs/nxffs_pack.c
+++ b/nuttx/fs/nxffs/nxffs_pack.c
@@ -41,7 +41,10 @@
#include <nuttx/config.h>
+#include <string.h>
#include <errno.h>
+#include <assert.h>
+#include <debug.h>
#include "nxffs.h"
@@ -52,6 +55,24 @@
/****************************************************************************
* Public Types
****************************************************************************/
+/* This structure supports access to one inode data stream */
+
+struct nxffs_packstream_s
+{
+ struct nxffs_entry_s entry; /* Described the inode header */
+ off_t fpos; /* Current file position */
+ off_t blkoffset; /* Offset to the current data block */
+ uint16_t blklen; /* Size of this block */
+ uint16_t blkpos; /* Position in block corresponding to fpos */
+};
+
+/* The structure supports the overall packing operation */
+
+struct nxffs_pack_s
+{
+ struct nxffs_packstream_s src; /* Describes the src stream */
+ struct nxffs_packstream_s dest; /* Describes the destination stream */
+};
/****************************************************************************
* Public Variables
@@ -62,6 +83,140 @@
****************************************************************************/
/****************************************************************************
+ * Name: nxffs_startblock
+ *
+ * Description:
+ * Find the position in FLASH memory where we should begin packing. That
+ * position is the place where there is a gap between the last and the next
+ * valid inode.
+ *
+ * Input Parameters:
+ * volume - The volume to be packed.
+ *
+ * Returned Values:
+ * Zero on success; Otherwise, a negated errno value is returned to
+ * indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static int nxffs_startblock(FAR struct nxffs_volume_s *volume,
+ FAR struct nxffs_pack_s *pack)
+{
+ struct nxffs_blkentry_s blkentry;
+ off_t wasted;
+ off_t offset;
+ off_t nbytes;
+ int ret;
+
+ memset(pack, 0, sizeof(struct nxffs_pack_s));
+
+ /* Find the FLASH offset to the first valid block */
+
+ volume->ioblock = 0;
+ ret = nxffs_validblock(volume, &volume->ioblock);
+ if (ret < 0)
+ {
+ /* No valid blocks? */
+
+ return nxffs_reformat(volume);
+ }
+
+ volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
+ offset = nxffs_iotell(volume);
+
+ /* Loop until we find a gap of unused FLASH large enough to warrant the
+ * compression.
+ */
+
+ for(;;)
+ {
+ /* Get the offset to the first valid inode entry */
+
+ ret = nxffs_nextentry(volume, offset, &pack->src.entry);
+ if (ret < 0)
+ {
+ /* No valid entries -- reformat the flash */
+
+ return nxffs_reformat(volume);
+ }
+
+ /* Is there wasted space between the offset where the we could have
+ * valid data and the offset to the beginning of the first valid
+ * inode header? NOTE: The threshold check is not accurate, there
+ * may or may not be intervening block headers making the separation
+ * seem larger than it is.
+ */
+
+ DEBUGASSERT(pack->src.entry.hoffset >= offset);
+ wasted = pack->src.entry.hoffset - offset;
+ if (wasted > CONFIG_NXFFS_PACKTHRESHOLD)
+ {
+ /* This is where we must begin packing */
+
+ memcpy(&pack->dest.entry, &pack->src.entry, sizeof(struct nxffs_entry_s));
+
+ pack->dest.entry.hoffset = offset;
+ pack->src.entry.name = NULL;
+ return OK;
+ }
+
+ /* Free the allocated memory in the entry */
+
+ nxffs_freeentry(&pack->src.entry);
+
+ /* Update the offset to the first byte at the end of the last data
+ * block.
+ */
+
+ nbytes = 0;
+ offset = pack->src.entry.doffset;
+
+ while (nbytes < pack->src.entry.datlen)
+ {
+ /* Read the next data block header */
+
+ ret = nxffs_nextblock(volume, offset, &blkentry);
+ if (ret < 0)
+ {
+ fdbg("Failed to find next data block: %d\n", -ret);
+ return ret;
+ }
+
+ /* Get the number of blocks and pointer to where the next
+ * data block might lie.
+ */
+
+ nbytes += blkentry.datlen;
+ offset = blkentry.hoffset + SIZEOF_NXFFS_DATA_HDR + blkentry.datlen;
+ }
+
+ /* Make sure there is space at this location for an inode header */
+
+ nxffs_ioseek(volume, offset);
+ if (volume->iooffset + SIZEOF_NXFFS_INODE_HDR > volume->geo.blocksize)
+ {
+ /* Find the next valid block */
+
+ volume->ioblock++;
+ ret = nxffs_validblock(volume, &volume->ioblock);
+ if (ret < 0)
+ {
+ /* No valid blocks? Then there is nothing we can do */
+
+ return -ENOSPC;
+ }
+
+ volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
+ offset = nxffs_iotell(volume);
+ }
+ }
+
+ /* We won't get here */
+
+ return -ENOSYS;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -83,6 +238,29 @@
int nxffs_pack(FAR struct nxffs_volume_s *volume)
{
+ struct nxffs_pack_s pack;
+ int ret;
+
+ /* Get the offset to the first valid inode entry */
+
+ ret = nxffs_startblock(volume, &pack);
+ if (ret < 0)
+ {
+ fdbg("Failed to find a start block: %d\n", -ret);
+ return ret;
+ }
+
+ /* A special case is where the entire FLASH needs to be reformatted. In
+ * this case, the source and destination offsets will both be zero.
+ */
+
+ if (pack.src.entry.hoffset == 0 && pack.dest.entry.hoffset == 0)
+ {
+ return OK;
+ }
+
+ /* Otherwise, begin pack at this src/dest block combination */
+
# warning "Missing logic"
return -ENOSYS;
}
diff --git a/nuttx/fs/nxffs/nxffs_read.c b/nuttx/fs/nxffs/nxffs_read.c
index bb400e232..30fcd09aa 100644
--- a/nuttx/fs/nxffs/nxffs_read.c
+++ b/nuttx/fs/nxffs/nxffs_read.c
@@ -61,13 +61,6 @@
* Public Types
****************************************************************************/
-struct nxffs_blkentry_s
-{
- off_t hoffset; /* Offset to the block data header */
- uint16_t datlen; /* Length of data following the header */
- uint16_t foffset; /* Offset to start of data */
-};
-
/****************************************************************************
* Public Variables
****************************************************************************/
@@ -146,127 +139,6 @@ static int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
}
/****************************************************************************
- * Name: nxffs_nextblock
- *
- * Description:
- * Search for the next valid data block starting at the provided
- * FLASH offset.
- *
- * 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.
- *
- ****************************************************************************/
-
-int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR struct nxffs_blkentry_s *blkentry)
-{
- int nmagic;
- int ch;
- int nerased;
- int ret;
-
- /* Seek to the first FLASH offset provided by the caller. */
-
- nxffs_ioseek(volume, offset);
-
- /* Skip the block header */
-
- if (volume->iooffset < SIZEOF_NXFFS_BLOCK_HDR)
- {
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- }
-
- /* Then begin searching */
-
- nerased = 0;
- nmagic = 0;
-
- for (;;)
- {
- /* Read the next character */
-
- ch = nxffs_getc(volume);
- if (ch < 0)
- {
- fvdbg("nxffs_getc failed: %d\n", -ch);
- return ch;
- }
-
- /* Check for another erased byte */
-
- else if (ch == CONFIG_NXFFS_ERASEDSTATE)
- {
- /* If we have encountered NXFFS_NERASED number of consecutive
- * erased bytes, then presume we have reached the end of valid
- * data.
- */
-
- if (++nerased >= NXFFS_NERASED)
- {
- fvdbg("No entry found\n");
- return -ENOENT;
- }
- }
- else
- {
- nerased = 0;
-
- /* Check for the magic sequence indicating the start of an NXFFS
- * data block or start of the next inode. There is the possibility
- * of this magic sequnce occurring in FLASH data. However, the
- * data block CRC should distinguish between real NXFFS data blocks
- * headers and such false alarms.
- */
-
- if (ch != g_datamagic[nmagic])
- {
- nmagic = 0;
- }
- else if (nmagic < NXFFS_MAGICSIZE - 1)
- {
- nmagic++;
- }
-
- /* We have found the magic sequence in the FLASH data that may
- * indicate the beginning of an NXFFS data block.
- */
-
- else
- {
- /* The offset to the header must be 4 bytes before the current
- * FLASH seek location.
- */
-
- blkentry->hoffset = nxffs_iotell(volume) - 4;
-
- /* Read the block header and verify the block at that address */
-
- ret = nxffs_rdblkhdr(volume, blkentry->hoffset, &blkentry->datlen);
- if (ret == OK)
- {
- fvdbg("Found a valid data block, offset: %d datlen: %d\n",
- blkentry->hoffset, blkentry->datlen);
- return OK;
- }
-
- /* False alarm.. keep looking */
-
- nmagic = 0;
- }
- }
- }
-
- /* We won't get here, but to keep some compilers happy: */
-
- return -ENOENT;
-}
-
-/****************************************************************************
* Name: nxffs_rdseek
*
* Description:
@@ -444,3 +316,125 @@ errout:
return (ssize_t)ret;
}
+/****************************************************************************
+ * Name: nxffs_nextblock
+ *
+ * Description:
+ * Search for the next valid data block starting at the provided
+ * FLASH offset.
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
+ FAR struct nxffs_blkentry_s *blkentry)
+{
+ int nmagic;
+ int ch;
+ int nerased;
+ int ret;
+
+ /* Seek to the first FLASH offset provided by the caller. */
+
+ nxffs_ioseek(volume, offset);
+
+ /* Skip the block header */
+
+ if (volume->iooffset < SIZEOF_NXFFS_BLOCK_HDR)
+ {
+ volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
+ }
+
+ /* Then begin searching */
+
+ nerased = 0;
+ nmagic = 0;
+
+ for (;;)
+ {
+ /* Read the next character */
+
+ ch = nxffs_getc(volume);
+ if (ch < 0)
+ {
+ fvdbg("nxffs_getc failed: %d\n", -ch);
+ return ch;
+ }
+
+ /* Check for another erased byte */
+
+ else if (ch == CONFIG_NXFFS_ERASEDSTATE)
+ {
+ /* If we have encountered NXFFS_NERASED number of consecutive
+ * erased bytes, then presume we have reached the end of valid
+ * data.
+ */
+
+ if (++nerased >= NXFFS_NERASED)
+ {
+ fvdbg("No entry found\n");
+ return -ENOENT;
+ }
+ }
+ else
+ {
+ nerased = 0;
+
+ /* Check for the magic sequence indicating the start of an NXFFS
+ * data block or start of the next inode. There is the possibility
+ * of this magic sequnce occurring in FLASH data. However, the
+ * data block CRC should distinguish between real NXFFS data blocks
+ * headers and such false alarms.
+ */
+
+ if (ch != g_datamagic[nmagic])
+ {
+ nmagic = 0;
+ }
+ else if (nmagic < NXFFS_MAGICSIZE - 1)
+ {
+ nmagic++;
+ }
+
+ /* We have found the magic sequence in the FLASH data that may
+ * indicate the beginning of an NXFFS data block.
+ */
+
+ else
+ {
+ /* The offset to the header must be 4 bytes before the current
+ * FLASH seek location.
+ */
+
+ blkentry->hoffset = nxffs_iotell(volume) - 4;
+
+ /* Read the block header and verify the block at that address */
+
+ ret = nxffs_rdblkhdr(volume, blkentry->hoffset, &blkentry->datlen);
+ if (ret == OK)
+ {
+ fvdbg("Found a valid data block, offset: %d datlen: %d\n",
+ blkentry->hoffset, blkentry->datlen);
+ return OK;
+ }
+
+ /* False alarm.. keep looking */
+
+ nmagic = 0;
+ }
+ }
+ }
+
+ /* We won't get here, but to keep some compilers happy: */
+
+ return -ENOENT;
+}
+
+