From 8698f6ddcaebf63f5324b3c28d95dcb315a16897 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 29 Apr 2011 20:59:40 +0000 Subject: Add beginning of a test for NXFFS git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3540 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/fs/nxffs/Make.defs | 3 +- nuttx/fs/nxffs/README.txt | 6 ++ nuttx/fs/nxffs/nxffs.h | 70 ++++++++++++--- nuttx/fs/nxffs/nxffs_blockstats.c | 2 +- nuttx/fs/nxffs/nxffs_cache.c | 32 ++++++- nuttx/fs/nxffs/nxffs_initialize.c | 90 ++++++++++++++++++-- nuttx/fs/nxffs/nxffs_open.c | 8 +- nuttx/fs/nxffs/nxffs_read.c | 174 ++++++++++++++++++++++++++++++++++++++ nuttx/fs/nxffs/nxffs_reformat.c | 10 +-- nuttx/fs/nxffs/nxffs_write.c | 147 ++++++++++++++++++++++++++++++++ 10 files changed, 509 insertions(+), 33 deletions(-) create mode 100644 nuttx/fs/nxffs/nxffs_read.c create mode 100644 nuttx/fs/nxffs/nxffs_write.c (limited to 'nuttx/fs') diff --git a/nuttx/fs/nxffs/Make.defs b/nuttx/fs/nxffs/Make.defs index 88c3d9cee..6409c23bc 100644 --- a/nuttx/fs/nxffs/Make.defs +++ b/nuttx/fs/nxffs/Make.defs @@ -37,7 +37,8 @@ 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_reformat.c nxffs_stat.c nxffs_unlink.c nxffs_util.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 a2577e1f8..cdbea34ca 100755 --- a/nuttx/fs/nxffs/README.txt +++ b/nuttx/fs/nxffs/README.txt @@ -92,3 +92,9 @@ that you should be aware before opting to use NXFFS: 6. The clean-up process occurs only during a write when the free FLASH memory at the end of the FLASH is exhausted. Thus, occasionally, file writing may take a long time. + +7. Another limitation is that there can be only a single NXFFS volume + mounted at any time. This has to do with the fact that we bind to + an MTD driver (instead of a block driver) and bypass all of the normal + mount operations. + diff --git a/nuttx/fs/nxffs/nxffs.h b/nuttx/fs/nxffs/nxffs.h index 4f903a072..5b1809ebc 100644 --- a/nuttx/fs/nxffs/nxffs.h +++ b/nuttx/fs/nxffs/nxffs.h @@ -50,19 +50,11 @@ #include #include +#include /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ -/* Configuration ************************************************************/ -#ifndef CONFIG_NXFFS_ERASEDSTATE -# define CONFIG_NXFFS_ERASEDSTATE 0xff -#endif - -#if CONFIG_NXFFS_ERASEDSTATE != 0xff && CONFIG_NXFFS_ERASEDSTATE != 0x00 -# error "CONFIG_NXFFS_ERASEDSTATE must be either 0x00 or 0xff" -#endif - /* NXFFS Definitions ********************************************************/ /* General NXFFS organization. The following example assumes 4 logical * blocks per FLASH erase block. The actual relationship is determined by @@ -141,6 +133,10 @@ * 6. The clean-up process occurs only during a write when the free FLASH * memory at the end of the FLASH is exhausted. Thus, occasionally, file * writing may take a long time. + * 7. Another limitation is that there can be only a single NXFFS volume + * mounted at any time. This has to do with the fact that we bind to + * an MTD driver (instead of a block driver) and bypass all of the normal + * mount operations. */ /* Values for logical block state. Basically, there are only two, perhaps @@ -149,19 +145,25 @@ * BLOCK_STATE_GOOD - The block is not known to be bad. * BLOCK_STATE_BAD - An error was found on the block and it is marked bad. * Other values - The block is bad and has an invalid state. + * + * Care is taken so that the GOOD to BAD transition only involves burning + * bits from the erased to non-erased state. */ -#define BLOCK_STATE_GOOD CONFIG_NXFFS_ERASEDSTATE -#define BLOCK_STATE_BAD 0xaa +#define BLOCK_STATE_GOOD (CONFIG_NXFFS_ERASEDSTATE ^ 0x44) +#define BLOCK_STATE_BAD (CONFIG_NXFFS_ERASEDSTATE ^ 0x55) /* Values for NXFFS inode state. Similar there are 2 (maybe 3) inode states: * * INODE_STATE_FILE - The inode is a valid usuable, file * INODE_STATE_DELETED - The inode has been deleted. + * + * Care is taken so that the GOOD to BAD transition only involves burning + * bits from the erased to non-erased state. */ -#define INODE_STATE_FILE CONFIG_NXFFS_ERASEDSTATE -#define INODE_STATE_DELETED 0x55 +#define INODE_STATE_FILE (CONFIG_NXFFS_ERASEDSTATE ^ 0x22) +#define INODE_STATE_DELETED (CONFIG_NXFFS_ERASEDSTATE ^ 0xaa) /* Number of bytes in an the NXFFS magic sequences */ @@ -316,6 +318,18 @@ extern const uint8_t g_inodemagic[NXFFS_MAGICSIZE]; extern const uint8_t g_datamagic[NXFFS_MAGICSIZE]; +/* If CONFIG_NXFSS_PREALLOCATED is defined, then this is the single, pre- + * allocated NXFFS volume instance. + */ + +#ifdef CONFIG_NXFSS_PREALLOCATED +extern struct nxffs_volume_s g_volume; +#endif + +/* A singly-linked list of open files */ + +extern struct nxffs_ofile_s *g_ofiles; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ @@ -474,12 +488,14 @@ extern int nxffs_getc(FAR struct nxffs_volume_s *volume); * * Description: * Read a sequence of data bytes from the FLASH memory. This function - * allows the data in the formatted FLASH blocks to be read as a continuous\ + * allows the data in the formatted FLASH blocks to be read as a continuous * byte stream, skipping over bad blocks and block headers as necessary. * * Input Parameters: * volume - Describes the NXFFS volume. The paramters ioblock and iooffset * in the volume structure determine the behavior of nxffs_getc(). + * buffer - A pointer to memory to receive the data read from FLASH. + * buflen - The maximum number of bytes to read from FLASH. * * Returned Value: * The number of bytes read is returned on success. Otherwise, a negated @@ -492,6 +508,29 @@ extern int nxffs_getc(FAR struct nxffs_volume_s *volume); extern ssize_t nxffs_rddata(FAR struct nxffs_volume_s *volume, FAR uint8_t *buffer, size_t buflen); +/**************************************************************************** + * Name: nxffs_wrdata + * + * Description: + * Write a sequence of data bytes into volume cache memory. Nothing is + * actually written to FLASH! This function allows the data in the formatted + * FLASH blocks to be read as a continuous byte stream, skipping over bad + * blocks and block headers as necessary. + * + * Input Parameters: + * volume - Describes the NXFFS volume. + * buffer - A pointer to memory to containing the data to write to FLASH. + * buflen - The maximum number of bytes to write to FLASH. + * + * Returned Value: + * The number of bytes written is returned on success. Otherwise, a negated + * errno indicating the nature of the failure. + * + ****************************************************************************/ + +extern ssize_t nxffs_wrdata(FAR struct nxffs_volume_s *volume, + FAR const uint8_t *buffer, size_t buflen); + /**************************************************************************** * Name: nxffs_freeentry * @@ -700,9 +739,12 @@ extern int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name * See include/nuttx/fs.h * * - nxffs_open() and nxffs_close() are defined in nxffs_open.c + * - nxffs_read() is defined in nxffs_read.c + * - nxffs_write() is defined in nxffs_write.c * - nxffs_ioctl() is defined in nxffs_ioctl.c * - nxffs_opendir(), nxffs_readdir(), and nxffs_rewindir() are defined in * nxffs_dirent.c + * - nxffs_bind() and nxffs_unbind() are defined in nxffs_initialize.c * - nxffs_stat() and nxffs_statfs() are defined in nxffs_stat.c * - nxffs_unlink() is defined nxffs_unlink.c * diff --git a/nuttx/fs/nxffs/nxffs_blockstats.c b/nuttx/fs/nxffs/nxffs_blockstats.c index 8ad6f0978..9f7ca3af7 100644 --- a/nuttx/fs/nxffs/nxffs_blockstats.c +++ b/nuttx/fs/nxffs/nxffs_blockstats.c @@ -116,7 +116,7 @@ int nxffs_blockstats(FAR struct nxffs_volume_s *volume, for (bptr = volume->cache, lblock = 0; lblock < volume->blkper; - bptr += SIZEOF_NXFFS_BLOCK_HDR, lblock++) + bptr += volume->geo.blocksize, lblock++) { FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)bptr; diff --git a/nuttx/fs/nxffs/nxffs_cache.c b/nuttx/fs/nxffs/nxffs_cache.c index a2774ddfd..f149de7cb 100644 --- a/nuttx/fs/nxffs/nxffs_cache.c +++ b/nuttx/fs/nxffs/nxffs_cache.c @@ -95,7 +95,7 @@ int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block, /* Check if the requested data is already in the cache */ - if (block != volume->cblock || nblocks <= volume->ncached) + if (block != volume->cblock || nblocks > volume->ncached) { /* Read the specified blocks into cache */ @@ -229,12 +229,14 @@ int nxffs_getc(FAR struct nxffs_volume_s *volume) * * Description: * Read a sequence of data bytes from the FLASH memory. This function - * allows the data in the formatted FLASH blocks to be read as a continuous\ + * allows the data in the formatted FLASH blocks to be read as a continuous * byte stream, skipping over bad blocks and block headers as necessary. * * Input Parameters: * volume - Describes the NXFFS volume. The paramters ioblock and iooffset * in the volume structure determine the behavior of nxffs_getc(). + * buffer - A pointer to memory to receive the data read from FLASH. + * buflen - The maximum number of bytes to read from FLASH. * * Returned Value: * The number of bytes read is returned on success. Otherwise, a negated @@ -267,3 +269,29 @@ ssize_t nxffs_rddata(FAR struct nxffs_volume_s *volume, return buflen; } +/**************************************************************************** + * Name: nxffs_wrdata + * + * Description: + * Write a sequence of data bytes into volume cache memory. Nothing is + * actually written to FLASH! This function allows the data in the formatted + * FLASH blocks to be read as a continuous byte stream, skipping over bad + * blocks and block headers as necessary. + * + * Input Parameters: + * volume - Describes the NXFFS volume. + * buffer - A pointer to memory to containing the data to write to FLASH. + * buflen - The maximum number of bytes to write to FLASH. + * + * Returned Value: + * The number of bytes written is returned on success. Otherwise, a negated + * errno indicating the nature of the failure. + * + ****************************************************************************/ + +ssize_t nxffs_wrdata(FAR struct nxffs_volume_s *volume, + FAR const uint8_t *buffer, size_t buflen) +{ +#warning "Missing Logic" + return -ENOSYS; +} diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c index 8d96ffa15..fc2d97b65 100644 --- a/nuttx/fs/nxffs/nxffs_initialize.c +++ b/nuttx/fs/nxffs/nxffs_initialize.c @@ -41,6 +41,7 @@ #include +#include #include #include #include @@ -119,6 +120,14 @@ const uint8_t g_inodemagic[NXFFS_MAGICSIZE] = { 'I', 'n', 'o', 'd' }; const uint8_t g_datamagic[NXFFS_MAGICSIZE] = { 'D', 'a', 't', 'a' }; +/* If CONFIG_NXFSS_PREALLOCATED is defined, then this is the single, pre- + * allocated NXFFS volume instance. + */ + +#ifdef CONFIG_NXFSS_PREALLOCATED +struct nxffs_volume_s g_volume; +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -135,19 +144,31 @@ const uint8_t g_datamagic[NXFFS_MAGICSIZE] = { 'D', 'a', 't', 'a' }; * * Input Parameters: * mtd - The MTD device that supports the FLASH interface. - * start - The first block of the file system begins at this block number - * in the FLASH - * nblocks - This number of blocks is set aside for the file system. + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. * ****************************************************************************/ -int nxffs_initialize(FAR struct mtd_dev_s *mtd, off_t start, off_t nblocks) +int nxffs_initialize(FAR struct mtd_dev_s *mtd) { FAR struct nxffs_volume_s *volume; struct nxffs_blkstats_s stats; off_t threshold; int ret; + /* If CONFIG_NXFSS_PREALLOCATED is defined, then this is the single, pre- + * allocated NXFFS volume instance. + */ + +#ifdef CONFIG_NXFSS_PREALLOCATED + + volume = &g_volume; + memset(volume, 0, sizeof(struct nxffs_volume_s)); + +#else + /* Allocate a NXFFS volume structure */ volume = (FAR struct nxffs_volume_s *)kzalloc(sizeof(struct nxffs_volume_s)); @@ -156,6 +177,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd, off_t start, off_t nblocks) ret = -ENOMEM; goto errout; } +#endif /* Initialize the NXFFS volume structure */ @@ -175,7 +197,7 @@ int nxffs_initialize(FAR struct mtd_dev_s *mtd, off_t start, off_t nblocks) /* Allocate one, in-memory erase block buffer */ - volume->cache = (FAR uint8_t *)kmalloc(volume->geo.erasesize); + volume->cache = (FAR uint8_t *)kmalloc(volume->geo.erasesize); if (!volume->cache) { fdbg("Failed to allocate an erase block buffer\n"); @@ -238,7 +260,6 @@ errout_with_iobuffer: kfree(volume->cache); errout_with_volume: kfree(volume); -errout: return ret; } @@ -400,3 +421,60 @@ int nxffs_limits(FAR struct nxffs_volume_s *volume) return OK; } +/**************************************************************************** + * Name: nxffs_bind + * + * Description: + * This function implements a portion of the mount operation. Normmally, + * the bind() method allocates and initializes the mountpoint private data + * then binds the blockdriver inode to the filesystem private data. The + * final binding of the private data (containing the blockdriver) to the + * mountpoint is performed by mount(). + * + * For the NXFFS, this sequence is quite different for the following + * reasons: + * + * 1. A block driver is not used. Instead, an MTD instance was provided + * to nxfs_initialize prior to mounting. So, in this sense, the NXFFS + * file system is already bound. + * + * 2. Since the volume was already bound to the MTD driver, all allocations + * and initializations have already been performed. Essentially, all + * mount operations have been bypassed and now we just need to provide + * the pre-allocated volume instance. + * + * 3. The tricky thing is that there is no mechanism to associate multiple + * NXFFS volumes to the multiple volumes bound to different MTD drivers. + * Hence, the limitation of a single NXFFS volume. + * + ****************************************************************************/ + +int nxffs_bind(FAR struct inode *blkdriver, FAR const void *data, + FAR void **handle) +{ +#ifndef CONFIG_NXFSS_PREALLOCATED +# error "No design to support dynamic allocation of volumes" +#else + + /* If CONFIG_NXFSS_PREALLOCATED is defined, then this is the single, pre- + * allocated NXFFS volume instance. + */ + + DEBUGASSERT(g_volume.cache); + *handle = &g_volume; +#endif + return OK; +} + +/**************************************************************************** + * Name: nxffs_unbind + * + * Description: This implements the filesystem portion of the umount + * operation. + * + ****************************************************************************/ + +int nxffs_unbind(FAR void *handle, FAR struct inode **blkdriver) +{ + return g_ofiles ? -EBUSY : OK; +} diff --git a/nuttx/fs/nxffs/nxffs_open.c b/nuttx/fs/nxffs/nxffs_open.c index 88bfbf3ff..f057ab4bc 100644 --- a/nuttx/fs/nxffs/nxffs_open.c +++ b/nuttx/fs/nxffs/nxffs_open.c @@ -65,14 +65,14 @@ * Public Variables ****************************************************************************/ +/* A singly-linked list of open files */ + +struct nxffs_ofile_s *g_ofiles; + /**************************************************************************** * Private Variables ****************************************************************************/ -/* A singly-linked list of open files */ - -static struct nxffs_ofile_s *g_ofiles; - /**************************************************************************** * Private Functions ****************************************************************************/ diff --git a/nuttx/fs/nxffs/nxffs_read.c b/nuttx/fs/nxffs/nxffs_read.c new file mode 100644 index 000000000..d8c2e9567 --- /dev/null +++ b/nuttx/fs/nxffs/nxffs_read.c @@ -0,0 +1,174 @@ +/**************************************************************************** + * fs/nxffs/nxffs_read.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include + +#include +#include + +#include "nxffs.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxffs_rdseek + * + * Description: + * Seek to the file position before read or write access. Note that the + * simplier nxffs_ioseek() cannot be used for this purpose. File offsets + * are not easily mapped to FLASH offsets due to intervening block and + * data headers. + * + * Input Parameters: + * volume - Describes the current volume + * entry - Describes the open inode + * fpos - The desired file position + * + ****************************************************************************/ + +static ssize_t nxffs_rdseek(FAR struct nxffs_volume_s *volume, + FAR struct nxffs_entry_s *entry, + off_t fpos) +{ +#warning "Missing Logic" + return 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: nxffs_read + * + * Description: + * This is an implementation of the NuttX standard file system read + * method. + * + ****************************************************************************/ + +ssize_t nxffs_read(FAR struct file *filep, FAR char *buffer, size_t buflen) +{ + FAR struct nxffs_volume_s *volume; + FAR struct nxffs_ofile_s *ofile; + ssize_t ret; + + fvdbg("Read %d bytes from offset %d\n", buflen, filep->f_pos); + + /* Sanity checks */ + + DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL); + + /* Recover the open file state from the struct file instance */ + + ofile = (FAR struct nxffs_ofile_s *)filep->f_priv; + + /* Recover the volume state from the open file */ + + 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; + } + + /* Check if the file was opened with read access */ + + if ((ofile->mode & O_RDOK) == 0) + { + fdbg("File not open for read access\n"); + ret = -EACCES; + 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); + ret = -EACCES; + goto errout_with_semaphore; + } + + /* Read data from that file offset */ + + ret = nxffs_rddata(volume, (FAR uint8_t *)buffer, buflen); + if (ret > 0) + { + /* Update the file offset */ + + filep->f_pos += ret; + } + +errout_with_semaphore: + sem_post(&volume->exclsem); +errout: + return ret; +} + diff --git a/nuttx/fs/nxffs/nxffs_reformat.c b/nuttx/fs/nxffs/nxffs_reformat.c index 8f34a9373..672d57866 100644 --- a/nuttx/fs/nxffs/nxffs_reformat.c +++ b/nuttx/fs/nxffs/nxffs_reformat.c @@ -95,7 +95,7 @@ static int nxffs_format(FAR struct nxffs_volume_s *volume) memset(volume->cache, CONFIG_NXFFS_ERASEDSTATE, volume->geo.erasesize); for (blkptr = volume->cache, i = 0; i < volume->blkper; - blkptr += SIZEOF_NXFFS_BLOCK_HDR, i++) + blkptr += volume->geo.blocksize, i++) { FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr; memcpy(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE); @@ -121,7 +121,7 @@ static int nxffs_format(FAR struct nxffs_volume_s *volume) nxfrd = MTD_BWRITE(volume->mtd, lblock, volume->blkper, volume->cache); if (nxfrd != volume->blkper) { - fdbg("Write erase block %d failed: %d\n", alignedblock, nxfrd); + fdbg("Write erase block %d failed: %d\n", lblock, nxfrd); return -EIO; } } @@ -176,7 +176,7 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume) modified = false; for (blkptr = volume->cache, i = 0; i < volume->blkper; - blkptr += SIZEOF_NXFFS_BLOCK_HDR, i++) + blkptr += volume->geo.blocksize, i++) { FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr; @@ -184,7 +184,7 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume) bad = false; if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0 || - blkhdr->state == BLOCK_STATE_GOOD) + blkhdr->state != BLOCK_STATE_GOOD) { bad = true;; } @@ -228,7 +228,7 @@ static int nxffs_badblocks(FAR struct nxffs_volume_s *volume) nxfrd = MTD_BWRITE(volume->mtd, lblock, volume->blkper, volume->cache); if (nxfrd != volume->blkper) { - fdbg("Write erase block %d failed: %d\n", alignedblock, nxfrd); + fdbg("Write erase block %d failed: %d\n", lblock, nxfrd); return -EIO; } } diff --git a/nuttx/fs/nxffs/nxffs_write.c b/nuttx/fs/nxffs/nxffs_write.c new file mode 100644 index 000000000..363a1d60f --- /dev/null +++ b/nuttx/fs/nxffs/nxffs_write.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * fs/nxffs/nxffs_write.c + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include + +#include +#include + +#include "nxffs.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nxffs_write + * + * Description: + * This is an implementation of the NuttX standard file system write + * method. + * + ****************************************************************************/ + +ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer, size_t buflen) +{ + FAR struct nxffs_volume_s *volume; + FAR struct nxffs_wrfile_s *wrfile; + ssize_t ret; + + fvdbg("Write %d bytes to offset %d\n", buflen, filep->f_pos); + + /* Sanity checks */ + + DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL); + + /* Recover the open file state from the struct file instance */ + + wrfile = (FAR struct nxffs_wrfile_s *)filep->f_priv; + + /* Recover the volume state from the open file */ + + 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; + } + + /* Check if the file was opened with write access */ + +#ifdef CONFIG_DEBUG + if ((wrfile->ofile.mode & O_WROK) == 0) + { + fdbg("File not open for write access\n"); + ret = -EACCES; + goto errout_with_semaphore; + } +#endif + + /* Seek to the current file offset */ + + nxffs_ioseek(volume, wrfile->dathdr + wrfile->wrlen); + + /* Write data to that file offset */ + + ret = nxffs_wrdata(volume, (FAR const uint8_t*)buffer, buflen); + if (ret > 0) + { + /* Update the file offset */ + + filep->f_pos += ret; + } +#warning "Add check for block full" + +errout_with_semaphore: + sem_post(&volume->exclsem); +errout: + return ret; +} -- cgit v1.2.3