aboutsummaryrefslogtreecommitdiff
path: root/nuttx/fs/romfs
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/fs/romfs')
-rw-r--r--nuttx/fs/romfs/Kconfig14
-rw-r--r--nuttx/fs/romfs/Make.defs48
-rw-r--r--nuttx/fs/romfs/fs_romfs.c1194
-rw-r--r--nuttx/fs/romfs/fs_romfs.h230
-rw-r--r--nuttx/fs/romfs/fs_romfsutil.c973
5 files changed, 0 insertions, 2459 deletions
diff --git a/nuttx/fs/romfs/Kconfig b/nuttx/fs/romfs/Kconfig
deleted file mode 100644
index 6a91011ab..000000000
--- a/nuttx/fs/romfs/Kconfig
+++ /dev/null
@@ -1,14 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see misc/tools/kconfig-language.txt.
-#
-
-config FS_ROMFS
- bool "ROMFS file system"
- default n
- depends on !DISABLE_MOUNTPOINT
- ---help---
- Enable ROMFS filesystem support
-
-if FS_ROMFS
-endif
diff --git a/nuttx/fs/romfs/Make.defs b/nuttx/fs/romfs/Make.defs
deleted file mode 100644
index e87cbdf9e..000000000
--- a/nuttx/fs/romfs/Make.defs
+++ /dev/null
@@ -1,48 +0,0 @@
-############################################################################
-# fs/romfs/Make.defs
-#
-# Copyright (C) 2008, 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_ROMFS),y)
-# Files required for ROMFS file system support
-
-ASRCS +=
-CSRCS += fs_romfs.c fs_romfsutil.c
-
-# Include ROMFS build support
-
-DEPPATH += --dep-path romfs
-VPATH += :romfs
-CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)fs$(DELIM)romfs}
-
-endif
diff --git a/nuttx/fs/romfs/fs_romfs.c b/nuttx/fs/romfs/fs_romfs.c
deleted file mode 100644
index 6a6fca355..000000000
--- a/nuttx/fs/romfs/fs_romfs.c
+++ /dev/null
@@ -1,1194 +0,0 @@
-/****************************************************************************
- * rm/romfs/fs_romfs.h
- *
- * Copyright (C) 2008-2009, 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/types.h>
-#include <sys/statfs.h>
-#include <sys/stat.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <stdlib.h>
-#include <unistd.h>
-#include <string.h>
-#include <fcntl.h>
-#include <limits.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/fs/ioctl.h>
-#include <nuttx/fs/dirent.h>
-
-#include "fs_romfs.h"
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int romfs_open(FAR struct file *filep, FAR const char *relpath,
- int oflags, mode_t mode);
-static int romfs_close(FAR struct file *filep);
-static ssize_t romfs_read(FAR struct file *filep, FAR char *buffer,
- size_t buflen);
-static off_t romfs_seek(FAR struct file *filep, off_t offset, int whence);
-static int romfs_ioctl(FAR struct file *filep, int cmd,
- unsigned long arg);
-
-static int romfs_dup(FAR const struct file *oldp, FAR struct file *newp);
-
-static int romfs_opendir(FAR struct inode *mountpt,
- FAR const char *relpath,
- FAR struct fs_dirent_s *dir);
-static int romfs_readdir(FAR struct inode *mountpt,
- FAR struct fs_dirent_s *dir);
-static int romfs_rewinddir(FAR struct inode *mountpt,
- FAR struct fs_dirent_s *dir);
-
-static int romfs_bind(FAR struct inode *blkdriver, FAR const void *data,
- FAR void **handle);
-static int romfs_unbind(FAR void *handle, FAR struct inode **blkdriver);
-static int romfs_statfs(FAR struct inode *mountpt,
- FAR struct statfs *buf);
-
-static int romfs_stat(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct stat *buf);
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Public 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 romfs_operations =
-{
- romfs_open, /* open */
- romfs_close, /* close */
- romfs_read, /* read */
- NULL, /* write */
- romfs_seek, /* seek */
- romfs_ioctl, /* ioctl */
-
- NULL, /* sync */
- romfs_dup, /* dup */
-
- romfs_opendir, /* opendir */
- NULL, /* closedir */
- romfs_readdir, /* readdir */
- romfs_rewinddir, /* rewinddir */
-
- romfs_bind, /* bind */
- romfs_unbind, /* unbind */
- romfs_statfs, /* statfs */
-
- NULL, /* unlink */
- NULL, /* mkdir */
- NULL, /* rmdir */
- NULL, /* rename */
- romfs_stat /* stat */
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: romfs_open
- ****************************************************************************/
-
-static int romfs_open(FAR struct file *filep, FAR const char *relpath,
- int oflags, mode_t mode)
-{
- struct romfs_dirinfo_s dirinfo;
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_file_s *rf;
- int ret;
-
- fvdbg("Open '%s'\n", relpath);
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv == NULL && filep->f_inode != NULL);
-
- /* Get mountpoint private data from the inode reference from the file
- * structure
- */
-
- rm = (FAR struct romfs_mountpt_s*)filep->f_inode->i_private;
-
- DEBUGASSERT(rm != NULL);
-
- /* Check if the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* ROMFS is read-only. Any attempt to open with any kind of write
- * access is not permitted.
- */
-
- if ((oflags & O_WRONLY) != 0 || (oflags & O_RDONLY) == 0)
- {
- fdbg("Only O_RDONLY supported\n");
- ret = -EACCES;
- goto errout_with_semaphore;
- }
-
- /* Initialize the directory info structure */
-
- memset(&dirinfo, 0, sizeof(struct romfs_dirinfo_s));
-
- /* Locate the directory entry for this path */
-
- ret = romfs_finddirentry(rm, &dirinfo, relpath);
- if (ret < 0)
- {
- fdbg("Failed to find directory directory entry for '%s': %d\n",
- relpath, ret);
- goto errout_with_semaphore;
- }
-
- /* The full path exists -- but is the final component a file
- * or a directory?
- */
-
- if (IS_DIRECTORY(dirinfo.rd_next))
- {
- /* It is a directory */
-
- ret = -EISDIR;
- fdbg("'%s' is a directory\n", relpath);
- goto errout_with_semaphore;
- }
-
-#ifdef CONFIG_FILE_MODE
-# warning "Missing check for privileges based on inode->i_mode"
-#endif
-
- /* Create an instance of the file private data to describe the opened
- * file.
- */
-
- rf = (FAR struct romfs_file_s *)kzalloc(sizeof(struct romfs_file_s));
- if (!rf)
- {
- fdbg("Failed to allocate private data\n", ret);
- ret = -ENOMEM;
- goto errout_with_semaphore;
- }
-
- /* Initialize the file private data (only need to initialize
- * non-zero elements)
- */
-
- rf->rf_size = dirinfo.rd_size;
-
- /* Get the start of the file data */
-
- ret = romfs_datastart(rm, dirinfo.rd_dir.fr_curroffset,
- &rf->rf_startoffset);
- if (ret < 0)
- {
- fdbg("Failed to locate start of file data: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Configure buffering to support access to this file */
-
- ret = romfs_fileconfigure(rm, rf);
- if (ret < 0)
- {
- fdbg("Failed configure buffering: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Attach the private date to the struct file instance */
-
- filep->f_priv = rf;
-
- /* Then insert the new instance into the mountpoint structure.
- * It needs to be there (1) to handle error conditions that effect
- * all files, and (2) to inform the umount logic that we are busy
- * (but a simple reference count could have done that).
- */
-
- rf->rf_next = rm->rm_head;
- rm->rm_head = rf->rf_next;
-
- romfs_semgive(rm);
- return OK;
-
- /* Error exits */
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_close
- ****************************************************************************/
-
-static int romfs_close(FAR struct file *filep)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_file_s *rf;
- int ret = OK;
-
- fvdbg("Closing\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover our private data from the struct file instance */
-
- rf = filep->f_priv;
- rm = filep->f_inode->i_private;
-
- DEBUGASSERT(rm != NULL);
-
- /* Do not check if the mount is healthy. We must support closing of
- * the file even when there is healthy mount.
- */
-
- /* Deallocate the memory structures created when the open method
- * was called.
- *
- * Free the sector buffer that was used to manage partial sector
- * accesses.
- */
-
- if (!rm->rm_xipbase && rf->rf_buffer)
- {
- kfree(rf->rf_buffer);
- }
-
- /* Then free the file structure itself. */
-
- kfree(rf);
- filep->f_priv = NULL;
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_read
- ****************************************************************************/
-
-static ssize_t romfs_read(FAR struct file *filep, FAR char *buffer,
- size_t buflen)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_file_s *rf;
- unsigned int bytesread;
- unsigned int readsize;
- unsigned int nsectors;
- uint32_t offset;
- size_t bytesleft;
- off_t sector;
- FAR uint8_t *userbuffer = (FAR uint8_t*)buffer;
- int sectorndx;
- 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 our private data from the struct file instance */
-
- rf = filep->f_priv;
- rm = filep->f_inode->i_private;
-
- DEBUGASSERT(rm != NULL);
-
- /* Make sure that the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Get the number of bytes left in the file */
-
- bytesleft = rf->rf_size - filep->f_pos;
-
- /* Truncate read count so that it does not exceed the number
- * of bytes left in the file.
- */
-
- if (buflen > bytesleft)
- {
- buflen = bytesleft;
- }
-
- /* Loop until either (1) all data has been transferred, or (2) an
- * error occurs.
- */
-
- readsize = 0;
- while (buflen > 0)
- {
- /* Get the first sector and index to read from. */
-
- offset = rf->rf_startoffset + filep->f_pos;
- sector = SEC_NSECTORS(rm, offset);
- sectorndx = offset & SEC_NDXMASK(rm);
- bytesread = 0;
-
- /* Check if the user has provided a buffer large enough to
- * hold one or more complete sectors -AND- the read is
- * aligned to a sector boundary.
- */
-
- nsectors = SEC_NSECTORS(rm, buflen);
- if (nsectors > 0 && sectorndx == 0)
- {
- /* Read maximum contiguous sectors directly to the user's
- * buffer without using our tiny read buffer.
- */
-
- /* Read all of the sectors directly into user memory */
-
- fvdbg("Read %d sectors starting with %d\n", nsectors, sector);
- ret = romfs_hwread(rm, userbuffer, sector, nsectors);
- if (ret < 0)
- {
- fdbg("romfs_hwread failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- sector += nsectors;
- bytesread = nsectors * rm->rm_hwsectorsize;
- }
- else
- {
- /* We are reading a partial sector. First, read the whole sector
- * into the file data buffer. This is a caching buffer so if
- * it is already there then all is well.
- */
-
- fvdbg("Read sector %d\n", sector);
- ret = romfs_filecacheread(rm, rf, sector);
- if (ret < 0)
- {
- fdbg("romfs_filecacheread failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Copy the partial sector into the user buffer */
-
- bytesread = rm->rm_hwsectorsize - sectorndx;
- if (bytesread > buflen)
- {
- /* We will not read to the end of the buffer */
-
- bytesread = buflen;
- }
- else
- {
- /* We will read to the end of the buffer (or beyond) */
-
- sector++;
- }
-
- fvdbg("Return %d bytes from sector offset %d\n", bytesread, sectorndx);
- memcpy(userbuffer, &rf->rf_buffer[sectorndx], bytesread);
- }
-
- /* Set up for the next sector read */
-
- userbuffer += bytesread;
- filep->f_pos += bytesread;
- readsize += bytesread;
- buflen -= bytesread;
- }
-
- romfs_semgive(rm);
- return readsize;
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_seek
- ****************************************************************************/
-
-static off_t romfs_seek(FAR struct file *filep, off_t offset, int whence)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_file_s *rf;
- off_t position;
- int ret;
-
- fvdbg("Seek to offset: %d whence: %d\n", offset, whence);
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover our private data from the struct file instance */
-
- rf = filep->f_priv;
- rm = filep->f_inode->i_private;
-
- DEBUGASSERT(rm != NULL);
-
- /* Map the offset according to the whence option */
-
- switch (whence)
- {
- case SEEK_SET: /* The offset is set to offset bytes. */
- position = offset;
- break;
-
- case SEEK_CUR: /* The offset is set to its current location plus
- * offset bytes. */
-
- position = offset + filep->f_pos;
- break;
-
- case SEEK_END: /* The offset is set to the size of the file plus
- * offset bytes. */
-
- position = offset + rf->rf_size;
- break;
-
- default:
- fdbg("Whence is invalid: %d\n", whence);
- return -EINVAL;
- }
-
- /* Make sure that the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Limit positions to the end of the file. */
-
- if (position > rf->rf_size)
- {
- /* Otherwise, the position is limited to the file size */
-
- position = rf->rf_size;
- }
-
- /* Set file position and return success */
-
- filep->f_pos = position;
- fvdbg("New file position: %d\n", filep->f_pos);
-
- romfs_semgive(rm);
- return OK;
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_ioctl
- ****************************************************************************/
-
-static int romfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_file_s *rf;
- FAR void **ppv = (FAR void**)arg;
-
- fvdbg("cmd: %d arg: %08lx\n", cmd, arg);
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover our private data from the struct file instance */
-
- rf = filep->f_priv;
- rm = filep->f_inode->i_private;
-
- DEBUGASSERT(rm != NULL);
-
- /* Only one ioctl command is supported */
-
- if (cmd == FIOC_MMAP && rm->rm_xipbase && ppv)
- {
- /* Return the address on the media corresponding to the start of
- * the file.
- */
-
- *ppv = (void*)(rm->rm_xipbase + rf->rf_startoffset);
- return OK;
- }
-
- fdbg("Invalid cmd: %d \n", cmd);
- return -ENOTTY;
-}
-
-/****************************************************************************
- * Name: romfs_dup
- ****************************************************************************/
-
-static int romfs_dup(FAR const struct file *oldp, FAR struct file *newp)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_file_s *oldrf;
- FAR struct romfs_file_s *newrf;
- int ret;
-
- fvdbg("Dup %p->%p\n", oldp, newp);
-
- /* Sanity checks */
-
- DEBUGASSERT(oldp->f_priv != NULL &&
- newp->f_priv == NULL &&
- newp->f_inode != NULL);
-
- /* Get mountpoint private data from the inode reference from the file
- * structure
- */
-
- rm = (FAR struct romfs_mountpt_s*)newp->f_inode->i_private;
- DEBUGASSERT(rm != NULL);
-
- /* Check if the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Recover the old private data from the old struct file instance */
-
- oldrf = oldp->f_priv;
-
- /* Create an new instance of the file private data to describe the new
- * dup'ed file.
- */
-
- newrf = (FAR struct romfs_file_s *)kmalloc(sizeof(struct romfs_file_s));
- if (!newrf)
- {
- fdbg("Failed to allocate private data\n", ret);
- ret = -ENOMEM;
- goto errout_with_semaphore;
- }
-
- /* Copy all file private data (except for the buffer) */
-
- newrf->rf_startoffset = oldrf->rf_startoffset;
- newrf->rf_size = oldrf->rf_size;
-
- /* Configure buffering to support access to this file */
-
- ret = romfs_fileconfigure(rm, newrf);
- if (ret < 0)
- {
- fdbg("Failed configure buffering: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Attach the new private date to the new struct file instance */
-
- newp->f_priv = newrf;
-
- /* Then insert the new instance into the mountpoint structure.
- * It needs to be there (1) to handle error conditions that effect
- * all files, and (2) to inform the umount logic that we are busy
- * (but a simple reference count could have done that).
- */
-
- newrf->rf_next = rm->rm_head;
- rm->rm_head = newrf->rf_next;
-
- romfs_semgive(rm);
- return OK;
-
- /* Error exits */
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_opendir
- *
- * Description:
- * Open a directory for read access
- *
- ****************************************************************************/
-
-static int romfs_opendir(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct fs_dirent_s *dir)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_dirinfo_s dirinfo;
- int ret;
-
- fvdbg("relpath: '%s'\n", relpath);
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover our private data from the inode instance */
-
- rm = mountpt->i_private;
-
- /* Make sure that the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Find the requested directory */
-
- ret = romfs_finddirentry(rm, &dirinfo, relpath);
- if (ret < 0)
- {
- fdbg("Failed to find directory '%s': %d\n", relpath, ret);
- goto errout_with_semaphore;
- }
-
- /* Verify that it is some kind of directory */
-
- if (!IS_DIRECTORY(dirinfo.rd_next))
- {
- /* The entry is not a directory */
-
- fdbg("'%s' is not a directory: %d\n", relpath);
- ret = -ENOTDIR;
- goto errout_with_semaphore;
- }
-
- /* The entry is a directory */
-
- memcpy(&dir->u.romfs, &dirinfo.rd_dir, sizeof(struct fs_romfsdir_s));
- romfs_semgive(rm);
- return OK;
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ERROR;
-}
-
-/****************************************************************************
- * Name: romfs_readdir
- *
- * Description: Read the next directory entry
- *
- ****************************************************************************/
-
-static int romfs_readdir(FAR struct inode *mountpt,
- FAR struct fs_dirent_s *dir)
-{
- FAR struct romfs_mountpt_s *rm;
- uint32_t linkoffset;
- uint32_t next;
- uint32_t info;
- uint32_t size;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover our private data from the inode instance */
-
- rm = mountpt->i_private;
-
- /* Make sure that the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Loop, skipping over unsupported items in the file system */
-
- for (;;)
- {
- /* Have we reached the end of the directory */
-
- if (!dir->u.romfs.fr_curroffset)
- {
- /* We signal the end of the directory by returning the
- * special error -ENOENT
- */
-
- fdbg("End of directory\n");
- ret = -ENOENT;
- goto errout_with_semaphore;
- }
-
- /* Parse the directory entry */
-
- ret = romfs_parsedirentry(rm, dir->u.romfs.fr_curroffset, &linkoffset,
- &next, &info, &size);
- if (ret < 0)
- {
- fdbg("romfs_parsedirentry failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Save the filename */
-
- ret = romfs_parsefilename(rm, dir->u.romfs.fr_curroffset, dir->fd_dir.d_name);
- if (ret < 0)
- {
- fdbg("romfs_parsefilename failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Set up the next directory entry offset */
-
- dir->u.romfs.fr_curroffset = next & RFNEXT_OFFSETMASK;
-
- /* Check the file type */
-
- if (IS_DIRECTORY(next))
- {
- dir->fd_dir.d_type = DTYPE_DIRECTORY;
- break;
- }
- else if (IS_FILE(next))
- {
- dir->fd_dir.d_type = DTYPE_FILE;
- break;
- }
- }
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_rewindir
- *
- * Description: Reset directory read to the first entry
- *
- ****************************************************************************/
-
-static int romfs_rewinddir(FAR struct inode *mountpt,
- FAR struct fs_dirent_s *dir)
-{
- FAR struct romfs_mountpt_s *rm;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover our private data from the inode instance */
-
- rm = mountpt->i_private;
-
- /* Make sure that the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret == OK)
- {
- dir->u.romfs.fr_curroffset = dir->u.romfs.fr_firstoffset;
- }
-
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_bind
- *
- * Description: This implements a portion of the mount operation. This
- * function allocates and initializes the mountpoint private data and
- * 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().
- *
- ****************************************************************************/
-
-static int romfs_bind(FAR struct inode *blkdriver, FAR const void *data,
- FAR void **handle)
-{
- struct romfs_mountpt_s *rm;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Open the block driver */
-
- if (!blkdriver || !blkdriver->u.i_bops)
- {
- fdbg("No block driver/ops\n");
- return -ENODEV;
- }
-
- if (blkdriver->u.i_bops->open &&
- blkdriver->u.i_bops->open(blkdriver) != OK)
- {
- fdbg("No open method\n");
- return -ENODEV;
- }
-
- /* Create an instance of the mountpt state structure */
-
- rm = (FAR struct romfs_mountpt_s *)kzalloc(sizeof(struct romfs_mountpt_s));
- if (!rm)
- {
- fdbg("Failed to allocate mountpoint structure\n");
- return -ENOMEM;
- }
-
- /* Initialize the allocated mountpt state structure. The filesystem is
- * responsible for one reference ont the blkdriver inode and does not
- * have to addref() here (but does have to release in ubind().
- */
-
- sem_init(&rm->rm_sem, 0, 0); /* Initialize the semaphore that controls access */
- rm->rm_blkdriver = blkdriver; /* Save the block driver reference */
-
- /* Get the hardware configuration and setup buffering appropriately */
-
- ret = romfs_hwconfigure(rm);
- if (ret < 0)
- {
- fdbg("romfs_hwconfigure failed: %d\n", ret);
- goto errout_with_sem;
- }
-
- /* Then complete the mount by getting the ROMFS configuratrion from
- * the ROMF header
- */
-
- ret = romfs_fsconfigure(rm);
- if (ret < 0)
- {
- fdbg("romfs_fsconfigure failed: %d\n", ret);
- goto errout_with_buffer;
- }
-
- /* Mounted! */
-
- *handle = (void*)rm;
- romfs_semgive(rm);
- return OK;
-
-errout_with_buffer:
- if (!rm->rm_xipbase)
- {
- kfree(rm->rm_buffer);
- }
-
-errout_with_sem:
- sem_destroy(&rm->rm_sem);
- kfree(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_unbind
- *
- * Description: This implements the filesystem portion of the umount
- * operation.
- *
- ****************************************************************************/
-
-static int romfs_unbind(FAR void *handle, FAR struct inode **blkdriver)
-{
- FAR struct romfs_mountpt_s *rm = (FAR struct romfs_mountpt_s*)handle;
- int ret;
-
- fvdbg("Entry\n");
-
-#ifdef CONFIG_DEBUG
- if (!rm)
- {
- return -EINVAL;
- }
-#endif
-
- /* Check if there are sill any files opened on the filesystem. */
-
- romfs_semtake(rm);
- if (rm->rm_head)
- {
- /* We cannot unmount now.. there are open files */
-
- fdbg("There are open files\n");
- ret = -EBUSY;
- }
- else
- {
- /* Unmount ... close the block driver */
-
- if (rm->rm_blkdriver)
- {
- struct inode *inode = rm->rm_blkdriver;
- if (inode)
- {
- if (inode->u.i_bops && inode->u.i_bops->close)
- {
- (void)inode->u.i_bops->close(inode);
- }
-
- /* We hold a reference to the block driver but should
- * not but mucking with inodes in this context. So, we will just return
- * our contained reference to the block driver inode and let the umount
- * logic dispose of it.
- */
-
- if (blkdriver)
- {
- *blkdriver = inode;
- }
- }
- }
-
- /* Release the mountpoint private data */
-
- if (!rm->rm_xipbase && rm->rm_buffer)
- {
- kfree(rm->rm_buffer);
- }
-
- sem_destroy(&rm->rm_sem);
- kfree(rm);
- return OK;
- }
-
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_statfs
- *
- * Description: Return filesystem statistics
- *
- ****************************************************************************/
-
-static int romfs_statfs(FAR struct inode *mountpt, FAR struct statfs *buf)
-{
- FAR struct romfs_mountpt_s *rm;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private);
-
- /* Get the mountpoint private data from the inode structure */
-
- rm = mountpt->i_private;
-
- /* Check if the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret < 0)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Fill in the statfs info */
-
- memset(buf, 0, sizeof(struct statfs));
- buf->f_type = ROMFS_MAGIC;
-
- /* We will claim that the optimal transfer size is the size of one sector */
-
- buf->f_bsize = rm->rm_hwsectorsize;
-
- /* Everything else follows in units of sectors */
-
- buf->f_blocks = SEC_NSECTORS(rm, rm->rm_volsize + SEC_NDXMASK(rm));
- buf->f_bfree = 0;
- buf->f_bavail = 0;
- buf->f_namelen = NAME_MAX;
-
- romfs_semgive(rm);
- return OK;
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_stat
- *
- * Description: Return information about a file or directory
- *
- ****************************************************************************/
-
-static int romfs_stat(FAR struct inode *mountpt, FAR const char *relpath,
- FAR struct stat *buf)
-{
- FAR struct romfs_mountpt_s *rm;
- FAR struct romfs_dirinfo_s dirinfo;
- int ret;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private);
-
- /* Get the mountpoint private data from the inode structure */
-
- rm = mountpt->i_private;
-
- /* Check if the mount is still healthy */
-
- romfs_semtake(rm);
- ret = romfs_checkmount(rm);
- if (ret != OK)
- {
- fdbg("romfs_checkmount failed: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- /* Find the directory entry corresponding to relpath. */
-
- ret = romfs_finddirentry(rm, &dirinfo, relpath);
-
- /* If nothing was found, then we fail with EEXIST */
-
- if (ret < 0)
- {
- fvdbg("Failed to find directory: %d\n", ret);
- goto errout_with_semaphore;
- }
-
- memset(buf, 0, sizeof(struct stat));
- if (IS_DIRECTORY(dirinfo.rd_next))
- {
- /* It's a read-only directory name */
-
- buf->st_mode = S_IFDIR|S_IROTH|S_IRGRP|S_IRUSR;
- if (IS_EXECUTABLE(dirinfo.rd_next))
- {
- buf->st_mode |= S_IXOTH|S_IXGRP|S_IXUSR;
- }
- }
- else if (IS_FILE(dirinfo.rd_next))
- {
- /* It's a read-only file name */
-
- buf->st_mode = S_IFREG|S_IROTH|S_IRGRP|S_IRUSR;
- if (IS_EXECUTABLE(dirinfo.rd_next))
- {
- buf->st_mode |= S_IXOTH|S_IXGRP|S_IXUSR;
- }
- }
- else
- {
- /* Otherwise, pretend like the unsupported node does not exist */
-
- fvdbg("Unsupported inode: %d\n", dirinfo.rd_next);
- ret = -ENOENT;
- goto errout_with_semaphore;
- }
-
- /* File/directory size, access block size */
-
- buf->st_size = dirinfo.rd_size;
- buf->st_blksize = rm->rm_hwsectorsize;
- buf->st_blocks = (buf->st_size + buf->st_blksize - 1) / buf->st_blksize;
-
- ret = OK;
-
-errout_with_semaphore:
- romfs_semgive(rm);
- return ret;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
diff --git a/nuttx/fs/romfs/fs_romfs.h b/nuttx/fs/romfs/fs_romfs.h
deleted file mode 100644
index 6a337d2c5..000000000
--- a/nuttx/fs/romfs/fs_romfs.h
+++ /dev/null
@@ -1,230 +0,0 @@
-/****************************************************************************
- * fs/romfs/fs_romfs.h
- *
- * Copyright (C) 2008-2009, 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.
- *
- ****************************************************************************/
-
-#ifndef __FS_ROMFS_FS_ROMFS_H
-#define __FS_ROMFS_FS_ROMFS_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-
-#include <nuttx/fs/dirent.h>
-
-#include "../fs_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* Volume header (multi-byte values are big-endian) */
-
-#define ROMFS_VHDR_ROM1FS 0 /* 0-7: "-rom1fs-" */
-#define ROMFS_VHDR_SIZE 8 /* 8-11: Number of accessible bytes in this fs. */
-#define ROMFS_VHDR_CHKSUM 12 /* 12-15: Checksum of the first 512 bytes. */
-#define ROMFS_VHDR_VOLNAME 16 /* 16-..: Zero terminated volume name, padded to
- * 16 byte boundary. */
-
-#define ROMFS_VHDR_MAGIC "-rom1fs-"
-
-/* File header offset (multi-byte values are big-endian) */
-
-#define ROMFS_FHDR_NEXT 0 /* 0-3: Offset of the next file header
- * (zero if no more files) */
-#define ROMFS_FHDR_INFO 4 /* 4-7: Info for directories/hard links/
- * devices */
-#define ROMFS_FHDR_SIZE 8 /* 8-11: Size of this file in bytes */
-#define ROMFS_FHDR_CHKSUM 12 /* 12-15: Checksum covering the meta data,
- * including the file name, and
- * padding. */
-#define ROMFS_FHDR_NAME 16 /* 16-..: Zero terminated volume name, padded
- * to 16 byte boundary. */
-
-/* Bits 0-3 of the rf_next offset provide mode information. These are the
- * values specified in */
-
-#define RFNEXT_MODEMASK 7 /* Bits 0-2: Mode; bit 3: Executable */
-#define RFNEXT_ALLMODEMASK 15 /* Bits 0-3: All mode bits */
-#define RFNEXT_OFFSETMASK (~15) /* Bits n-3: Offset to next entry */
-
-#define RFNEXT_HARDLINK 0 /* rf_info = Link destination file header */
-#define RFNEXT_DIRECTORY 1 /* rf_info = First file's header */
-#define RFNEXT_FILE 2 /* rf_info = Unused, must be zero */
-#define RFNEXT_SOFTLINK 3 /* rf_info = Unused, must be zero */
-#define RFNEXT_BLOCKDEV 4 /* rf_info = 16/16 bits major/minor number */
-#define RFNEXT_CHARDEV 5 /* rf_info = 16/16 bits major/minor number */
-#define RFNEXT_SOCKET 6 /* rf_info = Unused, must be zero */
-#define RFNEXT_FIFO 7 /* rf_info = Unused, must be zero */
-#define RFNEXT_EXEC 8 /* Modifier of RFNEXT_DIRECTORY and RFNEXT_FILE */
-
-#define IS_MODE(rfn,mode) ((((uint32_t)(rfn))&RFNEXT_MODEMASK)==(mode))
-#define IS_HARDLINK(rfn) IS_MODE(rfn,RFNEXT_HARDLINK)
-#define IS_DIRECTORY(rfn) IS_MODE(rfn,RFNEXT_DIRECTORY)
-#define IS_FILE(rfn) IS_MODE(rfn,RFNEXT_FILE)
-#define IS_EXECUTABLE(rfn) (((rfn) & RFNEXT_EXEC) != 0)
-
-/* RFNEXT_SOFTLINK, RFNEXT_BLOCKDEV, RFNEXT_CHARDEV, RFNEXT_SOCKET, and
- * RFNEXT_FIFO are not presently supported in NuttX.
- */
-
-/* Alignment macros */
-
-#define ROMFS_ALIGNMENT 16
-#define ROMFS_MAXPADDING (ROMFS_ALIGNMENT-1)
-#define ROMFS_ALIGNMASK (~ROMFS_MAXPADDING)
-#define ROMFS_ALIGNUP(addr) ((((uint32_t)(addr))+ROMFS_MAXPADDING)&ROMFS_ALIGNMASK)
-#define ROMFS_ALIGNDOWN(addr) (((uint32_t)(addr))&ROMFS_ALIGNMASK)
-
-/* Offset and sector conversions */
-
-#define SEC_NDXMASK(r) ((r)->rm_hwsectorsize - 1)
-#define SEC_NSECTORS(r,o) ((o) / (r)->rm_hwsectorsize)
-#define SEC_ALIGN(r,o) ((o) & ~SEC_NDXMASK(r))
-
-/* Maximum numbr of links that will be followed before we decide that there
- * is a problem.
- */
-
-#define ROMF_MAX_LINKS 64
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/* This structure represents the overall mountpoint state. An instance of this
- * structure is retained as inode private data on each mountpoint that is
- * mounted with a fat32 filesystem.
- */
-
-struct romfs_file_s;
-struct romfs_mountpt_s
-{
- struct inode *rm_blkdriver; /* The block driver inode that hosts the FAT32 fs */
- struct romfs_file_s *rm_head; /* A list to all files opened on this mountpoint */
-
- bool rm_mounted; /* true: The file system is ready */
- uint16_t rm_hwsectorsize; /* HW: Sector size reported by block driver*/
- sem_t rm_sem; /* Used to assume thread-safe access */
- uint32_t rm_rootoffset; /* Saved offset to the first root directory entry */
- uint32_t rm_hwnsectors; /* HW: The number of sectors reported by the hardware */
- uint32_t rm_volsize; /* Size of the ROMFS volume */
- uint32_t rm_cachesector; /* Current sector in the rm_buffer */
- uint8_t *rm_xipbase; /* Base address of directly accessible media */
- uint8_t *rm_buffer; /* Device sector buffer, allocated if rm_xipbase==0 */
-};
-
-/* This structure represents on open file under the mountpoint. An instance
- * of this structure is retained as struct file specific information on each
- * opened file.
- */
-
-struct romfs_file_s
-{
- struct romfs_file_s *rf_next; /* Retained in a singly linked list */
- uint32_t rf_startoffset; /* Offset to the start of the file data */
- uint32_t rf_size; /* Size of the file in bytes */
- uint32_t rf_cachesector; /* Current sector in the rf_buffer */
- uint8_t *rf_buffer; /* File sector buffer, allocated if rm_xipbase==0 */
-};
-
-/* This structure is used internally for describing the result of
- * walking a path
- */
-
-struct romfs_dirinfo_s
-{
- /* These values describe the directory containing the terminal
- * path component (of the terminal component itself if it is
- * a directory.
- */
-
- struct fs_romfsdir_s rd_dir; /* Describes directory. */
-
- /* Values from the ROMFS file entry */
-
- uint32_t rd_next; /* Offset of the next file header+flags */
- uint32_t rd_size; /* Size (if file) */
-};
-
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-EXTERN void romfs_semtake(struct romfs_mountpt_s *rm);
-EXTERN void romfs_semgive(struct romfs_mountpt_s *rm);
-EXTERN int romfs_hwread(struct romfs_mountpt_s *rm, uint8_t *buffer,
- uint32_t sector, unsigned int nsectors);
-EXTERN int romfs_filecacheread(struct romfs_mountpt_s *rm,
- struct romfs_file_s *rf, uint32_t sector);
-EXTERN int romfs_hwconfigure(struct romfs_mountpt_s *rm);
-EXTERN int romfs_fsconfigure(struct romfs_mountpt_s *rm);
-EXTERN int romfs_fileconfigure(struct romfs_mountpt_s *rm,
- struct romfs_file_s *rf);
-EXTERN int romfs_checkmount(struct romfs_mountpt_s *rm);
-EXTERN int romfs_finddirentry(struct romfs_mountpt_s *rm,
- struct romfs_dirinfo_s *dirinfo,
- const char *path);
-EXTERN int romfs_parsedirentry(struct romfs_mountpt_s *rm,
- uint32_t offset, uint32_t *poffset, uint32_t *pnext,
- uint32_t *pinfo, uint32_t *psize);
-EXTERN int romfs_parsefilename(struct romfs_mountpt_s *rm, uint32_t offset,
- char *pname);
-EXTERN int romfs_datastart(struct romfs_mountpt_s *rm, uint32_t offset,
- uint32_t *start);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __FS_ROMFS_FS_ROMFS_H */
diff --git a/nuttx/fs/romfs/fs_romfsutil.c b/nuttx/fs/romfs/fs_romfsutil.c
deleted file mode 100644
index 4857fb6d3..000000000
--- a/nuttx/fs/romfs/fs_romfsutil.c
+++ /dev/null
@@ -1,973 +0,0 @@
-/****************************************************************************
- * rm/romfs/fs_romfsutil.h
- *
- * Copyright (C) 2008-2009 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/types.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <stdlib.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/fs/ioctl.h>
-#include <nuttx/fs/dirent.h>
-
-#include "fs_romfs.h"
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: romfs_swap32
- *
- * Desciption:
- * Convert the 32-bit big endian value to little endian
- *
- ****************************************************************************/
-
-#ifndef CONFIG_ENDIAN_BIG
-static inline uint32_t romfs_swap32(uint32_t value)
-{
- return ((((value) & 0x000000ff) << 24) | (((value) & 0x0000ff00) << 8) |
- (((value) & 0x00ff0000) >> 8) | (((value) & 0xff000000) >> 24));
-}
-#endif
-
-/****************************************************************************
- * Name: romfs_devread32
- *
- * Desciption:
- * Read the big-endian 32-bit value from the mount device buffer
- *
- * Assumption:
- * All values are aligned to 32-bit boundaries
- *
- ****************************************************************************/
-
-static uint32_t romfs_devread32(struct romfs_mountpt_s *rm, int ndx)
-{
- /* Extract the value */
-
- uint32_t value = *(uint32_t*)&rm->rm_buffer[ndx];
-
- /* Value is begin endian -- return the native host endian-ness. */
-#ifdef CONFIG_ENDIAN_BIG
- return value;
-#else
- return romfs_swap32(value);
-#endif
-}
-
-/****************************************************************************
- * Name: romfs_checkentry
- *
- * Desciption:
- * Check if the entry at offset is a directory or file path segment
- *
- ****************************************************************************/
-
-static inline int romfs_checkentry(struct romfs_mountpt_s *rm, uint32_t offset,
- const char *entryname, int entrylen,
- struct romfs_dirinfo_s *dirinfo)
-{
- char name[NAME_MAX+1];
- uint32_t linkoffset;
- uint32_t next;
- uint32_t info;
- uint32_t size;
- int ret;
-
- /* Parse the directory entry at this offset (which may be re-directed
- * to some other entry if HARLINKED).
- */
-
- ret = romfs_parsedirentry(rm, offset, &linkoffset, &next, &info, &size);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Now we are pointing to the real entry of interest. Is it a
- * directory? Or a file?
- */
-
- if (IS_DIRECTORY(next) || IS_FILE(next))
- {
- /* Get the name of the directory entry. */
-
- ret = romfs_parsefilename(rm, offset, name);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Then check if this the name segment we are looking for. The
- * string comparison is awkward because there is no terminator
- * on entryname (there is a terminator on name, however)
- */
-
- if (memcmp(entryname, name, entrylen) == 0 &&
- strlen(name) == entrylen)
- {
- /* Found it -- save the component info and return success */
-
- if (IS_DIRECTORY(next))
- {
- dirinfo->rd_dir.fr_firstoffset = info;
- dirinfo->rd_dir.fr_curroffset = info;
- dirinfo->rd_size = 0;
- }
- else
- {
- dirinfo->rd_dir.fr_curroffset = offset;
- dirinfo->rd_size = size;
- }
- dirinfo->rd_next = next;
- return OK;
- }
- }
-
- /* The entry is not a directory or it does not have the matching name */
-
- return -ENOENT;
-}
-
-/****************************************************************************
- * Name: romfs_devcacheread
- *
- * Desciption:
- * Read the specified sector for specified offset into the sector cache.
- * Return the index into the sector corresponding to the offset
- *
- ****************************************************************************/
-
-int16_t romfs_devcacheread(struct romfs_mountpt_s *rm, uint32_t offset)
-{
- uint32_t sector;
- int ret;
-
- /* rm->rm_cachesector holds the current sector that is buffer in or referenced
- * by rm->tm_buffer. If the requested sector is the same as this sector,
- * then we do nothing.
- */
-
- sector = SEC_NSECTORS(rm, offset);
- if (rm->rm_cachesector != sector)
- {
- /* Check the access mode */
-
- if (rm->rm_xipbase)
- {
- /* In XIP mode, rf_buffer is just an offset pointer into the device
- * address space.
- */
-
- rm->rm_buffer = rm->rm_xipbase + SEC_ALIGN(rm, offset);
- }
- else
- {
- /* In non-XIP mode, we will have to read the new sector.*/
-
- ret = romfs_hwread(rm, rm->rm_buffer, sector, 1);
- if (ret < 0)
- {
- return (int16_t)ret;
- }
- }
-
- /* Update the cached sector number */
-
- rm->rm_cachesector = sector;
- }
-
- /* Return the offset */
-
- return offset & SEC_NDXMASK(rm);
-}
-
-/****************************************************************************
- * Name: romfs_followhardlinks
- *
- * Desciption:
- * Given the offset to a file header, check if the file is a hardlink.
- * If so, traverse the hard links until the terminal, non-linked header
- * so found and return that offset.
- *
- ****************************************************************************/
-
-static int romfs_followhardlinks(struct romfs_mountpt_s *rm, uint32_t offset,
- uint32_t *poffset)
-{
- uint32_t next;
- int16_t ndx;
- int i;
-
- /* Loop while we are redirected by hardlinks */
-
- for (i = 0; i < ROMF_MAX_LINKS; i++)
- {
- /* Read the sector containing the offset into memory */
-
- ndx = romfs_devcacheread(rm, offset);
- if (ndx < 0)
- {
- return ndx;
- }
-
- /* Check if this is a hard link */
-
- next = romfs_devread32(rm, ndx + ROMFS_FHDR_NEXT);
- if (!IS_HARDLINK(next))
- {
- *poffset = offset;
- return OK;
- }
-
- /* Follow the hard-link */
-
- offset = romfs_devread32(rm, ndx + ROMFS_FHDR_INFO);
- }
-
- return -ELOOP;
-}
-
-/****************************************************************************
- * Name: romfs_searchdir
- *
- * Desciption:
- * This is part of the romfs_finddirentry log. Search the directory
- * beginning at dirinfo->fr_firstoffset for entryname.
- *
- ****************************************************************************/
-
-static inline int romfs_searchdir(struct romfs_mountpt_s *rm,
- const char *entryname, int entrylen,
- struct romfs_dirinfo_s *dirinfo)
-{
- uint32_t offset;
- uint32_t next;
- int16_t ndx;
- int ret;
-
- /* Then loop through the current directory until the directory
- * with the matching name is found. Or until all of the entries
- * the directory have been examined.
- */
-
- offset = dirinfo->rd_dir.fr_firstoffset;
- do
- {
- /* Read the sector into memory (do this before calling
- * romfs_checkentry() so we won't have to read the sector
- * twice in the event that the offset refers to a hardlink).
- */
-
- ndx = romfs_devcacheread(rm, offset);
- if (ndx < 0)
- {
- return ndx;
- }
-
- /* Because everything is chunked and aligned to 16-bit boundaries,
- * we know that most the basic node info fits into the sector.
- */
-
- next = romfs_devread32(rm, ndx + ROMFS_FHDR_NEXT) & RFNEXT_OFFSETMASK;
-
- /* Check if the name this entry is a directory with the matching
- * name
- */
-
- ret = romfs_checkentry(rm, offset, entryname, entrylen, dirinfo);
- if (ret == OK)
- {
- /* Its a match! Return success */
-
- return OK;
- }
-
- /* No match... select the offset to the next entry */
-
- offset = next;
- }
- while (next != 0);
-
- /* There is nothing in this directory with that name */
-
- return -ENOENT;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: romfs_semtake
- ****************************************************************************/
-
-void romfs_semtake(struct romfs_mountpt_s *rm)
-{
- /* Take the semaphore (perhaps waiting) */
-
- while (sem_wait(&rm->rm_sem) != 0)
- {
- /* The only case that an error should occur here is if
- * the wait was awakened by a signal.
- */
-
- ASSERT(*get_errno_ptr() == EINTR);
- }
-}
-
-/****************************************************************************
- * Name: romfs_semgive
- ****************************************************************************/
-
-void romfs_semgive(struct romfs_mountpt_s *rm)
-{
- sem_post(&rm->rm_sem);
-}
-
-/****************************************************************************
- * Name: romfs_hwread
- *
- * Desciption: Read the specified sector into the sector buffer
- *
- ****************************************************************************/
-
-int romfs_hwread(struct romfs_mountpt_s *rm, uint8_t *buffer, uint32_t sector,
- unsigned int nsectors)
-{
- int ret = -ENODEV;
-
- /* Check the access mode */
-
- if (rm->rm_xipbase)
- {
- /* In XIP mode, we just copy the requested data */
-
- memcpy(buffer,
- rm->rm_xipbase + sector*rm->rm_hwsectorsize,
- nsectors*rm->rm_hwsectorsize);
- ret = OK;
- }
- else
- {
- /* In non-XIP mode, we have to read the data from the device */
-
- struct inode *inode = rm->rm_blkdriver;
- ssize_t nsectorsread;
-
- DEBUGASSERT(inode);
- if (inode->u.i_bops && inode->u.i_bops->read)
- {
- nsectorsread =
- inode->u.i_bops->read(inode, buffer, sector, nsectors);
-
- if (nsectorsread == (ssize_t)nsectors)
- {
- ret = OK;
- }
- else if (nsectorsread < 0)
- {
- ret = nsectorsread;
- }
- }
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: romfs_filecacheread
- *
- * Desciption:
- * Read the specified sector into the sector cache
- *
- ****************************************************************************/
-
-int romfs_filecacheread(struct romfs_mountpt_s *rm, struct romfs_file_s *rf, uint32_t sector)
-{
- int ret;
-
- fvdbg("sector: %d cached: %d sectorsize: %d XIP base: %p buffer: %p\n",
- sector, rf->rf_cachesector, rm->rm_hwsectorsize,
- rm->rm_xipbase, rf->rf_buffer);
-
- /* rf->rf_cachesector holds the current sector that is buffer in or referenced
- * by rf->rf_buffer. If the requested sector is the same as this sector,
- * then we do nothing.
- */
-
- if (rf->rf_cachesector != sector)
- {
- /* Check the access mode */
-
- if (rm->rm_xipbase)
- {
- /* In XIP mode, rf_buffer is just an offset pointer into the device
- * address space.
- */
-
- rf->rf_buffer = rm->rm_xipbase + sector * rm->rm_hwsectorsize;
- fvdbg("XIP buffer: %p\n", rf->rf_buffer);
- }
- else
- {
- /* In non-XIP mode, we will have to read the new sector.*/
-
- fvdbg("Calling romfs_hwread\n");
- ret = romfs_hwread(rm, rf->rf_buffer, sector, 1);
- if (ret < 0)
- {
- fdbg("romfs_hwread failed: %d\n", ret);
- return ret;
- }
- }
-
- /* Update the cached sector number */
-
- rf->rf_cachesector = sector;
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Name: romfs_hwconfigure
- *
- * Desciption:
- * This function is called as part of the ROMFS mount operation It
- * configures the ROMFS filestem for use on this block driver. This includes
- * the accounting for the geometry of the device, setting up any XIP modes
- * of operation, and/or allocating any cache buffers.
- *
- ****************************************************************************/
-
-int romfs_hwconfigure(struct romfs_mountpt_s *rm)
-{
- struct inode *inode = rm->rm_blkdriver;
- struct geometry geo;
- int ret;
-
- /* Get the underlying device geometry */
-
-#ifdef CONFIG_DEBUG
- if (!inode || !inode->u.i_bops || !inode->u.i_bops->geometry)
- {
- return -ENODEV;
- }
-#endif
-
- ret = inode->u.i_bops->geometry(inode, &geo);
- if (ret != OK)
- {
- return ret;
- }
-
- if (!geo.geo_available)
- {
- return -EBUSY;
- }
-
- /* Save that information in the mount structure */
-
- rm->rm_hwsectorsize = geo.geo_sectorsize;
- rm->rm_hwnsectors = geo.geo_nsectors;
-
- /* Determine if block driver supports the XIP mode of operation */
-
- rm->rm_cachesector = (uint32_t)-1;
-
- if (inode->u.i_bops->ioctl)
- {
- ret = inode->u.i_bops->ioctl(inode, BIOC_XIPBASE,
- (unsigned long)&rm->rm_xipbase);
- if (ret == OK && rm->rm_xipbase)
- {
- /* Yes.. Then we will directly access the media (vs.
- * copying into an allocated sector buffer.
- */
-
- rm->rm_buffer = rm->rm_xipbase;
- rm->rm_cachesector = 0;
- return OK;
- }
- }
-
- /* Allocate the device cache buffer for normal sector accesses */
-
- rm->rm_buffer = (uint8_t*)malloc(rm->rm_hwsectorsize);
- if (!rm->rm_buffer)
- {
- return -ENOMEM;
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Name: romfs_fsconfigure
- *
- * Desciption:
- * This function is called as part of the ROMFS mount operation It
- * sets up the mount structure to include configuration information contained
- * in the ROMFS header. This is the place where we actually determine if
- * the media contains a ROMFS filesystem.
- *
- ****************************************************************************/
-
-int romfs_fsconfigure(struct romfs_mountpt_s *rm)
-{
- const char *name;
- int16_t ndx;
-
- /* Then get information about the ROMFS filesystem on the devices managed
- * by this block driver. Read sector zero which contains the volume header.
- */
-
- ndx = romfs_devcacheread(rm, 0);
- if (ndx < 0)
- {
- return ndx;
- }
-
- /* Verify the magic number at that identifies this as a ROMFS filesystem */
-
- if (memcmp(rm->rm_buffer, ROMFS_VHDR_MAGIC, 8) != 0)
- {
- return -EINVAL;
- }
-
- /* Then extract the values we need from the header and return success */
-
- rm->rm_volsize = romfs_devread32(rm, ROMFS_VHDR_SIZE);
-
- /* The root directory entry begins right after the header */
-
- name = (const char*)&rm->rm_buffer[ROMFS_VHDR_VOLNAME];
- rm->rm_rootoffset = ROMFS_ALIGNUP(ROMFS_VHDR_VOLNAME + strlen(name) + 1);
-
- /* and return success */
-
- rm->rm_mounted = true;
- return OK;
-}
-
-/****************************************************************************
- * Name: romfs_fileconfigure
- *
- * Desciption:
- * This function is called as part of the ROMFS file open operation It
- * sets up the file structure to handle buffer appropriately, depending
- * upon XIP mode or not.
- *
- ****************************************************************************/
-
-int romfs_fileconfigure(struct romfs_mountpt_s *rm, struct romfs_file_s *rf)
-{
- /* Check if XIP access mode is supported. If so, then we do not need
- * to allocate anything.
- */
-
- if (rm->rm_xipbase)
- {
- /* We'll put a valid address in rf_buffer just in case. */
-
- rf->rf_cachesector = 0;
- rf->rf_buffer = rm->rm_xipbase;
- }
- else
- {
- /* Nothing in the cache buffer */
-
- rf->rf_cachesector = (uint32_t)-1;
-
- /* Create a file buffer to support partial sector accesses */
-
- rf->rf_buffer = (uint8_t*)malloc(rm->rm_hwsectorsize);
- if (!rf->rf_buffer)
- {
- return -ENOMEM;
- }
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Name: romfs_checkmount
- *
- * Desciption: Check if the mountpoint is still valid.
- *
- * The caller should hold the mountpoint semaphore
- *
- ****************************************************************************/
-
-int romfs_checkmount(struct romfs_mountpt_s *rm)
-{
- struct inode *inode;
- struct geometry geo;
- int ret;
-
- /* If the fs_mounted flag is false, then we have already handled the loss
- * of the mount.
- */
-
- DEBUGASSERT(rm && rm->rm_blkdriver);
- if (rm->rm_mounted)
- {
- /* We still think the mount is healthy. Check an see if this is
- * still the case
- */
-
- inode = rm->rm_blkdriver;
- if (inode->u.i_bops && inode->u.i_bops->geometry)
- {
- ret = inode->u.i_bops->geometry(inode, &geo);
- if (ret == OK && geo.geo_available && !geo.geo_mediachanged)
- {
- return OK;
- }
- }
-
- /* If we get here, the mount is NOT healthy */
-
- rm->rm_mounted = false;
- }
-
- return -ENODEV;
-}
-
-/****************************************************************************
- * Name: romfs_finddirentry
- *
- * Desciption:
- * Given a path to something that may or may not be in the file system,
- * return the directory entry of the item.
- *
- ****************************************************************************/
-
-int romfs_finddirentry(struct romfs_mountpt_s *rm, struct romfs_dirinfo_s *dirinfo,
- const char *path)
-{
- const char *entryname;
- const char *terminator;
- int entrylen;
- int ret;
-
- /* Start with the first element after the root directory */
-
- dirinfo->rd_dir.fr_firstoffset = rm->rm_rootoffset;
- dirinfo->rd_dir.fr_curroffset = rm->rm_rootoffset;
- dirinfo->rd_next = RFNEXT_DIRECTORY;
- dirinfo->rd_size = 0;
-
- /* The root directory is a special case */
-
- if (!path || path[0] == '\0')
- {
- return OK;
- }
-
- /* Then loop for each directory/file component in the full path */
-
- entryname = path;
- terminator = NULL;
-
- for (;;)
- {
- /* Find the start of the next path component */
-
- while (*entryname == '/') entryname++;
-
- /* Find the end of the next path component */
-
- terminator = strchr(entryname, '/');
- if (!terminator)
- {
- entrylen = strlen(entryname);
- }
- else
- {
- entrylen = terminator - entryname;
- }
-
- /* Long path segment names will be truncated to NAME_MAX */
-
- if (entrylen > NAME_MAX)
- {
- entrylen = NAME_MAX;
- }
-
- /* Then find the entry in the current directory with the
- * matching name.
- */
-
- ret = romfs_searchdir(rm, entryname, entrylen, dirinfo);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Was that the last path component? */
-
- if (!terminator)
- {
- /* Yes.. return success */
-
- return OK;
- }
-
- /* No... If that was not the last path component, then it had
- * better have been a directory
- */
-
- if (!IS_DIRECTORY(dirinfo->rd_next))
- {
- return -ENOTDIR;
- }
-
- /* Setup to search the next directory for the next component
- * of the path
- */
-
- entryname = terminator;
- }
-
- return ERROR; /* Won't get here */
-}
-
-/****************************************************************************
- * Name: romfs_parsedirentry
- *
- * Desciption:
- * Return the directory entry at this offset. If rf is NULL, then the
- * mount device resources are used. Otherwise, file resources are used.
- *
- ****************************************************************************/
-
-int romfs_parsedirentry(struct romfs_mountpt_s *rm, uint32_t offset, uint32_t *poffset,
- uint32_t *pnext, uint32_t *pinfo, uint32_t *psize)
-{
- uint32_t save;
- uint32_t next;
- int16_t ndx;
- int ret;
-
- /* Read the sector into memory */
-
- ndx = romfs_devcacheread(rm, offset);
- if (ndx < 0)
- {
- return ndx;
- }
-
- /* Yes.. Save the first 'next' value. That has the offset needed to
- * traverse the parent directory. But we may need to change the type
- * after we follow the hard links.
- */
-
- save = romfs_devread32(rm, ndx + ROMFS_FHDR_NEXT);
-
- /* Traverse hardlinks as necesssary to get to the real file header */
-
- ret = romfs_followhardlinks(rm, offset, poffset);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Because everything is chunked and aligned to 16-bit boundaries,
- * we know that most the basic node info fits into the sector. The
- * associated name may not, however.
- */
-
- next = romfs_devread32(rm, ndx + ROMFS_FHDR_NEXT);
- *pnext = (save & RFNEXT_OFFSETMASK) | (next & RFNEXT_ALLMODEMASK);
- *pinfo = romfs_devread32(rm, ndx + ROMFS_FHDR_INFO);
- *psize = romfs_devread32(rm, ndx + ROMFS_FHDR_SIZE);
- return OK;
-}
-
-/****************************************************************************
- * Name: romfs_parsefilename
- *
- * Desciption:
- * Return the filename from directory entry at this offset
- *
- ****************************************************************************/
-
-int romfs_parsefilename(struct romfs_mountpt_s *rm, uint32_t offset, char *pname)
-{
- int16_t ndx;
- uint16_t namelen;
- uint16_t chunklen;
- bool done;
-
- /* Loop until the whole name is obtained or until NAME_MAX characters
- * of the name have been parsed.
- */
-
- offset += ROMFS_FHDR_NAME;
- for (namelen = 0, done = false; namelen < NAME_MAX && !done;)
- {
- /* Read the sector into memory */
-
- ndx = romfs_devcacheread(rm, offset);
- if (ndx < 0)
- {
- return ndx;
- }
-
- /* Is the name terminated in this 16-byte block */
-
- if (rm->rm_buffer[ndx + 15] == '\0')
- {
- /* Yes.. then this chunk is less than 16 */
-
- chunklen = strlen((char*)&rm->rm_buffer[ndx]);
- done = true;
- }
- else
- {
- /* No.. then this chunk is 16 bytes in length */
-
- chunklen = 16;
- }
-
- /* Check if we would exceed the NAME_MAX */
-
- if (namelen + chunklen > NAME_MAX)
- {
- chunklen = NAME_MAX - namelen;
- done = true;
- }
-
- /* Copy the chunk */
-
- memcpy(&pname[namelen], &rm->rm_buffer[ndx], chunklen);
- namelen += chunklen;
- }
-
- /* Terminate the name (NAME_MAX+1 chars total) and return success */
-
- pname[namelen] = '\0';
- return OK;
-}
-
-/****************************************************************************
- * Name: romfs_datastart
- *
- * Desciption:
- * Given the offset to a file header, return the offset to the start of
- * the file data
- *
- ****************************************************************************/
-
-int romfs_datastart(struct romfs_mountpt_s *rm, uint32_t offset, uint32_t *start)
-{
- int16_t ndx;
- int ret;
-
- /* Traverse hardlinks as necesssary to get to the real file header */
-
- ret = romfs_followhardlinks(rm, offset, &offset);
- if (ret < 0)
- {
- return ret;
- }
-
- /* Loop until the header size is obtained. */
-
- offset += ROMFS_FHDR_NAME;
- for (;;)
- {
- /* Read the sector into memory */
-
- ndx = romfs_devcacheread(rm, offset);
- if (ndx < 0)
- {
- return ndx;
- }
-
- /* Get the offset to the next chunk */
-
- offset += 16;
- if (offset >= rm->rm_volsize)
- {
- return -EIO;
- }
-
- /* Is the name terminated in this 16-byte block */
-
- if (rm->rm_buffer[ndx + 15] == '\0')
- {
- /* Yes.. then the data starts at the next chunk */
-
- *start = offset;
- return OK;
- }
- }
-
- return -EINVAL; /* Won't get here */
-}
-