aboutsummaryrefslogtreecommitdiff
path: root/nuttx/fs/nxffs
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/fs/nxffs')
-rw-r--r--nuttx/fs/nxffs/Kconfig51
-rw-r--r--nuttx/fs/nxffs/Make.defs49
-rw-r--r--nuttx/fs/nxffs/README.txt180
-rw-r--r--nuttx/fs/nxffs/nxffs.h1084
-rw-r--r--nuttx/fs/nxffs/nxffs_block.c186
-rw-r--r--nuttx/fs/nxffs/nxffs_blockstats.c152
-rw-r--r--nuttx/fs/nxffs/nxffs_cache.c261
-rw-r--r--nuttx/fs/nxffs/nxffs_dirent.c217
-rw-r--r--nuttx/fs/nxffs/nxffs_dump.c479
-rw-r--r--nuttx/fs/nxffs/nxffs_initialize.c522
-rw-r--r--nuttx/fs/nxffs/nxffs_inode.c502
-rw-r--r--nuttx/fs/nxffs/nxffs_ioctl.c150
-rw-r--r--nuttx/fs/nxffs/nxffs_open.c1322
-rw-r--r--nuttx/fs/nxffs/nxffs_pack.c1572
-rw-r--r--nuttx/fs/nxffs/nxffs_read.c473
-rw-r--r--nuttx/fs/nxffs/nxffs_reformat.c267
-rw-r--r--nuttx/fs/nxffs/nxffs_stat.c186
-rw-r--r--nuttx/fs/nxffs/nxffs_unlink.c187
-rw-r--r--nuttx/fs/nxffs/nxffs_util.c181
-rw-r--r--nuttx/fs/nxffs/nxffs_write.c853
20 files changed, 0 insertions, 8874 deletions
diff --git a/nuttx/fs/nxffs/Kconfig b/nuttx/fs/nxffs/Kconfig
deleted file mode 100644
index 9f4ef8231..000000000
--- a/nuttx/fs/nxffs/Kconfig
+++ /dev/null
@@ -1,51 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see misc/tools/kconfig-language.txt.
-#
-
-config FS_NXFFS
- bool "NXFFS file system"
- default n
- depends on !DISABLE_MOUNTPOINT
- ---help---
- Enable NuttX FLASH file system (NXFF) support.
-
-if FS_NXFFS
-config NXFFS_ERASEDSTATE
- hex "FLASH erased state"
- default 0xff
- ---help---
- The erased state of FLASH.
- This must have one of the values of 0xff or 0x00.
- Default: 0xff.
-
-config NXFFS_PACKTHRESHOLD
- int "Re-packing threshold"
- default 32
- ---help---
- When packing flash file data,
- don't both with file chunks smaller than this number of data bytes.
- Default: 32.
-
-config NXFFS_MAXNAMLEN
- int "Maximum file name length"
- default 255
- ---help---
- The maximum size of an NXFFS file name.
- Default: 255.
-
-config NXFFS_TAILTHRESHOLD
- int "Tail threshold"
- default 8192
- ---help---
- clean-up can either mean
- packing files together toward the end of the file or, if file are
- deleted at the end of the file, clean up can simply mean erasing
- the end of FLASH memory so that it can be re-used again. However,
- doing this can also harm the life of the FLASH part because it can
- mean that the tail end of the FLASH is re-used too often. This
- threshold determines if/when it is worth erased the tail end of FLASH
- and making it available for re-use (and possible over-wear).
- Default: 8192.
-
-endif
diff --git a/nuttx/fs/nxffs/Make.defs b/nuttx/fs/nxffs/Make.defs
deleted file mode 100644
index ccf1ba661..000000000
--- a/nuttx/fs/nxffs/Make.defs
+++ /dev/null
@@ -1,49 +0,0 @@
-############################################################################
-# fs/nxffs/Make.defs
-#
-# Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# Redistribution and use in source and binary forms, with or without
-# 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.
-#
-############################################################################
-
-ifeq ($(CONFIG_FS_NXFFS),y)
-ASRCS +=
-CSRCS += nxffs_block.c nxffs_blockstats.c nxffs_cache.c nxffs_dirent.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
-
-# Include NXFFS build support
-
-DEPPATH += --dep-path nxffs
-VPATH += :nxffs
-CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)fs$(DELIM)nxffs}
-
-endif
diff --git a/nuttx/fs/nxffs/README.txt b/nuttx/fs/nxffs/README.txt
deleted file mode 100644
index a10fb97a5..000000000
--- a/nuttx/fs/nxffs/README.txt
+++ /dev/null
@@ -1,180 +0,0 @@
-NXFFS README
-^^^^^^^^^^^^
-
-This README file contains information about the implemenation of the NuttX
-wear-leveling FLASH file system, NXFFS.
-
-Contents:
-
- General NXFFS organization
- General operation
- Headers
- NXFFS Limitations
- Multiple Writers
- ioctls
- Things to Do
-
-General NXFFS organization
-==========================
-
-The following example assumes 4 logical blocks per FLASH erase block. The
-actual relationship is determined by the FLASH geometry reported by the MTD
-driver.
-
-ERASE LOGICAL Inodes begin with a inode header. inode may
-BLOCK BLOCK CONTENTS be marked as "deleted," pending re-packing.
- n 4*n --+--------------+
- |BBBBBBBBBBBBBB| Logic block header
- |IIIIIIIIIIIIII| Inodes begin with a inode header
- |DDDDDDDDDDDDDD| Data block containing inode data block
- | (Inode Data) |
- 4*n+1 --+--------------+
- |BBBBBBBBBBBBBB| Logic block header
- |DDDDDDDDDDDDDD| Inodes may consist of multiple data blocks
- | (Inode Data) |
- |IIIIIIIIIIIIII| Next inode header
- | | Possibly a few unused bytes at the end of a block
- 4*n+2 --+--------------+
- |BBBBBBBBBBBBBB| Logic block header
- |DDDDDDDDDDDDDD|
- | (Inode Data) |
- 4*n+3 --+--------------+
- |BBBBBBBBBBBBBB| Logic block header
- |IIIIIIIIIIIIII| Next inode header
- |DDDDDDDDDDDDDD|
- | (Inode Data) |
- n+1 4*(n+1) --+--------------+
- |BBBBBBBBBBBBBB| Logic block header
- | | All FLASH is unused after the end of the final
- | | inode.
- --+--------------+
-
-General operation
-=================
-
- Inodes are written starting at the beginning of FLASH. As inodes are
- deleted, they are marked as deleted but not removed. As new inodes are
- written, allocations proceed to toward the end of the FLASH -- thus,
- supporting wear leveling by using all FLASH blocks equally.
-
- When the FLASH becomes full (no more space at the end of the FLASH), a
- re-packing operation must be performed: All inodes marked deleted are
- finally removed and the remaining inodes are packed at the beginning of
- the FLASH. Allocations then continue at the freed FLASH memory at the
- end of the FLASH.
-
-Headers
-=======
- BLOCK HEADER:
- The block header is used to determine if the block has every been
- formatted and also indicates bad blocks which should never be used.
-
- INODE HEADER:
- Each inode begins with an inode header that contains, among other things,
- the name of the inode, the offset to the first data block, and the
- length of the inode data.
-
- At present, the only kind of inode support is a file. So for now, the
- term file and inode are interchangeable.
-
- INODE DATA HEADER:
- Inode data is enclosed in a data header. For a given inode, there
- is at most one inode data block per logical block. If the inode data
- spans more than one logical block, then the inode data may be enclosed
- in multiple data blocks, one per logical block.
-
-NXFFS Limitations
-=================
-
-This implementation is very simple as, as a result, has several limitations
-that you should be aware before opting to use NXFFS:
-
-1. Since the files are contiguous in FLASH and since allocations always
- proceed toward the end of the FLASH, there can only be one file opened
- for writing at a time. Multiple files may be opened for reading.
-
-2. Files may not be increased in size after they have been closed. The
- O_APPEND open flag is not supported.
-
-3. Files are always written sequential. Seeking within a file opened for
- writing will not work.
-
-4. There are no directories, however, '/' may be used within a file name
- string providing some illusion of directories.
-
-5. Files may be opened for reading or for writing, but not both: The O_RDWR
- open flag is not supported.
-
-6. The re-packing 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.
-
-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.
-
-ioctls
-======
-
-The file system supports to ioctls:
-
-FIOC_REFORMAT: Will force the flash to be erased and a fresh, empty
- NXFFS file system to be written on it.
-FIOC_OPTIMIZE: Will force immediate repacking of the file system. This
- will increase the amount of wear on the FLASH if you use this!
-
-Things to Do
-============
-
-- 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 inefficiency 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.
-- Fault tolerance must be improved. We need to be absolutely certain that
- any FLASH errors do not cause the file system to behavior incorrectly.
-- Wear leveling might be improved (?). Files are re-packed at the front
- of FLASH as part of the clean-up operation. However, that means the files
- that are not modified often become fixed in place at the beginning of
- FLASH. This reduces the size of the pool moving files at the end of the
- FLASH. As the file system becomes more filled with fixed files at the
- front of the device, the level of wear on the blocks at the end of the
- FLASH increases.
-- When the time comes to reorganization the FLASH, the system may be
- inavailable for a long time. That is a bad behavior. What is needed,
- I think, is a garbage collection task that runs periodically so that
- when the big reorganizaiton event occurs, most of the work is already
- done. That garbarge collection should search for valid blocks that no
- longer contain valid data. It should pre-erase them, put them in
- a good but empty state... all ready for file system re-organization.
-
-
-
diff --git a/nuttx/fs/nxffs/nxffs.h b/nuttx/fs/nxffs/nxffs.h
deleted file mode 100644
index 083e00fa7..000000000
--- a/nuttx/fs/nxffs/nxffs.h
+++ /dev/null
@@ -1,1084 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs.h
- *
- * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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.
- *
- ****************************************************************************/
-
-#ifndef __FS_NXFFS_NXFFS_H
-#define __FS_NXFFS_NXFFS_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <semaphore.h>
-
-#include <nuttx/mtd.h>
-#include <nuttx/fs/nxffs.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-/* NXFFS Definitions ********************************************************/
-/* General NXFFS organization. The following example assumes 4 logical
- * blocks per FLASH erase block. The actual relationship is determined by
- * the FLASH geometry reported by the MTD driver.
- *
- * ERASE LOGICAL Inodes begin with a inode header. inode may
- * BLOCK BLOCK CONTENTS be marked as "deleted," pending re-packing.
- * n 4*n --+--------------+
- * |BBBBBBBBBBBBBB| Logic block header
- * |IIIIIIIIIIIIII| Inodes begin with a inode header
- * |DDDDDDDDDDDDDD| Data block containing inode data block
- * | (Inode Data) |
- * 4*n+1 --+--------------+
- * |BBBBBBBBBBBBBB| Logic block header
- * |DDDDDDDDDDDDDD| Inodes may consist of multiple data blocks
- * | (Inode Data) |
- * |IIIIIIIIIIIIII| Next inode header
- * | | Possibly a few unused bytes at the end of a block
- * 4*n+2 --+--------------+
- * |BBBBBBBBBBBBBB| Logic block header
- * |DDDDDDDDDDDDDD|
- * | (Inode Data) |
- * 4*n+3 --+--------------+
- * |BBBBBBBBBBBBBB| Logic block header
- * |IIIIIIIIIIIIII| Next inode header
- * |DDDDDDDDDDDDDD|
- * | (Inode Data) |
- * n+1 4*(n+1) --+--------------+
- * |BBBBBBBBBBBBBB| Logic block header
- * | | All FLASH is unused after the end of the final
- * | | inode.
- * --+--------------+
- *
- * General operation:
- * Inodes are written starting at the beginning of FLASH. As inodes are
- * deleted, they are marked as deleted but not removed. As new inodes are
- * written, allocations proceed to toward the end of the FLASH -- thus,
- * supporting wear leveling by using all FLASH blocks equally.
- *
- * When the FLASH becomes full (no more space at the end of the FLASH), a
- * re-packing operation must be performed: All inodes marked deleted are
- * finally removed and the remaining inodes are packed at the beginning of
- * the FLASH. Allocations then continue at the freed FLASH memory at the
- * end of the FLASH.
- *
- * BLOCK HEADER:
- * The block header is used to determine if the block has every been
- * formatted and also indicates bad blocks which should never be used.
- *
- * INODE HEADER:
- * Each inode begins with an inode header that contains, among other things,
- * the name of the inode, the offset to the first data block, and the
- * length of the inode data.
- *
- * At present, the only kind of inode support is a file. So for now, the
- * term file and inode are interchangeable.
- *
- * INODE DATA HEADER:
- * Inode data is enclosed in a data header. For a given inode, there
- * is at most one inode data block per logical block. If the inode data
- * spans more than one logical block, then the inode data may be enclosed
- * in multiple data blocks, one per logical block.
- *
- * NXFFS Limitations:
- * 1. Since the files are contiguous in FLASH and since allocations always
- * proceed toward the end of the FLASH, there can only be one file opened
- * for writing at a time. Multiple files may be opened for reading.
- * 2. Files may not be increased in size after they have been closed. The
- * O_APPEND open flag is not supported.
- * 3. Files are always written sequential. Seeking within a file opened for
- * writing will not work.
- * 4. There are no directories, however, '/' may be used within a file name
- * string providing some illusion of directories.
- * 5. Files may be opened for reading or for writing, but not both: The O_RDWR
- * open flag is not supported.
- * 6. The re-packing 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
- * three, states:
- *
- * 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 ^ 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.
- * Other values - The inode is bad and has an invalid state.
- *
- * Care is taken so that the VALID to DELETED transition only involves burning
- * bits from the erased to non-erased state.
- */
-
-#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 */
-
-#define NXFFS_MAGICSIZE 4
-
-/* When we allocate FLASH for a new inode data block, we will require that
- * space is available to hold this minimum number of data bytes in addition
- * to the size of the data block headeer.
- */
-
-#define NXFFS_MINDATA 16
-
-/* Internal definitions *****************************************************/
-/* If we encounter this number of erased bytes, we assume that all of the
- * flash beyond this point is erased.
- */
-
-#define NXFFS_NERASED 128
-
-/* Quasi-standard definitions */
-
-#ifndef MIN
-# define MIN(a,b) (a < b ? a : b)
-#endif
-
-#ifndef MAX
-# define MAX(a,b) (a > b ? a : b)
-#endif
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/* This structure defines each packed block on the FLASH media */
-
-struct nxffs_block_s
-{
- uint8_t magic[4]; /* 0-3: Magic number for valid block */
- uint8_t state; /* 4: Block state: See BLOCK_STATE_* */
-};
-#define SIZEOF_NXFFS_BLOCK_HDR 5
-
-/* This structure defines each packed NXFFS inode header on the FLASH media */
-
-struct nxffs_inode_s
-{
- uint8_t magic[4]; /* 0-3: Magic number for valid inode */
- uint8_t state; /* 4: Inode state: See INODE_STATE_* */
- uint8_t namlen; /* 5: Length of the inode name */
- uint8_t noffs[4]; /* 6-9: FLASH offset to the file name */
- uint8_t doffs[4]; /* 10-13: FLASH offset to the first data block */
- uint8_t utc[4]; /* 14-17: Creation time */
- uint8_t crc[4]; /* 18-21: CRC32 */
- uint8_t datlen[4]; /* 22-25: Length of data in bytes */
-};
-#define SIZEOF_NXFFS_INODE_HDR 26
-
-/* This structure defines each packed NXFFS data header on the FLASH media */
-
-struct nxffs_data_s
-{
- uint8_t magic[4]; /* 0-3: Magic number for valid data */
- uint8_t crc[4]; /* 4-7: CRC32 */
- uint8_t datlen[2]; /* 8-9: Length of data in bytes */
-};
-#define SIZEOF_NXFFS_DATA_HDR 10
-
-/* This is an in-memory representation of the NXFFS inode as extracted from
- * FLASH and with additional state information.
- */
-
-struct nxffs_entry_s
-{
- off_t hoffset; /* FLASH offset to the inode header */
- off_t noffset; /* FLASH offset to the inode name */
- off_t doffset; /* FLASH offset to the first data header */
- FAR char *name; /* inode name */
- uint32_t utc; /* Time stamp */
- 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.
- */
-
-struct nxffs_ofile_s
-{
- struct nxffs_ofile_s *flink; /* Supports a singly linked list */
- int16_t crefs; /* Reference count */
- mode_t oflags; /* Open mode */
- struct nxffs_entry_s entry; /* Describes the NXFFS inode entry */
-};
-
-/* A file opened for writing require some additional information */
-
-struct nxffs_wrfile_s
-{
- /* The following fields provide the common open file information. */
-
- struct nxffs_ofile_s ofile;
-
- /* 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 */
- off_t doffset; /* FLASH offset to the current data header */
- uint32_t crc; /* Accumulated data block CRC */
-};
-
-/* This structure represents the overall state of on NXFFS instance. */
-
-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 blkper; /* R/W blocks per erase block */
- uint16_t iooffset; /* Next offset in read/write access (in ioblock) */
- off_t inoffset; /* Offset to the first valid inode header */
- off_t froffset; /* Offset to the first free byte */
- off_t nblocks; /* Number of R/W blocks on volume */
- off_t ioblock; /* Current block number being accessed */
- 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; /* On cached erase block for general I/O */
- FAR uint8_t *pack; /* A full erase block to support packing */
-};
-
-/* This structure describes the state of the blocks on the NXFFS volume */
-
-struct nxffs_blkstats_s
-{
- off_t nblocks; /* Total number of FLASH blocks */
- off_t ngood; /* Number of good FLASH blocks found */
- off_t nbad; /* Number of well-formatted FLASH blocks marked as bad */
- off_t nunformat; /* Number of unformatted FLASH blocks */
- off_t ncorrupt; /* Number of blocks with correupted format info */
-};
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/* The magic number that appears that the beginning of each NXFFS (logical)
- * block
- */
-
-extern const uint8_t g_blockmagic[NXFFS_MAGICSIZE];
-
-/* The magic number that appears that the beginning of each NXFFS inode */
-
-extern const uint8_t g_inodemagic[NXFFS_MAGICSIZE];
-
-/* The magic number that appears that the beginning of each NXFFS inode
- * data block.
- */
-
-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
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_limits
- *
- * Description:
- * Recalculate file system limits: (1) the FLASH offset to the first,
- * valid inode, and (2) the FLASH offset to the first, unused byte after
- * the last inode (invalid or not).
- *
- * The first, lower limit must be recalculated: (1) initially, (2)
- * whenever the first inode is deleted, or (3) whenever inode is moved
- * as part of the file system packing operation.
- *
- * The second, upper limit must be (1) incremented whenever new file
- * data is written, or (2) recalculated as part of the file system packing
- * operation.
- *
- * Input Parameters:
- * volume - Identifies the NXFFS volume
- *
- * Returned Value:
- * Zero on success. Otherwise, a negated error is returned indicating the
- * nature of the failure.
- *
- * Defined in nxffs_initialize.c
- *
- ****************************************************************************/
-
-extern int nxffs_limits(FAR struct nxffs_volume_s *volume);
-
-/****************************************************************************
- * Name: nxffs_rdle16
- *
- * Description:
- * Get a (possibly unaligned) 16-bit little endian value.
- *
- * Input Parameters:
- * val - A pointer to the first byte of the little endian value.
- *
- * Returned Values:
- * A uint16_t representing the whole 16-bit integer value
- *
- * Defined in nxffs_util.c
- *
- ****************************************************************************/
-
-extern uint16_t nxffs_rdle16(FAR const uint8_t *val);
-
-/****************************************************************************
- * Name: nxffs_wrle16
- *
- * Description:
- * Put a (possibly unaligned) 16-bit little endian value.
- *
- * Input Parameters:
- * dest - A pointer to the first byte to save the little endian value.
- * val - The 16-bit value to be saved.
- *
- * Returned Values:
- * None
- *
- * Defined in nxffs_util.c
- *
- ****************************************************************************/
-
-extern void nxffs_wrle16(uint8_t *dest, uint16_t val);
-
-/****************************************************************************
- * Name: nxffs_rdle32
- *
- * Description:
- * Get a (possibly unaligned) 32-bit little endian value.
- *
- * Input Parameters:
- * val - A pointer to the first byte of the little endian value.
- *
- * Returned Values:
- * A uint32_t representing the whole 32-bit integer value
- *
- * Defined in nxffs_util.c
- *
- ****************************************************************************/
-
-extern uint32_t nxffs_rdle32(FAR const uint8_t *val);
-
-/****************************************************************************
- * Name: nxffs_wrle32
- *
- * Description:
- * Put a (possibly unaligned) 32-bit little endian value.
- *
- * Input Parameters:
- * dest - A pointer to the first byte to save the little endian value.
- * val - The 32-bit value to be saved.
- *
- * Returned Value:
- * None
- *
- * Defined in nxffs_util.c
- *
- ****************************************************************************/
-
-extern void nxffs_wrle32(uint8_t *dest, uint32_t val);
-
-/****************************************************************************
- * Name: nxffs_erased
- *
- * Description:
- * Check if a block of memory is in the erased state.
- *
- * Input Parameters:
- * buffer - Address of the start of the memory to check.
- * buflen - The number of bytes to check.
- *
- * Returned Values:
- * The number of erased bytes found at the beginning of the memory region.
- *
- * Defined in nxffs_util.c
- *
- ****************************************************************************/
-
-extern size_t nxffs_erased(FAR const uint8_t *buffer, size_t buflen);
-
-/****************************************************************************
- * Name: nxffs_rdcache
- *
- * Description:
- * Read one I/O block into the volume cache memory.
- *
- * Input Parameters:
- * volume - Describes the current volume
- * block - The first logical block to read
- *
- * Returned Value:
- * Negated errnos are returned only in the case of MTD reported failures.
- * Nothing in the volume data itself will generate errors.
- *
- * Defined in nxffs_cache.c
- *
- ****************************************************************************/
-
-extern int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block);
-
-/****************************************************************************
- * Name: nxffs_wrcache
- *
- * Description:
- * Write one or more logical blocks from the volume cache memory.
- *
- * Input Parameters:
- * volume - Describes the current volume
- *
- * Returned Value:
- * Negated errnos are returned only in the case of MTD reported failures.
- *
- * Defined in nxffs_cache.c
- *
- ****************************************************************************/
-
-extern int nxffs_wrcache(FAR struct nxffs_volume_s *volume);
-
-/****************************************************************************
- * Name: nxffs_ioseek
- *
- * Description:
- * Seek to a position in FLASH memory. This simply sets up the offsets
- * and pointer values. This is a necessary step prior to using
- * nxffs_getc().
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * offset - The physical offset in bytes from the beginning of the FLASH
- * in bytes.
- *
- * Defined in nxffs_cache.c
- *
- ****************************************************************************/
-
-extern void nxffs_ioseek(FAR struct nxffs_volume_s *volume, off_t offset);
-
-/****************************************************************************
- * Name: nxffs_iotell
- *
- * Description:
- * Report the current position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- *
- * Returned Value:
- * The offset from the beginning of FLASH to the current seek position.
- *
- * Defined in nxffs_cache.c
- *
- ****************************************************************************/
-
-extern off_t nxffs_iotell(FAR struct nxffs_volume_s *volume);
-
-/****************************************************************************
- * Name: nxffs_getc
- *
- * Description:
- * Get the next byte from 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. The paramters ioblock and iooffset
- * in the volume structure determine the behavior of nxffs_getc().
- * reserve - If less than this much space is available at the end of the
- * block, then skip to the next block.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno indicating the
- * nature of the failure.
- *
- * Defined in nxffs_cache.c
- *
- ****************************************************************************/
-
-extern int nxffs_getc(FAR struct nxffs_volume_s *volume, uint16_t reserve);
-
-/****************************************************************************
- * Name: nxffs_freeentry
- *
- * Description:
- * The inode values returned by nxffs_nextentry() include allocated memory
- * (specifically, the file name string). This function should be called
- * to dispose of that memory when the inode entry is no longer needed.
- *
- * Note that the nxffs_entry_s containing structure is not freed. The
- * caller may call kfree upon return of this function if necessary to
- * free the entry container.
- *
- * Input parameters:
- * entry - The entry to be freed.
- *
- * Returned Value:
- * None
- *
- * Defined in nxffs_inode.c
- *
- ****************************************************************************/
-
-extern void nxffs_freeentry(FAR struct nxffs_entry_s *entry);
-
-/****************************************************************************
- * Name: nxffs_nextentry
- *
- * Description:
- * Search for the next valid inode starting at the provided FLASH offset.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- * 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.
- *
- * Defined in nxffs_inode.c
- *
- ****************************************************************************/
-
-extern int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR struct nxffs_entry_s *entry);
-
-/****************************************************************************
- * Name: nxffs_findinode
- *
- * Description:
- * Search for an inode with the provided name starting with the first
- * valid inode and proceeding to the end FLASH or until the matching
- * inode is found.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * name - The name of the inode to find
- * entry - The location to return information about the inode.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno is returned
- * that indicates the nature of the failure.
- *
- * Defined in nxffs_inode.c
- *
- ****************************************************************************/
-
-extern int nxffs_findinode(FAR struct nxffs_volume_s *volume,
- FAR const char *name,
- FAR struct nxffs_entry_s *entry);
-
-/****************************************************************************
- * Name: nxffs_inodeend
- *
- * Description:
- * Return an *approximiate* FLASH offset to end of the inode data. The
- * returned value is guaranteed to be be less then or equal to the offset
- * of the thing-of-interest in FLASH. Parsing for interesting things
- * can begin at that point.
- *
- * Assumption: The inode header has been verified by the caller and is
- * known to contain valid data.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * entry - Describes the inode.
- *
- * Returned Value:
- * A FLASH offset to the (approximate) end of the inode data. No errors
- * are detected.
- *
- * Defined in nxffs_inode.c
- *
- ****************************************************************************/
-
-extern off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry);
-
-/****************************************************************************
- * Name: nxffs_verifyblock
- *
- * Description:
- * Assure the the provided (logical) block number is in the block cache
- * and that it has a valid block header (i.e., proper magic and
- * marked good)
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * block - The (logical) block number to load and verify.
- *
- * Returned Values:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure.
- *
- * Defined in nxffs_block.c
- *
- ****************************************************************************/
-
-extern int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block);
-
-/****************************************************************************
- * Name: nxffs_validblock
- *
- * Description:
- * Find the next valid (logical) block in the volume.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * block - On entry, this provides the starting block number. If the
- * function is succesfful, then this memory location will hold the
- * block number of the next valid block on return.
- *
- * Returned Value:
- * Zero on success otherwise a negated errno value indicating the nature
- * of the failure.
- *
- * Defined in nxffs_block.c
- *
- ****************************************************************************/
-
-extern int nxffs_validblock(struct nxffs_volume_s *volume, off_t *block);
-
-/****************************************************************************
- * Name: nxffs_blockstats
- *
- * Description:
- * Analyze the NXFFS volume. This operation must be performed when the
- * volume is first mounted in order to detect if the volume has been
- * formatted and contains a usable NXFFS file system.
- *
- * Input Parameters:
- * volume - Describes the current NXFFS volume.
- * stats - On return, will hold nformation describing the state of the
- * volume.
- *
- * Returned Value:
- * Negated errnos are returned only in the case of MTD reported failures.
- * Nothing in the volume data itself will generate errors.
- *
- * Defined in nxffs_blockstats.c
- *
- ****************************************************************************/
-
-extern int nxffs_blockstats(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_blkstats_s *stats);
-
-/****************************************************************************
- * Name: nxffs_reformat
- *
- * Description:
- * Erase and reformat the entire volume. Verify each block and mark
- * improperly erased blocks as bad.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume to be reformatted.
- *
- * Returned Value:
- * Zero on success or a negated errno on a failure. Failures will be
- * returned n the case of MTD reported failures o.
- * Nothing in the volume data itself will generate errors.
- *
- * Defined in nxffs_reformat.c
- *
- ****************************************************************************/
-
-extern int nxffs_reformat(FAR struct nxffs_volume_s *volume);
-
-/****************************************************************************
- * Name: nxffs_findofile
- *
- * Description:
- * Search the list of already opened files to see if the inode of this
- * name is one of the opened files.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- * name - The name of the inode to check.
- *
- * Returned Value:
- * If an inode of this name is found in the list of opened inodes, then
- * a reference to the open file structure is returned. NULL is returned
- * otherwise.
- *
- * Defined in nxffs_open.c
- *
- ****************************************************************************/
-
-extern FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volume,
- FAR const char *name);
-
-/****************************************************************************
- * Name: nxffs_findwriter
- *
- * Description:
- * Search the list of already opened files and return the open file
- * instance for the write.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- *
- * Returned Value:
- * If there is an active writer of the volume, its open file instance is
- * returned. NULL is returned otherwise.
- *
- * Defined in nxffs_open.c
- *
- ****************************************************************************/
-
-extern FAR struct nxffs_wrfile_s *nxffs_findwriter(FAR struct nxffs_volume_s *volume);
-
-/****************************************************************************
- * Name: nxffs_wrinode
- *
- * Description:
- * Write the inode header (only to FLASH. This is done in two contexts:
- *
- * 1. When an inode is closed, or
- * 2. As part of the file system packing logic when an inode is moved.
- *
- * Note that in either case, the inode name has already been written to
- * FLASH.
- *
- * Input parameters
- * volume - Describes the NXFFS volume
- * entry - Describes the inode header to write
- *
- * Returned Value:
- * Zero is returned on success; Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- * Defined in nxffs_open.c
- *
- ****************************************************************************/
-
-extern int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry);
-
-/****************************************************************************
- * Name: nxffs_updateinode
- *
- * Description:
- * The packing logic has moved an inode. Check if any open files are using
- * this inode and, if so, move the data in the open file structure as well.
- *
- * Input parameters
- * volume - Describes the NXFFS volume
- * entry - Describes the new inode entry
- *
- * Returned Value:
- * Zero is returned on success; Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- ****************************************************************************/
-
-extern int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry);
-
-/****************************************************************************
- * Name: nxffs_wrreserve
- *
- * Description:
- * Find a valid location for a file system object of 'size'. A valid
- * location will have these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire object
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the checks of 1) and 2). The
- * end-of-filesystem offset, froffset, is update past this memory which,
- * in effect, reserves the memory.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * size - The size of the object to be reserved.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * candidate oject position
- * volume->iooffset - The offset in the block to the candidate object
- * position.
- * volume->froffset - Updated offset to the first free FLASH block after
- * the reserved memory.
- *
- * Defined in nxffs_write.c
- *
- ****************************************************************************/
-
-extern int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size);
-
-/****************************************************************************
- * Name: nxffs_wrverify
- *
- * Description:
- * Find a valid location for the object. A valid location will have
- * these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire header
- * (excluding the file name which may lie in the next block).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the check 3). On entry it assumes the
- * following settings (left by nxffs_wrreserve()):
- *
- * volume->ioblock - Read/write block number of the block containing the
- * candidate oject position
- * volume->iooffset - The offset in the block to the candidate object
- * position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * size - The size of the object to be verifed.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * verified object position
- * volume->iooffset - The offset in the block to the verified object
- * 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);
-
-/****************************************************************************
- * Name: nxffs_wrblkhdr
- *
- * Description:
- * Write the block header information. This is done (1) whenever the end-
- * block is encountered and (2) also when the file is closed in order to
- * flush the final block of data to FLASH.
- *
- * Input Parameters:
- * volume - Describes the state of the NXFFS volume
- * wrfile - Describes the state of the open file
- *
- * Returned Value:
- * Zero is returned on success; Otherwise, a negated errno value is
- * returned to indicate the nature of the failure.
- *
- * Defined in nxffs_write.c
- *
- ****************************************************************************/
-
-extern int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile);
-
-/****************************************************************************
- * 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_rdblkhdr
- *
- * Description:
- * Read and verify the data block header at the specified offset.
- *
- * Input Parameters:
- * volume - Describes the current volume.
- * offset - The byte offset from the beginning of FLASH where the data block
- * header is expected.
- * datlen - A memory location to return the data block length.
- *
- * Returned Value:
- * Zero on success. Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- * Defined in nxffs_read.c
- *
- ****************************************************************************/
-
-extern int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR uint16_t *datlen);
-
-/****************************************************************************
- * Name: nxffs_rminode
- *
- * Description:
- * Remove an inode from FLASH. This is the internal implementation of
- * the file system unlinke operation.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- * name - the name of the inode to be deleted.
- *
- * Returned Value:
- * Zero is returned if the inode is successfully deleted. Otherwise, a
- * negated errno value is returned indicating the nature of the failure.
- *
- ****************************************************************************/
-
-extern int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name);
-
-/****************************************************************************
- * Name: nxffs_pack
- *
- * Description:
- * Pack and re-write the filesystem in order to free up memory at the end
- * of FLASH.
- *
- * 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.
- *
- ****************************************************************************/
-
-extern int nxffs_pack(FAR struct nxffs_volume_s *volume);
-
-/****************************************************************************
- * Standard mountpoint operation methods
- *
- * Description:
- * See include/nuttx/fs/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_dup() is defined in nxffs_open.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
- *
- ****************************************************************************/
-
-struct file; /* Forward references */
-struct inode;
-struct fs_dirent_s;
-struct statfs;
-struct stat;
-
-int nxffs_open(FAR struct file *filep, FAR const char *relpath, int oflags,
- mode_t mode);
-int nxffs_close(FAR struct file *filep);
-ssize_t nxffs_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
-ssize_t nxffs_write(FAR struct file *filep, FAR const char *buffer,
- size_t buflen);
-int nxffs_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
-int nxffs_dup(FAR const struct file *oldp, FAR struct file *newp);
-int nxffs_opendir(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct fs_dirent_s *dir);
-int nxffs_readdir(FAR struct inode *mountpt, FAR struct fs_dirent_s *dir);
-int nxffs_rewinddir(FAR struct inode *mountpt, FAR struct fs_dirent_s *dir);
-int nxffs_bind(FAR struct inode *blkdriver, FAR const void *data,
- FAR void **handle);
-int nxffs_unbind(FAR void *handle, FAR struct inode **blkdriver);
-int nxffs_statfs(FAR struct inode *mountpt, FAR struct statfs *buf);
-int nxffs_stat(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct stat *buf);
-int nxffs_unlink(FAR struct inode *mountpt, FAR const char *relpath);
-
-#endif /* __FS_NXFFS_NXFFS_H */
-
-
diff --git a/nuttx/fs/nxffs/nxffs_block.c b/nuttx/fs/nxffs/nxffs_block.c
deleted file mode 100644
index 6701b6e6b..000000000
--- a/nuttx/fs/nxffs/nxffs_block.c
+++ /dev/null
@@ -1,186 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_block.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <errno.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_verifyblock
- *
- * Description:
- * Assure the the provided (logical) block number is in the block cache
- * and that it has a valid block header (i.e., proper magic and
- * marked good)
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * block - The (logical) block number to load and verify.
- *
- * Returned Values:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. -ENOENT is returned
- * if the block is a bad block.
- *
- ****************************************************************************/
-
-int nxffs_verifyblock(FAR struct nxffs_volume_s *volume, off_t block)
-{
- FAR struct nxffs_block_s *blkhdr;
- int ret;
-
- /* Make sure the the block is in the cache */
-
- ret = nxffs_rdcache(volume, block);
- if (ret < 0)
- {
- /* Perhaps we are at the end of the media */
-
- fvdbg("Failed to read data into cache: %d\n", ret);
- return ret;
- }
-
- /* Check if the block has a magic number (meaning that it is not
- * erased) and that it is valid (meaning that it is not marked
- * for deletion)
- */
-
- blkhdr = (FAR struct nxffs_block_s *)volume->cache;
- if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) == 0)
- {
- /* This does appear to be a block */
-
- if (blkhdr->state == BLOCK_STATE_GOOD)
- {
- /* The block is valid */
-
- return OK;
- }
- else if (blkhdr->state == BLOCK_STATE_BAD)
- {
- /* -ENOENT is a special indication that this is a properly marked
- * bad block
- */
-
- return -ENOENT;
- }
- }
-
- /* Whatever is here where a block header should be is invalid */
-
- return -EINVAL;
-}
-
-/****************************************************************************
- * Name: nxffs_validblock
- *
- * Description:
- * Find the next valid (logical) block in the volume.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * block - On entry, this provides the starting block number. If the
- * function is succesfful, then this memory location will hold the
- * block number of the next valid block on return.
- *
- * Returned Value:
- * Zero on success otherwise a negated errno value indicating the nature
- * of the failure.
- *
- ****************************************************************************/
-
-int nxffs_validblock(struct nxffs_volume_s *volume, off_t *block)
-{
- off_t i;
- int ret;
-
- DEBUGASSERT(volume && block);
-
- /* Loop for each possible block or until a valid block is found */
-
- for (i = *block; i < volume->nblocks; i++)
- {
- /* Loop until we find a valid block */
-
- ret = nxffs_verifyblock(volume, i);
- if (ret == OK)
- {
- /* We found it, return the block number */
-
- *block = i;
- return OK;
- }
- }
-
- /* ENOSPC is special return value that means that there is no further,
- * valid blocks left in the volume.
- */
-
- fdbg("No valid block found\n");
- return -ENOSPC;
-}
diff --git a/nuttx/fs/nxffs/nxffs_blockstats.c b/nuttx/fs/nxffs/nxffs_blockstats.c
deleted file mode 100644
index 348374e67..000000000
--- a/nuttx/fs/nxffs/nxffs_blockstats.c
+++ /dev/null
@@ -1,152 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_blockstats.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <errno.h>
-#include <debug.h>
-
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_blockstats
- *
- * Description:
- * Analyze the NXFFS volume. This operation must be performed when the
- * volume is first mounted in order to detect if the volume has been
- * formatted and contains a usable NXFFS file system.
- *
- * Input Parameters:
- * volume - Describes the current NXFFS volume.
- * stats - On return, will hold nformation describing the state of the
- * volume.
- *
- * Returned Value:
- * Negated errnos are returned only in the case of MTD reported failures.
- * Nothing in the volume data itself will generate errors.
- *
- ****************************************************************************/
-
-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 */
- int ret;
-
- /* Process each erase block */
-
- memset(stats, 0, sizeof(struct nxffs_blkstats_s));
-
- for (ioblock = 0; ioblock < volume->nblocks; ioblock += volume->blkper)
- {
- /* Read the full erase block */
-
- ret = MTD_BREAD(volume->mtd, ioblock, volume->blkper, volume->pack);
- if (ret < volume->blkper)
- {
- fdbg("Failed to read erase block %d: %d\n", ioblock / volume->blkper, -ret);
- return ret;
- }
-
- /* Process each logical block */
-
- for (bptr = volume->pack, lblock = 0;
- lblock < volume->blkper;
- bptr += volume->geo.blocksize, lblock++)
- {
- FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)bptr;
-
- /* Collect statistics */
-
- stats->nblocks++;
- if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0)
- {
- stats->nunformat++;
- }
- else if (blkhdr->state == BLOCK_STATE_BAD)
- {
- stats->nbad++;
- }
- else if (blkhdr->state == BLOCK_STATE_GOOD)
- {
- stats-> ngood++;
- }
- else
- {
- stats->ncorrupt++;
- }
- }
- }
-
- fdbg("Number blocks: %d\n", stats->nblocks);
- fdbg(" Good blocks: %d\n", stats->ngood);
- fdbg(" Bad blocks: %d\n", stats->nbad);
- fdbg(" Unformatted blocks: %d\n", stats->nunformat);
- fdbg(" Corrupt blocks: %d\n", stats->ncorrupt);
- return OK;
-}
-
-
diff --git a/nuttx/fs/nxffs/nxffs_cache.c b/nuttx/fs/nxffs/nxffs_cache.c
deleted file mode 100644
index 0cc97980e..000000000
--- a/nuttx/fs/nxffs/nxffs_cache.c
+++ /dev/null
@@ -1,261 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_cache.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_rdcache
- *
- * Description:
- * Read one I/O block into the volume block cache memory.
- *
- * Input Parameters:
- * volume - Describes the current volume
- * block - The first logical block to read
- *
- * Returned Value:
- * Negated errnos are returned only in the case of MTD reported failures.
- * Nothing in the volume data itself will generate errors.
- *
- ****************************************************************************/
-
-int nxffs_rdcache(FAR struct nxffs_volume_s *volume, off_t block)
-{
- size_t nxfrd;
-
- /* Check if the requested data is already in the cache */
-
- if (block != volume->cblock)
- {
- /* Read the specified blocks into cache */
-
- nxfrd = MTD_BREAD(volume->mtd, block, 1, volume->cache);
- if (nxfrd != 1)
- {
- fvdbg("Read block %d failed: %d\n", block, nxfrd);
- return -EIO;
- }
-
- /* Remember what is in the cache */
-
- volume->cblock = block;
- }
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_wrcache
- *
- * Description:
- * Write one or more logical blocks from the volume cache memory.
- *
- * Input Parameters:
- * volume - Describes the current volume
- *
- * Returned Value:
- * Negated errnos are returned only in the case of MTD reported failures.
- *
- ****************************************************************************/
-
-int nxffs_wrcache(FAR struct nxffs_volume_s *volume)
-{
- size_t nxfrd;
-
- /* Write the current block from the cache */
-
- nxfrd = MTD_BWRITE(volume->mtd, volume->cblock, 1, volume->cache);
- if (nxfrd != 1)
- {
- fdbg("Write block %d failed: %d\n", volume->cblock, nxfrd);
- return -EIO;
- }
-
- /* Write was successful */
-
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_ioseek
- *
- * Description:
- * Seek to a position in FLASH memory. This simply sets up the offsets
- * and pointer values. This is a necessary step prior to using
- * nxffs_getc().
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * offset - The physical offset in bytes from the beginning of the FLASH
- * in bytes.
- *
- ****************************************************************************/
-
-void nxffs_ioseek(FAR struct nxffs_volume_s *volume, off_t offset)
-{
- /* Convert the offset into a block number and a byte offset into the
- * block.
- */
-
- volume->ioblock = offset / volume->geo.blocksize;
- volume->iooffset = offset - volume->geo.blocksize * volume->ioblock;
-}
-
-/****************************************************************************
- * Name: nxffs_iotell
- *
- * Description:
- * Report the current position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- *
- * Returned Value:
- * The offset from the beginning of FLASH to the current seek position.
- *
- ****************************************************************************/
-
-off_t nxffs_iotell(FAR struct nxffs_volume_s *volume)
-{
- return volume->ioblock * volume->geo.blocksize + volume->iooffset;
-}
-
-/****************************************************************************
- * Name: nxffs_getc
- *
- * Description:
- * Get the next byte from 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. The paramters ioblock and iooffset
- * in the volume structure determine the behavior of nxffs_getc().
- * reserve - If less than this much space is available at the end of the
- * block, then skip to the next block.
- *
- * 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)
-{
- int ret;
-
- DEBUGASSERT(reserve > 0);
-
- /* Loop to skip over bad blocks */
-
- do
- {
- /* Check if we have the reserve amount at the end of the current block */
-
- if (volume->iooffset + reserve > volume->geo.blocksize)
- {
- /* Check for attempt to read past the end of FLASH */
-
- off_t nextblock = volume->ioblock + 1;
- if (nextblock >= volume->nblocks)
- {
- fvdbg("End of FLASH encountered\n");
- return -ENOSPC;
- }
-
- /* Set up the seek to the data just after the header in the
- * next block.
- */
-
- volume->ioblock = nextblock;
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- }
-
- /* Make sure that the block is in the cache. The special error
- * -ENOENT indicates the block was read successfully but was not
- * marked as a good block. In this case we need to skip to the
- * next block. All other errors are fatal.
- */
-
- ret = nxffs_verifyblock(volume, volume->ioblock);
- if (ret < 0 && ret != -ENOENT)
- {
- fvdbg("Failed to read valid data into cache: %d\n", ret);
- return ret;
- }
- }
- while (ret != OK);
-
- /* Return the the character at this offset. Note that on return,
- * iooffset could point to the byte outside of the current block.
- */
-
- ret = (int)volume->cache[volume->iooffset];
- volume->iooffset++;
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_dirent.c b/nuttx/fs/nxffs/nxffs_dirent.c
deleted file mode 100644
index 221549438..000000000
--- a/nuttx/fs/nxffs/nxffs_dirent.c
+++ /dev/null
@@ -1,217 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_dirent.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <dirent.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-#include <nuttx/mtd.h>
-#include <nuttx/fs/dirent.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_opendir
- *
- * Description:
- * Open a directory for read access
- *
- ****************************************************************************/
-
-int nxffs_opendir(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct fs_dirent_s *dir)
-{
- struct nxffs_volume_s *volume;
- int ret;
-
- fvdbg("relpath: \"%s\"\n", relpath ? relpath : "NULL");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover the file system state from the NuttX inode instance */
-
- volume = mountpt->i_private;
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- goto errout;
- }
-
- /* The requested directory must be the volume-relative "root" directory */
-
- if (relpath && relpath[0] != '\0')
- {
- ret = -ENOENT;
- goto errout_with_semaphore;
- }
-
- /* Set the offset to the offset to the first valid inode */
-
- dir->u.nxffs.nx_offset = volume->inoffset;
- ret = OK;
-
-errout_with_semaphore:
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_readdir
- *
- * Description: Read the next directory entry
- *
- ****************************************************************************/
-
-int nxffs_readdir(FAR struct inode *mountpt, FAR struct fs_dirent_s *dir)
-{
- FAR struct nxffs_volume_s *volume;
- FAR struct nxffs_entry_s entry;
- off_t offset;
- int ret;
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover the file system state from the NuttX inode instance */
-
- volume = mountpt->i_private;
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- goto errout;
- }
-
- /* Read the next inode header from the offset */
-
- offset = dir->u.nxffs.nx_offset;
- ret = nxffs_nextentry(volume, offset, &entry);
-
- /* If the read was successful, then handle the reported inode. Note
- * that when the last inode has been reported, the value -ENOENT will
- * be returned.. which is correct for the readdir() method.
- */
-
- if (ret == OK)
- {
- /* Return the filename and file type */
-
- fvdbg("Offset %d: \"%s\"\n", entry.hoffset, entry.name);
- dir->fd_dir.d_type = DTYPE_FILE;
- strncpy(dir->fd_dir.d_name, entry.name, NAME_MAX+1);
-
- /* Discard this entry and set the next offset. */
-
- dir->u.nxffs.nx_offset = nxffs_inodeend(volume, &entry);
- nxffs_freeentry(&entry);
- ret = OK;
- }
-
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_rewindir
- *
- * Description:
- * Reset directory read to the first entry
- *
- ****************************************************************************/
-
-int nxffs_rewinddir(FAR struct inode *mountpt, FAR struct fs_dirent_s *dir)
-{
- FAR struct nxffs_volume_s *volume;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover the file system state from the NuttX inode instance */
-
- volume = mountpt->i_private;
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- goto errout;
- }
-
- /* Reset the offset to the FLASH offset to the first valid inode */
-
- dir->u.nxffs.nx_offset = volume->inoffset;
- ret = OK;
-
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_dump.c b/nuttx/fs/nxffs/nxffs_dump.c
deleted file mode 100644
index 9caac4c4b..000000000
--- a/nuttx/fs/nxffs/nxffs_dump.c
+++ /dev/null
@@ -1,479 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_dump.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <crc32.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/fs/ioctl.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-/* Re-define fdbg so that the output does not have so much diagnostic info.
- * This should still, however, always agree with the defintion in debug.h.
- */
-
-#undef fdbg
-#define fdbg syslog
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-struct nxffs_blkinfo_s
-{
- struct mtd_geometry_s geo;
- FAR uint8_t *buffer;
- off_t nblocks;
- off_t block;
- off_t offset;
- bool verbose;
-};
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const char g_hdrformat[] = " BLOCK:OFFS TYPE STATE LENGTH\n";
-static const char g_format[] = " %5d:%-5d %s %s %5d\n";
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_analyzeinode
- *
- * Description:
- * Analyze one candidate inode found in the block.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
-static inline ssize_t nxffs_analyzeinode(FAR struct nxffs_blkinfo_s *blkinfo,
- int offset)
-{
- FAR struct nxffs_inode_s inode;
- off_t nextblock;
- uint8_t state;
- uint32_t noffs;
- uint32_t doffs;
- uint32_t utc;
- uint32_t ecrc;
- uint32_t datlen;
- uint32_t crc;
- size_t spaceleft;
-
- /* Verify that there is space for an inode header remaining in the block */
-
- if (offset + SIZEOF_NXFFS_INODE_HDR > blkinfo->geo.blocksize)
- {
- /* No.. then this can't be an inode header */
-
- return ERROR;
- }
-
- /* Unpack the header */
-
- memcpy(&inode, &blkinfo->buffer[offset], SIZEOF_NXFFS_INODE_HDR);
- noffs = nxffs_rdle32(inode.noffs);
- doffs = nxffs_rdle32(inode.doffs);
- utc = nxffs_rdle32(inode.utc);
- ecrc = nxffs_rdle32(inode.crc);
- datlen = nxffs_rdle32(inode.datlen);
-
- /* Misc. sanity checks */
-
- if (noffs < blkinfo->offset + offset + SIZEOF_NXFFS_BLOCK_HDR)
- {
- /* The name begins before the inode header. This can't can't be
- * a real inode header (or it is a corrupted one).
- */
-
- return ERROR;
- }
-
-
- /* Can we verify the inode? We need to have the inode name in the same
- * block to do that (or get access to the next block)
- */
-
- if (doffs < blkinfo->offset + offset + SIZEOF_NXFFS_BLOCK_HDR)
- {
- /* The first data block begins before the inode header. This can't can't
- * be a real inode header (or it is a corrupted one).
- */
-
- return ERROR;
- }
-
- spaceleft = (blkinfo->nblocks - blkinfo->block) * blkinfo->geo.blocksize;
- spaceleft -= (offset + SIZEOF_NXFFS_BLOCK_HDR);
- if (datlen > spaceleft)
- {
- /* The data length is greater than what would fit in the rest of FLASH
- * (even ignoring block and data header sizes.
- */
-
- return ERROR;
- }
-
- /* The name begins after the inode header. Does it begin in this block? */
-
- nextblock = blkinfo->offset + blkinfo->geo.blocksize;
- if (noffs > nextblock)
- {
- /* Not than we cannot verify the inode header */
-
- if (blkinfo->verbose)
- {
- fdbg(g_format, blkinfo->block, offset, "INODE", "UNVERFD", datlen);
- }
- return ERROR;
- }
-
- /* The name begins in this block. Does it also end in this block? */
-
- if (noffs + inode.namlen > nextblock)
- {
- /* No.. Assume that this is not an inode. */
-
- return ERROR;
- }
-
- /* Calculate the CRC */
-
- state = inode.state;
- inode.state = CONFIG_NXFFS_ERASEDSTATE;
- nxffs_wrle32(inode.crc, 0);
-
- crc = crc32((FAR const uint8_t *)&inode, SIZEOF_NXFFS_INODE_HDR);
- crc = crc32part(&blkinfo->buffer[noffs - blkinfo->offset], inode.namlen, crc);
-
- if (crc != ecrc)
- {
- fdbg(g_format, blkinfo->block, offset, "INODE", "CRC BAD", datlen);
- return ERROR;
- }
-
- /* If must be a good header */
-
- if (state == INODE_STATE_FILE)
- {
- if (blkinfo->verbose)
- {
- fdbg(g_format, blkinfo->block, offset, "INODE", "OK ", datlen);
- }
- }
- else if (state == INODE_STATE_DELETED)
- {
- if (blkinfo->verbose)
- {
- fdbg(g_format, blkinfo->block, offset, "INODE", "DELETED", datlen);
- }
- }
- else
- {
- fdbg(g_format, blkinfo->block, offset, "INODE", "CORRUPT", datlen);
- }
-
- /* Return the block-relative offset to the next byte after the inode name */
-
- return noffs + inode.namlen - offset - blkinfo->offset;
-}
-#endif
-
-/****************************************************************************
- * Name: nxffs_analyzedata
- *
- * Description:
- * Analyze one candidate inode found in the block.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
-static inline ssize_t nxffs_analyzedata(FAR struct nxffs_blkinfo_s *blkinfo,
- int offset)
-{
- struct nxffs_data_s dathdr;
- uint32_t ecrc;
- uint16_t datlen;
- uint32_t crc;
-
- /* Copy and unpack the data block header */
-
- memcpy(&dathdr, &blkinfo->buffer[offset], SIZEOF_NXFFS_DATA_HDR);
- ecrc = nxffs_rdle32(dathdr.crc);
- datlen = nxffs_rdle16(dathdr.datlen);
-
- /* Sanity checks */
-
- if (offset + SIZEOF_NXFFS_DATA_HDR + datlen > blkinfo->geo.blocksize)
- {
- /* Data does not fit in within the block, this can't be a data block */
-
- return ERROR;
- }
-
- /* Calculate the CRC */
-
- nxffs_wrle32(dathdr.crc, 0);
-
- crc = crc32((FAR const uint8_t *)&dathdr, SIZEOF_NXFFS_DATA_HDR);
- crc = crc32part(&blkinfo->buffer[offset + SIZEOF_NXFFS_DATA_HDR], datlen, crc);
-
- if (crc != ecrc)
- {
- fdbg(g_format, blkinfo->block, offset, "DATA ", "CRC BAD", datlen);
- return ERROR;
- }
-
- /* If must be a good header */
-
- if (blkinfo->verbose)
- {
- fdbg(g_format, blkinfo->block, offset, "DATA ", "OK ", datlen);
- }
- return SIZEOF_NXFFS_DATA_HDR + datlen;
-}
-#endif
-
-/****************************************************************************
- * Name: nxffs_analyze
- *
- * Description:
- * Analyze the content of one block.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
-static inline void nxffs_analyze(FAR struct nxffs_blkinfo_s *blkinfo)
-{
- FAR struct nxffs_block_s *blkhdr;
- ssize_t nbytes;
- int hdrndx;
- int datndx;
- int inndx;
- int i;
-
- /* Verify that there is a header on the block */
-
- blkhdr = (FAR struct nxffs_block_s *)blkinfo->buffer;
- if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0)
- {
- fdbg(g_format, blkinfo->block, 0, "BLOCK", "NO FRMT",
- blkinfo->geo.blocksize);
- }
- else if (blkhdr->state == BLOCK_STATE_GOOD)
- {
- size_t datsize = blkinfo->geo.blocksize - SIZEOF_NXFFS_BLOCK_HDR;
- size_t nerased = nxffs_erased(blkinfo->buffer + SIZEOF_NXFFS_BLOCK_HDR, datsize);
- if (nerased == datsize)
- {
- if (blkinfo->verbose)
- {
- fdbg(g_format, blkinfo->block, 0, "BLOCK", "ERASED ",
- blkinfo->geo.blocksize);
- }
- return;
- }
-#if 0 /* Too much output, to little information */
- else
- {
- fdbg(g_format, blkinfo->block, 0, "BLOCK", "IN USE ",
- blkinfo->geo.blocksize);
- }
-#endif
- }
- else if (blkhdr->state == BLOCK_STATE_BAD)
- {
- fdbg(g_format, blkinfo->block, 0, "BLOCK", "BAD ",
- blkinfo->geo.blocksize);
- }
- else
- {
- fdbg(g_format, blkinfo->block, 0, "BLOCK", "CORRUPT",
- blkinfo->geo.blocksize);
- }
-
- /* Serach for Inode and data block headers. */
-
- inndx = 0;
- datndx = 0;
-
- for (i = SIZEOF_NXFFS_BLOCK_HDR; i < blkinfo->geo.blocksize; i++)
- {
- uint8_t ch = blkinfo->buffer[i];
-
- if (ch == g_inodemagic[inndx])
- {
- inndx++;
- datndx = 0;
-
- if (inndx == NXFFS_MAGICSIZE)
- {
- hdrndx = i - NXFFS_MAGICSIZE + 1;
- nbytes = nxffs_analyzeinode(blkinfo, hdrndx);
- if (nbytes > 0)
- {
- i = hdrndx + nbytes - 1;
- }
- inndx = 0;
- }
- }
- else if (ch == g_datamagic[datndx])
- {
- datndx++;
- inndx = 0;
-
- if (datndx == NXFFS_MAGICSIZE)
- {
- hdrndx = i - NXFFS_MAGICSIZE + 1;
- nbytes = nxffs_analyzedata(blkinfo, hdrndx);
- if (nbytes > 0)
- {
- i = hdrndx + nbytes - 1;
- }
- datndx = 0;
- }
- }
- }
-
-}
-#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.
- * verbose - FALSE: only show errors
- *
- * 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, bool verbose)
-{
-#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
- struct nxffs_blkinfo_s blkinfo;
- 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).
- */
-
- memset(&blkinfo, 0, sizeof(struct nxffs_blkinfo_s));
- ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&blkinfo.geo));
- if (ret < 0)
- {
- fdbg("ERROR: MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", -ret);
- goto errout;
- }
-
- /* Save the verbose output indication */
-
- blkinfo.verbose = verbose;
-
- /* Allocate a buffer to hold one block */
-
- blkinfo.buffer = (FAR uint8_t *)kmalloc(blkinfo.geo.blocksize);
- if (!blkinfo.buffer)
- {
- fdbg("ERROR: Failed to allocate block cache\n");
- ret = -ENOMEM;
- goto errout;
- }
-
- /* Now read every block on the device */
-
- fdbg("NXFFS Dump:\n");
- fdbg(g_hdrformat);
-
- blkinfo.nblocks = blkinfo.geo.erasesize * blkinfo.geo.neraseblocks / blkinfo.geo.blocksize;
- for (blkinfo.block = 0, blkinfo.offset = 0;
- blkinfo.block < blkinfo.nblocks;
- blkinfo.block++, blkinfo.offset += blkinfo.geo.blocksize)
- {
- /* Read the next block */
-
- ret = MTD_BREAD(mtd, blkinfo.block, 1, blkinfo.buffer);
- if (ret < 0)
- {
- fdbg("ERROR: Failed to read block %d\n", blkinfo.block);
- goto errout_with_block;
- }
-
- /* Analyze the block */
-
- nxffs_analyze(&blkinfo);
- }
- fdbg("%d blocks analyzed\n", blkinfo.nblocks);
-
-errout_with_block:
- kfree(blkinfo.buffer);
-errout:
- return ret;
-
-#else
- return -ENOSYS;
-#endif
-}
diff --git a/nuttx/fs/nxffs/nxffs_initialize.c b/nuttx/fs/nxffs/nxffs_initialize.c
deleted file mode 100644
index 4e7428c73..000000000
--- a/nuttx/fs/nxffs/nxffs_initialize.c
+++ /dev/null
@@ -1,522 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_initialize.c
- *
- * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <errno.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/mtd.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/fs/ioctl.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/* See fs_mount.c -- this structure is explicitly externed there.
- * We use the old-fashioned kind of initializers so that this will compile
- * with any compiler.
- */
-
-const struct mountpt_operations nxffs_operations =
-{
- nxffs_open, /* open */
- nxffs_close, /* close */
- nxffs_read, /* read */
- nxffs_write, /* write */
- NULL, /* seek -- Use f_pos in struct file */
- nxffs_ioctl, /* ioctl */
-
- NULL, /* sync -- No buffered data */
- nxffs_dup, /* dup */
-
- nxffs_opendir, /* opendir */
- NULL, /* closedir */
- nxffs_readdir, /* readdir */
- nxffs_rewinddir, /* rewinddir */
-
- nxffs_bind, /* bind */
- nxffs_unbind, /* unbind */
- nxffs_statfs, /* statfs */
-
- nxffs_unlink, /* unlink */
- NULL, /* mkdir -- no directories */
- NULL, /* rmdir -- no directories */
- NULL, /* rename -- cannot rename in place if name is longer */
- nxffs_stat /* stat */
-};
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/* The magic number that appears that the beginning of each NXFFS (logical)
- * block
- */
-
-const uint8_t g_blockmagic[NXFFS_MAGICSIZE] = { 'B', 'l', 'c', 'k' };
-
-/* The magic number that appears that the beginning of each NXFFS inode */
-
-const uint8_t g_inodemagic[NXFFS_MAGICSIZE] = { 'I', 'n', 'o', 'd' };
-
-/* The magic number that appears that the beginning of each NXFFS inode
- * data block.
- */
-
-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
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_initialize
- *
- * Description:
- * Initialize to provide NXFFS on an MTD interface
- *
- * Input Parameters:
- * mtd - The MTD device that supports the FLASH interface.
- *
- * 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)
-{
- 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));
- if (!volume)
- {
- ret = -ENOMEM;
- goto errout;
- }
-#endif
-
- /* Initialize the NXFFS volume structure */
-
- volume->mtd = mtd;
- volume->cblock = (off_t)-1;
- 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
- * from the size of a pointer).
- */
-
- ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&volume->geo));
- if (ret < 0)
- {
- fdbg("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", -ret);
- goto errout_with_volume;
- }
-
- /* Allocate one I/O block buffer to general files system access */
-
- volume->cache = (FAR uint8_t *)kmalloc(volume->geo.blocksize);
- if (!volume->cache)
- {
- fdbg("Failed to allocate an erase block buffer\n");
- ret = -ENOMEM;
- goto errout_with_volume;
- }
-
- /* Pre-allocate one, full, in-memory erase block. This is needed for filesystem
- * packing (but is useful in other places as well). This buffer is not needed
- * often, but is best to have pre-allocated and in-place.
- */
-
- volume->pack = (FAR uint8_t *)kmalloc(volume->geo.erasesize);
- 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
- */
-
- volume->blkper = volume->geo.erasesize / volume->geo.blocksize;
- volume->nblocks = volume->geo.neraseblocks * volume->blkper;
- DEBUGASSERT((off_t)volume->blkper * volume->geo.blocksize == volume->geo.erasesize);
-
- /* Check if there is a valid NXFFS file system on the flash */
-
- ret = nxffs_blockstats(volume, &stats);
- if (ret < 0)
- {
- fdbg("Failed to collect block statistics: %d\n", -ret);
- goto errout_with_buffer;
- }
-
- /* If the proportion of good blocks is low or the proportion of unformatted
- * blocks is high, then reformat the FLASH.
- */
-
- threshold = stats.nblocks / 5;
- if (stats.ngood < threshold || stats.nunformat > threshold)
- {
- /* Reformat the volume */
-
- ret = nxffs_reformat(volume);
- if (ret < 0)
- {
- fdbg("Failed to reformat the volume: %d\n", -ret);
- goto errout_with_buffer;
- }
-
- /* Get statistics on the re-formatted volume */
-
-#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_FS)
- ret = nxffs_blockstats(volume, &stats);
- if (ret < 0)
- {
- fdbg("Failed to collect block statistics: %d\n", -ret);
- goto errout_with_buffer;
- }
-#endif
- }
-
- /* Get the file system limits */
-
- ret = nxffs_limits(volume);
- if (ret == OK)
- {
- return OK;
- }
- fdbg("Failed to calculate file system limits: %d\n", -ret);
-
-errout_with_buffer:
- kfree(volume->pack);
-errout_with_cache:
- kfree(volume->cache);
-errout_with_volume:
-#ifndef CONFIG_NXFSS_PREALLOCATED
- kfree(volume);
-#endif
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_limits
- *
- * Description:
- * Recalculate file system limits: (1) the FLASH offset to the first,
- * valid inode, and (2) the FLASH offset to the first, unused byte after
- * the last inode (invalid or not).
- *
- * The first, lower limit must be recalculated: (1) initially, (2)
- * whenever the first inode is deleted, or (3) whenever inode is moved
- * as part of the file system packing operation.
- *
- * The second, upper limit must be (1) incremented whenever new file
- * data is written, or (2) recalculated as part of the file system packing
- * operation.
- *
- * Input Parameters:
- * volume - Identifies the NXFFS volume
- *
- * Returned Value:
- * Zero on success. Otherwise, a negated error is returned indicating the
- * nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_limits(FAR struct nxffs_volume_s *volume)
-{
- FAR struct nxffs_entry_s entry;
- off_t block;
- off_t offset;
- bool noinodes = false;
- int nerased;
- int ret;
-
- /* Get the offset to the first valid block on the FLASH */
-
- block = 0;
- ret = nxffs_validblock(volume, &block);
- if (ret < 0)
- {
- fdbg("Failed to find a valid block: %d\n", -ret);
- return ret;
- }
-
- /* Then find the first valid inode in or beyond the first valid block */
-
- offset = block * volume->geo.blocksize;
- ret = nxffs_nextentry(volume, offset, &entry);
- if (ret < 0)
- {
- /* The value -ENOENT is special. This simply means that the FLASH
- * was searched to the end and no valid inode was found... the file
- * system is empty (or, in more perverse cases, all inodes are
- * deleted or corrupted).
- */
-
- if (ret != -ENOENT)
- {
- fdbg("nxffs_nextentry failed: %d\n", -ret);
- return ret;
- }
-
- /* Set a flag the just indicates that no inodes were found. Later,
- * we will set the location of the first inode to be the same as
- * the location of the free FLASH region.
- */
-
- fvdbg("No inodes found\n");
- noinodes = true;
- }
- else
- {
- /* Save the offset to the first inode */
-
- volume->inoffset = entry.hoffset;
- fvdbg("First inode at offset %d\n", volume->inoffset);
-
- /* Discard this entry and set the next offset. */
-
- offset = nxffs_inodeend(volume, &entry);
- nxffs_freeentry(&entry);
- }
-
- /* Now, search for the last valid entry */
-
- if (!noinodes)
- {
- while ((ret = nxffs_nextentry(volume, offset, &entry)) == OK)
- {
- /* Discard the entry and guess the next offset. */
-
- offset = nxffs_inodeend(volume, &entry);
- nxffs_freeentry(&entry);
- }
- fvdbg("Last inode before offset %d\n", offset);
- }
-
- /* No inodes were found after this offset. Now search for a block of
- * erased flash.
- */
-
- nxffs_ioseek(volume, offset);
- nerased = 0;
- for (;;)
- {
- int ch = nxffs_getc(volume, 1);
- if (ch < 0)
- {
- /* Failed to read the next byte... this could mean that the FLASH
- * is full?
- */
-
- if (volume->ioblock + 1 >= volume->nblocks &&
- volume->iooffset + 1 >= volume->geo.blocksize)
- {
- /* Yes.. the FLASH is full. Force the offsets to the end of FLASH */
-
- volume->froffset = volume->nblocks * volume->geo.blocksize;
- fvdbg("Assume no free FLASH, froffset: %d\n", volume->froffset);
- if (noinodes)
- {
- volume->inoffset = volume->froffset;
- fvdbg("No inodes, inoffset: %d\n", volume->inoffset);
- }
- return OK;
- }
-
- // No? Then it is some other failure that we do not know how to handle
-
- fdbg("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)
- {
- /* Okay.. we have a long stretch of erased FLASH in a valid
- * FLASH block. Let's say that this is the beginning of
- * the free FLASH region.
- */
-
- volume->froffset = offset;
- fvdbg("Free FLASH region begins at offset: %d\n", volume->froffset);
- if (noinodes)
- {
- volume->inoffset = offset;
- fvdbg("First inode at offset %d\n", volume->inoffset);
- }
- return OK;
- }
- }
- else
- {
- offset += nerased + 1;
- nerased = 0;
- }
- }
-
- /* Won't get here */
-
- 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)
-{
-#ifndef CONFIG_NXFSS_PREALLOCATED
-# error "No design to support dynamic allocation of volumes"
-#else
- return g_volume.ofiles ? -EBUSY : OK;
-#endif
-}
diff --git a/nuttx/fs/nxffs/nxffs_inode.c b/nuttx/fs/nxffs/nxffs_inode.c
deleted file mode 100644
index 505a6c686..000000000
--- a/nuttx/fs/nxffs/nxffs_inode.c
+++ /dev/null
@@ -1,502 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_inode.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <crc32.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_rdentry
- *
- * Description:
- * Read the inode entry at this offset. Called only from nxffs_nextentry().
- *
- * Input Parameters:
- * volume - Describes the current volume.
- * offset - The byte offset from the beginning of FLASH where the inode
- * header is expected.
- * entry - A memory location to return the expanded inode header
- * information.
- *
- * Returned Value:
- * Zero on success. Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- * On return, the
- *
- ****************************************************************************/
-
-static int nxffs_rdentry(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR struct nxffs_entry_s *entry)
-{
- struct nxffs_inode_s inode;
- uint32_t ecrc;
- uint32_t crc;
- uint8_t state;
- int namlen;
- int ret;
-
- DEBUGASSERT(volume && entry);
- memset(entry, 0, sizeof(struct nxffs_entry_s));
-
- /* Read the header at the FLASH offset */
-
- nxffs_ioseek(volume, offset);
- memcpy(&inode, &volume->cache[volume->iooffset], SIZEOF_NXFFS_INODE_HDR);
-
- /* Check if the file state is recognized. */
-
- state = inode.state;
- if (state != INODE_STATE_FILE && state != INODE_STATE_DELETED)
- {
- /* This can't be a valid inode.. don't bother with the rest */
-
- ret = -ENOENT;
- goto errout_no_offset;
- }
-
- /* Copy the packed header into the user-friendly buffer */
-
- entry->hoffset = offset;
- entry->noffset = nxffs_rdle32(inode.noffs);
- entry->doffset = nxffs_rdle32(inode.doffs);
- entry->utc = nxffs_rdle32(inode.utc);
- entry->datlen = nxffs_rdle32(inode.datlen);
-
- /* Modify the packed header and perform the (partial) CRC calculation */
-
- ecrc = nxffs_rdle32(inode.crc);
- inode.state = CONFIG_NXFFS_ERASEDSTATE;
- memset(inode.crc, 0, 4);
- crc = crc32((FAR const uint8_t *)&inode, SIZEOF_NXFFS_INODE_HDR);
-
- /* Allocate memory to hold the variable-length file name */
-
- namlen = inode.namlen;
- entry->name = (FAR char *)kmalloc(namlen + 1);
- if (!entry->name)
- {
- fdbg("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);
-
- /* 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);
- goto errout_with_name;
- }
-
- /* Read the file name from the expected offset in FLASH */
-
- memcpy(entry->name, &volume->cache[volume->iooffset], namlen);
- entry->name[namlen] = '\0';
-
- /* Finish the CRC calculation and verify the entry */
-
- crc = crc32part((FAR const uint8_t *)entry->name, namlen, crc);
- if (crc != ecrc)
- {
- fdbg("CRC entry: %08x CRC calculated: %08x\n", ecrc, crc);
- ret = -EIO;
- goto errout_with_name;
- }
-
- /* We have a good inode header.. but it still could a deleted file.
- * Check the file state.
- */
-
- if (state != INODE_STATE_FILE)
- {
- /* It is a deleted file. But still, the data offset and the
- * start size are good so we can use this information to advance
- * further in FLASH memory and reduce the search time.
- */
-
- offset = nxffs_inodeend(volume, entry);
- nxffs_freeentry(entry);
- ret = -ENOENT;
- goto errout;
- }
-
- /* Everything is good.. leave the offset pointing to the valid inode
- * header.
- */
-
- return OK;
-
- /* On errors where we are suspicious of the validity of the inode header,
- * we need to increment the file position to just after the "good" magic
- * word.
- */
-
-errout_with_name:
- nxffs_freeentry(entry);
-errout_no_offset:
- offset += NXFFS_MAGICSIZE;
-errout:
- nxffs_ioseek(volume, offset);
- return ret;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_freeentry
- *
- * Description:
- * The inode values returned by nxffs_nextentry() include allocated memory
- * (specifically, the file name string). This function should be called
- * to dispose of that memory when the inode entry is no longer needed.
- *
- * Note that the nxffs_entry_s containing structure is not freed. The
- * caller may call kfree upon return of this function if necessary to
- * free the entry container.
- *
- * Input parameters:
- * entry - The entry to be freed.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void nxffs_freeentry(FAR struct nxffs_entry_s *entry)
-{
- if (entry->name)
- {
- kfree(entry->name);
- entry->name = NULL;
- }
-}
-
-/****************************************************************************
- * Name: nxffs_nextentry
- *
- * Description:
- * Search for the next valid inode starting at the provided FLASH offset.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- * 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.
- *
- ****************************************************************************/
-
-int nxffs_nextentry(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR struct nxffs_entry_s *entry)
-{
- int nmagic;
- int ch;
- int nerased;
- int ret;
-
- /* Seek to the first FLASH offset provided by the caller. */
-
- nxffs_ioseek(volume, offset);
-
- /* Then begin searching */
-
- nerased = 0;
- nmagic = 0;
- for (;;)
- {
- /* Read the next character */
-
- ch = nxffs_getc(volume, SIZEOF_NXFFS_INODE_HDR - nmagic);
- 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
- * inode. There is the possibility of this magic sequnce occurring
- * in FLASH data. However, the header CRC should distinguish
- * between real NXFFS inode headers and such false alarms.
- */
-
- if (ch != g_inodemagic[nmagic])
- {
- /* Ooops... this is the not the right character for the magic
- * Sequence. Check if we need to restart or to cancel the sequence:
- */
-
- if (ch == g_inodemagic[0])
- {
- nmagic = 1;
- }
- else
- {
- nmagic = 0;
- }
- }
- else if (nmagic < NXFFS_MAGICSIZE - 1)
- {
- /* We have one more character in the magic sequence */
-
- nmagic++;
- }
-
- /* We have found the magic sequence in the FLASH data that may
- * indicate the beginning of an NXFFS inode.
- */
-
- else
- {
- /* The the FLASH offset where we found the matching magic number */
-
- offset = nxffs_iotell(volume) - NXFFS_MAGICSIZE;
-
- /* Try to extract the inode header from that position */
-
- ret = nxffs_rdentry(volume, offset, entry);
- if (ret == OK)
- {
- fvdbg("Found a valid fileheader, offset: %d\n", offset);
- return OK;
- }
-
- /* False alarm.. keep looking */
-
- nmagic = 0;
- }
- }
- }
-
- /* We won't get here, but to keep some compilers happy: */
-
- return -ENOENT;
-}
-
-/****************************************************************************
- * Name: nxffs_findinode
- *
- * Description:
- * Search for an inode with the provided name starting with the first
- * valid inode and proceeding to the end FLASH or until the matching
- * inode is found.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * name - The name of the inode to find
- * entry - The location to return information about the inode.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno is returned
- * that indicates the nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_findinode(FAR struct nxffs_volume_s *volume, FAR const char *name,
- FAR struct nxffs_entry_s *entry)
-{
- off_t offset;
- int ret;
-
- /* Start with the first valid inode that was discovered when the volume
- * was created (or modified after the last file system re-packing).
- */
-
- offset = volume->inoffset;
-
- /* Loop, checking each NXFFS inode until either: (1) we find the NXFFS inode
- * with the matching name, or (2) we reach the end of data written on the
- * media.
- */
-
- for (;;)
- {
- /* Get the next, valid NXFFS inode entry */
-
- ret = nxffs_nextentry(volume, offset, entry);
- if (ret < 0)
- {
- fvdbg("No inode found: %d\n", -ret);
- return ret;
- }
-
- /* Is this the NXFFS inode we are looking for? */
-
- else if (strcmp(name, entry->name) == 0)
- {
- /* Yes, return success with the entry data in 'entry' */
-
- return OK;
- }
-
- /* Discard this entry and try the next one. Here we set the
- * next offset using the raw data length as the offset
- * increment. This is, of course, not accurate because it
- * does not account for the data headers that enclose the
- * data. But it is guaranteed to be less than or equal to
- * the correct offset and, hence, better then searching
- * byte-for-byte.
- */
-
- offset = nxffs_inodeend(volume, entry);
- nxffs_freeentry(entry);
- }
-
- /* We won't get here, but for some compilers: */
-
- return -ENOENT;
-}
-
-/****************************************************************************
- * Name: nxffs_inodeend
- *
- * Description:
- * Return an *approximiate* FLASH offset to end of the inode data. The
- * returned value is guaranteed to be be less then or equal to the offset
- * of the thing-of-interest in FLASH. Parsing for interesting things
- * can begin at that point.
- *
- * Assumption: The inode header has been verified by the caller and is
- * known to contain valid data.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * entry - Describes the inode.
- *
- * Returned Value:
- * A FLASH offset to the (approximate) end of the inode data. No errors
- * are detected.
- *
- ****************************************************************************/
-
-off_t nxffs_inodeend(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry)
-{
- /* A zero length file will have no data blocks */
-
- if (entry->doffset)
- {
- /* This is the maximum size of one data block. It is the physcal size
- * of the block minus the minimum number of headers: block sna data
- */
-
- uint16_t maxsize = volume->geo.blocksize - SIZEOF_NXFFS_BLOCK_HDR - SIZEOF_NXFFS_DATA_HDR;
-
- /* This is the minimum number of blocks require to span all of the
- * inode data. One additional block could possibly be required -- we
- * could make this accurate by looking at the size of the first, perhaps
- * partial, data block.
- */
-
- off_t minblocks = (entry->datlen + maxsize - 1) / maxsize;
-
- /* And this is our best, simple guess at the end of the inode data */
-
- return entry->doffset + entry->datlen + minblocks * SIZEOF_NXFFS_DATA_HDR;
- }
-
- /* Otherwise, return an offset that accounts only for the inode header and
- * the inode name.
- */
-
- /* All valid inodes will have a name associated with them */
-
- 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
deleted file mode 100644
index 332878eb0..000000000
--- a/nuttx/fs/nxffs/nxffs_ioctl.c
+++ /dev/null
@@ -1,150 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_ioctl.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-#include <nuttx/fs/ioctl.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_ioctl
- *
- * Description:
- * Standard mountpoint ioctl method.
- *
- ****************************************************************************/
-
-int nxffs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
-{
- FAR struct nxffs_volume_s *volume;
- int ret;
-
- fvdbg("cmd: %d arg: %08lx\n", cmd, arg);
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover the file system state from the open file */
-
- volume = 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;
- }
-
- /* Only a reformat and optimize commands are supported */
-
- if (cmd == FIOC_REFORMAT)
- {
- fvdbg("Reformat command\n");
-
- /* We cannot reformat the volume if there are any open inodes */
-
- if (volume->ofiles)
- {
- fdbg("Open files\n");
- ret = -EBUSY;
- goto errout_with_semaphore;
- }
-
- /* Re-format the volume -- all is lost */
-
- ret = nxffs_reformat(volume);
- }
-
- else if (cmd == FIOC_OPTIMIZE)
- {
- fvdbg("Optimize command\n");
-
- /* Pack the volume */
-
- ret = nxffs_pack(volume);
- }
- else
- {
- /* No other commands supported */
-
- ret = -ENOTTY;
- }
-
-errout_with_semaphore:
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_open.c b/nuttx/fs/nxffs/nxffs_open.c
deleted file mode 100644
index 9fa4ef2e0..000000000
--- a/nuttx/fs/nxffs/nxffs_open.c
+++ /dev/null
@@ -1,1322 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_open.c
- *
- * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <fcntl.h>
-#include <time.h>
-#include <crc32.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* Since we are limited to a single file opened for writing, it makes sense
- * to pre-allocate the write state structure.
- */
-
-#ifdef CONFIG_NXFSS_PREALLOCATED
-static struct nxffs_wrfile_s g_wrfile;
-#endif
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_hdrpos
- *
- * Description:
- * Find a valid location for the inode header. A valid location will have
- * these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire header
- * (excluding the file name which may lie in the next block).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the checks of 1) and 2).
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Contains the current guess for the header position. On
- * successful return, this field will hold the selected header
- * position.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * wrfile->ofile.entry.hoffset - FLASH offset to candidate header position
- * volume->ioblock - Read/write block number of the block containing the
- * header position
- * volume->iooffset - The offset in the block to the candidate header
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-static inline int nxffs_hdrpos(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile)
-{
- int ret;
-
- /* Reserve memory for the object */
-
- ret = nxffs_wrreserve(volume, SIZEOF_NXFFS_INODE_HDR);
- if (ret == OK)
- {
- /* Save the offset to the FLASH region reserved for the inode header */
-
- wrfile->ofile.entry.hoffset = nxffs_iotell(volume);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_nampos
- *
- * Description:
- * Find a valid location for the inode name. A valid location will have
- * these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire name
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the checks of 1) and 2).
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Contains the current guess for the name position. On
- * successful return, this field will hold the selected name
- * position.
- * namlen - The length of the name.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * wrfile->ofile.entry.noffset - FLASH offset to candidate name position
- * volume->ioblock - Read/write block number of the block containing the
- * name position
- * volume->iooffset - The offset in the block to the candidate name
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-static inline int nxffs_nampos(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile,
- int namlen)
-{
- int ret;
-
- /* Reserve memory for the object */
-
- ret = nxffs_wrreserve(volume, namlen);
- if (ret == OK)
- {
- /* Save the offset to the FLASH region reserved for the inode name */
-
- wrfile->ofile.entry.noffset = nxffs_iotell(volume);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_hdrerased
- *
- * Description:
- * Find a valid location for the inode header. A valid location will have
- * these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire header
- * (excluding the file name which may lie in the next block).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the check 3).
- *
- * On entry it assumes:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * header position
- * volume->iooffset - The offset in the block to the candidate header
- * position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Contains the current guess for the header position. On
- * successful return, this field will hold the selected header
- * position.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * wrfile->ofile.entry.hoffset - FLASH offset to candidate header position
- * volume->ioblock - Read/write block number of the block containing the
- * header position
- * volume->iooffset - The offset in the block to the candidate header
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-static inline int nxffs_hdrerased(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile)
-{
- int ret;
-
- /* Find a valid location to save the inode header */
-
- ret = nxffs_wrverify(volume, SIZEOF_NXFFS_INODE_HDR);
- if (ret == OK)
- {
- /* This is where we will put the header */
-
- wrfile->ofile.entry.hoffset = nxffs_iotell(volume);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_namerased
- *
- * Description:
- * Find a valid location for the inode name. A valid location will have
- * these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire name
- * (excluding the file name which may lie in the next block).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the check 3).
- *
- * On entry it assumes:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * name position
- * volume->iooffset - The offset in the block to the candidate name
- * position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Contains the current guess for the name position. On
- * successful return, this field will hold the selected name
- * position.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * wrfile->ofile.entry.noffset - FLASH offset to candidate name position
- * volume->ioblock - Read/write block number of the block containing the
- * name position
- * volume->iooffset - The offset in the block to the candidate name
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-static inline int nxffs_namerased(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile,
- int namlen)
-{
- int ret;
-
- /* Find a valid location to save the inode name */
-
- ret = nxffs_wrverify(volume, namlen);
- if (ret == OK)
- {
- /* This is where we will put the name */
-
- wrfile->ofile.entry.noffset = nxffs_iotell(volume);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wrname
- *
- * Description:
- * Write the inode name to cache at the position verified by
- * nxffs_namerased().
- *
- * On entry it assumes:
- *
- * entry->noffset - FLASH offset to final name position
- * volume->ioblock - Read/write block number of the block containing the
- * name position
- * volume->iooffset - The offset in the block to the candidate name
- * position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * entry - Describes the entry to be written.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure.
- *
- ****************************************************************************/
-
-static inline int nxffs_wrname(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry,
- int namlen)
-{
- int ret;
-
- /* Seek to the inode name position and assure that it is in the volume
- * cache.
- */
-
- nxffs_ioseek(volume, entry->noffset);
- ret = nxffs_rdcache(volume, volume->ioblock);
- if (ret < 0)
- {
- fdbg("Failed to read inode name block %d: %d\n",
- volume->ioblock, -ret);
- return ret;
- }
-
- /* Copy the inode name to the volume cache and write the inode name block */
-
- memcpy(&volume->cache[volume->iooffset], entry->name, namlen);
- ret = nxffs_wrcache(volume);
- if (ret < 0)
- {
- fdbg("Failed to write inode header block %d: %d\n",
- volume->ioblock, -ret);
- }
-
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wropen
- *
- * Description:
- * Handle opening for writing. Only a single writer is permitted and only
- * file creation is supported.
- *
- ****************************************************************************/
-
-static inline int nxffs_wropen(FAR struct nxffs_volume_s *volume,
- FAR const char *name, mode_t oflags,
- FAR struct nxffs_ofile_s **ppofile)
-{
- FAR struct nxffs_wrfile_s *wrfile;
- FAR struct nxffs_entry_s entry;
- bool packed;
- bool truncate = false;
- int namlen;
- int ret;
-
- /* Limitation: Only a single writer is permitted. Writing may involve
- * extension of the file system in FLASH. Since files are contiguous
- * in FLASH, only a single file may be extending the FLASH region.
- */
-
- ret = sem_wait(&volume->wrsem);
- if (ret != OK)
- {
- 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);
- if (ret == OK)
- {
- FAR struct nxffs_ofile_s *ofile;
-
- /* It exists. Is the file already open for reading? */
-
- ofile = nxffs_findofile(volume, name);
- if (ofile)
- {
- /* The file is already open.
- * Limitation: Files cannot be open both for reading and writing.
- */
-
- fdbg("File is open for reading\n");
- ret = -ENOSYS;
- goto errout_with_exclsem;
- }
-
- /* It would be an error if we are asked to create the file
- * exclusively.
- */
-
- else if ((oflags & (O_CREAT|O_EXCL)) == (O_CREAT|O_EXCL))
- {
- fdbg("File exists, can't create O_EXCL\n");
- ret = -EEXIST;
- goto errout_with_exclsem;
- }
-
- /* Were we asked to truncate the file? NOTE: Don't truncate the
- * file if we were not also asked to created it. See below...
- * we will not re-create the file unless O_CREAT is also specified.
- */
-
- else if ((oflags & (O_CREAT|O_TRUNC)) == (O_CREAT|O_TRUNC))
- {
- /* Just schedule the removal the file and fall through to re-create it.
- * Note that the old file of the same name will not actually be removed
- * until the new file is successfully written.
- */
-
- truncate = true;
- }
-
- /* The file exists and we were not asked to truncate (and recreate) it.
- * Limitation: Cannot write to existing files.
- */
-
- else
- {
- fdbg("File %s exists and we were not asked to truncate it\n");
- ret = -ENOSYS;
- goto errout_with_exclsem;
- }
- }
-
- /* Okay, the file is not open and does not exists (maybe because we deleted
- * it). Now, make sure that we were asked to created it.
- */
-
- if ((oflags & O_CREAT) == 0)
- {
- fdbg("Not asked to create the file\n");
- ret = -ENOENT;
- goto errout_with_exclsem;
- }
-
- /* Make sure that the length of the file name will fit in a uint8_t */
-
- namlen = strlen(name);
- if (namlen > CONFIG_NXFFS_MAXNAMLEN)
- {
- fdbg("Name is too long: %d\n", namlen);
- ret = -EINVAL;
- goto errout_with_exclsem;
- }
-
- /* Yes.. Create a new structure that will describe the state of this open
- * file. NOTE that a special variant of the open file structure is used
- * that includes additional information to support the write operation.
- */
-
-#ifdef CONFIG_NXFSS_PREALLOCATED
- wrfile = &g_wrfile;
- memset(wrfile, 0, sizeof(struct nxffs_wrfile_s));
-#else
- wrfile = (FAR struct nxffs_wrfile_s *)kzalloc(sizeof(struct nxffs_wrfile_s));
- if (!wrfile)
- {
- ret = -ENOMEM;
- goto errout_with_exclsem;
- }
-#endif
-
- /* Initialize the open file state structure */
-
- wrfile->ofile.crefs = 1;
- wrfile->ofile.oflags = oflags;
- wrfile->ofile.entry.utc = time(NULL);
- wrfile->truncate = truncate;
-
- /* Save a copy of the inode name. */
-
- wrfile->ofile.entry.name = strdup(name);
- if (!wrfile->ofile.entry.name)
- {
- ret = -ENOMEM;
- goto errout_with_ofile;
- }
-
- /* Allocate FLASH memory for the file and set up for the write.
- *
- * Loop until the inode header is configured or until a failure occurs.
- * Note that nothing is written to FLASH. The inode header is not
- * written until the file is closed.
- */
-
- packed = false;
- for (;;)
- {
- /* File a valid location to position the inode header. Start with the
- * first byte in the free FLASH region.
- */
-
- ret = nxffs_hdrpos(volume, wrfile);
- if (ret == OK)
- {
- /* Find a region of memory in the block that is fully erased */
-
- ret = nxffs_hdrerased(volume, wrfile);
- if (ret == OK)
- {
- /* Valid memory for the inode header was found. Break out of
- * the loop.
- */
-
- break;
- }
- }
-
- /* If no valid memory is found searching to the end of the volume,
- * then -ENOSPC will be returned. Other errors are not handled.
- */
-
- if (ret != -ENOSPC || packed)
- {
- fdbg("Failed to find inode header memory: %d\n", -ret);
- goto errout_with_name;
- }
-
- /* -ENOSPC is a special case.. It means that the volume is full.
- * Try to pack the volume in order to free up some space.
- */
-
- ret = nxffs_pack(volume);
- if (ret < 0)
- {
- fdbg("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.
- */
-
- for (;;)
- {
- /* File a valid location to position the inode name. Start with the
- * first byte in the free FLASH region.
- */
-
- ret = nxffs_nampos(volume, wrfile, namlen);
- if (ret == OK)
- {
- /* Find a region of memory in the block that is fully erased */
-
- ret = nxffs_namerased(volume, wrfile, namlen);
- if (ret == OK)
- {
- /* Valid memory for the inode header was found. Write the
- * inode name to this location.
- */
-
- ret = nxffs_wrname(volume, &wrfile->ofile.entry, namlen);
- if (ret < 0)
- {
- fdbg("Failed to write the inode name: %d\n", -ret);
- goto errout_with_name;
- }
-
- /* Then just break out of the loop reporting success. Note
- * that the alllocated inode name string is retained; it
- * will be needed later to calculate the inode CRC.
- */
-
- break;
- }
- }
-
- /* If no valid memory is found searching to the end of the volume,
- * then -ENOSPC will be returned. Other errors are not handled.
- */
-
- if (ret != -ENOSPC || packed)
- {
- fdbg("Failed to find inode name memory: %d\n", -ret);
- goto errout_with_name;
- }
-
- /* -ENOSPC is a special case.. It means that the volume is full.
- * Try to pack the volume in order to free up some space.
- */
-
- ret = nxffs_pack(volume);
- if (ret < 0)
- {
- fdbg("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;
- }
-
- /* Add the open file structure to the head of the list of open files */
-
- wrfile->ofile.flink = volume->ofiles;
- volume->ofiles = &wrfile->ofile;
-
- /* Indicate that the volume is open for writing and return the open file
- * 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
- */
-
- *ppofile = &wrfile->ofile;
- sem_post(&volume->exclsem);
- return OK;
-
-errout_with_name:
- kfree(wrfile->ofile.entry.name);
-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;
-}
-
-/****************************************************************************
- * Name: nxffs_rdopen
- *
- * Description:
- * Open an existing file for reading.
- *
- ****************************************************************************/
-
-static inline int nxffs_rdopen(FAR struct nxffs_volume_s *volume,
- FAR const char *name,
- FAR struct nxffs_ofile_s **ppofile)
-{
- 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);
- if (ofile)
- {
- /* The file is already open.
- * Limitation: Files cannot be open both for reading and writing.
- */
-
- if ((ofile->oflags & O_WROK) != 0)
- {
- fdbg("File is open for writing\n");
- ret = -ENOSYS;
- goto errout_with_exclsem;
- }
-
- /* Just increment the reference count on the ofile */
-
- ofile->crefs++;
- fdbg("crefs: %d\n", ofile->crefs);
- }
-
- /* The file has not yet been opened.
- * Limitation: The file must exist. We do not support creation of files
- * read-only.
- */
-
- 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");
- ret = -ENOMEM;
- goto errout_with_exclsem;
- }
-
- /* Initialize the open file state structure */
-
- ofile->crefs = 1;
- ofile->oflags = O_RDOK;
-
- /* Find the file on this volume associated with this file name */
-
- ret = nxffs_findinode(volume, name, &ofile->entry);
- if (ret != OK)
- {
- fvdbg("Inode '%s' not found: %d\n", name, -ret);
- goto errout_with_ofile;
- }
-
- /* Add the open file structure to the head of the list of open files */
-
- ofile->flink = volume->ofiles;
- volume->ofiles = ofile;
- }
-
- /* 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;
-}
-
-/****************************************************************************
- * Name: nxffs_remofile
- *
- * Description:
- * Remove an entry from the open file list.
- *
- ****************************************************************************/
-
-static inline void nxffs_remofile(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_ofile_s *ofile)
-{
- FAR struct nxffs_ofile_s *prev;
- FAR struct nxffs_ofile_s *curr;
-
- /* Find the open file structure to be removed */
-
- for (prev = NULL, curr = volume->ofiles;
- curr && curr != ofile;
- prev = curr, curr = curr->flink);
-
- /* Was it found? */
-
- if (curr)
- {
- /* Yes.. at the head of the list? */
-
- if (prev)
- {
- prev->flink = ofile->flink;
- }
- else
- {
- volume->ofiles = ofile->flink;
- }
- }
- else
- {
- fdbg("ERROR: Open inode %p not found\n", ofile);
- }
-}
-
-/****************************************************************************
- * Name: nxffs_freeofile
- *
- * Description:
- * Free resources held by an open file.
- *
- ****************************************************************************/
-
-static inline void nxffs_freeofile(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_ofile_s *ofile)
-{
- /* 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)
- */
-
-#ifdef CONFIG_NXFSS_PREALLOCATED
- if ((FAR struct nxffs_wrfile_s*)ofile != &g_wrfile)
-#endif
- {
- kfree(ofile);
- }
-}
-
-/****************************************************************************
- * Name: nxffs_wrclose
- *
- * Description:
- * Perform special operations when a file is closed:
- * 1. Write the file block header
- * 2. Remove any file with the same name that was discovered when the
- * file was open for writing, and finally,
- * 3. Write the new file inode.
- *
- * Input parameters
- * volume - Describes the NXFFS volume
- * wrfile - Describes the state of the open file
- *
- ****************************************************************************/
-
-static inline int nxffs_wrclose(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile)
-{
- int ret;
-
- /* Is there an unfinalized write data? */
-
- if (wrfile->datlen > 0)
- {
- /* Yes.. Write the final file block header */
-
- ret = nxffs_wrblkhdr(volume, wrfile);
- if (ret < 0)
- {
- fdbg("Failed to write the final block of the file: %d\n", -ret);
- goto errout;
- }
- }
-
- /* Truncation is implemented by writing the new file, then deleting the
- * older version of the file. Note that we removed the entry from the
- * open file list earlier in the close sequence; this will prevent the
- * open file check from failing when we remove the old version of the
- * file.
- */
-
- if (wrfile->truncate && wrfile->ofile.entry.name)
- {
- fvdbg("Removing old file: %s\n", wrfile->ofile.entry.name);
-
- ret = nxffs_rminode(volume, wrfile->ofile.entry.name);
- if (ret < 0)
- {
- fdbg("nxffs_rminode failed: %d\n", -ret);
- goto errout;
- }
- }
-
- /* Write the inode header to FLASH */
-
- ret = nxffs_wrinode(volume, &wrfile->ofile.entry);
-
- /* The volume is now available for other writers */
-
-errout:
- sem_post(&volume->wrsem);
- return ret;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_findofile
- *
- * Description:
- * Search the list of already opened files to see if the inode of this
- * name is one of the opened files.
- *
- * Input Parameters:
- * name - The name of the inode to check.
- *
- * Returned Value:
- * If an inode of this name is found in the list of opened inodes, then
- * a reference to the open file structure is returned. NULL is returned
- * otherwise.
- *
- ****************************************************************************/
-
-FAR struct nxffs_ofile_s *nxffs_findofile(FAR struct nxffs_volume_s *volume,
- FAR const char *name)
-{
- FAR struct nxffs_ofile_s *ofile;
-
- /* Check every open file. Note that the volume exclsem protects the
- * list of open files.
- */
-
- for (ofile = volume->ofiles; ofile; ofile = ofile->flink)
- {
- /* Check for a name match */
-
- if (strcmp(name, ofile->entry.name) == 0)
- {
- return ofile;
- }
- }
-
- return NULL;
-}
-
-/****************************************************************************
- * Name: nxffs_findwriter
- *
- * Description:
- * Search the list of already opened files and return the open file
- * instance for the write.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- *
- * Returned Value:
- * If there is an active writer of the volume, its open file instance is
- * returned. NULL is returned otherwise.
- *
- ****************************************************************************/
-
-FAR struct nxffs_wrfile_s *nxffs_findwriter(FAR struct nxffs_volume_s *volume)
-{
- /* We can tell if the write is in-use because it will have an allocated
- * name attached.
- */
-
-#ifdef CONFIG_NXFSS_PREALLOCATED
- return g_wrfile.ofile.entry.name != NULL ? &g_wrfile : NULL;
-#else
-# error "Missing implementation"
-#endif
-}
-
-/****************************************************************************
- * Name: nxffs_open
- *
- * Description:
- * This is the standard mountpoint open method.
- *
- ****************************************************************************/
-
-int nxffs_open(FAR struct file *filep, FAR const char *relpath,
- int oflags, mode_t mode)
-{
- FAR struct nxffs_volume_s *volume;
- FAR struct nxffs_ofile_s *ofile = NULL;
- int ret;
-
- fvdbg("Open '%s'\n", relpath);
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv == NULL && filep->f_inode != NULL);
-
- /* Get the mountpoint private data from the NuttX inode reference in the
- * file structure
- */
-
- volume = (FAR struct nxffs_volume_s*)filep->f_inode->i_private;
- DEBUGASSERT(volume != NULL);
-
-#ifdef CONFIG_FILE_MODE
-# warning "Missing check for privileges based on inode->i_mode"
-#endif
-
- /* Limitation: A file must be opened for reading or writing, but not both.
- * There is no general way of extending the size of a file. Extending the
- * file size of possible if the file to be extended is the last in the
- * sequence on FLASH, but since that case is not the general case, no file
- * extension is supported.
- */
-
- switch (oflags & (O_WROK|O_RDOK))
- {
- case 0:
- default:
- fdbg("One of O_WRONLY/O_RDONLY must be provided\n");
- return -EINVAL;
-
- case O_WROK:
- ret = nxffs_wropen(volume, relpath, oflags, &ofile);
- break;
-
- case O_RDOK:
- ret = nxffs_rdopen(volume, relpath, &ofile);
- break;
-
- case O_WROK|O_RDOK:
- fdbg("O_RDWR is not supported\n");
- return -ENOSYS;
- }
-
- /* Save the reference to the open-specific state in filep->f_priv */
-
- if (ret == OK)
- {
- filep->f_priv = ofile;
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: binfs_dup
- *
- * Description:
- * Duplicate open file data in the new file structure.
- *
- ****************************************************************************/
-
-int nxffs_dup(FAR const struct file *oldp, FAR struct file *newp)
-{
-#ifdef CONFIG_DEBUG
- FAR struct nxffs_volume_s *volume;
-#endif
- FAR struct nxffs_ofile_s *ofile;
-
- fvdbg("Dup %p->%p\n", oldp, newp);
-
- /* Sanity checks */
-
-#ifdef CONFIG_DEBUG
- DEBUGASSERT(oldp->f_priv == NULL && oldp->f_inode != NULL);
-
- /* Get the mountpoint private data from the NuttX inode reference in the
- * file structure
- */
-
- volume = (FAR struct nxffs_volume_s*)oldp->f_inode->i_private;
- DEBUGASSERT(volume != NULL);
-#endif
-
- /* Recover the open file state from the struct file instance */
-
- ofile = (FAR struct nxffs_ofile_s *)oldp->f_priv;
-
- /* I do not think we need exclusive access to the volume to do this.
- * The volume exclsem protects the open file list and, hence, would
- * assure that the ofile is stable. However, it is assumed that the
- * caller holds a value file descriptor associated with this ofile,
- * so it should be stable throughout the life of this function.
- */
-
- /* Limitations: I do not think we have to be concerned about the
- * usual NXFFS file limitations here: dup'ing cannot resulting
- * in mixed reading and writing to the same file, or multiple
- * writer to different file.
- *
- * I notice that nxffs_wropen will prohibit multiple opens for
- * writing. But I do not thing that dup'ing a file already opened
- * for writing suffers from any of these issues.
- */
-
- /* Just increment the reference count on the ofile */
-
- ofile->crefs++;
- newp->f_priv = (FAR void *)ofile;
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_close
- *
- * Description:
- * This is the standard mountpoint close method.
- *
- ****************************************************************************/
-
-int nxffs_close(FAR struct file *filep)
-{
- FAR struct nxffs_volume_s *volume;
- FAR struct nxffs_ofile_s *ofile;
- int ret = -ENOSYS;
-
- fvdbg("Closing\n");
-
- /* 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;
- }
-
- /* Decrement the reference count on the open file */
-
- ret = OK;
- if (ofile->crefs == 1)
- {
- /* Decrementing the reference count would take it zero.
- *
- * Remove the entry from the open file list. We do this early
- * to avoid some chick-and-egg problems with file truncation.
- */
-
- nxffs_remofile(volume, ofile);
-
- /* Handle special finalization of the write operation. */
-
- if ((ofile->oflags & O_WROK) != 0)
- {
- ret = nxffs_wrclose(volume, (FAR struct nxffs_wrfile_s *)ofile);
- }
-
- /* Release all resouces held by the open file */
-
- nxffs_freeofile(volume, ofile);
- }
- else
- {
- /* Just decrement the reference count */
-
- ofile->crefs--;
- }
-
-
- filep->f_priv = NULL;
- sem_post(&volume->exclsem);
-
-errout:
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wrinode
- *
- * Description:
- * Write the inode header (only to FLASH. This is done in two contexts:
- *
- * 1. When an inode is closed, or
- * 2. As part of the file system packing logic when an inode is moved.
- *
- * Note that in either case, the inode name has already been written to
- * FLASH.
- *
- * Input parameters
- * volume - Describes the NXFFS volume
- * entry - Describes the inode header to write
- *
- * Returned Value:
- * Zero is returned on success; Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_wrinode(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry)
-{
- FAR struct nxffs_inode_s *inode;
- uint32_t crc;
- int namlen;
- int ret;
-
- /* Seek to the inode header position and assure that it is in the volume
- * cache.
- */
-
- nxffs_ioseek(volume, entry->hoffset);
- ret = nxffs_rdcache(volume, volume->ioblock);
- if (ret < 0)
- {
- fdbg("Failed to read inode header block %d: %d\n",
- volume->ioblock, -ret);
- goto errout;
- }
-
- /* Get the length of the inode name */
-
- namlen = strlen(entry->name);
- DEBUGASSERT(namlen < CONFIG_NXFFS_MAXNAMLEN); /* This was verified earlier */
-
- /* Initialize the inode header */
-
- inode = (FAR struct nxffs_inode_s *)&volume->cache[volume->iooffset];
- memcpy(inode->magic, g_inodemagic, NXFFS_MAGICSIZE);
-
- inode->state = CONFIG_NXFFS_ERASEDSTATE;
- inode->namlen = namlen;
-
- nxffs_wrle32(inode->noffs, entry->noffset);
- nxffs_wrle32(inode->doffs, entry->doffset);
- nxffs_wrle32(inode->utc, entry->utc);
- nxffs_wrle32(inode->crc, 0);
- nxffs_wrle32(inode->datlen, entry->datlen);
-
- /* Calculate the CRC */
-
- crc = crc32((FAR const uint8_t *)inode, SIZEOF_NXFFS_INODE_HDR);
- crc = crc32part((FAR const uint8_t *)entry->name, namlen, crc);
-
- /* Finish the inode header */
-
- inode->state = INODE_STATE_FILE;
- nxffs_wrle32(inode->crc, crc);
-
- /* Write the block with the inode header */
-
- ret = nxffs_wrcache(volume);
- if (ret < 0)
- {
- fdbg("Failed to write inode header block %d: %d\n",
- volume->ioblock, -ret);
- }
-
- /* The volume is now available for other writers */
-
-errout:
- sem_post(&volume->wrsem);
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_updateinode
- *
- * Description:
- * The packing logic has moved an inode. Check if any open files are using
- * this inode and, if so, move the data in the open file structure as well.
- *
- * Input parameters
- * volume - Describes the NXFFS volume
- * entry - Describes the new inode entry
- *
- * Returned Value:
- * Zero is returned on success; Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_updateinode(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry)
-{
- FAR struct nxffs_ofile_s *ofile;
-
- /* Find the open inode structure matching this name */
-
- ofile = nxffs_findofile(volume, entry->name);
- if (ofile)
- {
- /* Yes.. the file is open. Update the FLASH offsets to inode headers */
-
- ofile->entry.hoffset = entry->hoffset;
- 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
deleted file mode 100644
index 5a82ae4fd..000000000
--- a/nuttx/fs/nxffs/nxffs_pack.c
+++ /dev/null
@@ -1,1572 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_pack.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <errno.h>
-#include <assert.h>
-#include <crc32.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-/* This structure supports access to one inode data stream */
-
-struct nxffs_packstream_s
-{
- struct nxffs_entry_s entry; /* Describes 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
-{
- /* These describe the source and destination streams */
-
- struct nxffs_packstream_s src;
- struct nxffs_packstream_s dest;
-
- /* These describe the state of the current contents of the (destination)
- * volume->pack buffer.
- */
-
- FAR uint8_t *iobuffer; /* I/O block start position */
- off_t ioblock; /* I/O block number */
- off_t block0; /* First I/O block number in the erase block */
- uint16_t iooffset; /* I/O block offset */
-};
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_getblock
- *
- * Description:
- * Return the I/O block number that includes the provided offset.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * offset - FLASH offset
- *
- * Returned Value:
- * The I/O block number.
- *
- ****************************************************************************/
-
-static off_t nxffs_getblock(FAR struct nxffs_volume_s *volume, off_t offset)
-{
- return offset / volume->geo.blocksize;
-}
-
-/****************************************************************************
- * Name: nxffs_getoffset
- *
- * Description:
- * Given an I/O block number return the block offset corresponding to the
- * FLASH offset;
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * offset - FLASH offset
- *
- * Returned Value:
- * The I/O block number.
- *
- ****************************************************************************/
-
-static off_t nxffs_getoffset(FAR struct nxffs_volume_s *volume,
- off_t offset, off_t block)
-{
- return offset - block * volume->geo.blocksize;
-}
-
-/****************************************************************************
- * Name: nxffs_packtell
- *
- * Description:
- * Report the current destination position in the pack buffer.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * pack - The volume packing state structure.
- *
- * Returned Value:
- * The offset from the beginning of FLASH to the current seek position.
- *
- ****************************************************************************/
-
-static off_t nxffs_packtell(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- return pack->ioblock * volume->geo.blocksize + pack->iooffset;
-}
-
-/****************************************************************************
- * Name: nxffs_packvalid
- *
- * Description:
- * Check if the current destination block is valid.
- *
- * Input Parameters:
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * None
- *
- ****************************************************************************/
-
-static inline bool nxffs_packvalid(FAR struct nxffs_pack_s *pack)
-{
- FAR struct nxffs_block_s *blkhdr;
-
- blkhdr = (FAR struct nxffs_block_s *)pack->iobuffer;
- return (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) == 0 &&
- blkhdr->state == BLOCK_STATE_GOOD);
-}
-
-/****************************************************************************
- * Name: nxffs_mediacheck
- *
- * Description:
- * Verify that there is at least one valid block and at least one valid
- * inode header on the media. On successful return, the volume packing
- * structure is initialized and contains the offset to the first valid
- * inode header is returned.
- *
- * Input Parameters:
- * volume - The volume to be packed.
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * The offset to the data area on the first valid block. Zero is return
- * if there are no valid blocks or if there are no valid inode headers
- * after the first valid block.
- *
- ****************************************************************************/
-
-static inline off_t nxffs_mediacheck(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- off_t froffset;
- int ret;
-
- /* Initialize the packing structure to all zero */
-
- 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 offset zero. */
-
- return 0;
- }
-
- /* The offset to the free location to pack is then just after the block
- * header in this block.
- */
-
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- froffset = nxffs_iotell(volume);
-
- /* Get the offset to the first valid inode entry after this free offset */
-
- ret = nxffs_nextentry(volume, froffset, &pack->src.entry);
- if (ret < 0)
- {
- /* No valid entries on the media -- Return offset zero */
-
- return 0;
- }
-
- /* Okay.. the start block and first entry have been found */
-
- return froffset;
-}
-
-/****************************************************************************
- * Name: nxffs_startpos
- *
- * 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. On entry, the volume packing structure should be as it
- * was initialized by nxffx_mediacheck. on successful return, the volume
- * packing state structure will be updated to begin the packing operation.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- * froffset - On input, this is the location where we should be searching
- * for the location to begin packing. On successful return, froffset
- * will be set the the offset in FLASH where the first inode should be
- * copied to. If -ENOSPC is returned -- meaning that the FLASH is full
- * -- then no packing can be performed. In this case, then the free
- * flash offset is returned through this location.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure. If -ENOSPC is returned then the
- * free FLASH offset is also returned.
- *
- ****************************************************************************/
-
-static inline int nxffs_startpos(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack,
- off_t *froffset)
-{
- struct nxffs_blkentry_s blkentry;
- off_t offset = *froffset;
- off_t wasted;
- off_t nbytes;
- int ret;
-
- /* Loop until we find a gap of unused FLASH large enough to warrant
- * compacting.
- */
-
- for(;;)
- {
- /* 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. Describe the destination
- * inode header (only non-zero entries need to be initialized).
- */
-
- pack->dest.entry.name = pack->src.entry.name;
- pack->dest.entry.utc = pack->src.entry.utc;
- pack->dest.entry.datlen = pack->src.entry.datlen;
-
- /* The destination entry now "owns" the name string */
-
- pack->src.entry.name = NULL;
-
- /* Return the FLASH offset to the destination inode header */
-
- *froffset = offset;
- 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)
- {
- /* No.. not enough space here. 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
- * the end-of-flash indication.
- */
-
- *froffset = volume->froffset;
- return -ENOSPC;
- }
-
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- offset = nxffs_iotell(volume);
- }
-
- /* Get the offset to the next valid inode entry */
-
- ret = nxffs_nextentry(volume, offset, &pack->src.entry);
- if (ret < 0)
- {
- /* No more valid inode entries. Just return an end-of-flash error
- * indication. However, there could be many deleted inodes; set
- * volume->froffset to indicate the true free FLASH position.
- */
-
- *froffset = offset;
- return -ENOSPC;
- }
- }
-
- /* We won't get here */
-
- return -ENOSYS;
-}
-
-/****************************************************************************
- * Name: nxffs_srcsetup
- *
- * Description:
- * Given a valid src inode, configure the src data stream.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- * offset - FLASH offset to the data block header (will be zero for zero-
- * files.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static int nxffs_srcsetup(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack, off_t offset)
-{
- /* Start with the first data block */
-
- pack->src.blkoffset = offset;
- pack->src.blkpos = 0;
-
- /* Zero-length files have no valid data block offset */
-
- if (offset > 0)
- {
- /* Seek to the data block header, read and verify the block header */
-
- int ret = nxffs_rdblkhdr(volume, offset, &pack->src.blklen);
- if (ret < 0)
- {
- fdbg("Failed to verify the data block header: %d\n", -ret);
- }
- return ret;
- }
-
- DEBUGASSERT(pack->src.entry.datlen == 0);
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_destsetup
- *
- * Description:
- * Given a valid dest inode, configure the dest data stream.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static int nxffs_destsetup(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- size_t mindata;
- int namlen;
- int ret;
-
- /* The destination can be in one of three of states:
- *
- * State 1: The inode position was not yet been found. This condition can
- * only occur on initial entry into nxffs_packblock() when there we no space
- * for the inode header at the end of the previous block. We must now be
- * at the beginning of a shiny new I/O block, so we should always have
- * space for a new inode header right here.
- */
-
- if (pack->dest.entry.hoffset == 0)
- {
- /* Is there room for an inode structure in this block? */
-
- if(pack->iooffset + SIZEOF_NXFFS_INODE_HDR > volume->geo.blocksize)
- {
- /* No.. that inode name will not fit in this block. Return an
- * indication that we are at the end of the block and try again
- * later.
- */
-
- return -ENOSPC;
- }
-
- /* The inode header will be placed at this position (but not until
- * we are finished.
- */
-
- pack->dest.entry.hoffset = nxffs_packtell(volume, pack);
-
- /* Make sure that the initialize state of the inode header memory is
- * erased. This is important because we may not write to inode header
- * until it has already been written to FLASH.
- */
-
- memset(&pack->iobuffer[pack->iooffset], CONFIG_NXFFS_ERASEDSTATE,
- SIZEOF_NXFFS_INODE_HDR);
-
- /* Then set the new FLASH offset */
-
- pack->iooffset += SIZEOF_NXFFS_INODE_HDR;
- }
-
- /* State 2: inode position found, inode header not written, inode name
- * position not determined.
- */
-
- if (pack->dest.entry.noffset == 0)
- {
- /* Find the offset to the string memory. Will if fit in this block?
- * Note: iooffset has already been incremented to account for the
- * size of the inode header.
- */
-
- namlen = strlen(pack->dest.entry.name);
- if (pack->iooffset + namlen > volume->geo.blocksize)
- {
- /* No.. that inode name will not fit in this block. Return an
- * indication that we are at the end of the block and try again
- * later.
- */
-
- return -ENOSPC;
- }
-
- /* Yes.. Write the inode name to the volume packing buffer now, but do
- * not free the name string memory yet; it will be needed later to\
- * calculate the header CRC.
- */
-
- memcpy(&pack->iobuffer[pack->iooffset], pack->dest.entry.name, namlen);
-
- /* Reserve space for the inode name */
-
- pack->dest.entry.noffset = nxffs_packtell(volume, pack);
- pack->iooffset += namlen;
- }
-
- /* State 3: Inode header not-written, inode name written. Still need the position
- * of the first data block.
- *
- * Deal with the special case where the source inode is a zero length file
- * with no data blocks to be transferred.
- */
-
- if (pack->src.entry.doffset > 0)
- {
- if (pack->dest.entry.doffset == 0)
- {
- /* Will the data block header plus a minimal amount of data fit in this
- * block? (or the whole file if the file is very small).
- */
-
- mindata = MIN(NXFFS_MINDATA, pack->dest.entry.datlen);
- if (pack->iooffset + SIZEOF_NXFFS_DATA_HDR + mindata > volume->geo.blocksize)
- {
- /* No.. return an indication that we are at the end of the block
- * and try again later.
- */
-
- ret = -ENOSPC;
- goto errout;
- }
-
- /* Yes.. reserve space for the data block header */
-
- pack->dest.entry.doffset = nxffs_packtell(volume, pack);
- pack->iooffset += SIZEOF_NXFFS_DATA_HDR;
-
- /* Initialize the output data stream to start with the first data block */
-
- pack->dest.blkoffset = pack->dest.entry.doffset;
- pack->dest.blklen = 0;
- pack->dest.blkpos = 0;
- }
-
- /* State 4: Starting a new block. Verify that there is space in the current
- * block for another (minimal sized) block
- */
-
- if (pack->dest.blkoffset == 0)
- {
- /* Will the data block header plus a minimal amount of data fit in this
- * block? (or the whole file if the file is very small).
- */
-
- mindata = MIN(NXFFS_MINDATA, pack->dest.entry.datlen);
- if (pack->iooffset + SIZEOF_NXFFS_DATA_HDR + mindata > volume->geo.blocksize)
- {
- /* No.. return an indication that we are at the end of the block
- * and try again later.
- */
-
- ret = -ENOSPC;
- goto errout;
- }
-
- /* Yes.. reserve space for the data block header */
-
- pack->dest.blkoffset = nxffs_packtell(volume, pack);
- pack->iooffset += SIZEOF_NXFFS_DATA_HDR;
- pack->dest.blklen = 0;
- pack->dest.blkpos = 0;
- }
- }
-
- ret = OK;
-
-errout:
- volume->froffset = nxffs_packtell(volume, pack);
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wrinodehdr
- *
- * Description:
- * Write the destination inode header (only) to FLASH. Note that the inode
- * name has already been written to FLASH (thus greatly simplifying the
- * the complexity of this operation).
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure (not used).
- *
- ****************************************************************************/
-
-static int nxffs_wrinodehdr(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- FAR struct nxffs_inode_s *inode;
- off_t ioblock;
- uint16_t iooffset;
- uint32_t crc;
- int namlen;
- int ret;
-
- /* Get seek positions corresponding to the inode header location */
-
- ioblock = nxffs_getblock(volume, pack->dest.entry.hoffset);
- iooffset = nxffs_getoffset(volume, pack->dest.entry.hoffset, ioblock);
-
- /* The inode header is not written until all of the inode data has been
- * packed into its new location. As a result, there are two possibilities:
- *
- * 1. The inode header lies in the current, unwritten erase block,
- * 2. The inode header resides in an earlier erase block and has already
- * been written to FLASH.
- *
- * Recall that the inode name has already been written to FLASH. If that
- * were not the case, then there would be other complex possibilities.
- *
- * Case 2: Does the inode header reside in a block before the beginning
- * of the current erase block?
- */
-
- if (ioblock < pack->block0)
- {
- /* Case 2: The inode header lies in an earlier erase block that has
- * already been written to FLASH. In this case, if we are very
- * careful, we can just use the standard routine to write the inode
- * header that is called during the normal file close operation:
- */
-
- ret = nxffs_wrinode(volume, &pack->dest.entry);
- }
- else
- {
- /* Cases 1: Both the inode header and name are in the unwritten cache
- * memory.
- *
- * Initialize the inode header.
- */
-
- iooffset += (ioblock - pack->block0) * volume->geo.blocksize;
- inode = (FAR struct nxffs_inode_s *)&volume->pack[iooffset];
- memcpy(inode->magic, g_inodemagic, NXFFS_MAGICSIZE);
-
- nxffs_wrle32(inode->noffs, pack->dest.entry.noffset);
- nxffs_wrle32(inode->doffs, pack->dest.entry.doffset);
- nxffs_wrle32(inode->utc, pack->dest.entry.utc);
- nxffs_wrle32(inode->crc, 0);
- nxffs_wrle32(inode->datlen, pack->dest.entry.datlen);
-
- /* Get the length of the inode name */
-
- namlen = strlen(pack->dest.entry.name);
- DEBUGASSERT(namlen < CONFIG_NXFFS_MAXNAMLEN);
-
- inode->state = CONFIG_NXFFS_ERASEDSTATE;
- inode->namlen = namlen;
-
- /* Calculate the CRC */
-
- crc = crc32((FAR const uint8_t *)inode, SIZEOF_NXFFS_INODE_HDR);
- crc = crc32part((FAR const uint8_t *)pack->dest.entry.name, namlen, crc);
-
- /* Finish the inode header */
-
- inode->state = INODE_STATE_FILE;
- nxffs_wrle32(inode->crc, crc);
-
- /* If any open files reference this inode, then update the open file
- * state.
- */
-
- ret = nxffs_updateinode(volume, &pack->dest.entry);
- if (ret < 0)
- {
- fdbg("Failed to update inode info: %s\n", -ret);
- }
- }
-
- /* Reset the dest inode information */
-
- nxffs_freeentry(&pack->dest.entry);
- memset(&pack->dest, 0, sizeof(struct nxffs_packstream_s));
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wrdatthdr
- *
- * Description:
- * Write the destination data block header to FLASH.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static void nxffs_wrdathdr(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- FAR struct nxffs_data_s *dathdr;
- off_t ioblock;
- uint16_t iooffset;
- uint32_t crc;
-
- if (pack->dest.blklen > 0)
- {
- /* Get the offset in the block corresponding to the location of the data
- * block header. NOTE: This must lie in the same block as we currently have
- * buffered.
- */
-
- ioblock = nxffs_getblock(volume, pack->dest.blkoffset);
- iooffset = nxffs_getoffset(volume, pack->dest.blkoffset, ioblock);
- DEBUGASSERT(pack->dest.blkoffset && ioblock == pack->ioblock);
-
- /* Write the data block header to memory */
-
- dathdr = (FAR struct nxffs_data_s *)&pack->iobuffer[iooffset];
- memcpy(dathdr->magic, g_datamagic, NXFFS_MAGICSIZE);
- nxffs_wrle32(dathdr->crc, 0);
- nxffs_wrle16(dathdr->datlen, pack->dest.blklen);
-
- /* Update the entire data block CRC (including the header) */
-
- crc = crc32(&pack->iobuffer[iooffset], pack->dest.blklen + SIZEOF_NXFFS_DATA_HDR);
- nxffs_wrle32(dathdr->crc, crc);
- }
-
- /* Setup state to allocate the next data block */
-
- pack->dest.blkoffset = 0;
- pack->dest.blklen = 0;
- pack->dest.blkpos = 0;
-}
-
-/****************************************************************************
- * Name: nxffs_packtransfer
- *
- * Description:
- * Transfer data from the source to the destination buffer.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * None.
- *
- ****************************************************************************/
-
-static void nxffs_packtransfer(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- /* Determine how much data is available in the dest pack buffer */
-
- uint16_t destlen = volume->geo.blocksize - pack->iooffset;
-
- /* Dermined how much data is available in the src data block */
-
- uint16_t srclen = pack->src.blklen - pack->src.blkpos;
-
- /* Transfer the smaller of the two amounts data */
-
- uint16_t xfrlen = MIN(srclen, destlen);
- if (xfrlen > 0)
- {
- nxffs_ioseek(volume, pack->src.blkoffset + SIZEOF_NXFFS_DATA_HDR + pack->src.blkpos);
- memcpy(&pack->iobuffer[pack->iooffset], &volume->cache[volume->iooffset], xfrlen);
-
- /* Increment counts and offset for this data transfer */
-
- pack->src.fpos += xfrlen; /* Source data offsets */
- pack->src.blkpos += xfrlen;
- pack->dest.fpos += xfrlen; /* Destination data offsets */
- pack->dest.blkpos += xfrlen;
- pack->dest.blklen += xfrlen; /* Destination data block size */
- pack->iooffset += xfrlen; /* Destination I/O block offset */
- volume->iooffset += xfrlen; /* Source I/O block offset */
- volume->froffset += xfrlen; /* Free FLASH offset */
- }
-}
-
-/****************************************************************************
- * Name: nxffs_endsrcblock
- *
- * Description:
- * The end of a source data block has been encountered. Locate the next
- * source block and setup to continue the transfer.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static int nxffs_endsrcblock(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- struct nxffs_blkentry_s blkentry;
- off_t offset;
- int ret;
-
- /* Yes.. find the next data block in the source input stream. */
-
- offset = pack->src.blkoffset + SIZEOF_NXFFS_DATA_HDR + pack->src.blklen;
- ret = nxffs_nextblock(volume, offset, &blkentry);
- if (ret < 0)
- {
- fdbg("Failed to find next data block: %d\n", -ret);
- return ret;
- }
-
- /* Set up the source stream */
-
- pack->src.blkoffset = blkentry.hoffset;
- pack->src.blklen = blkentry.datlen;
- pack->src.blkpos = 0;
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_packblock
- *
- * Description:
- * Resume packing from the source stream into the newly identified
- * destination block.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static inline int nxffs_packblock(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- off_t offset;
- int ret;
-
- /* Are we currently processing a block from the source stream? */
-
- if (pack->src.blkoffset == 0)
- {
- /* No.. setup the source stream */
-
- ret = nxffs_srcsetup(volume, pack, pack->src.entry.doffset);
- if (ret < 0)
- {
- fdbg("Failed to configure the src stream: %d\n", -ret);
- return ret;
- }
- }
-
- /* We enter here on a new block every time, so we always have to setup
- * the dest data stream. There should never be data block allocated at
- * this point in time.
- */
-
- DEBUGASSERT(pack->dest.blkoffset == 0 && pack->dest.blkpos == 0);
-
- ret = nxffs_destsetup(volume, pack);
- if (ret < 0)
- {
- /* -ENOSPC is a special return value which simply means that all of
- * the FLASH has been used up to the end of the current. We need to
- * return OK in this case and resume at the next block.
- */
-
- if (ret == -ENOSPC)
- {
- return OK;
- }
- else
- {
- fdbg("Failed to configure the dest stream: %d\n", -ret);
- return ret;
- }
- }
-
- /* Loop, transferring data from the source block to the destination pack
- * buffer until either (1) the source stream is exhausted, (2) the destination
- * block is full, or (3) an error occurs.
- */
-
- for (;;)
- {
- /* Transfer data from the source buffer to the destination buffer */
-
- nxffs_packtransfer(volume, pack);
-
- /* Now, either the (1) src block has been fully transferred, (2) all
- * of the source data has been transferred, or (3) the the destination
- * block is full, .. or all three.
- *
- * Check if all of the bytes in the source inode have been transferred.
- */
-
- if (pack->src.fpos >= pack->src.entry.datlen)
- {
- /* Write the final destination data block header and inode
- * headers.
- */
-
- nxffs_wrdathdr(volume, pack);
- nxffs_wrinodehdr(volume, pack);
-
- /* Find the next valid source inode */
-
- offset = pack->src.blkoffset + pack->src.blklen;
- memset(&pack->src, 0, sizeof(struct nxffs_packstream_s));
-
- ret = nxffs_nextentry(volume, offset, &pack->src.entry);
- if (ret < 0)
- {
- /* No more valid inode entries. Just return an end-of-flash error
- * indication.
- */
-
- return -ENOSPC;
- }
-
- /* Setup the new source stream */
-
- ret = nxffs_srcsetup(volume, pack, pack->src.entry.doffset);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Setup the dest stream */
-
- memset(&pack->dest, 0, sizeof(struct nxffs_packstream_s));
- pack->dest.entry.name = pack->src.entry.name;
- pack->dest.entry.utc = pack->src.entry.utc;
- pack->dest.entry.datlen = pack->src.entry.datlen;
- pack->src.entry.name = NULL;
-
- /* Is there sufficient space at the end of the I/O block to hold
- * the inode header?
- */
-
- if (pack->iooffset + SIZEOF_NXFFS_INODE_HDR > volume->geo.blocksize)
- {
- /* No, just return success... we will handle this condition when
- * this function is called on the next I/O block.
- */
-
- return OK;
- }
-
- /* Configure the destination stream */
-
- ret = nxffs_destsetup(volume, pack);
- if (ret < 0)
- {
- /* -ENOSPC is a special return value which simply means that all of the
- * has been used up to the end. We need to return OK in this case and
- * resume at the next block.
- */
-
- if (ret == -ENOSPC)
- {
- return OK;
- }
- else
- {
- fdbg("Failed to configure the dest stream: %d\n", -ret);
- return ret;
- }
- }
- }
-
- /* Not at the end of the source data stream. Check if we are at the
- * end of the current source data block.
- */
-
- else if (pack->src.blkpos >= pack->src.blklen)
- {
- ret = nxffs_endsrcblock(volume, pack);
- if (ret < 0)
- {
- return ret;
- }
- }
-
- /* Check if the destination block is full */
-
- if (pack->iooffset >= volume->geo.blocksize)
- {
- /* Yes.. Write the destination data block header and return success */
-
- nxffs_wrdathdr(volume, pack);
- return OK;
- }
- }
-
- return -ENOSYS;
-}
-
-/****************************************************************************
- * Name: nxffs_setupwriter
- *
- * Description:
- * Writing is performed at the end of the free FLASH region. When we
- * finish packing the other inodes, we still need to pack the partially
- * written file at the end of FLASH. This function performs the setup
- * necessary to perform that packing phase.
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * If there is an active writer of the volume, its open file instance is
- * returned. NULL is returned otherwise.
- *
- ****************************************************************************/
-
-static FAR struct nxffs_wrfile_s *
-nxffs_setupwriter(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack)
-{
- FAR struct nxffs_wrfile_s *wrfile;
-
- /* Is there a writer? */
-
- wrfile = nxffs_findwriter(volume);
- if (wrfile)
- {
- /* Yes... It is the activity of this write that probably initiated
- * this packing activity. The writer may have failed in one of several
- * different stages:
- *
- * hoffset == 0: The write failed early before even FLASH for the inode
- * header was set aside.
- * noffset == 0: The write failed after the inode header was set aside,
- * but before the inode name was written.
- * doffset == 0: The write failed after writing the inode name, bue
- * before any data blocks were written to FLASH.
- *
- * If no FLASH has been set aside for the write, then we don't need to
- * do anything here.
- */
-
- if (wrfile->ofile.entry.hoffset > 0)
- {
- /* Initialize for the packing operation. */
-
- memset(&pack->dest, 0, sizeof(struct nxffs_packstream_s));
- pack->dest.entry.name = strdup(wrfile->ofile.entry.name);
- pack->dest.entry.utc = wrfile->ofile.entry.utc;
- pack->dest.entry.datlen = wrfile->ofile.entry.datlen;
-
- memset(&pack->src, 0, sizeof(struct nxffs_packstream_s));
- memcpy(&pack->src.entry, &wrfile->ofile.entry, sizeof(struct nxffs_entry_s));
- pack->src.entry.name = NULL;
- return wrfile;
- }
- }
-
- return NULL;
-}
-
-/****************************************************************************
- * Name: nxffs_packwriter
- *
- * Description:
- * There is a write in progress at the time that the volume is packed.
- * This is the normal case because it is the write failures that trigger
- * the packing operation to begin with.
- *
- * Writing is performed at the end of the free FLASH region and this
- * implemenation is restricted to a single writer. The new inode is not
- * written to FLASH until the the writer is closed and so will not be
- * found by nxffs_packblock().
- *
- * Input Parameters:
- * volume - The volume to be packed
- * pack - The volume packing state structure.
- *
- * Returned Values:
- * Zero on success; Otherwise, a negated errno value is returned to
- * indicate the nature of the failure.
- *
- ****************************************************************************/
-
-static inline int nxffs_packwriter(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_pack_s *pack,
- FAR struct nxffs_wrfile_s *wrfile)
-{
- int ret;
-
- /* Are we currently processing a block from the source stream? */
-
- if (pack->src.blkoffset == 0)
- {
- /* No.. setup the source stream */
-
- ret = nxffs_srcsetup(volume, pack, pack->src.entry.doffset);
- if (ret < 0)
- {
- fdbg("Failed to configure the src stream: %d\n", -ret);
- return ret;
- }
- }
-
- /* We enter here on a new block every time, so we always have to setup
- * the dest data stream. There should never be data block allocated at
- * this point in time.
- */
-
- DEBUGASSERT(pack->dest.blkoffset == 0 && pack->dest.blkpos == 0);
-
- ret = nxffs_destsetup(volume, pack);
- if (ret < 0)
- {
- /* -ENOSPC is a special return value which simply means that all of the
- * has been used up to the end. We need to return OK in this case and
- * resume at the next block.
- */
-
- if (ret == -ENOSPC)
- {
- return OK;
- }
- else
- {
- fdbg("Failed to configure the dest stream: %d\n", -ret);
- return ret;
- }
- }
-
- /* Loop, transferring data from the source block to the destination pack
- * buffer until either (1) the source stream is exhausted, (2) the destination
- * block is full, or (3) an error occurs.
- */
-
- for (;;)
- {
- /* Transfer data from the source buffer to the destination buffer */
-
- nxffs_packtransfer(volume, pack);
-
- /* Now, either the (1) src block has been fully transferred, (2) all
- * of the source data has been transferred, or (3) the the destination
- * block is full, .. or all three.
- *
- * Check if all of the bytes in the source inode have been transferred.
- */
-
- if (pack->src.fpos >= pack->src.entry.datlen)
- {
- /* Write the final destination data block header and inode
- * headers.
- */
-
- nxffs_wrdathdr(volume, pack);
-
- /* Set the new offsets in the open file instance. */
-
- wrfile->ofile.entry.hoffset = pack->dest.entry.hoffset;
- wrfile->ofile.entry.noffset = pack->dest.entry.noffset;
- wrfile->ofile.entry.doffset = pack->dest.entry.doffset;
-
- /* Return an end-of-flash error to indicate that all of the write
- * data has been transferred.
- */
-
- return -ENOSPC;
- }
-
- /* Not at the end of the source data stream. Check if we are at the
- * end of the current source data block.
- */
-
- else if (pack->src.blkpos >= pack->src.blklen)
- {
- ret = nxffs_endsrcblock(volume, pack);
- if (ret < 0)
- {
- return ret;
- }
- }
-
- /* Check if the destination block is full */
-
- if (pack->iooffset >= volume->geo.blocksize)
- {
- /* Yes.. Write the destination data block header and return success */
-
- nxffs_wrdathdr(volume, pack);
- return OK;
- }
- }
-
- return -ENOSYS;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_pack
- *
- * Description:
- * Pack and re-write the filesystem in order to free up memory at the end
- * of FLASH.
- *
- * 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.
- *
- ****************************************************************************/
-
-int nxffs_pack(FAR struct nxffs_volume_s *volume)
-{
- struct nxffs_pack_s pack;
- FAR struct nxffs_wrfile_s *wrfile;
- off_t iooffset;
- off_t eblock;
- off_t block;
- bool packed;
- int i;
- int ret;
-
- /* Get the offset to the first valid inode entry */
-
- wrfile = NULL;
- packed = false;
-
- iooffset = nxffs_mediacheck(volume, &pack);
- if (iooffset == 0)
- {
- /* 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
- * really is nothing on the FLASH, or (2) there is a file being written
- * to the FLASH now.
- */
-
- /* Is there a writer? */
-
- wrfile = nxffs_setupwriter(volume, &pack);
- if (wrfile)
- {
- /* If there is a write, just set ioffset to the offset of data in
- * first block. Setting 'packed' to true will supress normal inode
- * packing operation. Then we can start compacting the FLASH.
- */
-
- iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- packed = true;
- goto start_pack;
- }
- else
- {
- /* No, there is no write in progress. We just have an empty flash
- * full of deleted files. In this case, the media needs to be re-
- * formatted.
- */
-
- ret = nxffs_reformat(volume);
- if (ret == OK)
- {
- /* The free flash offset will be in the first valid block of
- * the FLASH.
- */
-
- block = 0;
- ret = nxffs_validblock(volume, &block);
- if (ret == OK)
- {
- /* Set to the offset past the block header in the first
- * valid block
- */
-
- volume->froffset =
- block * volume->geo.blocksize + SIZEOF_NXFFS_BLOCK_HDR;
- }
- }
-
- return ret;
- }
- }
-
- /* There is a valid format and valid inodes on the media.. setup up to
- * begin the packing operation.
- */
-
- ret = nxffs_startpos(volume, &pack, &iooffset);
- if (ret < 0)
- {
- /* This is a normal situation if the volume is full */
-
- if (ret == -ENOSPC)
- {
- /* In the case where the volume is full, nxffs_startpos() will
- * recalculate the free FLASH offset and store it in iooffset. There
- * may be deleted files at the end of FLASH. In this case, we don't
- * have to pack any files, we simply have to erase FLASH at the end.
- * But don't do this unless there is some particularly big FLASH
- * savings (otherwise, we risk wearing out these final blocks).
- */
-
- if (iooffset + CONFIG_NXFFS_TAILTHRESHOLD < volume->froffset)
- {
- /* Setting 'packed' to true will supress normal inode packing
- * operation.
- */
-
- packed = true;
-
- /* Writing is performed at the end of the free FLASH region.
- * If we are not packing files, we could still need to pack
- * the partially written file at the end of FLASH.
- */
-
- wrfile = nxffs_setupwriter(volume, &pack);
- }
-
- /* Otherwise return OK.. meaning that there is nothing more we can
- * do to recover FLASH space.
- */
-
- else
- {
- return OK;
- }
- }
- else
- {
- fvdbg("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
- * iooffset.
- */
-
-start_pack:
-
- pack.ioblock = nxffs_getblock(volume, iooffset);
- pack.iooffset = nxffs_getoffset(volume, iooffset, pack.ioblock);
- volume->froffset = iooffset;
-
- /* Then pack all erase blocks starting with the erase block that contains
- * the ioblock and through the final erase block on the FLASH.
- */
-
- for (eblock = pack.ioblock / volume->blkper;
- eblock < volume->geo.neraseblocks;
- eblock++)
- {
- /* Read the erase block into the pack buffer. We need to do this even
- * if we are overwriting the entire block so that we skip over
- * previously marked bad blocks.
- */
-
- pack.block0 = eblock * volume->blkper;
- 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);
- goto errout_with_pack;
- }
-
- /* Pack each I/O block */
-
- for (i = 0, block = pack.block0, pack.iobuffer = volume->pack;
- i < volume->blkper;
- i++, block++, pack.iobuffer += volume->geo.blocksize)
- {
- /* The first time here, the ioblock may point to an offset into
- * the erase block. We just need to skip over those cases.
- */
-
- if (block >= pack.ioblock)
- {
- /* Set the I/O position. Note on the first time we get
- * pack.iooffset will hold the offset in the first I/O block
- * to the first inode header. After that, it will always
- * refer to the first byte after the block header.
- */
-
- pack.ioblock = block;
-
- /* If this is not a valid block or if we have already
- * finished packing the valid inode entries, then just fall
- * through, reset the FLASH memory to the erase state, and
- * write the reset values to FLASH. (The first block that
- * we want to process will always be valid -- we have
- * already verified that).
- */
-
- if (nxffs_packvalid(&pack))
- {
- /* Have we finished packing inodes? */
-
- if (!packed)
- {
- DEBUGASSERT(wrfile == NULL);
-
- /* Pack inode data into this block */
-
- ret = nxffs_packblock(volume, &pack);
- if (ret < 0)
- {
- /* The error -ENOSPC is a special value that simply
- * means that there is nothing further to be packed.
- */
-
- if (ret == -ENOSPC)
- {
- packed = true;
-
- /* Writing is performed at the end of the free
- * FLASH region and this implemenation is restricted
- * to a single writer. The new inode is not
- * written to FLASH until the the writer is closed
- * and so will not be found by nxffs_packblock().
- */
-
- wrfile = nxffs_setupwriter(volume, &pack);
- }
- else
- {
- /* Otherwise, something really bad happened */
-
- fdbg("Failed to pack into block %d: %d\n",
- block, ret);
- goto errout_with_pack;
- }
- }
- }
-
- /* If all of the "normal" inodes have been packed, then check if
- * we need to pack the current, in-progress write operation.
- */
-
- if (wrfile)
- {
- DEBUGASSERT(packed == true);
-
- /* Pack write data into this block */
-
- ret = nxffs_packwriter(volume, &pack, wrfile);
- if (ret < 0)
- {
- /* The error -ENOSPC is a special value that simply
- * means that there is nothing further to be packed.
- */
-
- if (ret == -ENOSPC)
- {
- wrfile = NULL;
- }
- else
- {
- /* Otherwise, something really bad happened */
-
- fdbg("Failed to pack into block %d: %d\n",
- block, ret);
- goto errout_with_pack;
- }
- }
- }
- }
-
- /* Set any unused portion at the end of the block to the
- * erased state.
- */
-
- if (pack.iooffset < volume->geo.blocksize)
- {
- memset(&pack.iobuffer[pack.iooffset],
- CONFIG_NXFFS_ERASEDSTATE,
- volume->geo.blocksize - pack.iooffset);
- }
-
- /* Next time through the loop, pack.iooffset will point to the
- * first byte after the block header.
- */
-
- pack.iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- }
- }
-
- /* We now have an in-memory image of how we want this erase block to
- * appear. Now it is safe to erase the block.
- */
-
- ret = MTD_ERASE(volume->mtd, eblock, 1);
- if (ret < 0)
- {
- fdbg("Failed to erase block %d [%d]: %d\n",
- eblock, pack.block0, -ret);
- goto errout_with_pack;
- }
-
- /* Write the packed I/O block to FLASH */
-
- ret = MTD_BWRITE(volume->mtd, pack.block0, volume->blkper, volume->pack);
- if (ret < 0)
- {
- fdbg("Failed to write erase block %d [%]: %d\n",
- eblock, pack.block0, -ret);
- goto errout_with_pack;
- }
- }
-
-errout_with_pack:
- nxffs_freeentry(&pack.src.entry);
- nxffs_freeentry(&pack.dest.entry);
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_read.c b/nuttx/fs/nxffs/nxffs_read.c
deleted file mode 100644
index b638dbfd4..000000000
--- a/nuttx/fs/nxffs/nxffs_read.c
+++ /dev/null
@@ -1,473 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_read.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <fcntl.h>
-#include <crc32.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-#include <nuttx/mtd.h>
-
-#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
- * blkentry - Describes the block entry that we are positioned in
- *
- ****************************************************************************/
-
-static ssize_t nxffs_rdseek(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_entry_s *entry,
- off_t fpos,
- FAR struct nxffs_blkentry_s *blkentry)
-{
- size_t datstart;
- size_t datend;
- off_t offset;
- int ret;
-
- /* The initial FLASH offset will be the offset to first data block of
- * the inode
- */
-
- offset = entry->doffset;
- if (offset == 0)
- {
- /* Zero length files will have no data blocks */
-
- return -ENOSPC;
- }
-
- /* Loop until we read the data block containing the desired position */
-
- datend = 0;
- do
- {
- /* Check if the next data block contains the sought after file position */
-
- ret = nxffs_nextblock(volume, offset, blkentry);
- if (ret < 0)
- {
- fdbg("nxffs_nextblock failed: %d\n", -ret);
- return ret;
- }
-
- /* Get the range of data offsets for this data block */
-
- datstart = datend;
- datend += blkentry->datlen;
-
- /* Offset to search for the the next data block */
-
- offset = blkentry->hoffset + SIZEOF_NXFFS_DATA_HDR + blkentry->datlen;
- }
- while (datend <= fpos);
-
- /* Return the offset to the data within the current data block */
-
- blkentry->foffset = fpos - datstart;
- nxffs_ioseek(volume, blkentry->hoffset + SIZEOF_NXFFS_DATA_HDR + blkentry->foffset);
- return OK;
-}
-
-/****************************************************************************
- * 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;
- struct nxffs_blkentry_s blkentry;
- ssize_t total;
- size_t available;
- size_t readsize;
- int 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->oflags & O_RDOK) == 0)
- {
- fdbg("File not open for read access\n");
- ret = -EACCES;
- goto errout_with_semaphore;
- }
-
- /* Loop until all bytes have been read */
-
- for (total = 0; total < buflen; )
- {
- /* Don't seek past the end of the file */
-
- if (filep->f_pos >= ofile->entry.datlen)
- {
- /* Return the partial read */
-
- filep->f_pos = ofile->entry.datlen;
- break;
- }
-
- /* Seek to the current file offset */
-
- ret = nxffs_rdseek(volume, &ofile->entry, filep->f_pos, &blkentry);
- if (ret < 0)
- {
- fdbg("nxffs_rdseek failed: %d\n", -ret);
- ret = -EACCES;
- goto errout_with_semaphore;
- }
-
- /* How many bytes are available at this offset */
-
- available = blkentry.datlen - blkentry.foffset;
-
- /* Don't read more than we need to */
-
- readsize = buflen - total;
- if (readsize > available)
- {
- readsize = available;
- }
-
- /* Read data from that file offset */
-
- memcpy(&buffer[total], &volume->cache[volume->iooffset], readsize);
-
- /* Update the file offset */
-
- filep->f_pos += readsize;
- total += readsize;
- }
-
- sem_post(&volume->exclsem);
- return total;
-
-errout_with_semaphore:
- sem_post(&volume->exclsem);
-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, SIZEOF_NXFFS_DATA_HDR - nmagic);
- 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])
- {
- /* Ooops... this is the not the right character for the magic
- * Sequence. Check if we need to restart or to cancel the sequence:
- */
-
- if (ch == g_datamagic[0])
- {
- nmagic = 1;
- }
- else
- {
- nmagic = 0;
- }
- }
- else if (nmagic < NXFFS_MAGICSIZE - 1)
- {
- /* We have one more character in the magic sequence */
-
- 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) - NXFFS_MAGICSIZE;
-
- /* 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.. Restore the volume cache position (that was
- * destroyed by nxfs_rdblkhdr()) and keep looking.
- */
-
- nxffs_ioseek(volume, blkentry->hoffset + NXFFS_MAGICSIZE);
- nmagic = 0;
- }
- }
- }
-
- /* We won't get here, but to keep some compilers happy: */
-
- return -ENOENT;
-}
-
-/****************************************************************************
- * Name: nxffs_rdblkhdr
- *
- * Description:
- * Read and verify the data block header at the specified offset.
- *
- * Input Parameters:
- * volume - Describes the current volume.
- * offset - The byte offset from the beginning of FLASH where the data block
- * header is expected.
- * datlen - A memory location to return the data block length.
- *
- * Returned Value:
- * Zero on success. Otherwise, a negated errno value is returned
- * indicating the nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_rdblkhdr(FAR struct nxffs_volume_s *volume, off_t offset,
- FAR uint16_t *datlen)
-{
- struct nxffs_data_s blkhdr;
- uint32_t ecrc;
- uint32_t crc;
- uint16_t doffset;
- uint16_t dlen;
- int ret;
-
- /* Make sure the the block containing the data block header is in the cache */
-
- nxffs_ioseek(volume, offset);
- ret = nxffs_rdcache(volume, volume->ioblock);
- if (ret < 0)
- {
- fvdbg("Failed to read data into cache: %d\n", ret);
- return ret;
- }
-
- /* Read the header at the FLASH offset */
-
- doffset = volume->iooffset;
- memcpy(&blkhdr, &volume->cache[doffset], SIZEOF_NXFFS_DATA_HDR);
-
- /* Extract the data length */
-
- dlen = nxffs_rdle16(blkhdr.datlen);
-
- /* Get the offset to the beginning of the data */
-
- doffset += SIZEOF_NXFFS_DATA_HDR;
-
- /* Make sure that all of the data fits within the block */
-
- if ((uint32_t)doffset + (uint32_t)dlen > (uint32_t)volume->geo.blocksize)
- {
- 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);
-
- nxffs_wrle32(blkhdr.crc, 0);
- crc = crc32((FAR const uint8_t *)&blkhdr, SIZEOF_NXFFS_DATA_HDR);
- crc = crc32part(&volume->cache[doffset], dlen, crc);
-
- if (crc != ecrc)
- {
- fdbg("CRC failure\n");
- return -EIO;
- }
-
- /* Looks good! Return the data length and success */
-
- *datlen = dlen;
- return OK;
-}
-
-
-
diff --git a/nuttx/fs/nxffs/nxffs_reformat.c b/nuttx/fs/nxffs/nxffs_reformat.c
deleted file mode 100644
index d3c00893d..000000000
--- a/nuttx/fs/nxffs/nxffs_reformat.c
+++ /dev/null
@@ -1,267 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_reformat.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <errno.h>
-#include <debug.h>
-
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_format
- *
- * Description:
- * Erase and reformat the entire volume.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume to be reformatted.
- *
- * Returned Value:
- * Zero on success or a negated errno on a failure. Failures will be
- * returned n the case of MTD reported failures o.
- * Nothing in the volume data itself will generate errors.
- *
- ****************************************************************************/
-
-static int nxffs_format(FAR struct nxffs_volume_s *volume)
-{
- FAR uint8_t *blkptr; /* Pointer to next block data */
- off_t eblock; /* Erase block number */
- off_t lblock; /* Logical block number */
- ssize_t nxfrd; /* Number of blocks transferred */
- int i;
- int ret;
-
- /* Create an image of one properly formatted erase sector */
-
- memset(volume->pack, CONFIG_NXFFS_ERASEDSTATE, volume->geo.erasesize);
- for (blkptr = volume->pack, i = 0;
- i < volume->blkper;
- blkptr += volume->geo.blocksize, i++)
- {
- FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr;
- memcpy(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE);
- blkhdr->state = BLOCK_STATE_GOOD;
- }
-
- /* Erase and format each erase block */
-
- for (eblock = 0; eblock < volume->geo.neraseblocks; eblock++)
- {
- /* Erase the block */
-
- ret = MTD_ERASE(volume->mtd, eblock, 1);
- if (ret < 0)
- {
- fdbg("Erase block %d failed: %d\n", eblock, ret);
- return ret;
- }
-
- /* Write the formatted image to the erase block */
-
- lblock = eblock * volume->blkper;
- nxfrd = MTD_BWRITE(volume->mtd, lblock, volume->blkper, volume->pack);
- if (nxfrd != volume->blkper)
- {
- fdbg("Write erase block %d failed: %d\n", lblock, nxfrd);
- return -EIO;
- }
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_badblocks
- *
- * Description:
- * Verify each block and mark improperly erased blocks as bad.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume to be reformatted.
- *
- * Returned Value:
- * Zero on success or a negated errno on a failure. Failures will be
- * returned n the case of MTD reported failures o.
- * Nothing in the volume data itself will generate errors.
- *
- ****************************************************************************/
-
-static int nxffs_badblocks(FAR struct nxffs_volume_s *volume)
-{
- FAR uint8_t *blkptr; /* Pointer to next block data */
- off_t eblock; /* Erase block number */
- off_t lblock; /* Logical block number */
- ssize_t nxfrd; /* Number of blocks transferred */
- bool good; /* TRUE: block is good */
- bool modified; /* TRUE: The erase block has been modified */
- int i;
-
- /* Read and verify each erase block */
-
- for (eblock = 0; eblock < volume->geo.neraseblocks; eblock++)
- {
- /* Read the entire erase block */
-
- lblock = eblock * volume->blkper;
- nxfrd = MTD_BREAD(volume->mtd, lblock, volume->blkper, volume->pack);
- if (nxfrd != volume->blkper)
- {
- fdbg("Read erase block %d failed: %d\n", lblock, nxfrd);
- return -EIO;
- }
-
- /* Process each logical block */
-
- modified = false;
- for (blkptr = volume->pack, i = 0;
- i < volume->blkper;
- blkptr += volume->geo.blocksize, i++)
- {
- FAR struct nxffs_block_s *blkhdr = (FAR struct nxffs_block_s*)blkptr;
-
- /* Check block header */
-
- good = true;
- if (memcmp(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE) != 0 ||
- blkhdr->state != BLOCK_STATE_GOOD)
- {
- good = false;
- }
-
- /* Check that block data is erased */
-
- else
- {
- size_t blocksize = volume->geo.blocksize - SIZEOF_NXFFS_BLOCK_HDR;
- size_t erasesize = nxffs_erased(&blkptr[SIZEOF_NXFFS_BLOCK_HDR], blocksize);
- good = (blocksize == erasesize);
- }
-
- /* If the block is bad, attempt to re-write the block header indicating
- * a bad block (of course, if the block has failed, this may not be
- * possible, depending upon failure modes.
- */
-
- if (!good)
- {
- memcpy(blkhdr->magic, g_blockmagic, NXFFS_MAGICSIZE);
- blkhdr->state = BLOCK_STATE_BAD;
- modified = true;
- }
- }
-
- /* If the erase block was modified, then re-write it */
-
- nxfrd = MTD_BWRITE(volume->mtd, lblock, volume->blkper, volume->pack);
- if (nxfrd != volume->blkper)
- {
- fdbg("Write erase block %d failed: %d\n", lblock, nxfrd);
- return -EIO;
- }
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_reformat
- *
- * Description:
- * Erase and reformat the entire volume. Verify each block and mark
- * improperly erased blocks as bad.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume to be reformatted.
- *
- * Returned Value:
- * Zero on success or a negated errno on a failure. Failures will be
- * returned n the case of MTD reported failures o.
- * Nothing in the volume data itself will generate errors.
- *
- ****************************************************************************/
-
-int nxffs_reformat(FAR struct nxffs_volume_s *volume)
-{
- int ret;
-
- /* Erase and reformat the entire volume */
-
- ret = nxffs_format(volume);
- if (ret < 0)
- {
- fdbg("Failed to reformat the volume: %d\n", -ret);
- return ret;
- }
-
- /* Check for bad blocks */
-
- ret = nxffs_badblocks(volume);
- if (ret < 0)
- {
- fdbg("Bad block check failed: %d\n", -ret);
- }
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_stat.c b/nuttx/fs/nxffs/nxffs_stat.c
deleted file mode 100644
index d4d58a72c..000000000
--- a/nuttx/fs/nxffs/nxffs_stat.c
+++ /dev/null
@@ -1,186 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_stat.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <sys/stat.h>
-#include <sys/statfs.h>
-
-#include <string.h>
-#include <fcntl.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_statfs
- *
- * Description: Return filesystem statistics
- *
- ****************************************************************************/
-
-int nxffs_statfs(FAR struct inode *mountpt, FAR struct statfs *buf)
-{
- FAR struct nxffs_volume_s *volume;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private);
-
- /* Get the mountpoint private data from the NuttX inode structure */
-
- volume = mountpt->i_private;
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- goto errout;
- }
-
- /* Fill in the statfs info */
-#warning "Need f_bfree, f_bavail, f_files, f_ffree calculation"
-
- memset(buf, 0, sizeof(struct statfs));
- buf->f_type = NXFFS_MAGIC;
- buf->f_bsize = volume->geo.blocksize;
- buf->f_blocks = volume->nblocks;
- buf->f_namelen = volume->geo.blocksize - SIZEOF_NXFFS_BLOCK_HDR - SIZEOF_NXFFS_INODE_HDR;
- ret = OK;
-
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_stat
- *
- * Description: Return information about a file or directory
- *
- ****************************************************************************/
-
-int nxffs_stat(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct stat *buf)
-{
- FAR struct nxffs_volume_s *volume;
- struct nxffs_entry_s entry;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private && buf);
-
- /* Get the mountpoint private data from the NuttX inode structure */
-
- volume = mountpt->i_private;
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- goto errout;
- }
-
- /* Initialize the return stat instance */
-
- memset(buf, 0, sizeof(struct stat));
- buf->st_blksize = volume->geo.blocksize;
- buf->st_blocks = entry.datlen / (volume->geo.blocksize - SIZEOF_NXFFS_BLOCK_HDR);
-
- /* The requested directory must be the volume-relative "root" directory */
-
- if (relpath && relpath[0] != '\0')
- {
- /* Not the top directory.. find the NXFFS inode with this name */
-
- ret = nxffs_findinode(volume, relpath, &entry);
- if (ret < 0)
- {
- fdbg("Inode '%s' not found: %d\n", -ret);
- goto errout_with_semaphore;
- }
-
- buf->st_mode = S_IFREG|S_IXOTH|S_IXGRP|S_IXUSR;
- buf->st_size = entry.datlen;
- buf->st_atime = entry.utc;
- buf->st_mtime = entry.utc;
- buf->st_ctime = entry.utc;
- }
- else
- {
- /* It's a read/execute-only directory name */
-
- buf->st_mode = S_IFDIR|S_IROTH|S_IRGRP|S_IRUSR|S_IXOTH|S_IXGRP|S_IXUSR;
- }
-
- ret = OK;
-
-errout_with_semaphore:
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_unlink.c b/nuttx/fs/nxffs/nxffs_unlink.c
deleted file mode 100644
index 73b0f360a..000000000
--- a/nuttx/fs/nxffs/nxffs_unlink.c
+++ /dev/null
@@ -1,187 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_unlink.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <errno.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_rminode
- *
- * Description:
- * Remove an inode from FLASH. This is the internal implementation of
- * the file system unlinke operation.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume.
- * name - the name of the inode to be deleted.
- *
- * Returned Value:
- * Zero is returned if the inode is successfully deleted. Otherwise, a
- * negated errno value is returned indicating the nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_rminode(FAR struct nxffs_volume_s *volume, FAR const char *name)
-{
- FAR struct nxffs_ofile_s *ofile;
- FAR struct nxffs_inode_s *inode;
- struct nxffs_entry_s entry;
- int ret;
-
- /* Check if the file is open */
-
- ofile = nxffs_findofile(volume, name);
- if (ofile)
- {
- /* We can't remove the inode if it is open */
-
- fdbg("Inode '%s' is open\n", name);
- ret = -EBUSY;
- goto errout;
- }
-
- /* Find the NXFFS inode */
-
- ret = nxffs_findinode(volume, name, &entry);
- if (ret < 0)
- {
- fdbg("Inode '%s' not found\n", name);
- goto errout;
- }
-
- /* Set the position to the FLASH offset of the file header (nxffs_findinode
- * should have left the block in the cache).
- */
-
- nxffs_ioseek(volume, entry.hoffset);
-
- /* Make sure the the block is in the cache */
-
- ret = nxffs_rdcache(volume, volume->ioblock);
- if (ret < 0)
- {
- fdbg("Failed to read data into cache: %d\n", ret);
- goto errout_with_entry;
- }
-
- /* Change the file status... it is no longer valid */
-
- inode = (FAR struct nxffs_inode_s *)&volume->cache[volume->iooffset];
- inode->state = INODE_STATE_DELETED;
-
- /* Then write the cached block back to FLASH */
-
- ret = nxffs_wrcache(volume);
- if (ret < 0)
- {
- fdbg("Failed to read data into cache: %d\n", ret);
- }
-
-errout_with_entry:
- nxffs_freeentry(&entry);
-errout:
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_unlink
- *
- * Description: Remove a file
- *
- ****************************************************************************/
-
-int nxffs_unlink(FAR struct inode *mountpt, FAR const char *relpath)
-{
- FAR struct nxffs_volume_s *volume;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private);
-
- /* Get the mountpoint private data from the NuttX inode structure */
-
- volume = mountpt->i_private;
- ret = sem_wait(&volume->exclsem);
- if (ret != OK)
- {
- goto errout;
- }
-
- /* Then remove the NXFFS inode */
-
- ret = nxffs_rminode(volume, relpath);
-
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
diff --git a/nuttx/fs/nxffs/nxffs_util.c b/nuttx/fs/nxffs/nxffs_util.c
deleted file mode 100644
index f424e71e0..000000000
--- a/nuttx/fs/nxffs/nxffs_util.c
+++ /dev/null
@@ -1,181 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_util.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_rdle16
- *
- * Description:
- * Get a (possibly unaligned) 16-bit little endian value.
- *
- * Input Parameters:
- * val - A pointer to the first byte of the little endian value.
- *
- * Returned Value:
- * A uint16_t representing the whole 16-bit integer value
- *
- ****************************************************************************/
-
-uint16_t nxffs_rdle16(FAR const uint8_t *val)
-{
- return (uint16_t)val[1] << 8 | (uint16_t)val[0];
-}
-
-/****************************************************************************
- * Name: nxffs_wrle16
- *
- * Description:
- * Put a (possibly unaligned) 16-bit little endian value.
- *
- * Input Parameters:
- * dest - A pointer to the first byte to save the little endian value.
- * val - The 16-bit value to be saved.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void nxffs_wrle16(uint8_t *dest, uint16_t val)
-{
- dest[0] = val & 0xff; /* Little endian means LS byte first in byte stream */
- dest[1] = val >> 8;
-}
-
-/****************************************************************************
- * Name: nxffs_rdle32
- *
- * Description:
- * Get a (possibly unaligned) 32-bit little endian value.
- *
- * Input Parameters:
- * val - A pointer to the first byte of the little endian value.
- *
- * Returned Value:
- * A uint32_t representing the whole 32-bit integer value
- *
- ****************************************************************************/
-
-uint32_t nxffs_rdle32(FAR const uint8_t *val)
-{
- /* Little endian means LS halfword first in byte stream */
-
- return (uint32_t)nxffs_rdle16(&val[2]) << 16 | (uint32_t)nxffs_rdle16(val);
-}
-
-/****************************************************************************
- * Name: nxffs_wrle32
- *
- * Description:
- * Put a (possibly unaligned) 32-bit little endian value.
- *
- * Input Parameters:
- * dest - A pointer to the first byte to save the little endian value.
- * val - The 32-bit value to be saved.
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void nxffs_wrle32(uint8_t *dest, uint32_t val)
-{
- /* Little endian means LS halfword first in byte stream */
-
- nxffs_wrle16(dest, (uint16_t)(val & 0xffff));
- nxffs_wrle16(dest+2, (uint16_t)(val >> 16));
-}
-
-/****************************************************************************
- * Name: nxffs_erased
- *
- * Description:
- * Check if a block of memory is in the erased state.
- *
- * Input Parameters:
- * buffer - Address of the start of the memory to check.
- * buflen - The number of bytes to check.
- *
- * Returned Values:
- * The number of erased bytes found at the beginning of the memory region.
- *
- ****************************************************************************/
-
-size_t nxffs_erased(FAR const uint8_t *buffer, size_t buflen)
-{
- size_t nerased = 0;
-
- for (; nerased < buflen; nerased++)
- {
- if (*buffer != CONFIG_NXFFS_ERASEDSTATE)
- {
- break;
- }
- buffer++;
- }
-
- return nerased;
-}
diff --git a/nuttx/fs/nxffs/nxffs_write.c b/nuttx/fs/nxffs/nxffs_write.c
deleted file mode 100644
index bf32b0fb4..000000000
--- a/nuttx/fs/nxffs/nxffs_write.c
+++ /dev/null
@@ -1,853 +0,0 @@
-/****************************************************************************
- * fs/nxffs/nxffs_write.c
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <fcntl.h>
-#include <crc32.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/fs/fs.h>
-#include <nuttx/mtd.h>
-
-#include "nxffs.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nxffs_hdrpos
- *
- * Description:
- * Find a valid location for the data block header. A valid location will
- * have these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire header
- * PLUS some meaningful amount of data (NXFFS_MINDATA).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the checks of 1) and 2).
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Contains the current guess for the header position. On
- * successful return, this field will hold the selected header
- * position.
- * size - The minimum size of the current write.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * wrfile->doffset - Flash offset to candidate data block header position
- * volume->ioblock - Read/write block number of the block containing the
- * header position
- * volume->iooffset - The offset in the block to the candidate header
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-static inline int nxffs_hdrpos(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile,
- size_t size)
-{
- int ret;
-
- /* Reserve memory for the object */
-
- ret = nxffs_wrreserve(volume, SIZEOF_NXFFS_DATA_HDR + size);
- if (ret == OK)
- {
- /* Save the offset to the FLASH region reserved for the data block
- * header
- */
-
- wrfile->doffset = nxffs_iotell(volume);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_hdrerased
- *
- * Description:
- * Find a valid location for the data block header. A valid location will
- * have these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire header
- * PLUS some meaningful amount of data (NXFFS_MINDATA).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the check 3). On entry it assumes:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * header position
- * volume->iooffset - The offset in the block to the candidate header
- * position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Contains the current guess for the header position. On
- * successful return, this field will hold the selected header
- * position.
- * size - The minimum size of the current write.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * wrfile->doffset - Flash offset to candidate data block header position
- * volume->ioblock - Read/write block number of the block containing the
- * header position
- * volume->iooffset - The offset in the block to the candidate header
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-static inline int nxffs_hdrerased(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile,
- size_t size)
-{
- int ret;
-
- /* Find a valid location to save the inode header */
-
- ret = nxffs_wrverify(volume, SIZEOF_NXFFS_DATA_HDR + size);
- if (ret == OK)
- {
- /* This is where we will put the data block header */
-
- wrfile->doffset = nxffs_iotell(volume);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wralloc
- *
- * Description:
- * Allocate FLASH memory for the data block.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Describes the open file to be written.
- * size - Size of the current write operation.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure.
- *
- ****************************************************************************/
-
-static inline int nxffs_wralloc(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile,
- size_t size)
-{
- bool packed;
- int ret;
-
- /* Allocate FLASH memory for the data block.
- *
- * Loop until the data block header is configured or until a failure
- * occurs. Note that nothing is written to FLASH. The data block header
- * is not written until either (1) the file is closed, or (2) the data
- * region is fully populated.
- */
-
- packed = false;
- for (;;)
- {
- size_t mindata = MIN(NXFFS_MINDATA, size);
-
- /* File a valid location to position the data block. Start with
- * the first byte in the free FLASH region.
- */
-
- ret = nxffs_hdrpos(volume, wrfile, mindata);
- if (ret == OK)
- {
- /* Find a region of memory in the block that is fully erased */
-
- ret = nxffs_hdrerased(volume, wrfile, mindata);
- if (ret == OK)
- {
- /* Valid memory for the data block was found. Return success. */
-
- return OK;
- }
- }
-
- /* If no valid memory is found searching to the end of the volume,
- * then -ENOSPC will be returned. Other errors are not handled.
- */
-
- if (ret != -ENOSPC || packed)
- {
- fdbg("Failed to find inode header memory: %d\n", -ret);
- return -ENOSPC;
- }
-
- /* -ENOSPC is a special case.. It means that the volume is full.
- * Try to pack the volume in order to free up some space.
- */
-
- ret = nxffs_pack(volume);
- if (ret < 0)
- {
- fdbg("Failed to pack the volume: %d\n", -ret);
- return ret;
- }
-
- /* After packing the volume, froffset will be updated to point to the
- * new free flash region. Try again.
- */
-
- nxffs_ioseek(volume, volume->froffset);
- packed = true;
- }
-
- /* Can't get here */
-
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_reverify
- *
- * Description:
- * Verify that the partial flash data block in the volume cache is valid.
- * On entry, this function assumes:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * data block.
- * volume->iooffset - The offset in the block to the data block.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Describes the open file to be written.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure.
- *
- ****************************************************************************/
-
-static inline int nxffs_reverify(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile)
-{
- uint32_t crc;
- off_t offset;
-
- if (wrfile->datlen > 0)
- {
- /* Get the offset to the start of the data */
-
- offset = volume->iooffset + SIZEOF_NXFFS_DATA_HDR;
- DEBUGASSERT(offset + wrfile->datlen < volume->geo.blocksize);
-
- /* Calculate the CRC of the partial data block */
-
- crc = crc32(&volume->cache[offset], wrfile->datlen);
-
- /* It must match the previoulsy calculated CRC value */
-
- if (crc != wrfile->crc)
- {
- fdbg("CRC failure\n");
- return -EIO;
- }
- }
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_wrappend
- *
- * Description:
- * Append FLASH data to the data block.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * wrfile - Describes the open file to be written.
- * buffer - Address of buffer of data to be written.
- * buflen - The number of bytes remaimining to be written
- *
- * Returned Value:
- * The number of bytes written is returned on success. Otherwise, a
- * negated errno value is returned indicating the nature of the failure.
- *
- ****************************************************************************/
-
-static inline ssize_t nxffs_wrappend(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile,
- FAR const char *buffer, size_t buflen)
-{
- ssize_t maxsize;
- size_t nbytestowrite;
- ssize_t nbytesleft;
- off_t offset;
- int ret;
-
- /* Get the offset to the start of unwritten data */
-
- offset = volume->iooffset + wrfile->datlen + SIZEOF_NXFFS_DATA_HDR;
-
- /* Determine that maximum amount of data that can be written to this
- * block.
- */
-
- maxsize = volume->geo.blocksize - offset;
- DEBUGASSERT(maxsize > 0);
-
- /* But don't try to write over any unerased bytes */
-
- maxsize = nxffs_erased(&volume->cache[offset], maxsize);
-
- /* Write as many bytes as we can into the data buffer */
-
- nbytestowrite = MIN(maxsize, buflen);
- nbytesleft = maxsize - nbytestowrite;
-
- if (nbytestowrite > 0)
- {
- /* Copy the data into the volume write cache */
-
- memcpy(&volume->cache[offset], buffer, nbytestowrite);
-
- /* Increment the number of bytes written to the data block */
-
- wrfile->datlen += nbytestowrite;
-
- /* Re-calculate the CRC */
-
- offset = volume->iooffset + SIZEOF_NXFFS_DATA_HDR;
- wrfile->crc = crc32(&volume->cache[offset], wrfile->datlen);
-
- /* 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);
- return ret;
- }
- }
- }
-
- /* Check if the data block is now full */
-
- if (nbytesleft <= 0)
- {
- /* The data block is full, write the block to FLASH */
-
- ret = nxffs_wrblkhdr(volume, wrfile);
- if (ret < 0)
- {
- fdbg("nxffs_wrblkdhr failed: %d\n", -ret);
- return ret;
- }
- }
-
- /* Return the number of bytes written to FLASH this time */
-
- return nbytestowrite;
-}
-
-/****************************************************************************
- * 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 remaining;
- ssize_t nwritten;
- ssize_t total;
- int 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 */
-
- if ((wrfile->ofile.oflags & O_WROK) == 0)
- {
- fdbg("File not open for write access\n");
- ret = -EACCES;
- goto errout_with_semaphore;
- }
-
- /* Loop until we successfully appended all of the data to the file (or an
- * error occurs)
- */
-
- for (total = 0; total < buflen; )
- {
- remaining = buflen - total;
-
- /* Have we already allocated the data block? */
-
- if (wrfile->doffset == 0)
- {
- /* No, allocate the data block now, re-packing if necessary. */
-
- wrfile->datlen = 0;
- ret = nxffs_wralloc(volume, wrfile, remaining);
- if (ret < 0)
- {
- fdbg("Failed to allocate a data block: %d\n", -ret);
- goto errout_with_semaphore;
- }
- }
-
- /* Seek to the FLASH block containing the data block */
-
- nxffs_ioseek(volume, wrfile->doffset);
-
- /* Verify that the FLASH data that was previously written is still intact */
-
- ret = nxffs_reverify(volume, wrfile);
- if (ret < 0)
- {
- fdbg("Failed to verify FLASH data block: %d\n", -ret);
- goto errout_with_semaphore;
- }
-
- /* Append the data to the end of the data block and write the updated
- * block to flash.
- */
-
- nwritten = nxffs_wrappend(volume, wrfile, &buffer[total], remaining);
- if (nwritten < 0)
- {
- fdbg("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;
- }
-
- /* Success.. return the number of bytes written */
-
- ret = total;
- filep->f_pos = wrfile->datlen;
-
-errout_with_semaphore:
- sem_post(&volume->exclsem);
-errout:
- return ret;
-}
-
-/****************************************************************************
- * Name: nxffs_wrreserve
- *
- * Description:
- * Find a valid location for a file system object of 'size'. A valid
- * location will have these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire object
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the checks of 1) and 2). The
- * end-of-filesystem offset, froffset, is update past this memory which,
- * in effect, reserves the memory.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * size - The size of the object to be reserved.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * candidate oject position
- * volume->iooffset - The offset in the block to the candidate object
- * position.
- * volume->froffset - Updated offset to the first free FLASH block after
- * the reserved memory.
- *
- ****************************************************************************/
-
-int nxffs_wrreserve(FAR struct nxffs_volume_s *volume, size_t size)
-{
- int ret;
-
- /* Seek to the beginning of the free FLASH region */
-
- nxffs_ioseek(volume, volume->froffset);
-
- /* Check for a seek past the end of the volume */
-
- if (volume->ioblock >= volume->nblocks)
- {
- /* Return -ENOSPC to indicate that the volume is full */
-
- return -ENOSPC;
- }
-
- /* Skip over block headers */
-
- if (volume->iooffset < SIZEOF_NXFFS_BLOCK_HDR)
- {
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- }
-
- /* Make sure that there is space there to hold the entire object */
-
- if (volume->iooffset + size > volume->geo.blocksize)
- {
- /* 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 */
-
- fdbg("No space in last block\n");
- return -ENOSPC;
- }
-
- /* This is not the last block in the volume, so just seek to the
- * beginning of the next, valid block.
- */
-
- volume->ioblock++;
- ret = nxffs_validblock(volume, &volume->ioblock);
- if (ret < 0)
- {
- fdbg("No more valid blocks\n");
- return ret;
- }
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- }
-
- /* Update the pointer to the first next free FLASH memory -- reserving this
- * block of memory.
- */
-
- volume->froffset = nxffs_iotell(volume) + size;
- return OK;
-}
-
-/****************************************************************************
- * Name: nxffs_wrverify
- *
- * Description:
- * Find a valid location for the object. A valid location will have
- * these properties:
- *
- * 1. It will lie in the free flash region.
- * 2. It will have enough contiguous memory to hold the entire header
- * (excluding the file name which may lie in the next block).
- * 3. The memory at this location will be fully erased.
- *
- * This function will only perform the check 3). On entry it assumes the
- * following settings (left by nxffs_wrreserve()):
- *
- * volume->ioblock - Read/write block number of the block containing the
- * candidate oject position
- * volume->iooffset - The offset in the block to the candidate object
- * position.
- *
- * Input Parameters:
- * volume - Describes the NXFFS volume
- * size - The size of the object to be verifed.
- *
- * Returned Value:
- * Zero is returned on success. Otherwise, a negated errno value is
- * returned indicating the nature of the failure. Of special interest
- * the return error of -ENOSPC which means that the FLASH volume is
- * full and should be repacked.
- *
- * On successful return the following are also valid:
- *
- * volume->ioblock - Read/write block number of the block containing the
- * verified object position
- * volume->iooffset - The offset in the block to the verified object
- * position.
- * volume->froffset - Updated offset to the first free FLASH block.
- *
- ****************************************************************************/
-
-int nxffs_wrverify(FAR struct nxffs_volume_s *volume, size_t size)
-{
- uint16_t iooffset;
- int nerased;
- int ret;
- int i;
-
- /* Search to the very last block in the volume if we have to */
-
- 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);
- return ret;
- }
-
- /* Search to the very end of this block if we have to */
-
- iooffset = volume->iooffset;
- nerased = 0;
-
- for (i = volume->iooffset; i < volume->geo.blocksize; i++)
- {
- /* Is this byte erased? */
-
- if (volume->cache[i] == CONFIG_NXFFS_ERASEDSTATE)
- {
- /* Yes.. increment the count of contiguous, erased bytes */
-
- nerased++;
-
- /* Is the whole header memory erased? */
-
- if (nerased >= size)
- {
- /* Yes.. this this is where we will put the object */
-
- off_t offset = volume->ioblock * volume->geo.blocksize + iooffset;
-
- /* Update the free flash offset and return success */
-
- volume->froffset = offset + size;
- return OK;
- }
- }
-
- /* This byte is not erased! (It should be unless the block is bad) */
-
- else
- {
- nerased = 0;
- iooffset = i + 1;
- }
- }
-
- /* If we get here, then we have looked at every byte in the the block
- * and did not find any sequence of erased bytes long enough to hold
- * the object. Skip to the next, valid block.
- */
-
- volume->ioblock++;
- ret = nxffs_validblock(volume, &volume->ioblock);
- if (ret < 0)
- {
- fdbg("No more valid blocks\n");
- return ret;
- }
-
- volume->iooffset = SIZEOF_NXFFS_BLOCK_HDR;
- volume->froffset = volume->ioblock * volume->geo.blocksize + SIZEOF_NXFFS_BLOCK_HDR;
- }
-
- /* Return -ENOSPC if there is no erased memory left in the volume for
- * the object.
- */
-
- fdbg("Not enough memory left to hold the file header\n");
- return -ENOSPC;
-}
-
-/****************************************************************************
- * Name: nxffs_wrblkhdr
- *
- * Description:
- * Write the block header information. This is done (1) whenever the end-
- * block is encountered and (2) also when the file is closed in order to
- * flush the final block of data to FLASH.
- *
- * Input Parameters:
- * volume - Describes the state of the NXFFS volume
- * wrfile - Describes the state of the open file
- *
- * Returned Value:
- * Zero is returned on success; Otherwise, a negated errno value is
- * returned to indicate the nature of the failure.
- *
- ****************************************************************************/
-
-int nxffs_wrblkhdr(FAR struct nxffs_volume_s *volume,
- FAR struct nxffs_wrfile_s *wrfile)
-{
- FAR struct nxffs_data_s *dathdr;
- int ret;
-
- /* Write the data block header to memory */
-
- nxffs_ioseek(volume, wrfile->doffset);
- dathdr = (FAR struct nxffs_data_s *)&volume->cache[volume->iooffset];
- memcpy(dathdr->magic, g_datamagic, NXFFS_MAGICSIZE);
- nxffs_wrle32(dathdr->crc, 0);
- nxffs_wrle16(dathdr->datlen, wrfile->datlen);
-
- /* Update the entire data block CRC (including the header) */
-
- wrfile->crc = crc32(&volume->cache[volume->iooffset], wrfile->datlen + SIZEOF_NXFFS_DATA_HDR);
- nxffs_wrle32(dathdr->crc, wrfile->crc);
-
- /* And write the data block to FLASH */
-
- ret = nxffs_wrcache(volume);
- if (ret < 0)
- {
- fdbg("nxffs_wrcache failed: %d\n", -ret);
- goto errout;
- }
-
- /* After the block has been successfully written to flash, update the inode
- * statistics and reset the write state.
- *
- * volume:
- * froffset - The offset the next free FLASH region. Set to just after
- * the inode data block that we just wrote. This is where we will
- * begin the search for the next inode header or data block.
- */
-
- volume->froffset = (wrfile->doffset + wrfile->datlen + SIZEOF_NXFFS_DATA_HDR);
-
- /* wrfile->file.entry:
- * datlen: Total file length accumulated so far. When the file is
- * closed, this will hold the file length.
- * doffset: Offset to the first data block. Only the offset to the
- * first data block is saved.
- */
-
- wrfile->ofile.entry.datlen += wrfile->datlen;
- if (wrfile->ofile.entry.doffset == 0)
- {
- wrfile->ofile.entry.doffset = wrfile->doffset;
- }
-
- /* Return success */
-
- ret = OK;
-
-errout:
- wrfile->crc = 0;
- wrfile->doffset = 0;
- wrfile->datlen = 0;
- return ret;
-}
-