summaryrefslogtreecommitdiff
path: root/nuttx/fs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-01 14:48:27 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-01 14:48:27 +0000
commit6f1d568b0527740e828559bdd6f86d187689496b (patch)
treea1e993abfef3b0666e237c7eb565208a227c4f62 /nuttx/fs
parente120ff0a0ef5c0f0125fc0e4b21bead8c67f8727 (diff)
downloadpx4-nuttx-6f1d568b0527740e828559bdd6f86d187689496b.tar.gz
px4-nuttx-6f1d568b0527740e828559bdd6f86d187689496b.tar.bz2
px4-nuttx-6f1d568b0527740e828559bdd6f86d187689496b.zip
Extend NXFFS tests; bugfixes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3547 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/fs')
-rw-r--r--nuttx/fs/nxffs/Make.defs6
-rwxr-xr-xnuttx/fs/nxffs/README.txt40
-rw-r--r--nuttx/fs/nxffs/nxffs.h18
-rw-r--r--nuttx/fs/nxffs/nxffs_dump.c183
-rw-r--r--nuttx/fs/nxffs/nxffs_initialize.c1
-rw-r--r--nuttx/fs/nxffs/nxffs_open.c104
-rw-r--r--nuttx/fs/nxffs/nxffs_read.c71
7 files changed, 351 insertions, 72 deletions
diff --git a/nuttx/fs/nxffs/Make.defs b/nuttx/fs/nxffs/Make.defs
index 4d7dcf3f4..a73950c3f 100644
--- a/nuttx/fs/nxffs/Make.defs
+++ b/nuttx/fs/nxffs/Make.defs
@@ -36,9 +36,9 @@
ifeq ($(CONFIG_FS_NXFFS),y)
ASRCS +=
CSRCS += nxffs_block.c nxffs_blockstats.c nxffs_cache.c nxffs_dirent.c \
- nxffs_initialize.c nxffs_inode.c nxffs_ioctl.c nxffs_open.c \
- nxffs_pack.c nxffs_read.c nxffs_reformat.c nxffs_stat.c \
- nxffs_unlink.c nxffs_util.c nxffs_write.c
+ nxffs_dump.c nxffs_initialize.c nxffs_inode.c nxffs_ioctl.c \
+ nxffs_open.c nxffs_pack.c nxffs_read.c nxffs_reformat.c \
+ nxffs_stat.c nxffs_unlink.c nxffs_util.c nxffs_write.c
# Argument for dependency checking
diff --git a/nuttx/fs/nxffs/README.txt b/nuttx/fs/nxffs/README.txt
index 156a3436a..47a7d7f97 100755
--- a/nuttx/fs/nxffs/README.txt
+++ b/nuttx/fs/nxffs/README.txt
@@ -10,6 +10,8 @@ Contents:
General operation
Headers
NXFFS Limitations
+ Multiple Writers
+ Things to Do
General NXFFS organization
==========================
@@ -111,3 +113,41 @@ that you should be aware before opting to use NXFFS:
an MTD driver (instead of a block driver) and bypass all of the normal
mount operations.
+Multiple Writers
+================
+
+As mentioned in the limitations above, there can be only one file opened
+for writing at a time. If one thread has a file opened for writing and
+another thread attempts to open a file for writing, then that second
+thread will be blocked and will have to wait for the first thread to
+close the file.
+
+Such behavior may or may not be a problem for your application, depending
+(1) how long the first thread keeps the file open for writing and (2) how
+critical the behavior of the second thread is. Note that writing to FLASH
+can always trigger a major FLASH reorganization and, hence, there is no
+way to guarantee the first condition: The first thread may have the file
+open for a long time even if it only intends to write a small amount.
+
+Also note that a deadlock condition would occur if the SAME thread
+attempted to open two files for writing. The thread would would be
+blocked waiting for itself to close the first file.
+
+Things to Do
+============
+
+- The implementation is not yet finished. It needs at, a minimum,
+ completion of the file system packing logic. It is not usuable without
+ that feature.
+- The statfs() implementation is minimal. It whould have some calcuation
+ of the f_bfree, f_bavail, f_files, f_ffree return values.
+- There are too many allocs and frees. More structures may need to be
+ pre-allocated.
+- The file name is always extracted and held in allocated, variable-length
+ memory. The file name is not used during reading and eliminating the
+ file name in the entry structure would improve performance.
+- There is a big inefficient in reading. On each read, the logic searches
+ for the read position from the beginning of the file each time. This
+ may be necessary whenever an lseek() is done, but not in general. Read
+ performance could be improved by keeping FLASH offset and read positional
+ information in the read open file structure.
diff --git a/nuttx/fs/nxffs/nxffs.h b/nuttx/fs/nxffs/nxffs.h
index 9ed65cf67..912e0db92 100644
--- a/nuttx/fs/nxffs/nxffs.h
+++ b/nuttx/fs/nxffs/nxffs.h
@@ -259,21 +259,7 @@ struct nxffs_wrfile_s
struct nxffs_ofile_s ofile;
- /* The following fields are required to support the current write
- * operation.
- *
- * 1. Inode header location determined (but not yet written).
- * 2. Block header location determined (but not yet written).
- * 3. Check FLASH memory to make sure that it is erased.
- * 4. As data is written, datlen is updated and the data is written to FLASH.
- * 5. If the end of the FLASH block is encountered, the data block CRC is
- * calculated and the block header is also written to flash.
- * 6. When the file is closed, the final, partial data block is written to
- * FLASH in the same way. Any previously identified file with the same
- * name is deleted. The final file size is determined, the header
- * CRC is calculated, and the inode header is written to FLASH, completing
- * the write operation.
- */
+ /* The following fields are required to support the write operation */
bool truncate; /* Delete a file of the same name */
uint16_t datlen; /* Number of bytes written in data block */
@@ -287,8 +273,8 @@ struct nxffs_volume_s
{
FAR struct mtd_dev_s *mtd; /* Supports FLASH access */
sem_t exclsem; /* Used to assure thread-safe access */
+ sem_t wrsem; /* Enforces single writer restriction */
struct mtd_geometry_s geo; /* Device geometry */
- uint8_t wrbusy: 1; /* 1: Volume open for writing */
uint8_t blkper; /* R/W blocks per erase block */
uint8_t ncached; /* Number of blocks in cache */
uint16_t iooffset; /* Next offset in read/write access (in ioblock) */
diff --git a/nuttx/fs/nxffs/nxffs_dump.c b/nuttx/fs/nxffs/nxffs_dump.c
new file mode 100644
index 000000000..e93200afd
--- /dev/null
+++ b/nuttx/fs/nxffs/nxffs_dump.c
@@ -0,0 +1,183 @@
+/****************************************************************************
+ * fs/nxffs/nxffs_dump.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * References: Linux/Documentation/filesystems/romfs.txt
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <string.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/ioctl.h>
+#include <nuttx/mtd.h>
+
+#include "nxffs.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxffs_analyze
+ *
+ * Description:
+ * Analyze the content of one block.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
+static inline void nxffs_analyze(FAR uint8_t *buffer, size_t buflen, off_t blockno)
+{
+ FAR struct nxffs_block_s *blkhdr;
+
+ /* Verify that there is a header on the block */
+
+ blkhdr = (FAR struct nxffs_block_s *)buffer;
+ if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0)
+ {
+ fdbg("Block %d: ERROR -- no header\n", blockno);
+ }
+ else if (blkhdr->state == BLOCK_STATE_GOOD)
+ {
+ fdbg("Block %d: GOOD\n", blockno);
+ }
+ else if (blkhdr->state == BLOCK_STATE_BAD)
+ {
+ fdbg("Block %d: BAD\n", blockno);
+ }
+ else
+ {
+ fdbg("Block %d: ERROR -- bad state\n", blockno);
+ }
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nxffs_dump
+ *
+ * Description:
+ * Dump a summary of the contents of an NXFFS file system. CONFIG_DEBUG
+ * and CONFIG_DEBUG_FS must be enabled for this function to do anything.
+ *
+ * Input Parameters:
+ * mtd - The MTD device that provides the interface to NXFFS-formatted media.
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+int nxffs_dump(FAR struct mtd_dev_s *mtd)
+{
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
+ struct mtd_geometry_s geo;
+ FAR uint8_t *buffer;
+ off_t nblocks;
+ off_t block;
+ int ret;
+
+ /* Get the volume geometry. (casting to uintptr_t first eliminates
+ * complaints on some architectures where the sizeof long is different
+ * from the size of a pointer).
+ */
+
+ ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo));
+ if (ret < 0)
+ {
+ fdbg("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", -ret);
+ goto errout;
+ }
+
+ /* Allocate a buffer to hold one block */
+
+ buffer = (FAR uint8_t *)kmalloc(geo.blocksize);
+ if (!buffer)
+ {
+ fdbg("Failed to allocate block cache\n");
+ ret = -ENOMEM;
+ goto errout;
+ }
+
+ /* Now read every block on the device */
+
+ nblocks = geo.erasesize * geo.neraseblocks / geo.blocksize;
+ for (block = 0; block < nblocks; block++)
+ {
+ /* Read the next block */
+
+ ret = MTD_BREAD(mtd, block, 1, buffer);
+ if (ret < 0)
+ {
+ fdbg("Failed to read block %d\n", block);
+ goto errout_with_block;
+ }
+
+ /* Analyze the block */
+
+ nxffs_analyze(buffer, geo.blocksize, block);
+ }
+
+errout_with_block:
+ kfree(buffer);
+errout:
+ return ret;
+
+#else
+ return -ENOSYS;
+#endif
+}
diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c
index cd729a9f2..adf1f76f7 100644
--- a/nuttx/fs/nxffs/nxffs_initialize.c
+++ b/nuttx/fs/nxffs/nxffs_initialize.c
@@ -183,6 +183,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd)
volume->mtd = mtd;
sem_init(&volume->exclsem, 0, 1);
+ sem_init(&volume->wrsem, 0, 1);
/* Get the volume geometry. (casting to uintptr_t first eliminates
* complaints on some architectures where the sizeof long is different
diff --git a/nuttx/fs/nxffs/nxffs_open.c b/nuttx/fs/nxffs/nxffs_open.c
index 09a82f6e9..f2b5c3e04 100644
--- a/nuttx/fs/nxffs/nxffs_open.c
+++ b/nuttx/fs/nxffs/nxffs_open.c
@@ -340,13 +340,27 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
* in FLASH, only a single file may be extending the FLASH region.
*/
- if (volume->wrbusy)
+ ret = sem_wait(&volume->wrsem);
+ if (ret != OK)
{
- fdbg("There is already a file writer\n");
- ret = -ENOSYS;
+ fdbg("sem_wait failed: %d\n", ret);
+ ret = -errno;
goto errout;
}
+ /* Get exclusive access to the volume. Note that the volume exclsem
+ * protects the open file list. Note that exclsem is ALWAYS taken
+ * after wrsem to avoid deadlocks.
+ */
+
+ ret = sem_wait(&volume->exclsem);
+ if (ret != OK)
+ {
+ fdbg("sem_wait failed: %d\n", ret);
+ ret = -errno;
+ goto errout_with_wrsem;
+ }
+
/* Check if the file exists */
ret = nxffs_findinode(volume, name, &entry);
@@ -360,7 +374,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
{
fdbg("File exists, can't create O_EXCL\n");
ret = -EEXIST;
- goto errout;
+ goto errout_with_exclsem;
}
/* Were we asked to truncate the file? NOTE: Don't truncate the
@@ -386,7 +400,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
{
fdbg("File %s exists and we were not asked to truncate it\n");
ret = -ENOSYS;
- goto errout;
+ goto errout_with_exclsem;
}
}
@@ -398,7 +412,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
{
fdbg("Not asked to create the file\n");
ret = -ENOENT;
- goto errout;
+ goto errout_with_exclsem;
}
/* Make sure that the length of the file name will fit in a uint8_t */
@@ -408,7 +422,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
{
fdbg("Name is too long: %d\n", namlen);
ret = -EINVAL;
- goto errout;
+ goto errout_with_exclsem;
}
/* Yes.. Create a new structure that will describe the state of this open
@@ -424,7 +438,7 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
if (!wrfile)
{
ret = -ENOMEM;
- goto errout;
+ goto errout_with_exclsem;
}
#endif
@@ -563,11 +577,13 @@ static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
volume->ofiles = &wrfile->ofile;
/* Indicate that the volume is open for writing and return the open file
- * instance.
+ * instance. Releasing exclsem allows other readers while the write is
+ * in progress. But wrsem is still held for this open file, preventing
+ * any further writers until this inode is closed.s
*/
- volume->wrbusy = 1;
*ppofile = &wrfile->ofile;
+ sem_post(&volume->exclsem);
return OK;
errout_with_name:
@@ -576,6 +592,11 @@ errout_with_ofile:
#ifndef CONFIG_NXFSS_PREALLOCATED
kfree(wrfile);
#endif
+
+errout_with_exclsem:
+ sem_post(&volume->exclsem);
+errout_with_wrsem:
+ sem_post(&volume->wrsem);
errout:
return ret;
}
@@ -595,6 +616,18 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
FAR struct nxffs_ofile_s *ofile;
int ret;
+ /* Get exclusive access to the volume. Note that the volume exclsem
+ * protects the open file list.
+ */
+
+ ret = sem_wait(&volume->exclsem);
+ if (ret != OK)
+ {
+ fdbg("sem_wait failed: %d\n", ret);
+ ret = -errno;
+ goto errout;
+ }
+
/* Check if the file has already been opened (for reading) */
ofile = nxffs_findofile(volume, name);
@@ -607,7 +640,8 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
if ((ofile->mode & O_WROK) != 0)
{
fdbg("File is open for writing\n");
- return -ENOSYS;
+ ret = -ENOSYS;
+ goto errout_with_exclsem;
}
/* Just increment the reference count on the ofile */
@@ -629,7 +663,8 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
if (!ofile)
{
fdbg("ofile allocation failed\n");
- return -ENOMEM;
+ ret = -ENOMEM;
+ goto errout_with_exclsem;
}
/* Initialize the open file state structure */
@@ -643,8 +678,7 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
if (ret != OK)
{
fdbg("Inode '%s' not found: %d\n", name, -ret);
- kfree(ofile);
- return ret;
+ goto errout_with_ofile;
}
/* Add the open file structure to the head of the list of open files */
@@ -656,7 +690,15 @@ static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
/* Return the open file state structure */
*ppofile = ofile;
+ sem_post(&volume->exclsem);
return OK;
+
+errout_with_ofile:
+ kfree(ofile);
+errout_with_exclsem:
+ sem_post(&volume->exclsem);
+errout:
+ return ret;
}
/****************************************************************************
@@ -851,7 +893,7 @@ static int nxffs_wrclose(FAR struct nxffs_volume_s *volume,
/* The volume is now available for other writers */
errout:
- volume->wrbusy = 0;
+ sem_post(&volume->wrsem);
return ret;
}
@@ -926,18 +968,6 @@ int nxffs_open(FAR struct file *filep, FAR const char *relpath,
volume = (FAR struct nxffs_volume_s*)filep->f_inode->i_private;
DEBUGASSERT(volume != NULL);
- /* Get exclusive access to the volume. Note that the volume exclsem
- * protects the open file list.
- */
-
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- ret = -errno;
- fdbg("sem_wait failed: %d\n", ret);
- goto errout;
- }
-
#ifdef CONFIG_FILE_MODE
# warning "Missing check for privileges based on inode->i_mode"
#endif
@@ -949,13 +979,12 @@ int nxffs_open(FAR struct file *filep, FAR const char *relpath,
* extension is supported.
*/
- switch (mode & (O_WROK|O_RDOK))
+ switch (oflags & (O_WROK|O_RDOK))
{
case 0:
default:
fdbg("One of O_WRONLY/O_RDONLY must be provided\n");
- ret = -EINVAL;
- goto errout_with_semaphore;
+ return -EINVAL;
case O_WROK:
ret = nxffs_wropen(volume, relpath, mode, &ofile);
@@ -967,18 +996,15 @@ int nxffs_open(FAR struct file *filep, FAR const char *relpath,
case O_WROK|O_RDOK:
fdbg("O_RDWR is not supported\n");
- ret = -ENOSYS;
- goto errout_with_semaphore;
+ return -ENOSYS;
}
- /* Save open-specific state in filep->f_priv */
+ /* Save the reference to the open-specific state in filep->f_priv */
- filep->f_priv = ofile;
- ret = OK;
-
-errout_with_semaphore:
- sem_post(&volume->exclsem);
-errout:
+ if (ret == OK)
+ {
+ filep->f_priv = ofile;
+ }
return ret;
}
diff --git a/nuttx/fs/nxffs/nxffs_read.c b/nuttx/fs/nxffs/nxffs_read.c
index 3648c1314..38b09acb1 100644
--- a/nuttx/fs/nxffs/nxffs_read.c
+++ b/nuttx/fs/nxffs/nxffs_read.c
@@ -61,6 +61,12 @@
* Public Types
****************************************************************************/
+struct nxffs_blkentry_s
+{
+ off_t hoffset; /* Offset to the block data header */
+ uint16_t datlen; /* Length of data following the header */
+};
+
/****************************************************************************
* Public Variables
****************************************************************************/
@@ -88,7 +94,7 @@
****************************************************************************/
static int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR size_t *datlen)
+ FAR uint16_t *datlen)
{
struct nxffs_data_s blkhdr;
uint32_t ecrc;
@@ -154,7 +160,7 @@ static int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
****************************************************************************/
int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR size_t *datlen)
+ FAR struct nxffs_blkentry_s *blkentry)
{
int nmagic;
int ch;
@@ -165,6 +171,13 @@ int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
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;
@@ -222,7 +235,15 @@ int nxffs_nextblock(FAR struct nxffs_volume_s *volume, off_t offset,
else
{
- ret = nxffs_rdblkhdr(volume, offset, datlen);
+ /* 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)
{
fdbg("Found a valid fileheader\n");
@@ -261,31 +282,42 @@ static ssize_t nxffs_rdseek(FAR struct nxffs_volume_s *volume,
FAR struct nxffs_entry_s *entry,
off_t fpos)
{
- size_t datlen = 0;
- size_t blklen = 0;
+ struct nxffs_blkentry_s blkentry;
+ size_t datstart;
+ size_t datend;
off_t offset = fpos;
int ret;
/* Loop until we read the data block containing the desired position */
+ datend = 0;
do
{
- /* Get the data offset at the start of the next data block */
+ /* Find the next the next data block */
- datlen += blklen;
-
- /* Get the length of the next data block */
-
- ret = nxffs_nextblock(volume, offset, &blklen);
+ ret = nxffs_nextblock(volume, offset, &blkentry);
if (ret < 0)
{
fdbg("nxffs_nextblock failed: %d\n", -ret);
return ret;
}
+
+ /* Get the range of data offses for this data block */
+
+ datstart = datend;
+ datend += blkentry.datlen;
+
+ /* Protect against reading past the end of the file */
+
+ /* Offset to search for the the next data block */
+
+ offset += blkentry.hoffset + SIZEOF_NXFFS_DATA_HDR + blkentry.datlen;
}
- while (datlen <= fpos && datlen + blklen > fpos);
+ while (datend <= fpos);
+
+ /* Return the offset to the data within the current data block */
- volume->iooffset += (fpos - datlen);
+ nxffs_ioseek(volume, blkentry.hoffset + SIZEOF_NXFFS_DATA_HDR + fpos - datstart);
return OK;
}
@@ -343,12 +375,23 @@ ssize_t nxffs_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
goto errout_with_semaphore;
}
+ /* Don't seek past the end of the file */
+
+ if (filep->f_pos >= ofile->entry.datlen)
+ {
+ /* Return end-of-file */
+
+ filep->f_pos = ofile->entry.datlen;
+ ret = 0;
+ goto errout_with_semaphore;
+ }
+
/* Seek to the current file offset */
ret = nxffs_rdseek(volume, &ofile->entry, filep->f_pos);
if (ret < 0)
{
- fdbg("nxffs_fwseek failed: %d\n", -ret);
+ fdbg("nxffs_rdseek failed: %d\n", -ret);
ret = -EACCES;
goto errout_with_semaphore;
}