From ad47fd1b4bdeee2bb4d65d6349eca4d34e2a750b Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 2 Aug 2008 14:44:25 +0000 Subject: Fat directory git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@797 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/fs/fat/Make.defs | 37 + nuttx/fs/fat/fs_fat32.c | 2210 +++++++++++++++++++++++++++++++++++++ nuttx/fs/fat/fs_fat32.h | 584 ++++++++++ nuttx/fs/fat/fs_fat32attrib.c | 190 ++++ nuttx/fs/fat/fs_fat32util.c | 2445 +++++++++++++++++++++++++++++++++++++++++ 5 files changed, 5466 insertions(+) create mode 100644 nuttx/fs/fat/Make.defs create mode 100644 nuttx/fs/fat/fs_fat32.c create mode 100644 nuttx/fs/fat/fs_fat32.h create mode 100644 nuttx/fs/fat/fs_fat32attrib.c create mode 100644 nuttx/fs/fat/fs_fat32util.c (limited to 'nuttx/fs') diff --git a/nuttx/fs/fat/Make.defs b/nuttx/fs/fat/Make.defs new file mode 100644 index 000000000..2b5fdda45 --- /dev/null +++ b/nuttx/fs/fat/Make.defs @@ -0,0 +1,37 @@ +############################################################################ +# Make.defs +# +# Copyright (C) 2008 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +FAT_ASRCS = +FAT_CSRCS = fs_fat32.c fs_fat32attrib.c fs_fat32util.c diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c new file mode 100644 index 000000000..a54298bce --- /dev/null +++ b/nuttx/fs/fat/fs_fat32.c @@ -0,0 +1,2210 @@ +/**************************************************************************** + * fs_fat32.c + * + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * Microsoft FAT documentation + * Some good ideas were leveraged from the FAT implementation: + * 'Copyright (C) 2007, ChaN, all right reserved.' + * which has an unrestricted license. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "fs_internal.h" +#include "fs_fat32.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int fat_open(FAR struct file *filp, const char *relpath, + int oflags, mode_t mode); +static int fat_close(FAR struct file *filp); +static ssize_t fat_read(FAR struct file *filp, char *buffer, size_t buflen); +static ssize_t fat_write(FAR struct file *filp, const char *buffer, + size_t buflen); +static off_t fat_seek(FAR struct file *filp, off_t offset, int whence); +static int fat_ioctl(FAR struct file *filp, int cmd, unsigned long arg); +static int fat_sync(FAR struct file *filp); + +static int fat_opendir(struct inode *mountpt, const char *relpath, + struct internal_dir_s *dir); +static int fat_readdir(struct inode *mountpt, struct internal_dir_s *dir); +static int fat_rewinddir(struct inode *mountpt, struct internal_dir_s *dir); + +static int fat_bind(FAR struct inode *blkdriver, const void *data, + void **handle); +static int fat_unbind(void *handle, FAR struct inode **blkdriver); +static int fat_statfs(struct inode *mountpt, struct statfs *buf); + +static int fat_unlink(struct inode *mountpt, const char *relpath); +static int fat_mkdir(struct inode *mountpt, const char *relpath, + mode_t mode); +static int fat_rmdir(struct inode *mountpt, const char *relpath); +static int fat_rename(struct inode *mountpt, const char *oldrelpath, + const char *newrelpath); +static int fat_stat(struct inode *mountpt, const char *relpath, 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 fat_operations = +{ + fat_open, + fat_close, + fat_read, + fat_write, + fat_seek, + fat_ioctl, + fat_sync, + + fat_opendir, + NULL, + fat_readdir, + fat_rewinddir, + + fat_bind, + fat_unbind, + fat_statfs, + + fat_unlink, + fat_mkdir, + fat_rmdir, + fat_rename, + fat_stat +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fat_open + ****************************************************************************/ + +static int fat_open(FAR struct file *filp, const char *relpath, + int oflags, mode_t mode) +{ + struct fat_dirinfo_s dirinfo; + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv == NULL && filp->f_inode != NULL); + + /* Get the mountpoint inode reference from the file structure and the + * mountpoint private data from the inode structure + */ + + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != NULL); + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Initialize the directory info structure */ + + memset(&dirinfo, 0, sizeof(struct fat_dirinfo_s)); + + /* Locate the directory entry for this path */ + + ret = fat_finddirentry(fs, &dirinfo, relpath); + + /* Three possibililities: (1) a node exists for the relpath and + * dirinfo describes the directory entry of the entity, (2) the + * node does not exist, or (3) some error occurred. + */ + + if (ret == OK) + { + boolean readonly; + + /* The name exists -- but is it a file or a directory? */ + + if (dirinfo.fd_entry == NULL || + (DIR_GETATTRIBUTES(dirinfo.fd_entry) & FATATTR_DIRECTORY)) + { + /* It is a directory */ + ret = -EISDIR; + goto errout_with_semaphore; + } + + /* It would be an error if we are asked to create it exclusively */ + + if ((oflags & (O_CREAT|O_EXCL)) == (O_CREAT|O_EXCL)) + { + /* Already exists -- can't create it exclusively */ + ret = -EEXIST; + goto errout_with_semaphore; + } + +#ifdef CONFIG_FILE_MODE +# warning "Missing check for privileges based on inode->i_mode" +#endif + + /* Check if the caller has sufficient privileges to open the file */ + + readonly = ((DIR_GETATTRIBUTES(dirinfo.fd_entry) & FATATTR_READONLY) != 0); + if (((oflags & O_WRONLY) != 0) && readonly) + { + ret = -EACCES; + goto errout_with_semaphore; + } + + /* If O_TRUNC is specified and the file is opened for writing, + * then truncate the file. This operation requires that the file is + * writable, but we have already checked that. O_TRUNC without write + * access is ignored. + */ + + if ((oflags & (O_TRUNC|O_WRONLY)) == (O_TRUNC|O_WRONLY)) + { + /* Truncate the file to zero length */ + + ret = fat_dirtruncate(fs, &dirinfo); + if (ret < 0) + { + goto errout_with_semaphore; + } + } + + /* fall through to finish the file open operations */ + + } + else if (ret == -ENOENT) + { + /* The file does not exist. Were we asked to create it? */ + + if ((oflags & O_CREAT) == 0) + { + /* No.. then we fail with -ENOENT */ + ret = -ENOENT; + goto errout_with_semaphore; + } + + /* Yes.. create the file */ + + ret = fat_dircreate(fs, &dirinfo); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Fall through to finish the file open operation */ + } + else + { + /* An error occurred while checking for file existence -- + * such as if an invalid path were provided. + */ + + goto errout_with_semaphore; + } + + /* Create an instance of the file private date to describe the opened + * file. + */ + + ff = (struct fat_file_s *)zalloc(sizeof(struct fat_file_s)); + if (!ff) + { + ret = -ENOMEM; + goto errout_with_semaphore; + } + + /* Create a file buffer to support partial sector accesses */ + + ff->ff_buffer = (ubyte*)malloc(fs->fs_hwsectorsize); + if (!ff->ff_buffer) + { + ret = -ENOMEM; + goto errout_with_struct; + } + + /* Initialize the file private data (only need to initialize non-zero elements) */ + + ff->ff_open = TRUE; + ff->ff_oflags = oflags; + ff->ff_sectorsincluster = 1; + + /* Save information that can be used later to recover the directory entry */ + + ff->ff_dirsector = fs->fs_currentsector; + ff->ff_dirindex = dirinfo.dir.fd_index; + + /* File cluster/size info */ + + ff->ff_startcluster = + ((uint32)DIR_GETFSTCLUSTHI(dirinfo.fd_entry) << 16) | + DIR_GETFSTCLUSTLO(dirinfo.fd_entry); + + ff->ff_size = DIR_GETFILESIZE(dirinfo.fd_entry); + + /* In write/append mode, we need to set the file pointer to the end of the file */ + + if ((oflags & (O_APPEND|O_WRONLY)) == (O_APPEND|O_WRONLY)) + { + ff->ff_position = ff->ff_size; + } + + /* Attach the private date to the struct file instance */ + + filp->f_priv = ff; + + /* 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). + */ + + ff->ff_next = fs->fs_head; + fs->fs_head = ff->ff_next; + + fat_semgive(fs); + return OK; + + /* Error exits -- goto's are nasty things, but they sure can make error + * handling a lot simpler. + */ + +errout_with_struct: + free(ff); + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_close + ****************************************************************************/ + +static int fat_close(FAR struct file *filp) +{ + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + int ret = OK; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv != NULL && filp->f_inode != NULL); + + /* Recover our private data from the struct file instance */ + + ff = filp->f_priv; + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != NULL); + + /* Do not check if the mount is healthy. We must support closing of + * the file even when there is healthy mount. + */ + + /* Synchronize the file buffers and disk content; update times */ + + ret = fat_sync(filp); + + /* Then deallocate the memory structures created when the open method + * was called. + * + * Free the sector buffer that was used to manage partial sector accesses. + */ + + if (ff->ff_buffer) + { + free(ff->ff_buffer); + } + + /* Then free the file structure itself. */ + + free(ff); + filp->f_priv = NULL; + return ret; +} + +/**************************************************************************** + * Name: fat_read + ****************************************************************************/ + +static ssize_t fat_read(FAR struct file *filp, char *buffer, size_t buflen) +{ + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + uint32 cluster; + unsigned int bytesread; + unsigned int readsize; + unsigned int nsectors; + size_t readsector; + size_t bytesleft; + ubyte *userbuffer = (ubyte*)buffer; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv != NULL && filp->f_inode != NULL); + + /* Recover our private data from the struct file instance */ + + ff = filp->f_priv; + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != NULL); + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Check if the file was opened with read access */ + + if ((ff->ff_oflags & O_RDOK) == 0) + { + ret = -EACCES; + goto errout_with_semaphore; + } + + /* Get the number of bytes left in the file */ + + bytesleft = ff->ff_size - ff->ff_position; + + /* 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; + readsector = ff->ff_currentsector; + while (buflen > 0) + { + /* Get offset into the sector where we begin the read */ + + int sectorindex = ff->ff_position & SEC_NDXMASK(fs); + bytesread = 0; + + /* Check if the current read stream happens to lie on a + * sector boundary. + */ + + if (sectorindex == 0) + { + /* Try to read another contiguous sector from the cluster */ + + ff->ff_sectorsincluster--; + + /* Are there unread sectors remaining in the cluster? */ + + if (ff->ff_sectorsincluster > 0) + { + /* Yes.. There are more sectors in this cluster to be read + * just increment the current sector number and read. + */ + + readsector = ff->ff_currentsector + 1; + } + else + { + /* No.. Handle the case of the first sector of the file */ + + if (ff->ff_position == 0) + { + /* Get the first cluster of the file */ + + cluster = ff->ff_startcluster; + } + + /* But in the general case, we have to find the next cluster + * in the FAT. + */ + + else + { + cluster = fat_getcluster(fs, ff->ff_currentcluster); + } + + /* Verify the cluster number */ + + if (cluster < 2 || cluster >= fs->fs_nclusters) + { + ret = -EINVAL; /* Not the right error */ + goto errout_with_semaphore; + } + + /* Setup to read the first sector from the new cluster */ + + ff->ff_currentcluster = cluster; + ff->ff_sectorsincluster = fs->fs_fatsecperclus; + readsector = fat_cluster2sector(fs, cluster); + } + } + + /* Check if the user has provided a buffer large enough to + * hold one or more complete sectors. + */ + + nsectors = buflen / fs->fs_hwsectorsize; + if (nsectors > 0) + { + /* Read maximum contiguous sectors directly to the user's + * buffer without using our tiny read buffer. + * + * Limit the number of sectors that we read on this time + * through the loop to the remaining contiguous sectors + * in this cluster + */ + + if (nsectors > ff->ff_sectorsincluster) + { + nsectors = ff->ff_sectorsincluster; + } + + /* We are not sure of the state of the file buffer so + * the safest thing to do is just invalidate it + */ + + (void)fat_ffcacheinvalidate(fs, ff); + + /* Read all of the sectors directory into user memory */ + + ret = fat_hwread(fs, userbuffer, readsector, nsectors); + if (ret < 0) + { + goto errout_with_semaphore; + } + + ff->ff_sectorsincluster -= nsectors - 1; + ff->ff_currentsector = readsector + nsectors - 1; + bytesread = nsectors * fs->fs_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. + */ + + ret = fat_ffcacheread(fs, ff, readsector); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Copy the partial sector into the user buffer */ + + bytesread = fs->fs_hwsectorsize - sectorindex; + if (bytesread > buflen) + { + bytesread = buflen; + } + + memcpy(userbuffer, &ff->ff_buffer[sectorindex], bytesread); + ff->ff_currentsector = readsector; + } + + /* Set up for the next sector read */ + + userbuffer += bytesread; + ff->ff_position += bytesread; + readsize += bytesread; + buflen -= bytesread; + } + + fat_semgive(fs); + return readsize; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_write + ****************************************************************************/ + +static ssize_t fat_write(FAR struct file *filp, const char *buffer, + size_t buflen) +{ + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + sint32 cluster; + size_t writesector; + unsigned int byteswritten; + unsigned int writesize; + unsigned int nsectors; + ubyte *userbuffer = (ubyte*)buffer; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv != NULL && filp->f_inode != NULL); + + /* Recover our private data from the struct file instance */ + + ff = filp->f_priv; + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != NULL); + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Check if the file was opened for write access */ + + if ((ff->ff_oflags & O_WROK) == 0) + { + ret = -EACCES; + goto errout_with_semaphore; + } + + /* Check if the file size would exceed the range of size_t */ + + if (ff->ff_size + buflen < ff->ff_size) + { + ret = -EFBIG; + goto errout_with_semaphore; + } + + /* Loop until either (1) all data has been transferred, or (2) an + * error occurs. + */ + + byteswritten = 0; + writesector = ff->ff_currentsector; + while (buflen > 0) + { + /* Get offset into the sector where we begin the read */ + + int sectorindex = ff->ff_position & SEC_NDXMASK(fs); + + /* Check if the current read stream happens to lie on a + * sector boundary. + */ + + if (sectorindex == 0) + { + /* Decrement the number of sectors left in this cluster */ + + ff->ff_sectorsincluster--; + + /* Are there unwritten sectors remaining in this cluster */ + + if (ff->ff_sectorsincluster > 0) + { + /* Yes.. There are more sectors in this cluster to be written. + * just increment the current sector number and write. + */ + + writesector = ff->ff_currentsector + 1; + } + else + { + /* No.. Handle the case of the first sector of the file */ + + if (ff->ff_position == 0) + { + /* Check the first cluster of the file. Zero means that + * the file is empty -- perhaps the file was truncated or + * created when it was opened + */ + + if (ff->ff_startcluster == 0) + { + /* In this case, we have to create a new cluster chain */ + + ff->ff_startcluster = fat_createchain(fs); + } + + /* Start writing at the first cluster of the file */ + + cluster = ff->ff_startcluster; + } + + /* But in the general case, we have to extend the current + * cluster by one (unless lseek was used to move the file + * position back from the end of the file) + */ + + else + { + /* Extend the chain by adding a new cluster after + * the last one + */ + + cluster = fat_extendchain(fs, ff->ff_currentcluster); + } + + /* Verify the cluster number */ + + if (cluster < 0) + { + ret = cluster; + goto errout_with_semaphore; + } + else if (cluster < 2 || cluster >= fs->fs_nclusters) + { + ret = -ENOSPC; + goto errout_with_semaphore; + } + + /* Setup to write the first sector from the new cluster */ + + ff->ff_currentcluster = cluster; + ff->ff_sectorsincluster = fs->fs_fatsecperclus; + writesector = fat_cluster2sector(fs, cluster); + } + } + + /* Check if there is unwritten data in the file buffer */ + + ret = fat_ffcacheflush(fs, ff); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Check if the user has provided a buffer large enough to + * hold one or more complete sectors. + */ + + nsectors = buflen / fs->fs_hwsectorsize; + if (nsectors > 0) + { + /* Write maximum contiguous sectors directly from the user's + * buffer without using our tiny read buffer. + * + * Limit the number of sectors that we write on this time + * through the loop to the remaining contiguous sectors + * in this cluster + */ + + if (nsectors > ff->ff_sectorsincluster) + { + nsectors = ff->ff_sectorsincluster; + } + + /* We are not sure of the state of the file buffer so + * the safest thing to do is just invalidate it + */ + + (void)fat_ffcacheinvalidate(fs, ff); + + /* Write all of the sectors directory from user memory */ + + ret = fat_hwwrite(fs, userbuffer, writesector, nsectors); + if (ret < 0) + { + goto errout_with_semaphore; + } + + ff->ff_sectorsincluster -= nsectors - 1; + ff->ff_currentsector = writesector + nsectors - 1; + writesize = nsectors * fs->fs_hwsectorsize; + ff->ff_bflags |= FFBUFF_MODIFIED; + } + else + { + /* We are write a partial sector. We will first have to + * read the full sector in memory as part of a read-modify-write + * operation. + */ + + if (ff->ff_position < ff->ff_size) + { + ff->ff_currentsector = writesector; + ret = fat_ffcacheread(fs, ff, writesector); + if (ret < 0) + { + goto errout_with_semaphore; + } + } + + /* Copy the partial sector from the user buffer */ + + writesize = fs->fs_hwsectorsize - sectorindex; + if (writesize > buflen) + { + writesize = buflen; + } + + memcpy(&ff->ff_buffer[sectorindex], userbuffer, writesize); + ff->ff_currentsector = writesector; + ff->ff_bflags |= (FFBUFF_DIRTY|FFBUFF_VALID|FFBUFF_MODIFIED); + } + + /* Set up for the next write */ + + userbuffer += writesize; + ff->ff_position += writesize; + byteswritten += writesize; + buflen -= writesize; + } + + /* The transfer has completed without error. Update the file size */ + + if (ff->ff_position > ff->ff_size) + { + ff->ff_size = ff->ff_position; + } + + fat_semgive(fs); + return byteswritten; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_seek + ****************************************************************************/ + +static off_t fat_seek(FAR struct file *filp, off_t offset, int whence) +{ + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + sint32 cluster; + ssize_t position; + unsigned int clustersize; + unsigned int sectoroffset; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv != NULL && filp->f_inode != NULL); + + /* Recover our private data from the struct file instance */ + + ff = filp->f_priv; + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != 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 + ff->ff_position; + break; + + case SEEK_END: /* The offset is set to the size of the file plus + * offset bytes. */ + + position = offset + ff->ff_size; + break; + + default: + return -EINVAL; + } + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Check if there is unwritten data in the file buffer */ + + ret = fat_ffcacheflush(fs, ff); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Attempts to set the position beyound the end of file will + * work if the file is open for write access. + */ + + if (position > ff->ff_size && (ff->ff_oflags & O_WROK) == 0) + { + /* Otherwise, the position is limited to the file size */ + position = ff->ff_size; + } + + /* Set file position to the beginning of the file */ + + ff->ff_position = 0; + ff->ff_sectorsincluster = 1; + + /* Move file position if necessary */ + + if (position) + { + /* Get the start cluster of the file */ + + cluster = ff->ff_startcluster; + if (!cluster) + { + /* Create a new cluster chain if the file does not have one */ + + cluster = fat_createchain(fs); + if (cluster < 0) + { + ret = cluster; + goto errout_with_semaphore; + } + ff->ff_startcluster = cluster; + } + + if (cluster) + { + /* If the file has a cluster chain, follow it to the + * requested position. + */ + + clustersize = fs->fs_fatsecperclus * fs->fs_hwsectorsize; + for (;;) + { + /* Skip over clusters prior to the one containing + * the requested position. + */ + + ff->ff_currentcluster = cluster; + if (position <= clustersize) + { + break; + } + + /* Extend the cluster chain if write in enabled. NOTE: + * this is not consistent with the lseek description: + * "The lseek() function allows the file offset to be + * set beyond the end of the file (but this does not + * change the size of the file). If data is later written + * at this point, subsequent reads of the data in the + * gap (a "hole") return null bytes ('\0') until data + * is actually written into the gap." + */ + + if ((ff->ff_oflags & O_WROK) != 0) + { + /* Extend the cluster chain (fat_extendchain + * will follow the existing chain or add new + * clusters as needed. + */ + + cluster = fat_extendchain(fs, cluster); + } + else + { + /* Other we can only follong the existing chain */ + + cluster = fat_getcluster(fs, cluster); + } + + if (cluster < 0) + { + /* An error occurred getting the cluster */ + + ret = cluster; + goto errout_with_semaphore; + } + + /* Zero means that there is no further clusters available + * in the chain. + */ + + if (cluster == 0) + { + /* At the position to the current locaiton and + * break out. + */ + + position = clustersize; + break; + } + + if (cluster >= fs->fs_nclusters) + { + ret = -ENOSPC; + goto errout_with_semaphore; + } + + /* Otherwise, update the position and continue looking */ + + ff->ff_position += clustersize; + position -= clustersize; + } + + /* We get here after we have found the sector containing + * the requested position. + */ + + sectoroffset = (position - 1) / fs->fs_hwsectorsize; + + /* And get the current sector from the cluster and + * the sectoroffset into the cluster. + */ + + ff->ff_currentsector = + fat_cluster2sector(fs, cluster) + sectoroffset; + + /* Load the sector corresponding to the position */ + + if ((position & SEC_NDXMASK(fs)) != 0) + { + ret = fat_ffcacheread(fs, ff, ff->ff_currentsector); + if (ret < 0) + { + goto errout_with_semaphore; + } + } + + /* Save the number of sectors left in the cluster */ + + ff->ff_sectorsincluster = fs->fs_fatsecperclus - sectoroffset; + + /* And save the new file position */ + + ff->ff_position += position; + } + } + + /* If we extended the size of the file, then mark the file as modified. */ + + if ((ff->ff_oflags & O_WROK) != 0 && ff->ff_position > ff->ff_size) + { + ff->ff_size = ff->ff_position; + ff->ff_bflags |= FFBUFF_MODIFIED; + } + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_ioctl + ****************************************************************************/ + +static int fat_ioctl(FAR struct file *filp, int cmd, unsigned long arg) +{ + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv != NULL && filp->f_inode != NULL); + + /* Recover our private data from the struct file instance */ + + ff = filp->f_priv; + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != NULL); + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + fat_semgive(fs); + return ret; + } + + /* ioctl calls are just passed through to the contained block driver */ + + fat_semgive(fs); + return -ENOSYS; +} + +/**************************************************************************** + * Name: fat_sync + * + * Description: Synchronize the file state on disk to match internal, in- + * memory state. + * + ****************************************************************************/ + +static int fat_sync(FAR struct file *filp) +{ + struct inode *inode; + struct fat_mountpt_s *fs; + struct fat_file_s *ff; + uint32 wrttime; + ubyte *direntry; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(filp->f_priv != NULL && filp->f_inode != NULL); + + /* Recover our private data from the struct file instance */ + + ff = filp->f_priv; + inode = filp->f_inode; + fs = inode->i_private; + + DEBUGASSERT(fs != NULL); + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Check if the has been modified in any way */ + if ((ff->ff_bflags & FFBUFF_MODIFIED) != 0) + { + /* Flush any unwritten data in the file buffer */ + + ret = fat_ffcacheflush(fs, ff); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Update the directory entry. First read the directory + * entry into the fs_buffer (preserving the ff_buffer) + */ + + ret = fat_fscacheread(fs, ff->ff_dirsector); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Recover a pointer to the specific directory entry + * in the sector using the saved directory index. + */ + + direntry = &fs->fs_buffer[ff->ff_dirindex * 32]; + + /* Set the archive bit, set the write time, and update + * anything that may have* changed in the directory + * entry: the file size, and the start cluster + */ + + direntry[DIR_ATTRIBUTES] |= FATATTR_ARCHIVE; + + DIR_PUTFILESIZE(direntry, ff->ff_size); + DIR_PUTFSTCLUSTLO(direntry, ff->ff_startcluster); + DIR_PUTFSTCLUSTHI(direntry, ff->ff_startcluster >> 16); + + wrttime = fat_systime2fattime(); + DIR_PUTWRTTIME(direntry, wrttime & 0xffff); + DIR_PUTWRTDATE(direntry, wrttime >> 16); + + /* Clear the modified bit in the flags */ + + ff->ff_bflags &= ~FFBUFF_MODIFIED; + + /* Flush these change to disk and update FSINFO (if + * appropriate. + */ + + fs->fs_dirty = TRUE; + ret = fat_updatefsinfo(fs); + } + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_opendir + * + * Description: Open a directory for read access + * + ****************************************************************************/ + +static int fat_opendir(struct inode *mountpt, const char *relpath, struct internal_dir_s *dir) +{ + struct fat_mountpt_s *fs; + struct fat_dirinfo_s dirinfo; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL); + + /* Recover our private data from the inode instance */ + + fs = mountpt->i_private; + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Find the requested directory */ + + ret = fat_finddirentry(fs, &dirinfo, relpath); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Check if this is the root directory */ + + if (dirinfo.fd_entry == NULL) + { + /* Handle the FAT12/16/32 root directory using the values setup by + * fat_finddirentry() above. + */ + + dir->u.fat.fd_startcluster = dirinfo.dir.fd_startcluster; + dir->u.fat.fd_currcluster = dirinfo.dir.fd_currcluster; + dir->u.fat.fd_currsector = dirinfo.dir.fd_currsector; + dir->u.fat.fd_index = dirinfo.dir.fd_index; + } + + /* This is not the root directory. Verify that it is some kind of directory */ + + else if ((DIR_GETATTRIBUTES(dirinfo.fd_entry) & FATATTR_DIRECTORY) == 0) + { + /* The entry is not a directory */ + ret = -ENOTDIR; + goto errout_with_semaphore; + } + else + { + /* The entry is a directory */ + + dir->u.fat.fd_startcluster = + ((uint32)DIR_GETFSTCLUSTHI(dirinfo.fd_entry) << 16) | + DIR_GETFSTCLUSTLO(dirinfo.fd_entry); + dir->u.fat.fd_currcluster = dir->u.fat.fd_startcluster; + dir->u.fat.fd_currsector = fat_cluster2sector(fs, dir->u.fat.fd_currcluster); + dir->u.fat.fd_index = 2; + } + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ERROR; +} + +/**************************************************************************** + * Name: fat_readdir + * + * Description: Read the next directory entry + * + ****************************************************************************/ + +static int fat_readdir(struct inode *mountpt, struct internal_dir_s *dir) +{ + struct fat_mountpt_s *fs; + unsigned int dirindex; + ubyte *direntry; + ubyte ch; + ubyte attribute; + int ret = OK; + + /* Sanity checks */ + + DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL); + + /* Recover our private data from the inode instance */ + + fs = mountpt->i_private; + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Read the next directory entry */ + + dir->fd_dir.d_name[0] = '\0'; + while (dir->u.fat.fd_currsector && dir->fd_dir.d_name[0] == '\0') + { + ret = fat_fscacheread(fs, dir->u.fat.fd_currsector); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Get a reference to the current directory entry */ + + dirindex = (dir->u.fat.fd_index & DIRSEC_NDXMASK(fs)) * 32; + direntry = &fs->fs_buffer[dirindex]; + + /* Has it reached to end of the directory */ + + ch = *direntry; + if (ch == DIR0_ALLEMPTY) + { + /* We signal the end of the directory by returning the + * special error -ENOENT + */ + + ret = -ENOENT; + goto errout_with_semaphore; + } + + /* No, is the current entry a valid entry? */ + + attribute = DIR_GETATTRIBUTES(direntry); + if (ch != DIR0_EMPTY && (attribute & FATATTR_VOLUMEID) == 0) + { + /* Yes.. get the name from the directory info */ + + (void)fat_dirname2path(dir->fd_dir.d_name, direntry); + + /* And the file type */ + + if ((attribute & FATATTR_DIRECTORY) == 0) + { + dir->fd_dir.d_type = DTYPE_FILE; + } + else + { + dir->fd_dir.d_type = DTYPE_DIRECTORY; + } + } + + /* Set up the next directory index */ + + if (fat_nextdirentry(fs, &dir->u.fat) != OK) + { + ret = -ENOENT; + goto errout_with_semaphore; + } + } + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_rewindir + * + * Description: Reset directory read to the first entry + * + ****************************************************************************/ + +static int fat_rewinddir(struct inode *mountpt, struct internal_dir_s *dir) +{ + struct fat_mountpt_s *fs; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL); + + /* Recover our private data from the inode instance */ + + fs = mountpt->i_private; + + /* Make sure that the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Check if this is the root directory */ + + if (fs->fs_type != FSTYPE_FAT32 && + dir->u.fat.fd_startcluster == 0) + { + /* Handle the FAT12/16 root directory */ + + dir->u.fat.fd_currcluster = 0; + dir->u.fat.fd_currsector = fs->fs_rootbase; + dir->u.fat.fd_index = 0; + } + else if (fs->fs_type == FSTYPE_FAT32 && + dir->u.fat.fd_startcluster == fs->fs_rootbase) + { + /* Handle the FAT32 root directory */ + + dir->u.fat.fd_currcluster = dir->u.fat.fd_startcluster; + dir->u.fat.fd_currsector = fat_cluster2sector(fs, fs->fs_rootbase); + dir->u.fat.fd_index = 0; + } + + /* This is not the root directory */ + + else + { + dir->u.fat.fd_currcluster = dir->u.fat.fd_startcluster; + dir->u.fat.fd_currsector = fat_cluster2sector(fs, dir->u.fat.fd_currcluster); + dir->u.fat.fd_index = 2; + } + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ERROR; +} + +/**************************************************************************** + * Name: fat_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 fat_bind(FAR struct inode *blkdriver, const void *data, + void **handle) +{ + struct fat_mountpt_s *fs; + int ret; + + /* Open the block driver */ + + if (!blkdriver || !blkdriver->u.i_bops) + { + return -ENODEV; + } + + if (blkdriver->u.i_bops->open && + blkdriver->u.i_bops->open(blkdriver) != OK) + { + return -ENODEV; + } + + /* Create an instance of the mountpt state structure */ + + fs = (struct fat_mountpt_s *)zalloc(sizeof(struct fat_mountpt_s)); + if (!fs) + { + 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(). + */ + + fs->fs_blkdriver = blkdriver; /* Save the block driver reference */ + sem_init(&fs->fs_sem, 0, 0); /* Initialize the semaphore that controls access */ + + /* Then get information about the FAT32 filesystem on the devices managed + * by this block driver. + */ + + ret = fat_mount(fs, TRUE); + if (ret != 0) + { + sem_destroy(&fs->fs_sem); + free(fs); + return ret; + } + + *handle = (void*)fs; + fat_semgive(fs); + return OK; +} + +/**************************************************************************** + * Name: fat_unbind + * + * Description: This implements the filesystem portion of the umount + * operation. + * + ****************************************************************************/ + +static int fat_unbind(void *handle, FAR struct inode **blkdriver) +{ + struct fat_mountpt_s *fs = (struct fat_mountpt_s*)handle; + int ret; + + if (!fs) + { + return -EINVAL; + } + + /* Check if there are sill any files opened on the filesystem. */ + + ret = OK; /* Assume success */ + fat_semtake(fs); + if (fs->fs_head) + { + /* We cannot unmount now.. there are open files */ + + ret = -EBUSY; + } + else + { + /* Unmount ... close the block driver */ + + if (fs->fs_blkdriver) + { + struct inode *inode = fs->fs_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 (fs->fs_buffer) + { + free(fs->fs_buffer); + } + free(fs); + } + + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_statfs + * + * Description: Return filesystem statistics + * + ****************************************************************************/ + +static int fat_statfs(struct inode *mountpt, struct statfs *buf) +{ + struct fat_mountpt_s *fs; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt && mountpt->i_private); + + /* Get the mountpoint private data from the inode structure */ + + fs = mountpt->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Fill in the statfs info */ + + memset(buf, 0, sizeof(struct statfs)); + buf->f_type = MSDOS_SUPER_MAGIC; + + /* We will claim that the optimal transfer size is the size of a cluster in bytes */ + + buf->f_bsize = fs->fs_fatsecperclus * fs->fs_hwsectorsize; + + /* Everything else follows in units of clusters */ + + buf->f_blocks = fs->fs_nclusters; /* Total data blocks in the file system */ + ret = fat_nfreeclusters(fs, &buf->f_bfree); /* Free blocks in the file system */ + buf->f_bavail = buf->f_bfree; /* Free blocks avail to non-superuser */ + buf->f_namelen = (8+1+3); /* Maximum length of filenames */ + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_unlink + * + * Description: Remove a file + * + ****************************************************************************/ + +static int fat_unlink(struct inode *mountpt, const char *relpath) +{ + struct fat_mountpt_s *fs; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt && mountpt->i_private); + + /* Get the mountpoint private data from the inode structure */ + + fs = mountpt->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret == OK) + { + /* If the file is open, the correct behavior is to remove the file + * name, but to keep the file cluster chain in place until the last + * open reference to the file is closed. + */ + +#warning "Need to defer deleting cluster chain if the file is open" + + /* Remove the file */ + + ret = fat_remove(fs, relpath, FALSE); + } + + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_mkdir + * + * Description: Create a directory + * + ****************************************************************************/ + +static int fat_mkdir(struct inode *mountpt, const char *relpath, mode_t mode) +{ + struct fat_mountpt_s *fs; + struct fat_dirinfo_s dirinfo; + ubyte *direntry; + ubyte *direntry2; + size_t parentsector; + ssize_t dirsector; + sint32 dircluster; + uint32 parentcluster; + uint32 crtime; + unsigned int i; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt && mountpt->i_private); + + /* Get the mountpoint private data from the inode structure */ + + fs = mountpt->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Find the directory where the new directory should be created. */ + + ret = fat_finddirentry(fs, &dirinfo, relpath); + + /* If anything exists at this location, then we fail with EEXIST */ + + if (ret == OK) + { + ret = -EEXIST; + goto errout_with_semaphore; + } + + /* What we want to see is for fat_finddirentry to fail with -ENOENT. + * This error means that no failure occurred but that nothing exists + * with this name. + */ + + if (ret != -ENOENT) + { + goto errout_with_semaphore; + } + + /* NOTE: There is no check that dirinfo.fd_name contains the final + * directory name. We could be creating an intermediate directory + * in the full relpath. + */ + + /* Allocate a directory entry for the new directory in this directory */ + + ret = fat_allocatedirentry(fs, &dirinfo); + if (ret != OK) + { + goto errout_with_semaphore; + } + parentsector = fs->fs_currentsector; + + /* Allocate a cluster for new directory */ + + dircluster = fat_createchain(fs); + if (dircluster < 0) + { + ret = dircluster; + goto errout_with_semaphore; + } + else if (dircluster < 2) + { + ret = -ENOSPC; + goto errout_with_semaphore; + } + + dirsector = fat_cluster2sector(fs, dircluster); + if (dirsector < 0) + { + ret = dirsector; + goto errout_with_semaphore; + } + + /* Flush any existing, dirty data in fs_buffer (because we need + * it to create the directory entries. + */ + + ret = fat_fscacheflush(fs); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Get a pointer to the first directory entry in the sector */ + + direntry = fs->fs_buffer; + + /* Now erase the contents of fs_buffer */ + + fs->fs_currentsector = dirsector; + memset(direntry, 0, fs->fs_hwsectorsize); + + /* Now clear all sectors in the new directory cluster (except for the first) */ + + for (i = 1; i < fs->fs_fatsecperclus; i++) + { + ret = fat_hwwrite(fs, direntry, ++dirsector, 1); + if (ret < 0) + { + goto errout_with_semaphore; + } + } + + /* Now create the "." directory entry in the first directory slot */ + + memset(&direntry[DIR_NAME], ' ', 8+3); + direntry[DIR_NAME] = '.'; + DIR_PUTATTRIBUTES(direntry, FATATTR_DIRECTORY); + + crtime = fat_systime2fattime(); + DIR_PUTCRTIME(direntry, crtime & 0xffff); + DIR_PUTWRTTIME(direntry, crtime & 0xffff); + DIR_PUTCRDATE(direntry, crtime >> 16); + DIR_PUTWRTDATE(direntry, crtime >> 16); + + /* Create ".." directory entry in the second directory slot */ + + direntry2 = direntry + 32; + + /* So far, the two entries are nearly the same */ + + memcpy(direntry2, direntry, 32); + direntry2[DIR_NAME+1] = '.'; + + /* Now add the cluster information to both directory entries */ + + DIR_PUTFSTCLUSTHI(direntry, dircluster >> 16); + DIR_PUTFSTCLUSTLO(direntry, dircluster); + + parentcluster = dirinfo.dir.fd_startcluster; + if (fs->fs_type != FSTYPE_FAT32 && parentcluster == fs->fs_rootbase) + { + parentcluster = 0; + } + + DIR_PUTFSTCLUSTHI(direntry2, parentcluster >> 16); + DIR_PUTFSTCLUSTLO(direntry2, parentcluster); + + /* Save the first sector of the directory cluster and re-read + * the parentsector + */ + + fs->fs_dirty = TRUE; + ret = fat_fscacheread(fs, parentsector); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Initialize the new entry directory entry in the parent directory */ + + direntry = dirinfo.fd_entry; + memset(direntry, 0, 32); + + memcpy(direntry, dirinfo.fd_name, 8+3); +#ifdef CONFIG_FLAT_LCNAMES + DIR_PUTNTRES(direntry, dirinfo.fd_ntflags); +#endif + DIR_PUTATTRIBUTES(dirinfo.fd_entry, FATATTR_DIRECTORY); + + /* Same creation time as for . and .. */ + + DIR_PUTCRTIME(dirinfo.fd_entry, crtime & 0xffff); + DIR_PUTWRTTIME(dirinfo.fd_entry, crtime & 0xffff); + DIR_PUTCRDATE(dirinfo.fd_entry, crtime >> 16); + DIR_PUTWRTDATE(dirinfo.fd_entry, crtime >> 16); + + /* Set subdirectory start cluster */ + + DIR_PUTFSTCLUSTLO(dirinfo.fd_entry, dircluster); + DIR_PUTFSTCLUSTHI(dirinfo.fd_entry, dircluster >> 16); + + /* Now update the FAT32 FSINFO sector */ + + fs->fs_dirty = TRUE; + ret = fat_updatefsinfo(fs); + if (ret < 0) + { + goto errout_with_semaphore; + } + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_rmdir + * + * Description: Remove a directory + * + ****************************************************************************/ + +int fat_rmdir(struct inode *mountpt, const char *relpath) +{ + struct fat_mountpt_s *fs; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt && mountpt->i_private); + + /* Get the mountpoint private data from the inode structure */ + + fs = mountpt->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret == OK) + { + /* If the directory is open, the correct behavior is to remove the directory + * name, but to keep the directory cluster chain in place until the last + * open reference to the directory is closed. + */ + +#warning "Need to defer deleting cluster chain if the directory is open" + + /* Remove the directory */ + + ret = fat_remove(fs, relpath, TRUE); + } + + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_rename + * + * Description: Rename a file or directory + * + ****************************************************************************/ + +int fat_rename(struct inode *mountpt, const char *oldrelpath, + const char *newrelpath) +{ + struct fat_mountpt_s *fs; + struct fat_dirinfo_s dirinfo; + size_t oldsector; + ubyte *olddirentry; + ubyte *newdirentry; + ubyte dirstate[32-11]; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt && mountpt->i_private); + + /* Get the mountpoint private data from the inode structure */ + + fs = mountpt->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Find the directory entry for the oldrelpath */ + + ret = fat_finddirentry(fs, &dirinfo, oldrelpath); + if (ret != OK) + { + /* Some error occurred -- probably -ENOENT */ + + goto errout_with_semaphore; + } + + /* Save the information that will need to recover the + * directory sector and directory entry offset to the + * old directory. + */ + + olddirentry = dirinfo.fd_entry; + + /* One more check: Make sure that the oldrelpath does + * not refer to the root directory. We can't rename the + * root directory. + */ + + if (!olddirentry) + { + ret = -EXDEV; + goto errout_with_semaphore; + } + + oldsector = fs->fs_currentsector; + memcpy(dirstate, &olddirentry[DIR_ATTRIBUTES], 32-11); + + /* No find the directory where we should create the newpath object */ + + ret = fat_finddirentry(fs, &dirinfo, newrelpath); + if (ret == OK) + { + /* It is an error if the object at newrelpath already exists */ + + ret = -EEXIST; + goto errout_with_semaphore; + } + + /* What we expect is -ENOENT mean that the full directory path was + * followed but that the object does not exists in the terminal directory. + */ + + if (ret != -ENOENT) + { + goto errout_with_semaphore; + } + + /* Reserve a directory entry */ + + ret = fat_allocatedirentry(fs, &dirinfo); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Create the new directory entry */ + + newdirentry = dirinfo.fd_entry; + + memcpy(&newdirentry[DIR_ATTRIBUTES], dirstate, 32-11); + memcpy(&newdirentry[DIR_NAME], dirinfo.fd_name, 8+3); +#ifdef CONFIG_FLAT_LCNAMES + DIR_PUTNTRES(newdirentry, dirinfo.fd_ntflags); +#else + DIR_PUTNTRES(newdirentry, 0); +#endif + fs->fs_dirty = TRUE; + + /* Now flush the new directory entry to disk and read the sector + * containing the old directory entry. + */ + + ret = fat_fscacheread(fs, oldsector); + if (ret < 0) + { + goto errout_with_semaphore; + } + + /* Remove the old entry */ + + olddirentry[DIR_NAME] = DIR0_EMPTY; + fs->fs_dirty = TRUE; + + /* Write the old entry to disk and update FSINFO if necessary */ + + ret = fat_updatefsinfo(fs); + if (ret < 0) + { + goto errout_with_semaphore; + } + + fat_semgive(fs); + return OK; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Name: fat_stat + * + * Description: Return information about a file or directory + * + ****************************************************************************/ + +static int fat_stat(struct inode *mountpt, const char *relpath, struct stat *buf) +{ + struct fat_mountpt_s *fs; + struct fat_dirinfo_s dirinfo; + uint16 date; + uint16 date2; + uint16 time; + ubyte attribute; + int ret; + + /* Sanity checks */ + + DEBUGASSERT(mountpt && mountpt->i_private); + + /* Get the mountpoint private data from the inode structure */ + + fs = mountpt->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Find the directory entry corresponding to relpath. */ + + ret = fat_finddirentry(fs, &dirinfo, relpath); + + /* If nothing was found, then we fail with EEXIST */ + + if (ret < 0) + { + goto errout_with_semaphore; + } + + memset(buf, 0, sizeof(struct stat)); + if (!dirinfo.fd_entry) + { + /* It's directory name of mount point */ + + buf->st_mode = S_IFDIR|S_IROTH|S_IRGRP|S_IRUSR|S_IWOTH|S_IWGRP|S_IWUSR; + ret = OK; + goto errout_with_semaphore; + } + + /* Get the FAT attribute and map it so some meaningful mode_t values */ + + attribute = DIR_GETATTRIBUTES(dirinfo.fd_entry); + if ((attribute & FATATTR_VOLUMEID) != 0) + { + ret = -ENOENT; + goto errout_with_semaphore; + } + + /* Set the access permissions. The file/directory is always readable + * by everyone but may be writeable by no-one. + */ + + buf->st_mode = S_IROTH|S_IRGRP|S_IRUSR; + if ((attribute & FATATTR_READONLY) == 0) + { + buf->st_mode |= S_IWOTH|S_IWGRP|S_IWUSR; + } + + /* We will report only types file or directory */ + + if ((attribute & FATATTR_DIRECTORY) != 0) + { + buf->st_mode |= S_IFDIR; + } + else + { + buf->st_mode |= S_IFREG; + } + + /* File/directory size, access block size */ + + buf->st_size = DIR_GETFILESIZE(dirinfo.fd_entry); + buf->st_blksize = fs->fs_fatsecperclus * fs->fs_hwsectorsize; + buf->st_blocks = (buf->st_size + buf->st_blksize - 1) / buf->st_blksize; + + /* Times */ + + date = DIR_GETWRTDATE(dirinfo.fd_entry); + time = DIR_GETWRTTIME(dirinfo.fd_entry); + buf->st_mtime = fat_fattime2systime(time, date); + + date2 = DIR_GETLASTACCDATE(dirinfo.fd_entry); + if (date == date2) + { + buf->st_atime = buf->st_mtime; + } + else + { + buf->st_atime = fat_fattime2systime(0, date2); + } + + date = DIR_GETCRDATE(dirinfo.fd_entry); + time = DIR_GETCRTIME(dirinfo.fd_entry); + buf->st_ctime = fat_fattime2systime(time, date); + + ret = OK; + +errout_with_semaphore: + fat_semgive(fs); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + diff --git a/nuttx/fs/fat/fs_fat32.h b/nuttx/fs/fat/fs_fat32.h new file mode 100644 index 000000000..ab48fa796 --- /dev/null +++ b/nuttx/fs/fat/fs_fat32.h @@ -0,0 +1,584 @@ +/**************************************************************************** + * fs_fat32.h + * + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_FAT_H +#define __FS_FAT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * These offsets describes the master boot record. + * + * The folowing fields are common to FAT12/16/32 (but all value descriptions + * refer to the interpretation under FAT32. + */ + +#define BS_JUMP 0 /* 3@0: Jump instruction to boot code (ignored) */ +#define BS_OEMNAME 3 /* 8@3: Usually "MSWIN4.1" */ +#define BS_BYTESPERSEC 11 /* 2@11: Bytes per sector: 512, 1024, 2048, 4096 */ +#define BS_SECPERCLUS 13 /* 1@13: Sectors per allocation unit: 2**n, n=0..7 */ +#define BS_RESVDSECCOUNT 14 /* 2@14: Reserved sector count: Usually 32 */ +#define BS_NUMFATS 16 /* 1@16: Number of FAT data structures: always 2 */ +#define BS_ROOTENTCNT 17 /* 2@17: FAT12/16: Must be 0 for FAT32 */ +#define BS_TOTSEC16 19 /* 2@19: FAT12/16: Must be 0, see BS32_totsec32 */ +#define BS_MEDIA 21 /* 1@21: Media code: f0, f8, f9-fa, fc-ff */ +#define BS_FATSZ16 22 /* 2@22: FAT12/16: Must be 0, see BS32_fatsz32 */ +#define BS_SECPERTRK 24 /* 2@24: Sectors per track geometry value */ +#define BS_NUMHEADS 26 /* 2@26: Number of heads geometry value */ +#define BS_HIDSEC 28 /* 4@28: Count of hidden sectors preceding FAT */ +#define BS_TOTSEC32 32 /* 4@32: Total count of sectors on the volume */ + +/* The following fields are only valid for FAT12/16 */ + +#define BS16_DRVNUM 36 /* 1@36: Drive number for MSDOS bootstrap */ + /* 1@37: Reserved (zero) */ +#define BS16_BOOTSIG 38 /* 1@38: Extended boot signature: 0x29 if following valid */ +#define BS16_VOLID 39 /* 4@39: Volume serial number */ +#define BS16_VOLLAB 43 /* 11@43: Volume label */ +#define BS16_FILESYSTYPE 54 /* 8@54: "FAT12 ", "FAT16 ", or "FAT " */ + +#define BS16_BOOTCODE 62 /* Boot code may be placed in the remainder of the sector */ +#define BS16_BOOTCODESIZE 448 + +/* The following fields are only valid for FAT32 */ + +#define BS32_FATSZ32 36 /* 4@36: Count of sectors occupied by one FAT */ +#define BS32_EXTFLAGS 40 /* 2@40: 0-3:Active FAT, 7=0 both FATS, 7=1 one FAT */ +#define BS32_FSVER 42 /* 2@42: MSB:Major LSB:Minor revision number (0.0) */ +#define BS32_ROOTCLUS 44 /* 4@44: Cluster no. of 1st cluster of root dir */ +#define BS32_FSINFO 48 /* 2@48: Sector number of fsinfo structure. Usually 1. */ +#define BS32_BKBOOTSEC 50 /* 2@50: Sector number of boot record. Usually 6 */ + /* 12@52: Reserved (zero) */ +#define BS32_DRVNUM 64 /* 1@64: Drive number for MSDOS bootstrap */ + /* 1@65: Reserverd (zero) */ +#define BS32_BOOTSIG 66 /* 1@66: Extended boot signature: 0x29 if following valid */ +#define BS32_VOLID 67 /* 4@67: Volume serial number */ +#define BS32_VOLLAB 71 /* 11@71: Volume label */ +#define BS32_FILESYSTYPE 82 /* 8@82: "FAT12 ", "FAT16 ", or "FAT " */ + +#define BS32_BOOTCODE 90 /* Boot code may be placed in the remainder of the sector */ +#define BS32_BOOTCODESIZE 420 + +/* If the sector is not an MBR, then it could have a partition table at + * this offset. + */ + +#define MBR_TABLE 446 + +/* The magic bytes at the end of the MBR are common to FAT12/16/32 */ + +#define BS_SIGNATURE 510 /* 2@510: Valid MBRs have 0x55aa here */ + +/**************************************************************************** + * Each FAT directory entry is 32-bytes long. The following define offsets + * relative to the beginning of a directory entry. + */ + +#define DIR_NAME 0 /* 11@ 0: NAME: 8 bytes + 3 byte extension */ +#define DIR_ATTRIBUTES 11 /* 1@11: File attibutes (see below) */ +#define DIR_NTRES 12 /* 1@12: Reserved for use by NT */ +#define DIR_CRTTIMETENTH 13 /* 1@13: Tenth sec creation timestamp */ +#define DIR_CRTIME 14 /* 2@14: Time file created */ +#define DIR_CRDATE 16 /* 2@16: Date file created */ +#define DIR_LASTACCDATE 18 /* 2@19: Last access date */ +#define DIR_FSTCLUSTHI 20 /* 2@20: MS first cluster number */ +#define DIR_WRTTIME 22 /* 2@22: Time of last write */ +#define DIR_WRTDATE 24 /* 2@24: Date of last write */ +#define DIR_FSTCLUSTLO 26 /* 2@26: LS first cluster number */ +#define DIR_FILESIZE 28 /* 4@28: File size in bytes */ +#define DIR_SIZE 32 + +/* First byte of the directory name has special meanings: */ + +#define DIR0_EMPTY 0xe5 /* The directory entry is empty */ +#define DIR0_ALLEMPTY 0x00 /* This entry and all following are empty */ +#define DIR0_E5 0x05 /* The actual value is 0xe5 */ + +/* NTRES flags in the FAT directory */ + +#define FATNTRES_LCNAME 0x08 /* Lower case in name */ +#define FATNTRES_LCEXT 0x10 /* Lower case in extension */ + +/* Directory indexing helper. Each directory entry is 32-bytes in length. + * The number of directory entries in a sector then varies with the size + * of the sector supported in hardware. + */ + +#define DIRSEC_NDXMASK(f) (((f)->fs_hwsectorsize - 1) >> 5) +#define DIRSEC_NDIRS(f) (((f)->fs_hwsectorsize) >> 5) +#define DIRSEC_BYTENDX(f,i) (((i) & DIRSEC_NDXMASK(fs)) << 5) + +#define SEC_NDXMASK(f) ((f)->fs_hwsectorsize - 1) +#define SEC_NSECTORS(f,n) ((n) / (f)->fs_hwsectorsize) + +/**************************************************************************** + * File system types */ + +#define FSTYPE_FAT12 0 +#define FSTYPE_FAT16 1 +#define FSTYPE_FAT32 2 + +/* File buffer flags */ + +#define FFBUFF_VALID 1 +#define FFBUFF_DIRTY 2 +#define FFBUFF_MODIFIED 4 + +/**************************************************************************** + * These offset describe the FSINFO sector + */ + +#define FSI_LEADSIG 0 /* 4@0: 0x41615252 */ + /* 480@4: Reserved (zero) */ +#define FSI_STRUCTSIG 484 /* 4@484: 0x61417272 */ +#define FSI_FREECOUNT 488 /* 4@488: Last free cluster count on volume */ +#define FSI_NXTFREE 492 /* 4@492: Cluster number of 1st free cluster */ + /* 12@496: Reserved (zero) */ +#define FSI_TRAILSIG 508 /* 4@508: 0xaa550000 */ + +/**************************************************************************** + * Access to data in raw sector data */ + +#define UBYTE_VAL(p,o) (((ubyte*)(p))[o]) +#define UBYTE_PTR(p,o) &UBYTE_VAL(p,o) +#define UBYTE_PUT(p,o,v) (UBYTE_VAL(p,o)=(ubyte)(v)) + +#define UINT16_PTR(p,o) ((uint16*)UBYTE_PTR(p,o)) +#define UINT16_VAL(p,o) (*UINT16_PTR(p,o)) +#define UINT16_PUT(p,o,v) (UINT16_VAL(p,o)=(uint16)(v)) + +#define UINT32_PTR(p,o) ((uint32*)UBYTE_PTR(p,o)) +#define UINT32_VAL(p,o) (*UINT32_PTR(p,o)) +#define UINT32_PUT(p,o,v) (UINT32_VAL(p,o)=(uint32)(v)) + +/* Regardless of the endian-ness of the target or alignment of the data, no + * special operations are required for byte, string or byte array accesses. + * The FAT data stream is little endian so multiple byte values must be + * accessed byte-by-byte for big-endian targets. + */ + +#define MBR_GETSECPERCLUS(p) UBYTE_VAL(p,BS_SECPERCLUS) +#define MBR_GETNUMFATS(p) UBYTE_VAL(p,BS_NUMFATS) +#define MBR_GETMEDIA(p) UBYTE_VAL(p,BS_MEDIA) +#define MBR_GETDRVNUM16(p) UBYTE_VAL(p,BS16_DRVNUM) +#define MBR_GETDRVNUM32(p) UBYTE_VAL(p,BS32_DRVNUM) +#define MBR_GETBOOTSIG16(p) UBYTE_VAL(p,BS16_BOOTSIG) +#define MBR_GETBOOTSIG32(p) UBYTE_VAL(p,BS32_BOOTSIG) + +#define DIR_GETATTRIBUTES(p) UBYTE_VAL(p,DIR_ATTRIBUTES) +#define DIR_GETNTRES(p) UBYTE_VAL(p,DIR_NTRES) +#define DIR_GETCRTTIMETENTH(p) UBYTE_VAL(p,DIR_CRTTIMETENTH) + +#define MBR_PUTSECPERCLUS(p,v) UBYTE_PUT(p,BS_SECPERCLUS),v) +#define MBR_PUTNUMFATS(p,v) UBYTE_PUT(p,BS_NUMFATS,v) +#define MBR_PUTMEDIA(p,v) UBYTE_PUT(p,BS_MEDIA,v) +#define MBR_PUTDRVNUM16(p,v) UBYTE_PUT(p,BS16_DRVNUM,v) +#define MBR_PUTDRVNUM32(p,v) UBYTE_PUT(p,BS32_DRVNUM,v) +#define MBR_PUTBOOTSIG16(p,v) UBYTE_PUT(p,BS16_BOOTSIG,v) +#define MBR_PUTBOOTSIG32(p,v) UBYTE_PUT(p,BS32_BOOTSIG,v) + +#define DIR_PUTATTRIBUTES(p,v) UBYTE_PUT(p,DIR_ATTRIBUTES,v) +#define DIR_PUTNTRES(p,v) UBYTE_PUT(p,DIR_NTRES,v) +#define DIR_PUTCRTTIMETENTH(p,v) UBYTE_PUT(p,DIR_CRTTIMETENTH,v) + +/* For the all targets, unaligned values need to be accessed byte-by-byte. + * Some architectures may handle unaligned accesses with special interrupt + * handlers. But even in that case, it is more efficient to avoid the traps. + */ + +/* Unaligned multi-byte access macros */ + +#define MBR_GETBYTESPERSEC(p) fat_getuint16(UBYTE_PTR(p,BS_BYTESPERSEC)) +#define MBR_GETROOTENTCNT(p) fat_getuint16(UBYTE_PTR(p,BS_ROOTENTCNT)) +#define MBR_GETTOTSEC16(p) fat_getuint16(UBYTE_PTR(p,BS_TOTSEC16)) +#define MBR_GETVOLID16(p) fat_getuint32(UBYTE_PTR(p,BS16_VOLID)) +#define MBR_GETVOLID32(p) fat_getuint32(UBYTE_PTR(p,BS32_VOLID)) + +#define MBR_PUTBYTESPERSEC(p,v) fat_putuint16(UBYTE_PTR(p,BS_BYTESPERSEC),v) +#define MBR_PUTROOTENTCNT(p,v) fat_putuint16(UBYTE_PTR(p,BS_ROOTENTCNT),v) +#define MBR_PUTTOTSEC16(p,v) fat_putuint16(UBYTE_PTR(p,BS_TOTSEC16),v) +#define MBR_PUTVOLID16(p,v) fat_putuint32(UBYTE_PTR(p,BS16_VOLID),v) +#define MBR_PUTVOLID32(p,v) fat_putuint32(UBYTE_PTR(p,BS32_VOLID),v) + +/* But for multi-byte values, the endian-ness of the target vs. the little + * endian order of the byte stream or alignment of the data within the byte + * stream can force special, byte-by-byte accesses. + */ + +#ifdef CONFIG_ENDIAN_BIG + +/* If the target is big-endian, then even aligned multi-byte values must be + * accessed byte-by-byte. + */ + +# define MBR_GETRESVDSECCOUNT(p) fat_getuint16(UBYTE_PTR(p,BS_RESVDSECCOUNT)) +# define MBR_GETFATSZ16(p) fat_getuint16(UBYTE_PTR(p,BS_FATSZ16)) +# define MBR_GETSECPERTRK(p) fat_getuint16(UBYTE_PTR(p,BS_SECPERTRK)) +# define MBR_GETNUMHEADS(p) fat_getuint16(UBYTE_PTR(p,BS_NUMHEADS)) +# define MBR_GETHIDSEC(p) fat_getuint32(UBYTE_PTR(p,BS_HIDSEC)) +# define MBR_GETTOTSEC32(p) fat_getuint32(UBYTE_PTR(p,BS_TOTSEC32)) +# define MBR_GETFATSZ32(p) fat_getuint32(UBYTE_PTR(p,BS32_FATSZ32)) +# define MBR_GETEXTFLAGS(p) fat_getuint16(UBYTE_PTR(p,BS32_EXTFLAGS)) +# define MBR_GETFSVER(p) fat_getuint16(UBYTE_PTR(p,BS32_FSVER)) +# define MBR_GETROOTCLUS(p) fat_getuint32(UBYTE_PTR(p,BS32_ROOTCLUS)) +# define MBR_GETFSINFO(p) fat_getuint16(UBYTE_PTR(p,BS32_FSINFO)) +# define MBR_GETBKBOOTSEC(p) fat_getuint16(UBYTE_PTR(p,BS32_BKBOOTSEC)) +# define MBR_GETSIGNATURE(p) fat_getuint16(UBYTE_PTR(p,BS_SIGNATURE)) + +# define MBR_GETPARTSECTOR(s) fat_getuint32(s) + +# define FSI_GETLEADSIG(p) fat_getuint32(UBYTE_PTR(p,FSI_LEADSIG)) +# define FSI_GETSTRUCTSIG(p) fat_getuint32(UBYTE_PTR(p,FSI_STRUCTSIG)) +# define FSI_GETFREECOUNT(p) fat_getuint32(UBYTE_PTR(p,FSI_FREECOUNT)) +# define FSI_GETNXTFREE(p) fat_getuint32(UBYTE_PTR(p,FSI_NXTFREE)) +# define FSI_GETTRAILSIG(p) fat_getuint32(UBYTE_PTR(p,FSI_TRAILSIG)) + +# define DIR_GETCRTIME(p) fat_getuint16(UBYTE_PTR(p,DIR_CRTIME)) +# define DIR_GETCRDATE(p) fat_getuint16(UBYTE_PTR(p,DIR_CRDATE)) +# define DIR_GETLASTACCDATE(p) fat_getuint16(UBYTE_PTR(p,DIR_LASTACCDATE)) +# define DIR_GETFSTCLUSTHI(p) fat_getuint16(UBYTE_PTR(p,DIR_FSTCLUSTHI)) +# define DIR_GETWRTTIME(p) fat_getuint16(UBYTE_PTR(p,DIR_WRTTIME)) +# define DIR_GETWRTDATE(p) fat_getuint16(UBYTE_PTR(p,DIR_WRTDATE)) +# define DIR_GETFSTCLUSTLO(p) fat_getuint16(UBYTE_PTR(p,DIR_FSTCLUSTLO)) +# define DIR_GETFILESIZE(p) fat_getuint32(UBYTE_PTR(p,DIR_FILESIZE)) + +# define FSI_GETLEADSIG(p) fat_getuint32(UBYTE_PTR(p,FSI_LEADSIG)) +# define FSI_GETSTRUCTSIG(p) fat_getuint32(UBYTE_PTR(p,FSI_STRUCTSIG)) +# define FSI_GETFREECOUNT(p) fat_getuint32(UBYTE_PTR(p,FSI_FREECOUNT)) +# define FSI_GETNXTFREE(p) fat_getuint32(UBYTE_PTR(p,FSI_NXTFREE)) +# define FSI_GETTRAILSIG(p) fat_getuint32(UBYTE_PTR(p,FSI_TRAILSIG)) + +# define FAT_GETFAT16(p,i) fat_getuint16(UBYTE_PTR(p,i)) +# define FAT_GETFAT32(p,i) fat_getuint32(UBYTE_PTR(p,i)) + +# define MBR_PUTRESVDSECCOUNT(p,v) fat_putuint16(UBYTE_PTR(p,BS_RESVDSECCOUNT,v)) +# define MBR_PUTFATSZ16(p,v) fat_putuint16(UBYTE_PTR(p,BS_FATSZ16,v)) +# define MBR_PUTSECPERTRK(p,v) fat_putuint16(UBYTE_PTR(p,BS_SECPERTRK,v)) +# define MBR_PUTNUMHEADS(p,v) fat_putuint16(UBYTE_PTR(p,BS_NUMHEADS,v)) +# define MBR_PUTHIDSEC(p,v) fat_putuint32(UBYTE_PTR(p,BS_HIDSEC,v)) +# define MBR_PUTTOTSEC32(p,v) fat_putuint32(UBYTE_PTR(p,BS_TOTSEC32,v)) +# define MBR_PUTFATSZ32(p,v) fat_putuint32(UBYTE_PTR(p,BS32_FATSZ32,v)) +# define MBR_PUTEXTFLAGS(p,v) fat_putuint16(UBYTE_PTR(p,BS32_EXTFLAGS,v)) +# define MBR_PUTFSVER(p,v) fat_putuint16(UBYTE_PTR(p,BS32_FSVER,v)) +# define MBR_PUTROOTCLUS(p,v) fat_putuint32(UBYTE_PTR(p,BS32_ROOTCLUS,v)) +# define MBR_PUTFSINFO(p,v) fat_putuint16(UBYTE_PTR(p,BS32_FSINFO,v)) +# define MBR_PUTBKBOOTSEC(p,v) fat_putuint16(UBYTE_PTR(p,BS32_BKBOOTSEC,v)) +# define MBR_PUTSIGNATURE(p,v) fat_getuint16(UBYTE_PTR(p,BS_SIGNATURE),v) + +# define FSI_PUTLEADSIG(p,v) fat_putuint32(UBYTE_PTR(p,FSI_LEADSIG),v) +# define FSI_PUTSTRUCTSIG(p,v) fat_putuint32(UBYTE_PTR(p,FSI_STRUCTSIG),v) +# define FSI_PUTFREECOUNT(p,v) fat_putuint32(UBYTE_PTR(p,FSI_FREECOUNT),v) +# define FSI_PUTNXTFREE(p,v) fat_putuint32(UBYTE_PTR(p,FSI_NXTFREE),v) +# define FSI_PUTTRAILSIG(p,v) fat_putuint32(UBYTE_PTR(p,FSI_TRAILSIG),v) + +# define DIR_PUTCRTIME(p,v) fat_putuint16(UBYTE_PTR(p,DIR_CRTIME),v) +# define DIR_PUTCRDATE(p,v) fat_putuint16(UBYTE_PTR(p,DIR_CRDATE),v) +# define DIR_PUTLASTACCDATE(p,v) fat_putuint16(UBYTE_PTR(p,DIR_LASTACCDATE),v) +# define DIR_PUTFSTCLUSTHI(p,v) fat_putuint16(UBYTE_PTR(p,DIR_FSTCLUSTHI),v) +# define DIR_PUTWRTTIME(p,v) fat_putuint16(UBYTE_PTR(p,DIR_WRTTIME),v) +# define DIR_PUTWRTDATE(p,v) fat_putuint16(UBYTE_PTR(p,DIR_WRTDATE),v) +# define DIR_PUTFSTCLUSTLO(p,v) fat_putuint16(UBYTE_PTR(p,DIR_FSTCLUSTLO),v) +# define DIR_PUTFILESIZE(p,v) fat_putuint32(UBYTE_PTR(p,DIR_FILESIZE),v) + +# define FSI_PUTLEADSIG(p,v) fat_putuint32(UBYTE_PTR(p,FSI_LEADSIG),v) +# define FSI_PUTSTRUCTSIG(p,v) fat_putuint32(UBYTE_PTR(p,FSI_STRUCTSIG),v) +# define FSI_PUTFREECOUNT(p,v) fat_putuint32(UBYTE_PTR(p,FSI_FREECOUNT),v) +# define FSI_PUTNXTFREE(p,v) fat_putuint32(UBYTE_PTR(p,FSI_NXTFREE),v) +# define FSI_PUTTRAILSIG(p,v) fat_putuint32(UBYTE_PTR(p,FSI_TRAILSIG),v) + +# define FAT_PUTFAT16(p,i,v) fat_putuint16(UBYTE_PTR(p,i),v) +# define FAT_PUTFAT32(p,i,v) fat_putuint32(UBYTE_PTR(p,i),v) + +#else + +/* But nothing special has to be done for the little endian-case for access + * to aligned mulitbyte values. + */ + +# define MBR_GETRESVDSECCOUNT(p) UINT16_VAL(p,BS_RESVDSECCOUNT) +# define MBR_GETFATSZ16(p) UINT16_VAL(p,BS_FATSZ16) +# define MBR_GETSECPERTRK(p) UINT16_VAL(p,BS_SECPERTRK) +# define MBR_GETNUMHEADS(p) UINT16_VAL(p,BS_NUMHEADS) +# define MBR_GETHIDSEC(p) UINT32_VAL(p,BS_HIDSEC) +# define MBR_GETTOTSEC32(p) UINT32_VAL(p,BS_TOTSEC32) +# define MBR_GETFATSZ32(p) UINT32_VAL(p,BS32_FATSZ32) +# define MBR_GETEXTFLAGS(p) UINT16_VAL(p,BS32_EXTFLAGS) +# define MBR_GETFSVER(p) UINT16_VAL(p,BS32_FSVER) +# define MBR_GETROOTCLUS(p) UINT32_VAL(p,BS32_ROOTCLUS) +# define MBR_GETFSINFO(p) UINT16_VAL(p,BS32_FSINFO) +# define MBR_GETBKBOOTSEC(p) UINT16_VAL(p,BS32_BKBOOTSEC) +# define MBR_GETSIGNATURE(p) UINT16_VAL(p,BS_SIGNATURE) + +# define MBR_GETPARTSECTOR(s) (*((uint32*)(s))) + +# define FSI_GETLEADSIG(p) UINT32_VAL(p,FSI_LEADSIG) +# define FSI_GETSTRUCTSIG(p) UINT32_VAL(p,FSI_STRUCTSIG) +# define FSI_GETFREECOUNT(p) UINT32_VAL(p,FSI_FREECOUNT) +# define FSI_GETNXTFREE(p) UINT32_VAL(p,FSI_NXTFREE) +# define FSI_GETTRAILSIG(p) UINT32_VAL(p,FSI_TRAILSIG) + +# define DIR_GETCRTIME(p) UINT16_VAL(p,DIR_CRTIME) +# define DIR_GETCRDATE(p) UINT16_VAL(p,DIR_CRDATE) +# define DIR_GETLASTACCDATE(p) UINT16_VAL(p,DIR_LASTACCDATE) +# define DIR_GETFSTCLUSTHI(p) UINT16_VAL(p,DIR_FSTCLUSTHI) +# define DIR_GETWRTTIME(p) UINT16_VAL(p,DIR_WRTTIME) +# define DIR_GETWRTDATE(p) UINT16_VAL(p,DIR_WRTDATE) +# define DIR_GETFSTCLUSTLO(p) UINT16_VAL(p,DIR_FSTCLUSTLO) +# define DIR_GETFILESIZE(p) UINT32_VAL(p,DIR_FILESIZE) + +# define FSI_GETLEADSIG(p) UINT32_VAL(p,FSI_LEADSIG) +# define FSI_GETSTRUCTSIG(p) UINT32_VAL(p,FSI_STRUCTSIG) +# define FSI_GETFREECOUNT(p) UINT32_VAL(p,FSI_FREECOUNT) +# define FSI_GETNXTFREE(p) UINT32_VAL(p,FSI_NXTFREE) +# define FSI_GETTRAILSIG(p) UINT32_VAL(p,FSI_TRAILSIG) + +# define FAT_GETFAT16(p,i) UINT16_VAL(p,i) +# define FAT_GETFAT32(p,i) UINT32_VAL(p,i) + +# define MBR_PUTRESVDSECCOUNT(p,v) UINT16_PUT(p,BS_RESVDSECCOUNT,v) +# define MBR_PUTFATSZ16(p,v) UINT16_PUT(p,BS_FATSZ16,v) +# define MBR_PUTSECPERTRK(p,v) UINT16_PUT(p,BS_SECPERTRK,v) +# define MBR_PUTNUMHEADS(p,v) UINT16_PUT(p,BS_NUMHEADS,v) +# define MBR_PUTHIDSEC(p,v) UINT32_PUT(p,BS_HIDSEC,v) +# define MBR_PUTTOTSEC32(p,v) UINT32_PUT(p,BS_TOTSEC32,v) +# define MBR_PUTFATSZ32(p,v) UINT32_PUT(p,BS32_FATSZ32,v) +# define MBR_PUTEXTFLAGS(p,v) UINT16_PUT(p,BS32_EXTFLAGS,v) +# define MBR_PUTFSVER(p,v) UINT16_PUT(p,BS32_FSVER,v) +# define MBR_PUTROOTCLUS(p,v) UINT32_PUT(p,BS32_ROOTCLUS,v) +# define MBR_PUTFSINFO(p,v) UINT16_PUT(p,BS32_FSINFO,v) +# define MBR_PUTBKBOOTSEC(p,v) UINT16_PUT(p,BS32_BKBOOTSEC,v) +# define MBR_PUTSIGNATURE(p,v) UINT16_PUT(p,BS_SIGNATURE,v) + +# define FSI_PUTLEADSIG(p,v) UINT32_PUT(p,FSI_LEADSIG,v) +# define FSI_PUTSTRUCTSIG(p,v) UINT32_PUT(p,FSI_STRUCTSIG,v) +# define FSI_PUTFREECOUNT(p,v) UINT32_PUT(p,FSI_FREECOUNT,v) +# define FSI_PUTNXTFREE(p,v) UINT32_PUT(p,FSI_NXTFREE,v) +# define FSI_PUTTRAILSIG(p,v) UINT32_PUT(p,FSI_TRAILSIG,v) + +# define DIR_PUTCRTIME(p,v) UINT16_PUT(p,DIR_CRTIME,v) +# define DIR_PUTCRDATE(p,v) UINT16_PUT(p,DIR_CRDATE,v) +# define DIR_PUTLASTACCDATE(p,v) UINT16_PUT(p,DIR_LASTACCDATE,v) +# define DIR_PUTFSTCLUSTHI(p,v) UINT16_PUT(p,DIR_FSTCLUSTHI,v) +# define DIR_PUTWRTTIME(p,v) UINT16_PUT(p,DIR_WRTTIME,v) +# define DIR_PUTWRTDATE(p,v) UINT16_PUT(p,DIR_WRTDATE,v) +# define DIR_PUTFSTCLUSTLO(p,v) UINT16_PUT(p,DIR_FSTCLUSTLO,v) +# define DIR_PUTFILESIZE(p,v) UINT32_PUT(p,DIR_FILESIZE,v) + +# define FSI_PUTLEADSIG(p,v) UINT32_PUT(p,FSI_LEADSIG,v) +# define FSI_PUTSTRUCTSIG(p,v) UINT32_PUT(p,FSI_STRUCTSIG,v) +# define FSI_PUTFREECOUNT(p,v) UINT32_PUT(p,FSI_FREECOUNT,v) +# define FSI_PUTNXTFREE(p,v) UINT32_PUT(p,FSI_NXTFREE,v) +# define FSI_PUTTRAILSIG(p,v) UINT32_PUT(p,FSI_TRAILSIG,v) + +# define FAT_PUTFAT16(p,i,v) UINT16_PUT(p,i,v) +# define FAT_PUTFAT32(p,i,v) UINT32_PUT(p,i,v) + +#endif + +/**************************************************************************** + * 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 fat_file_s; +struct fat_mountpt_s +{ + struct inode *fs_blkdriver; /* The block driver inode that hosts the FAT32 fs */ + struct fat_file_s *fs_head; /* A list to all files opened on this mountpoint */ + + sem_t fs_sem; /* Used to assume thread-safe access */ + size_t fs_hwsectorsize; /* HW: Sector size reported by block driver*/ + size_t fs_hwnsectors; /* HW: The number of sectors reported by the hardware */ + size_t fs_fatbase; /* Logical block of start of filesystem (past resd sectors) */ + size_t fs_rootbase; /* MBR: Cluster no. of 1st cluster of root dir */ + size_t fs_database; /* Logical block of start data sectors */ + size_t fs_fsinfo; /* MBR: Sector number of FSINFO sector */ + size_t fs_currentsector; /* The sector number buffered in fs_buffer */ + uint32 fs_nclusters; /* Maximum number of data clusters */ + uint32 fs_fatsize; /* MBR: Count of sectors occupied by one fat */ + uint32 fs_fattotsec; /* MBR: Total count of sectors on the volume */ + uint32 fs_fsifreecount; /* FSI: Last free cluster count on volume */ + uint32 fs_fsinextfree; /* FSI: Cluster number of 1st free cluster */ + uint16 fs_fatresvdseccount; /* MBR: The total number of reserved sectors */ + uint16 fs_rootentcnt; /* MBR: Count of 32-bit root directory entries */ + boolean fs_mounted; /* TRUE: The file system is ready */ + boolean fs_dirty; /* TRUE: fs_buffer is dirty */ + boolean fs_fsidirty; /* TRUE: FSINFO sector must be written to disk */ + ubyte fs_type; /* FSTYPE_FAT12, FSTYPE_FAT16, or FSTYPE_FAT32 */ + ubyte fs_fatnumfats; /* MBR: Number of FATs (probably 2) */ + ubyte fs_fatsecperclus; /* MBR: Sectors per allocation unit: 2**n, n=0..7 */ + ubyte *fs_buffer; /* This is an allocated buffer to hold one sector + * from the device */ +}; + +/* 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 fat_file_s +{ + struct fat_file_s *ff_next; /* Retained in a singly linked list */ + boolean ff_open; /* TRUE: The file is (still) open */ + ubyte ff_bflags; /* The file buffer flags */ + ubyte ff_oflags; /* Flags provided when file was opened */ + ubyte ff_sectorsincluster; /* Sectors remaining in cluster */ + uint16 ff_dirindex; /* Index into ff_dirsector to directory entry */ + uint32 ff_currentcluster; /* Current cluster being accessed */ + size_t ff_dirsector; /* Sector containing the directory entry */ + size_t ff_position; /* File position for read/write/seek in bytes */ + size_t ff_size; /* Size of the file in bytes */ + size_t ff_startcluster; /* Start cluster of file on media */ + size_t ff_currentsector; /* Current sector in the file buffer */ + ubyte *ff_buffer; /* File buffer (for partial sector accesses) */ +}; + +/* This structure is used internally for describing directory entries */ + +struct fat_dirinfo_s +{ + ubyte fd_name[8+3]; /* Filename -- directory format*/ +#ifdef CONFIG_FAT_LCNAMES + ubyte fd_ntflags; /* NTRes lower case flags */ +#endif + struct fs_fatdir_s dir; /* Used with opendir, readdir, etc. */ + ubyte *fd_entry; /* A pointer to the raw 32-byte entry */ +}; + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Pulblic Function Prototypes + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/* Utitilies to handle unaligned or byte swapped accesses */ + +EXTERN uint16 fat_getuint16(ubyte *ptr); +EXTERN uint32 fat_getuint32(ubyte *ptr); +EXTERN void fat_putuint16(ubyte *ptr, uint16 value16); +EXTERN void fat_putuint32(ubyte *ptr, uint32 value32); + +/* Manage the per-mount semaphore that protects access to shared resources */ + +EXTERN void fat_semtake(struct fat_mountpt_s *fs); +EXTERN void fat_semgive(struct fat_mountpt_s *fs); + +/* Get the current time for FAT creation and write times */ + +EXTERN uint32 fat_systime2fattime(void); +EXTERN time_t fat_fattime2systime(uint16 time, uint16 date); + +/* Handle hardware interactions for mounting */ + +EXTERN int fat_mount(struct fat_mountpt_s *fs, boolean writeable); +EXTERN int fat_checkmount(struct fat_mountpt_s *fs); + +/* low-level hardware access */ + +EXTERN int fat_hwread(struct fat_mountpt_s *fs, ubyte *buffer, + size_t sector, unsigned int nsectors); +EXTERN int fat_hwwrite(struct fat_mountpt_s *fs, ubyte *buffer, + size_t sector, unsigned int nsectors); + +/* Cluster / cluster chain access helpers */ + +EXTERN ssize_t fat_cluster2sector(struct fat_mountpt_s *fs, uint32 cluster ); +EXTERN ssize_t fat_getcluster(struct fat_mountpt_s *fs, uint32 clusterno); +EXTERN int fat_putcluster(struct fat_mountpt_s *fs, uint32 clusterno, + size_t startsector); +EXTERN int fat_removechain(struct fat_mountpt_s *fs, uint32 cluster); +EXTERN sint32 fat_extendchain(struct fat_mountpt_s *fs, uint32 cluster); + +#define fat_createchain(fs) fat_extendchain(fs, 0) + +/* Help for traversing directory trees */ + +EXTERN int fat_nextdirentry(struct fat_mountpt_s *fs, struct fs_fatdir_s *dir); +EXTERN int fat_finddirentry(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo, + const char *path); +EXTERN int fat_allocatedirentry(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo); + +EXTERN int fat_dirname2path(char *path, ubyte *direntry); + +/* File creation and removal helpers */ + +EXTERN int fat_dirtruncate(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo); +EXTERN int fat_dircreate(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo); +EXTERN int fat_remove(struct fat_mountpt_s *fs, const char *relpath, boolean directory); + +/* Mountpoint and file buffer cache (for partial sector accesses) */ + +EXTERN int fat_fscacheflush(struct fat_mountpt_s *fs); +EXTERN int fat_fscacheread(struct fat_mountpt_s *fs, size_t sector); +EXTERN int fat_ffcacheflush(struct fat_mountpt_s *fs, struct fat_file_s *ff); +EXTERN int fat_ffcacheread(struct fat_mountpt_s *fs, struct fat_file_s *ff, size_t sector); +EXTERN int fat_ffcacheinvalidate(struct fat_mountpt_s *fs, struct fat_file_s *ff); + +/* FSINFO sector support */ + +EXTERN int fat_updatefsinfo(struct fat_mountpt_s *fs); +EXTERN int fat_nfreeclusters(struct fat_mountpt_s *fs, size_t *pfreeclusters); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __FS_FAT32_H */ diff --git a/nuttx/fs/fat/fs_fat32attrib.c b/nuttx/fs/fat/fs_fat32attrib.c new file mode 100644 index 000000000..7537fbf98 --- /dev/null +++ b/nuttx/fs/fat/fs_fat32attrib.c @@ -0,0 +1,190 @@ +/************************************************************ + * fs_fat32attrib.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 Gregory Nutt 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. + * + ************************************************************/ + +/************************************************************ + * Compilation Switches + ************************************************************/ + +/************************************************************ + * Included Files + ************************************************************/ + +#include +#include +#include + +#include +#include + +#include "fs_internal.h" +#include "fs_fat32.h" + +/************************************************************ + * Private Functions + ************************************************************/ + +/************************************************************ + * Name: fat_attrib + ************************************************************/ + +static int fat_attrib(const char *path, fat_attrib_t *retattrib, + fat_attrib_t setbits, fat_attrib_t clearbits) +{ + struct fat_mountpt_s *fs; + struct fat_dirinfo_s dirinfo; + FAR struct inode *inode; + const char *relpath = NULL; + ubyte oldattributes; + ubyte newattributes; + int ret; + + /* Get an inode for this file */ + + inode = inode_find(path, &relpath); + if (!inode) + { + /* There is no mountpoint that includes in this path */ + + ret = ENOENT; + goto errout; + } + + /* Verify that the inode is a valid mountpoint. */ + + if (!INODE_IS_MOUNTPT(inode) || !inode->u.i_mops || !inode->i_private) + { + ret = ENXIO; + goto errout_with_inode; + } + + /* Get the mountpoint private data from the inode structure */ + + fs = inode->i_private; + + /* Check if the mount is still healthy */ + + fat_semtake(fs); + ret = fat_checkmount(fs); + if (ret != OK) + { + goto errout_with_semaphore; + } + + /* Find the file/directory entry for the oldrelpath */ + + ret = fat_finddirentry(fs, &dirinfo, relpath); + if (ret != OK) + { + /* Some error occurred -- probably -ENOENT */ + + goto errout_with_semaphore; + } + + /* Make sure that we found some valid file or directory */ + + if (!dirinfo.fd_entry) + { + /* Ooops.. we found the root directory */ + + ret = EACCES; + goto errout_with_semaphore; + } + + /* Get the current attributes */ + + oldattributes = DIR_GETATTRIBUTES(dirinfo.fd_entry); + newattributes = oldattributes; + + /* Set or clear any bits as requested */ + + newattributes &= ~(clearbits & (FATATTR_READONLY|FATATTR_HIDDEN|FATATTR_SYSTEM|FATATTR_ARCHIVE)); + newattributes |= (setbits & (FATATTR_READONLY|FATATTR_HIDDEN|FATATTR_SYSTEM|FATATTR_ARCHIVE)); + + /* Did any thingchange? */ + + if (newattributes != oldattributes) + { + DIR_PUTATTRIBUTES(dirinfo.fd_entry, newattributes); + fs->fs_dirty = TRUE; + ret = fat_updatefsinfo(fs); + if (ret != OK) + { + ret = -ret; + goto errout_with_semaphore; + } + } + + /* Success */ + + if (retattrib) + { + *retattrib = newattributes; + } + + fat_semgive(fs); + inode_release(inode); + return OK; + +errout_with_semaphore: + fat_semgive(fs); +errout_with_inode: + inode_release(inode); +errout: + *get_errno_ptr() = ret; + return ERROR; +} + +/************************************************************ + * Global Functions + ************************************************************/ + +/************************************************************ + * Name: fat_getattrib + ************************************************************/ + +int fat_getattrib(const char *path, fat_attrib_t *attrib) +{ + return fat_attrib(path, attrib, 0, 0); +} + +/************************************************************ + * Name: fat_setattrib + ************************************************************/ + +int fat_setattrib(const char *path, fat_attrib_t setbits, fat_attrib_t clearbits) +{ + return fat_attrib(path, NULL, setbits, clearbits); +} + diff --git a/nuttx/fs/fat/fs_fat32util.c b/nuttx/fs/fat/fs_fat32util.c new file mode 100644 index 000000000..48d1a6e19 --- /dev/null +++ b/nuttx/fs/fat/fs_fat32util.c @@ -0,0 +1,2445 @@ +/**************************************************************************** + * fs_fat32util.c + * + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * Microsoft FAT documentation + * Some good ideas were leveraged from the FAT implementation: + * 'Copyright (C) 2007, ChaN, all right reserved.' + * which has an unrestricted license. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "fs_internal.h" +#include "fs_fat32.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fat_path2dirname + * + * Desciption: Convert a user filename into a properly formatted FAT + * (short) filname as it would appear in a directory entry. Here are the + * rules for the 11 byte name in the directory: + * + * The first byte: + * - 0xe5 = The directory is free + * - 0x00 = This directory and all following directories are free + * - 0x05 = Really 0xe5 + * - 0x20 = May NOT be ' ' + * + * Any bytes + * 0x00-0x1f = (except for 0x00 and 0x05 in the first byte) + * 0x22 = '"' + * 0x2a-0x2c = '*', '+', ',' + * 0x2e-0x2f = '.', '/' + * 0x3a-0x3f = ':', ';', '<', '=', '>', '?' + * 0x5b-0x5d = '[', '\\', ;]' + * 0x7c = '|' + * + * Upper case characters are not allowed in directory names (without some + * poorly documented operatgions on the NTRes directory byte). Lower case + * codes may represent different characters in other character sets ("DOS + * code pages". The logic below does not, at present, support any other + * character sets. + * + ****************************************************************************/ + +static inline int fat_path2dirname(const char **path, struct fat_dirinfo_s *dirinfo, + char *terminator) +{ +#ifdef CONFIG_FAT_LCNAMES + unsigned int ntlcenable = FATNTRES_LCNAME | FATNTRES_LCEXT; + unsigned int ntlcfound = 0; +#endif + const char *node = *path; + int endndx; + ubyte ch; + int ndx = 0; + + /* Initialized the name with all spaces */ + + memset(dirinfo->fd_name, ' ', 8+3); + + /* Loop until the name is successfully parsed or an error occurs */ + + endndx = 8; + for (;;) + { + /* Get the next byte from the path */ + + ch = *node++; + + /* Check if this the last byte in this node of the name */ + + if ((ch == '\0' || ch == '/') && ndx != 0 ) + { + /* Return the accumulated NT flags and the terminating character */ +#ifdef CONFIG_FAT_LCNAMES + dirinfo->fd_ntflags = ntlcfound & ntlcenable; +#endif + *terminator = ch; + *path = node; + return OK; + } + + /* Accept only the printable character set. Note the first byte + * of the name could be 0x05 meaning that is it 0xe5, but this is + * not a printable character in this character in either case. + */ + + else if (!isgraph(ch)) + { + goto errout; + } + + /* Check for transition from name to extension */ + + else if (ch == '.') + { + /* Starting the extension */ + + ndx = 8; + endndx = 11; + continue; + } + + /* Reject printable characters forbidden by FAT */ + + else if (ch == '"' || (ch >= '*' && ch <= ',') || + ch == '.' || ch == '/' || + (ch >= ':' && ch <= '?') || + (ch >= '[' && ch <= ']') || + (ch == '|')) + { + goto errout; + } + + /* Check for upper case charaters */ + +#ifdef CONFIG_FAT_LCNAMES + else if (isupper(ch)) + { + /* Some or all of the characters in the name or extension + * are upper case. Force all of the characters to be interpreted + * as upper case. + */ + + if ( endndx == 8) + { + /* Clear lower case name bit in mask*/ + ntlcenable &= FATNTRES_LCNAME; + } + else + { + /* Clear lower case extension in mask */ + ntlcenable &= FATNTRES_LCNAME; + } + } +#endif + + /* Check for lower case characters */ + + else if (islower(ch)) + { + /* Convert the character to upper case */ + + ch = toupper(ch); + + /* Some or all of the characters in the name or extension + * are lower case. They can be interpreted as lower case if + * only if all of the characters in the name or extension are + * lower case. + */ + +#ifdef CONFIG_FAT_LCNAMES + if ( endndx == 8) + { + /* Set lower case name bit */ + ntlcfound |= FATNTRES_LCNAME; + } + else + { + /* Set lower case extension bit */ + ntlcfound |= FATNTRES_LCNAME; + } +#endif + } + + /* Check if the file name exceeds the size permitted (without + * long file name support + */ + + if (ndx >= endndx) + { + goto errout; + } + + /* Save next character in the accumulated name */ + + dirinfo->fd_name[ndx++] = ch; + } + + errout: + return -EINVAL; +} + +/**************************************************************************** + * Name: fat_checkfsinfo + * + * Desciption: Read the FAT32 FSINFO sector + * + ****************************************************************************/ + +static int fat_checkfsinfo(struct fat_mountpt_s *fs) +{ + /* Verify that this is, indeed, an FSINFO sector */ + + if (FSI_GETLEADSIG(fs->fs_buffer) == 0x41615252 && + FSI_GETSTRUCTSIG(fs->fs_buffer) == 0x61417272 && + FSI_GETTRAILSIG(fs->fs_buffer) == 0xaa550000) + { + fs->fs_fsinextfree = FSI_GETFREECOUNT(fs->fs_buffer); + fs->fs_fsifreecount = FSI_GETNXTFREE(fs->fs_buffer); + return OK; + } + return -ENODEV; +} + +/**************************************************************************** + * Name: fat_checkbootrecord + * + * Desciption: Read a sector and verify that it is a a FAT boot record. + * + ****************************************************************************/ + +static int fat_checkbootrecord(struct fat_mountpt_s *fs) +{ + uint32 ndatasectors; + uint32 fatsize; + uint16 rootdirsectors = 0; + boolean notfat32 = FALSE; + + /* Verify the MBR signature at offset 510 in the sector (true even + * if the sector size is greater than 512. All FAT file systems have + * this signature. On a FAT32 volume, the RootEntCount , FatSz16, and + * FatSz32 values should always be zero. The FAT sector size should + * match the reported hardware sector size. + */ + + if (MBR_GETSIGNATURE(fs->fs_buffer) != 0xaa55 || + MBR_GETBYTESPERSEC(fs->fs_buffer) != fs->fs_hwsectorsize) + { + return -ENODEV; + } + + /* Verify the FAT32 file system type. The determination of the file + * system type is based on the number of clusters on the volume: FAT12 + * volume has < 4085 cluseter, a FAT16 volume has fewer than 65,525 + * clusters, and any larger is FAT32. + * + * Get the number of 32-bit directory entries in root directory (zero + * for FAT32. + */ + + fs->fs_rootentcnt = MBR_GETROOTENTCNT(fs->fs_buffer); + if (fs->fs_rootentcnt != 0) + { + notfat32 = TRUE; /* Must be zero for FAT32 */ + rootdirsectors = (32 * fs->fs_rootentcnt + fs->fs_hwsectorsize - 1) / fs->fs_hwsectorsize; + } + + /* Determine the number of sectors in a FAT. */ + + fs->fs_fatsize = MBR_GETFATSZ16(fs->fs_buffer); /* Should be zero */ + if (fs->fs_fatsize) + { + notfat32 = TRUE; /* Must be zero for FAT32 */ + } + else + { + fs->fs_fatsize = MBR_GETFATSZ32(fs->fs_buffer); + } + + if (!fs->fs_fatsize || fs->fs_fatsize >= fs->fs_hwnsectors) + { + return -ENODEV; + } + + /* Get the total number of sectors on the volume. */ + + fs->fs_fattotsec = MBR_GETTOTSEC16(fs->fs_buffer); /* Should be zero */ + if (fs->fs_fattotsec) + { + notfat32 = TRUE; /* Must be zero for FAT32 */ + } + else + { + fs->fs_fattotsec = MBR_GETTOTSEC32(fs->fs_buffer); + } + + if (!fs->fs_fattotsec || fs->fs_fattotsec > fs->fs_hwnsectors) + { + return -ENODEV; + } + + /* Get the total number of reserved sectors */ + + fs->fs_fatresvdseccount = MBR_GETRESVDSECCOUNT(fs->fs_buffer); + if (fs->fs_fatresvdseccount > fs->fs_hwnsectors) + { + return -ENODEV; + } + + /* Get the number of FATs. This is probably two but could have other values */ + + fs->fs_fatnumfats = MBR_GETNUMFATS(fs->fs_buffer); + fatsize = fs->fs_fatnumfats * fs->fs_fatsize; + + /* Get the total number of data sectors */ + + ndatasectors = fs->fs_fattotsec - fs->fs_fatresvdseccount - fatsize - rootdirsectors; + if (ndatasectors > fs->fs_hwnsectors) + { + return -ENODEV; + } + + /* Get the sectors per cluster */ + + fs->fs_fatsecperclus = MBR_GETSECPERCLUS(fs->fs_buffer); + + /* Calculate the number of clusters */ + + fs->fs_nclusters = ndatasectors / fs->fs_fatsecperclus; + + /* Finally, the test: */ + + if (fs->fs_nclusters < 4085) + { + fs->fs_fsinfo = 0; + fs->fs_type = FSTYPE_FAT12; + } + else if (fs->fs_nclusters < 65525) + { + fs->fs_fsinfo = 0; + fs->fs_type = FSTYPE_FAT16; + } + else if (!notfat32) + { + fs->fs_fsinfo = fs->fs_fatbase + MBR_GETFSINFO(fs->fs_buffer); + fs->fs_type = FSTYPE_FAT32; + } + else + { + return -ENODEV; + } + + /* We have what appears to be a valid FAT filesystem! Save a few more things + * from the boot record that we will need later. + */ + + fs->fs_fatbase += fs->fs_fatresvdseccount; + + if (fs->fs_type == FSTYPE_FAT32) + { + fs->fs_rootbase = MBR_GETROOTCLUS(fs->fs_buffer); + } + else + { + fs->fs_rootbase = fs->fs_fatbase + fatsize; + } + + fs->fs_database = fs->fs_fatbase + fatsize + fs->fs_rootentcnt / DIRSEC_NDIRS(fs); + fs->fs_fsifreecount = 0xffffffff; + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fat_getuint16 + ****************************************************************************/ + +uint16 fat_getuint16(ubyte *ptr) +{ +#ifdef CONFIG_ENDIAN_BIG + /* The bytes always have to be swapped if the target is big-endian */ + + return ((uint16)ptr[0] << 8) | ptr[1]; +#else + /* Byte-by-byte transfer is still necessary if the address is un-aligned */ + + return ((uint16)ptr[1] << 8) | ptr[0]; +#endif +} + +/**************************************************************************** + * Name: fat_getuint32 + ****************************************************************************/ + +uint32 fat_getuint32(ubyte *ptr) +{ +#ifdef CONFIG_ENDIAN_BIG + /* The bytes always have to be swapped if the target is big-endian */ + + return ((uint32)fat_getuint16(&ptr[0]) << 16) | fat_getuint16(&ptr[2]); +#else + /* Byte-by-byte transfer is still necessary if the address is un-aligned */ + + return ((uint32)fat_getuint16(&ptr[2]) << 16) | fat_getuint16(&ptr[0]); +#endif +} + +/**************************************************************************** + * Name: fat_putuint16 + ****************************************************************************/ + +void fat_putuint16(ubyte *ptr, uint16 value16) +{ + ubyte *val = (ubyte*)&value16; +#ifdef CONFIG_ENDIAN_BIG + /* The bytes always have to be swapped if the target is big-endian */ + + ptr[0] = val[1]; + ptr[1] = val[0]; +#else + /* Byte-by-byte transfer is still necessary if the address is un-aligned */ + + ptr[0] = val[0]; + ptr[1] = val[1]; +#endif +} + +/**************************************************************************** + * Name: fat_putuint32 + ****************************************************************************/ + +void fat_putuint32(ubyte *ptr, uint32 value32) +{ + uint16 *val = (uint16*)&value32; +#ifdef CONFIG_ENDIAN_BIG + /* The bytes always have to be swapped if the target is big-endian */ + + fat_putuint16(&ptr[0], val[2]); + fat_putuint16(&ptr[2], val[0]); +#else + /* Byte-by-byte transfer is still necessary if the address is un-aligned */ + + fat_putuint16(&ptr[0], val[0]); + fat_putuint16(&ptr[2], val[2]); +#endif +} + +/**************************************************************************** + * Name: fat_semtake + ****************************************************************************/ + +void fat_semtake(struct fat_mountpt_s *fs) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&fs->fs_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: fat_semgive + ****************************************************************************/ + +void fat_semgive(struct fat_mountpt_s *fs) +{ + sem_post(&fs->fs_sem); +} + +/**************************************************************************** + * Name: fat_systime2fattime + * + * Desciption: Get the system time convertto a time and and date suitble + * for writing into the FAT FS. + * + * TIME in LS 16-bits: + * Bits 0:4 = 2 second count (0-29 representing 0-58 seconds) + * Bits 5-10 = minutes (0-59) + * Bits 11-15 = hours (0-23) + * DATE in MS 16-bits + * Bits 0:4 = Day of month (0-31) + * Bits 5:8 = Month of year (1-12) + * Bits 9:15 = Year from 1980 (0-127 representing 1980-2107) + * + ****************************************************************************/ + +uint32 fat_systime2fattime(void) +{ +#warning "Time not implemented" + return 0; +} + +/**************************************************************************** + * Name: fat_fattime2systime + * + * Desciption: Convert FAT data and time to a system time_t + * + * 16-bit FAT time: + * Bits 0:4 = 2 second count (0-29 representing 0-58 seconds) + * Bits 5-10 = minutes (0-59) + * Bits 11-15 = hours (0-23) + * 16-bit FAT date: + * Bits 0:4 = Day of month (0-31) + * Bits 5:8 = Month of year (1-12) + * Bits 9:15 = Year from 1980 (0-127 representing 1980-2107) + * + ****************************************************************************/ + +time_t fat_fattime2systime(uint16 fattime, uint16 fatdate) +{ +#warning "Time not implemented" + return 0; +} + +/**************************************************************************** + * Name: fat_mount + * + * Desciption: This function is called only when the mountpoint is first + * established. It initializes the mountpoint structure and verifies + * that a valid FAT32 filesystem is provided by the block driver. + * + * The caller should hold the mountpoint semaphore + * + ****************************************************************************/ + +int fat_mount(struct fat_mountpt_s *fs, boolean writeable) +{ + FAR struct inode *inode; + struct geometry geo; + int ret; + + /* Assume that the mount is successful */ + + fs->fs_mounted = TRUE; + + /* Check if there is media available */ + + inode = fs->fs_blkdriver; + if (!inode || !inode->u.i_bops || !inode->u.i_bops->geometry || + inode->u.i_bops->geometry(inode, &geo) != OK || !geo.geo_available) + { + ret = -ENODEV; + goto errout; + } + + /* Make sure that that the media is write-able (if write access is needed) */ + + if (writeable && !geo.geo_writeenabled) + { + ret = -EACCES; + goto errout; + } + + /* Save the hardware geometry */ + + fs->fs_hwsectorsize = geo.geo_sectorsize; + fs->fs_hwnsectors = geo.geo_nsectors; + + /* Allocate a buffer to hold one hardware sector */ + + fs->fs_buffer = (ubyte*)malloc(fs->fs_hwsectorsize); + if (!fs->fs_buffer) + { + ret = -ENOMEM; + goto errout; + } + + /* Search FAT boot record on the drive. First check at sector zero. This + * could be either the boot record or a partition that refers to the boot + * record. + * + * First read sector zero. This will be the first access to the drive and a + * likely failure point. + */ + + fs->fs_fatbase = 0; + ret = fat_hwread(fs, fs->fs_buffer, 0, 1); + if (ret < 0) + { + goto errout_with_buffer; + } + + if (fat_checkbootrecord(fs) != OK) + { + /* The contents of sector 0 is not a boot record. It could be a + * partition, however. Assume it is a partition and get the offset + * into the partition table. This table is at offset MBR_TABLE and is + * indexed by 16x the partition number. Here we support only + * parition 0. + */ + + ubyte *partition = &fs->fs_buffer[MBR_TABLE + 0]; + + /* Check if the partition exists and, if so, get the bootsector for that + * partition and see if we can find the boot record there. + */ + + if (partition[4]) + { + /* There appears to be a partition, get the sector number of the + * partition (LBA) + */ + + fs->fs_fatbase = MBR_GETPARTSECTOR(&partition[8]); + + /* Read the new candidate boot sector */ + + ret = fat_hwread(fs, fs->fs_buffer, fs->fs_fatbase, 1); + if (ret < 0) + { + goto errout_with_buffer; + } + + /* Check if this is a boot record */ + + if (fat_checkbootrecord(fs) != OK) + { + goto errout_with_buffer; + } + } + } + + /* We have what appears to be a valid FAT filesystem! Now read the + * FSINFO sector (FAT32 only) + */ + + if (fs->fs_type == FSTYPE_FAT32) + { + ret = fat_checkfsinfo(fs); + if (ret != OK) + { + goto errout_with_buffer; + } + } + + /* We did it! */ + + fdbg("FAT%d:\n", fs->fs_type == 0 ? 12 : fs->fs_type == 1 ? 16 : 32); + fdbg("\tHW sector size: %d\n", fs->fs_hwsectorsize); + fdbg("\t sectors: %d\n", fs->fs_hwnsectors); + fdbg("\tFAT reserved: %d\n", fs->fs_fatresvdseccount); + fdbg("\t sectors: %d\n", fs->fs_fattotsec); + fdbg("\t start sector: %d\n", fs->fs_fatbase); + fdbg("\t root sector: %d\n", fs->fs_rootbase); + fdbg("\t root entries: %d\n", fs->fs_rootentcnt); + fdbg("\t data sector: %d\n", fs->fs_database); + fdbg("\t FSINFO sector: %d\n", fs->fs_fsinfo); + fdbg("\t Num FATs: %d\n", fs->fs_fatnumfats); + fdbg("\t FAT size: %d\n", fs->fs_fatsize); + fdbg("\t sectors/cluster: %d\n", fs->fs_fatsecperclus); + fdbg("\t max clusters: %d\n", fs->fs_nclusters); + fdbg("\tFSI free count %d\n", fs->fs_fsifreecount); + fdbg("\t next free %d\n", fs->fs_fsinextfree); + + return OK; + + errout_with_buffer: + free(fs->fs_buffer); + fs->fs_buffer = 0; + errout: + fs->fs_mounted = FALSE; + return ret; +} + +/**************************************************************************** + * Name: fat_checkmount + * + * Desciption: Check if the mountpoint is still valid. + * + * The caller should hold the mountpoint semaphore + * + ****************************************************************************/ + +int fat_checkmount(struct fat_mountpt_s *fs) +{ + /* If the fs_mounted flag is FALSE, then we have already handled the loss + * of the mount. + */ + + if (fs && fs->fs_mounted) + { + struct fat_file_s *file; + + /* We still think the mount is healthy. Check an see if this is + * still the case + */ + + if (fs->fs_blkdriver) + { + struct inode *inode = fs->fs_blkdriver; + if (inode && inode->u.i_bops && inode->u.i_bops->geometry) + { + struct geometry geo; + int errcode = inode->u.i_bops->geometry(inode, &geo); + if (errcode == OK && geo.geo_available && !geo.geo_mediachanged) + { + return OK; + } + } + } + + /* If we get here, the mount is NOT healthy */ + + fs->fs_mounted = FALSE; + + /* Make sure that this is flagged in every opened file */ + + for (file = fs->fs_head; file; file = file->ff_next) + { + file->ff_open = FALSE; + } + } + return -ENODEV; +} + +/**************************************************************************** + * Name: fat_hwread + * + * Desciption: Read the specified sector into the sector buffer + * + ****************************************************************************/ + +int fat_hwread(struct fat_mountpt_s *fs, ubyte *buffer, size_t sector, + unsigned int nsectors) +{ + int ret = -ENODEV; + if (fs && fs->fs_blkdriver ) + { + struct inode *inode = fs->fs_blkdriver; + if (inode && inode->u.i_bops && inode->u.i_bops->read) + { + ssize_t nSectorsRead = inode->u.i_bops->read(inode, buffer, + sector, nsectors); + if (nSectorsRead == nsectors) + { + ret = OK; + } + else if (nSectorsRead < 0) + { + ret = nSectorsRead; + } + } + } + return ret; +} + +/**************************************************************************** + * Name: fat_hwwrite + * + * Desciption: Write the sector buffer to the specified sector + * + ****************************************************************************/ + +int fat_hwwrite(struct fat_mountpt_s *fs, ubyte *buffer, size_t sector, + unsigned int nsectors) +{ + int ret = -ENODEV; + if (fs && fs->fs_blkdriver ) + { + struct inode *inode = fs->fs_blkdriver; + if (inode && inode->u.i_bops && inode->u.i_bops->write) + { + ssize_t nSectorsWritten = + inode->u.i_bops->write(inode, buffer, sector, nsectors); + + if (nSectorsWritten == nsectors) + { + ret = OK; + } + else if (nSectorsWritten < 0) + { + ret = nSectorsWritten; + } + } + } + return ret; +} + +/**************************************************************************** + * Name: fat_cluster2sector + * + * Desciption: Convert a cluster number to a start sector number + * + ****************************************************************************/ + +ssize_t fat_cluster2sector(struct fat_mountpt_s *fs, uint32 cluster ) +{ + cluster -= 2; + if (cluster >= fs->fs_nclusters - 2) + { + return -EINVAL; + } + return cluster * fs->fs_fatsecperclus + fs->fs_database; +} + +/**************************************************************************** + * Name: fat_getcluster + * + * Desciption: Get the cluster start sector into the FAT. + * + * Return: <0: error, 0:cluster unassigned, >=0: start sector of cluster + * + ****************************************************************************/ + +ssize_t fat_getcluster(struct fat_mountpt_s *fs, uint32 clusterno) +{ + /* Verify that the cluster number is within range */ + + if (clusterno >= 2 && clusterno < fs->fs_nclusters) + { + /* Okay.. Read the next cluster from the FAT. The way we will do + * this depends on the type of FAT filesystm we are dealing with. + */ + + switch (fs->fs_type) + { + case FSTYPE_FAT12 : + { + size_t fatsector; + unsigned int fatoffset; + unsigned int startsector; + unsigned int fatindex; + + /* FAT12 is more complex because it has 12-bits (1.5 bytes) + * per FAT entry. Get the offset to the first byte: + */ + + fatoffset = (clusterno * 3) / 2; + fatsector = fs->fs_fatbase + SEC_NSECTORS(fs, fatoffset); + + /* Read the sector at this offset */ + + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + + /* Get the first, LS byte of the cluster from the FAT */ + + fatindex = fatoffset & SEC_NDXMASK(fs); + startsector = fs->fs_buffer[fatindex]; + + /* With FAT12, the second byte of the cluster number may lie in + * a different sector than the first byte. + */ + + fatindex++; + if (fatindex >= fs->fs_hwsectorsize) + { + fatsector++; + fatindex = 0; + + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + } + + /* Get the second, MS byte of the cluster for 16-bits. The + * does not depend on the endian-ness of the target, but only + * on the fact that the byte stream is little-endian. + */ + + startsector |= (unsigned int)fs->fs_buffer[fatindex] << 8; + + /* Now, pick out the correct 12 bit cluster start sector value */ + + if ((clusterno & 1) != 0) + { + /* Odd.. take the MS 12-bits */ + startsector >>= 4; + } + else + { + /* Even.. take the LS 12-bits */ + startsector &= 0x0fff; + } + return startsector; + } + + case FSTYPE_FAT16 : + { + unsigned int fatoffset = 2 * clusterno; + size_t fatsector = fs->fs_fatbase + SEC_NSECTORS(fs, fatoffset); + unsigned int fatindex = fatoffset & SEC_NDXMASK(fs); + + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + return FAT_GETFAT16(fs->fs_buffer, fatindex); + } + + case FSTYPE_FAT32 : + { + unsigned int fatoffset = 4 * clusterno; + size_t fatsector = fs->fs_fatbase + SEC_NSECTORS(fs, fatoffset); + unsigned int fatindex = fatoffset & SEC_NDXMASK(fs); + + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + return FAT_GETFAT16(fs->fs_buffer, fatindex) & 0x0fffffff; + } + default: + break; + } + } + + /* There is no cluster information, or an error occured */ + + return (ssize_t)-EINVAL; +} + +/**************************************************************************** + * Name: fat_putcluster + * + * Desciption: Write a new cluster start sector into the FAT + * + ****************************************************************************/ + +int fat_putcluster(struct fat_mountpt_s *fs, uint32 clusterno, size_t startsector) +{ + /* Verify that the cluster number is within range. Zero erases the cluster. */ + + if (clusterno == 0 || (clusterno >= 2 && clusterno < fs->fs_nclusters)) + { + /* Okay.. Write the next cluster into the FAT. The way we will do + * this depends on the type of FAT filesystm we are dealing with. + */ + + switch (fs->fs_type) + { + case FSTYPE_FAT12 : + { + size_t fatsector; + unsigned int fatoffset; + unsigned int fatindex; + ubyte value; + + /* FAT12 is more complex because it has 12-bits (1.5 bytes) + * per FAT entry. Get the offset to the first byte: + */ + + fatoffset = (clusterno * 3) / 2; + fatsector = fs->fs_fatbase + SEC_NSECTORS(fs, fatoffset); + + /* Make sure that the sector at this offset is in the cache */ + + if (fat_fscacheread(fs, fatsector)< 0) + { + /* Read error */ + break; + } + + /* Output the LS byte first handling the 12-bit alignment within + * the 16-bits + */ + + fatindex = fatoffset & SEC_NDXMASK(fs); + if ((clusterno & 1) != 0) + { + value = (fs->fs_buffer[fatindex] & 0x0f) | startsector << 4; + } + else + { + value = (ubyte)startsector; + } + fs->fs_buffer[fatindex] = value; + + /* With FAT12, the second byte of the cluster number may lie in + * a different sector than the first byte. + */ + + fatindex++; + if (fatindex >= fs->fs_hwsectorsize) + { + /* Read the next sector */ + + fatsector++; + fatindex = 0; + + /* Set the dirty flag to make sure the sector that we + * just modified is written out. + */ + + fs->fs_dirty = TRUE; + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + } + + /* Output the MS byte first handling the 12-bit alignment within + * the 16-bits + */ + + if ((clusterno & 1) != 0) + { + value = (ubyte)(startsector >> 4); + } + else + { + value = (fs->fs_buffer[fatindex] & 0xf0) | (startsector & 0x0f); + } + fs->fs_buffer[fatindex] = value; + } + break; + + case FSTYPE_FAT16 : + { + unsigned int fatoffset = 2 * clusterno; + size_t fatsector = fs->fs_fatbase + SEC_NSECTORS(fs, fatoffset); + unsigned int fatindex = fatoffset & SEC_NDXMASK(fs); + + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + FAT_PUTFAT16(fs->fs_buffer, fatindex, startsector & 0xffff); + } + break; + + case FSTYPE_FAT32 : + { + unsigned int fatoffset = 4 * clusterno; + size_t fatsector = fs->fs_fatbase + SEC_NSECTORS(fs, fatoffset); + unsigned int fatindex = fatoffset & SEC_NDXMASK(fs); + + if (fat_fscacheread(fs, fatsector) < 0) + { + /* Read error */ + break; + } + FAT_PUTFAT32(fs->fs_buffer, fatindex, startsector & 0x0fffffff); + } + break; + + default: + return -EINVAL; + } + + /* Mark the modified sector as "dirty" and return success */ + + fs->fs_dirty = 1; + return OK; + } + + return -EINVAL; +} + +/**************************************************************************** + * Name: fat_removechain + * + * Desciption: Remove an entire chain of clusters, starting with 'cluster' + * + ****************************************************************************/ + +int fat_removechain(struct fat_mountpt_s *fs, uint32 cluster) +{ + sint32 nextcluster; + int ret; + + /* Loop while there are clusters in the chain */ + + while (cluster >= 2 && cluster < fs->fs_nclusters) + { + /* Get the next cluster after the current one */ + + nextcluster = fat_getcluster(fs, cluster); + if (nextcluster < 0) + { + /* Error! */ + return nextcluster; + } + + /* Then nullify current cluster -- removing it from the chain */ + + ret = fat_putcluster(fs, cluster, 0); + if (ret < 0) + { + return ret; + } + + /* Update FSINFINFO data */ + + if (fs->fs_fsifreecount != 0xffffffff) + { + fs->fs_fsifreecount++; + fs->fs_fsidirty = 1; + } + + /* Then set up to remove the next cluster */ + + cluster = nextcluster; + } + + return OK; +} + +/**************************************************************************** + * Name: fat_extendchain + * + * Desciption: Add a new cluster to the chain following cluster (if cluster + * is non-NULL). if cluster is zero, then a new chain is created. + * + * Return: <0:error, 0: no free cluster, >=2: new cluster number + * + ****************************************************************************/ + +sint32 fat_extendchain(struct fat_mountpt_s *fs, uint32 cluster) +{ + ssize_t startsector; + uint32 newcluster; + uint32 startcluster; + int ret; + + /* The special value 0 is used when the new chain should start */ + + if (cluster == 0) + { + /* The FSINFO NextFree entry should be a good starting point + * in the search for a new cluster + */ + + startcluster = fs->fs_fsinextfree; + if (startcluster == 0 || startcluster >= fs->fs_nclusters) + { + /* But it is bad.. we have to start at the beginning */ + startcluster = 1; + } + } + else + { + /* We are extending an existing chain. Verify that this + * is a valid cluster by examining its start sector. + */ + + startsector = fat_getcluster(fs, cluster); + if (startsector < 0) + { + /* An error occurred, return the error value */ + return startsector; + } + else if (startsector < 2) + { + /* Oops.. this cluster does not exist. */ + return 0; + } + else if (startsector < fs->fs_nclusters) + { + /* It is already followed by next cluster */ + return startsector; + } + + /* Okay.. it checks out */ + + startcluster = cluster; + } + + /* Loop until (1) we discover that there are not free clusters + * (return 0), an errors occurs (return -errno), or (3) we find + * the next cluster (return the new cluster number). + */ + + newcluster = startcluster; + for (;;) + { + /* Examine the next cluster in the FAT */ + + newcluster++; + if (newcluster >= fs->fs_nclusters) + { + /* If we hit the end of the available clusters, then + * wrap back to the beginning because we might have + * started at a non-optimal place. But don't continue + * past the start cluster. + */ + + newcluster = 2; + if (newcluster > startcluster) + { + /* We are back past the starting cluster, then there + * is no free cluster. + */ + + return 0; + } + } + + /* We have a candidate cluster. Check if the cluster number is + * mapped to a group of sectors. + */ + + startsector = fat_getcluster(fs, newcluster); + if (startsector == 0) + { + /* Found have found a free cluster break out*/ + break; + } + else if (startsector < 0) + { + /* Some error occurred, return the error number */ + return startsector; + } + + /* We wrap all the back to the starting cluster? If so, then + * there are no free clusters. + */ + + if (newcluster == startcluster) + { + return 0; + } + } + + /* We get here only if we break out with an available cluster + * number in 'newcluster' Now mark that cluster as in-use. + */ + + ret = fat_putcluster(fs, newcluster, 0x0fffffff); + if (ret < 0) + { + /* An error occurred */ + return ret; + } + + /* And link if to the start cluster (if any)*/ + + if (cluster) + { + /* There is a start cluster -- link it */ + + ret = fat_putcluster(fs, cluster, newcluster); + if (ret < 0) + { + return ret; + } + } + + /* And update the FINSINFO for the next time we have to search */ + + fs->fs_fsinextfree = newcluster; + if (fs->fs_fsifreecount != 0xffffffff) + { + fs->fs_fsifreecount--; + fs->fs_fsidirty = 1; + } + + /* Return then number of the new cluster that was added to the chain */ + + return newcluster; +} + +/**************************************************************************** + * Name: fat_nextdirentry + * + * Desciption: Read the next directory entry from the sector in cache, + * reading the next sector(s) in the cluster as necessary. + * + ****************************************************************************/ + +int fat_nextdirentry(struct fat_mountpt_s *fs, struct fs_fatdir_s *dir) +{ + unsigned int cluster; + unsigned int ndx; + + /* Increment the index to the next 32-byte directory entry */ + + ndx = dir->fd_index + 1; + + /* Check if all of the directory entries in this sectory have + * been examined. + */ + + if ((ndx & (DIRSEC_NDIRS(fs)-1)) == 0) + { + /* Yes, then we will have to read the next sector */ + + dir->fd_currsector++; + + /* For FAT12/16, the root directory is a group of sectors relative + * to the first sector of the fat volume. + */ + + if (!dir->fd_currcluster) + { + /* For FAT12/16, the boot record tells us number of 32-bit directories + * that are contained in the root directory. This should correspond to + * an even number of sectors. + */ + + if (ndx >= fs->fs_rootentcnt) + { + /* When we index past this count, we have examined all of the entries in + * the root directory. + */ + + return ERROR; + } + } + else + { + /* Not a FAT12/16 root directory, check if we have examined the entire + * cluster comprising the directory. + * + * The current sector within the cluster is the entry number divided + * byte the number of entries per sector + */ + + int sector = ndx / DIRSEC_NDIRS(fs); + + /* We are finished with the cluster when the last sector of the cluster + * has been examined. + */ + + if ((sector & (fs->fs_fatsecperclus-1)) == 0) + { + /* Get next cluster */ + + cluster = fat_getcluster(fs, dir->fd_currcluster); + + /* Check if a valid cluster was obtained. */ + + if (cluster < 2 || cluster >= fs->fs_nclusters) + { + /* No, we have probably reached the end of the cluster list */ + return ERROR; + } + + /* Initialize for new cluster */ + + dir->fd_currcluster = cluster; + dir->fd_currsector = fat_cluster2sector(fs, cluster); + } + } + } + + /* Save the new index into dir->fd_currsector */ + + dir->fd_index = ndx; + return OK; +} + +/**************************************************************************** + * Name: fat_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 fat_finddirentry(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo, + const char *path) +{ + size_t cluster; + ubyte *direntry = NULL; + char terminator; + int ret; + + /* Initialize to traverse the chain. Set it to the cluster of + * the root directory + */ + + cluster = fs->fs_rootbase; + if (fs->fs_type == FSTYPE_FAT32) + { + /* For FAT32, the root directory is variable sized and is a + * cluster chain like any other directory. fs_rootbase holds + * the first cluster of the root directory. + */ + + dirinfo->dir.fd_startcluster = cluster; + dirinfo->dir.fd_currcluster = cluster; + dirinfo->dir.fd_currsector = fat_cluster2sector(fs, cluster); + } + else + { + /* For FAT12/16, the first sector of the root directory is a sector + * relative to the first sector of the fat volume. + */ + + dirinfo->dir.fd_startcluster = 0; + dirinfo->dir.fd_currcluster = 0; + dirinfo->dir.fd_currsector = cluster; + } + + /* fd_index is the index into the current directory table */ + + dirinfo->dir.fd_index = 0; + + /* If no path was provided, then the root directory must be exactly + * what the caller is looking for. + */ + + if (*path == '\0') + { + dirinfo->fd_entry = NULL; + return OK; + } + + /* Otherwise, loop until the path is found */ + + for (;;) + { + /* Convert the next the path segment name into the kind of + * name that we would see in the directory entry. + */ + + ret = fat_path2dirname(&path, dirinfo, &terminator); + if (ret < 0) + { + /* ERROR: The filename contains invalid characters or is + * too long. + */ + + return ret; + } + + /* Now search the current directory entry for an entry with this + * matching name. + */ + + for (;;) + { + /* Read the next sector into memory */ + + ret = fat_fscacheread(fs, dirinfo->dir.fd_currsector); + if (ret < 0) + { + return ret; + } + + /* Get a pointer to the directory entry */ + + direntry = &fs->fs_buffer[DIRSEC_BYTENDX(fs, dirinfo->dir.fd_index)]; + + /* Check if we are at the end of the directory */ + + if (direntry[DIR_NAME] == DIR0_ALLEMPTY) + { + return -ENOENT; + } + + /* Check if we have found the directory entry that we are looking for */ + + if (direntry[DIR_NAME] != DIR0_EMPTY && + !(DIR_GETATTRIBUTES(direntry) & FATATTR_VOLUMEID) && + !memcmp(&direntry[DIR_NAME], dirinfo->fd_name, 8+3) ) + { + /* Yes.. break out of the loop */ + break; + } + + /* No... get the next directory index and try again */ + + if (fat_nextdirentry(fs, &dirinfo->dir) != OK) + { + return -ENOENT; + } + } + + /* We get here only if we have found a directory entry that matches + * the path element that we are looking for. + * + * If the terminator character in the path was the end of the string + * then we have successfully found the directory entry that describes + * the path. + */ + + if (!terminator) + { + /* Return the pointer to the matching directory entry */ + dirinfo->fd_entry = direntry; + return OK; + } + + /* No.. then we have found one of the intermediate directories on + * the way to the final path target. In this case, make sure + * the thing that we found is, indeed, a directory. + */ + + if (!(DIR_GETATTRIBUTES(direntry) & FATATTR_DIRECTORY)) + { + /* Ooops.. we found something else */ + return -ENOTDIR; + } + + /* Get the cluster number of this directory */ + + cluster = + ((uint32)DIR_GETFSTCLUSTHI(direntry) << 16) | + DIR_GETFSTCLUSTLO(direntry); + + /* The restart scanning at the new directory */ + + dirinfo->dir.fd_currcluster = dirinfo->dir.fd_startcluster = cluster; + dirinfo->dir.fd_currsector = fat_cluster2sector(fs, cluster); + dirinfo->dir.fd_index = 2; + } +} + +/**************************************************************************** + * Name: fat_allocatedirentry + * + * Desciption: Find a free directory entry + * + ****************************************************************************/ + +int fat_allocatedirentry(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo) +{ + sint32 cluster; + size_t sector; + ubyte *direntry; + ubyte ch; + int ret; + int i; + + /* Re-initialize directory object */ + + cluster = dirinfo->dir.fd_startcluster; + if (cluster) + { + /* Cluster chain can be extended */ + + dirinfo->dir.fd_currcluster = cluster; + dirinfo->dir.fd_currsector = fat_cluster2sector(fs, cluster); + } + else + { + /* Fixed size FAT12/16 root directory is at fixxed offset/size */ + + dirinfo->dir.fd_currsector = fs->fs_rootbase; + } + dirinfo->dir.fd_index = 0; + + for (;;) + { + unsigned int dirindex; + + /* Read the directory sector into fs_buffer */ + + ret = fat_fscacheread(fs, dirinfo->dir.fd_currsector); + if (ret < 0) + { + return ret; + } + + /* Get a pointer to the entry at fd_index */ + + dirindex = (dirinfo->dir.fd_index & DIRSEC_NDXMASK(fs)) * 32; + direntry = &fs->fs_buffer[dirindex]; + + /* Check if this directory entry is empty */ + + ch = direntry[DIR_NAME]; + if (ch == DIR0_ALLEMPTY || ch == DIR0_EMPTY) + { + /* It is empty -- we have found a directory entry */ + + dirinfo->fd_entry = direntry; + return OK; + } + + ret = fat_nextdirentry(fs, &dirinfo->dir); + if (ret < 0) + { + return ret; + } + } + + /* If we get here, then we have reached the end of the directory table + * in this sector without finding a free directory enty. + * + * It this is a fixed size dirctory entry, then this is an error. + * Otherwise, we can try to extend the directory cluster chain to + * make space for the new directory entry. + */ + + if (!cluster) + { + /* The size is fixed */ + return -ENOSPC; + } + + /* Try to extend the cluster chain for this directory */ + + cluster = fat_extendchain(fs, dirinfo->dir.fd_currcluster); + if (cluster < 0) + { + return cluster; + } + + /* Flush out any cached date in fs_buffer.. we are going to use + * it to initialize the new directory cluster. + */ + + ret = fat_fscacheflush(fs); + if (ret < 0) + { + return ret; + } + + /* Clear all sectors comprising the new directory cluster */ + + fs->fs_currentsector = fat_cluster2sector(fs, cluster); + memset(fs->fs_buffer, 0, fs->fs_hwsectorsize); + + sector = sector; + for (i = fs->fs_fatsecperclus; i; i--) + { + ret = fat_hwwrite(fs, fs->fs_buffer, sector, 1); + if ( ret < 0) + { + return ret; + } + sector++; + } + + dirinfo->fd_entry = fs->fs_buffer; + return OK; +} + +/**************************************************************************** + * Name: fat_dirname2path + * + * Desciption: Convert a filename in a raw directory entry into a user + * filename. This is essentially the inverse operation of that performed + * by fat_path2dirname. See that function for more details. + * + ****************************************************************************/ + +int fat_dirname2path(char *path, ubyte *direntry) +{ +#ifdef CONFIG_FAT_LCNAMES + ubyte ntflags; +#endif + int ch; + int ndx; + + /* Check if we will be doing upper to lower case conversions */ + +#ifdef CONFIG_FAT_LCNAMES + ntflags = DIR_GETNTRES(direntry); +#endif + + /* Get the 8-byte filename */ + + for (ndx = 0; ndx < 8; ndx++) + { + /* Get the next filename character from the directory entry */ + + ch = direntry[ndx]; + + /* Any space (or ndx==8) terminates the filename */ + + if (ch == ' ') + { + break; + } + + /* In this version, we never write 0xe5 in the directoryfilenames + * (because we do not handle any character sets where 0xe5 is valid + * in a filaname), but we could encounted this in a filesystem + * written by some other system + */ + + if (ndx == 0 && ch == DIR0_E5) + { + ch = 0xe5; + } + + /* Check if we should perform upper to lower case conversion + * of the (whole) filename. + */ + +#ifdef CONFIG_FAT_LCNAMES + if (ntflags & FATNTRES_LCNAME && isupper(ch)) + { + ch = tolower(ch); + } +#endif + /* Copy the next character into the filename */ + + *path++ = ch; + } + + /* Check if there is an extension */ + + if (direntry[8] != ' ') + { + /* Yes, output the dot before the extension */ + + *path++ = '.'; + + /* Then output the (up to) 3 character extension */ + + for (ndx = 8; ndx < 11; ndx++) + { + /* Get the next extensions character from the directory entry */ + + ch = direntry[DIR_NAME + ndx]; + + /* Any space (or ndx==11) terminates the extension */ + + if (ch == ' ') + { + break; + } + + /* Check if we should perform upper to lower case conversion + * of the (whole) filename. + */ + +#ifdef CONFIG_FAT_LCNAMES + if (ntflags & FATNTRES_LCEXT && isupper(ch)) + { + ch = tolower(ch); + } +#endif + /* Copy the next character into the filename */ + + *path++ = ch; + } + } + + /* Put a null terminator at the end of the filename */ + + *path = '\0'; + return OK; +} + +/**************************************************************************** + * Name: fat_dirtruncate + * + * Desciption: Truncate an existing file to zero length + * + * Assumptions: The caller holds mountpoint semaphore, fs_buffer holds + * the directory entry, dirinfo refers to the current fs_buffer content. + * + ****************************************************************************/ + +int fat_dirtruncate(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo) +{ + unsigned int startcluster; + uint32 writetime; + size_t savesector; + int ret; + + /* Get start cluster of the file to truncate */ + + startcluster = + ((uint32)DIR_GETFSTCLUSTHI(dirinfo->fd_entry) << 16) | + DIR_GETFSTCLUSTLO(dirinfo->fd_entry); + + /* Clear the cluster start value in the directory and set the file size + * to zero. This makes the file look empty but also have to dispose of + * all of the clusters in the chain. + */ + + DIR_PUTFSTCLUSTHI(dirinfo->fd_entry, 0); + DIR_PUTFSTCLUSTLO(dirinfo->fd_entry, 0); + DIR_PUTFILESIZE(dirinfo->fd_entry, 0); + + /* Set the ARCHIVE attribute and update the write time */ + + DIR_PUTATTRIBUTES(dirinfo->fd_entry, FATATTR_ARCHIVE); + + writetime = fat_systime2fattime(); + DIR_PUTWRTTIME(dirinfo->fd_entry, writetime & 0xffff); + DIR_PUTWRTDATE(dirinfo->fd_entry, writetime > 16); + + /* This sector needs to be written back to disk eventually */ + + fs->fs_dirty = TRUE; + + /* Now remove the entire cluster chain comprising the file */ + + savesector = fs->fs_currentsector; + ret = fat_removechain(fs, startcluster); + if (ret < 0) + { + return ret; + } + + /* Setup FSINFO to resuse this cluster next */ + + fs->fs_fsinextfree = startcluster - 1; + + /* Make sure that the directory is still in the cache */ + + return fat_fscacheread(fs, savesector); +} + +/**************************************************************************** + * Name: fat_dircreate + * + * Desciption: Create a directory entry for a new file + * + ****************************************************************************/ + +int fat_dircreate(struct fat_mountpt_s *fs, struct fat_dirinfo_s *dirinfo) +{ + ubyte *direntry; + uint32 time; + int ret; + + /* Set up the directory entry */ + + ret = fat_allocatedirentry(fs, dirinfo); + if (ret != OK) + { + /* Failed to set up directory entry */ + return ret; + } + + /* Initialize the 32-byte directory entry */ + + direntry = dirinfo->fd_entry; + memset(direntry, 0, 32); + + /* Directory name info */ + + memcpy(&direntry[DIR_NAME], dirinfo->fd_name, 8+3); +#ifdef CONFIG_FLAT_LCNAMES + DIR_PUTNTRES(dirinfo->fd_entry, dirinfo->fd_ntflags); +#else + DIR_PUTNTRES(dirinfo->fd_entry, 0); +#endif + + /* ARCHIVE attribute, write time, creation time */ + DIR_PUTATTRIBUTES(dirinfo->fd_entry, FATATTR_ARCHIVE); + + time = fat_systime2fattime(); + DIR_PUTWRTTIME(dirinfo->fd_entry, time & 0xffff); + DIR_PUTCRTIME(dirinfo->fd_entry, time & 0xffff); + DIR_PUTWRTDATE(dirinfo->fd_entry, time >> 16); + DIR_PUTCRDATE(dirinfo->fd_entry, time >> 16); + + fs->fs_dirty = TRUE; + return OK; +} + +/**************************************************************************** + * Name: fat_remove + * + * Desciption: Remove a directory or file from the file system. This + * implements both rmdir() and unlink(). + * + ****************************************************************************/ + +int fat_remove(struct fat_mountpt_s *fs, const char *relpath, boolean directory) +{ + struct fat_dirinfo_s dirinfo; + uint32 dircluster; + size_t dirsector; + int ret; + + /* Find the directory entry referring to the entry to be deleted */ + + ret = fat_finddirentry(fs, &dirinfo, relpath); + if (ret != OK) + { + /* No such path */ + + return -ENOENT; + } + + /* Check if this is a FAT12/16 root directory */ + + if (dirinfo.fd_entry == NULL) + { + /* The root directory cannot be removed */ + + return -EPERM; + } + + /* The object has to have write access to be deleted */ + + if ((DIR_GETATTRIBUTES(dirinfo.fd_entry) & FATATTR_READONLY) != 0) + { + /* It is a read-only entry */ + + return -EACCES; + } + + /* Get the directory sector and cluster containing the + * entry to be deleted + */ + + dirsector = fs->fs_currentsector; + dircluster = + ((uint32)DIR_GETFSTCLUSTHI(dirinfo.fd_entry) << 16) | + DIR_GETFSTCLUSTLO(dirinfo.fd_entry); + + /* Is this entry a directory? */ + + if (DIR_GETATTRIBUTES(dirinfo.fd_entry) & FATATTR_DIRECTORY) + { + /* It is a sub-directory. Check if we are be asked to remove + * a directory or a file. + */ + + if (!directory) + { + /* We are asked to delete a file */ + + return -EISDIR; + } + + /* We are asked to delete a directory. Check if this + * sub-directory is empty + */ + + dirinfo.dir.fd_currcluster = dircluster; + dirinfo.dir.fd_currsector = fat_cluster2sector(fs, dircluster); + dirinfo.dir.fd_index = 2; + + /* Loop until either (1) an entry is found in the directory + * (error), (2) the directory is found to be empty, or (3) some + * error occurs. + */ + + for (;;) + { + unsigned int subdirindex; + ubyte *subdirentry; + + /* Make sure that the sector containing the of the + * subdirectory sector is in the cache + */ + + ret = fat_fscacheread(fs, dirinfo.dir.fd_currsector); + if (ret < 0) + { + return ret; + } + + /* Get a reference to the next entry in the directory */ + + subdirindex = (dirinfo.dir.fd_index & DIRSEC_NDXMASK(fs)) * 32; + subdirentry = &fs->fs_buffer[subdirindex]; + + /* Is this the last entry in the direcory? */ + + if (subdirentry[DIR_NAME] == DIR0_ALLEMPTY) + { + /* Yes then the directory is empty. Break out of the + * loop and delete the directory. + */ + + break; + } + + /* Check if the next entry refers to a file or directory */ + + if (subdirentry[DIR_NAME] != DIR0_EMPTY && + !(DIR_GETATTRIBUTES(subdirentry) & FATATTR_VOLUMEID)) + { + /* The directory is not empty */ + + return -ENOTEMPTY; + } + + /* Get the next directgory entry */ + + ret = fat_nextdirentry(fs, &dirinfo.dir); + if (ret < 0) + { + return ret; + } + } + } + else + { + /* It is a file. Check if we are be asked to remove a directory + * or a file. + */ + + if (directory) + { + /* We are asked to remove a directory */ + + return -ENOTDIR; + } + } + + /* Make sure that the directory containing the entry to be deleted is + * in the cache. + */ + + ret = fat_fscacheread(fs, dirsector); + if (ret < 0) + { + return ret; + } + + /* Mark the directory entry 'deleted' */ + + dirinfo.fd_entry[DIR_NAME] = DIR0_EMPTY; + fs->fs_dirty = TRUE; + + /* And remove the cluster chain making up the subdirectory */ + + ret = fat_removechain(fs, dircluster); + if (ret < 0) + { + return ret; + } + + /* Update the FSINFO sector (FAT32) */ + + ret = fat_updatefsinfo(fs); + if (ret < 0) + { + return ret; + } + + return OK; +} + +/**************************************************************************** + * Name: fat_fscacheflush + * + * Desciption: Flush any dirty sector if fs_buffer as necessary + * + ****************************************************************************/ + +int fat_fscacheflush(struct fat_mountpt_s *fs) +{ + int ret; + + /* Check if the fs_buffer is dirty. In this case, we will write back the + * contents of fs_buffer. + */ + + if (fs->fs_dirty) + { + /* Write the dirty sector */ + + ret = fat_hwwrite(fs, fs->fs_buffer, fs->fs_currentsector, 1); + if (ret < 0) + { + return ret; + } + + /* Does the sector lie in the FAT region? */ + + if (fs->fs_currentsector < fs->fs_fatbase + fs->fs_fatsize) + { + /* Yes, then make the change in the FAT copy as well */ + int i; + + for (i = fs->fs_fatnumfats; i >= 2; i--) + { + fs->fs_currentsector += fs->fs_fatsize; + ret = fat_hwwrite(fs, fs->fs_buffer, fs->fs_currentsector, 1); + if (ret < 0) + { + return ret; + } + } + } + + /* No longer dirty */ + + fs->fs_dirty = FALSE; + } + return OK; +} + +/**************************************************************************** + * Name: fat_fscacheread + * + * Desciption: Read the specified sector into the sector cache, flushing any + * existing dirty sectors as necessary. + * + ****************************************************************************/ + +int fat_fscacheread(struct fat_mountpt_s *fs, size_t sector) +{ + int ret; + + /* fs->fs_currentsector holds the current sector that is buffered in + * fs->fs_buffer. If the requested sector is the same as this sector, then + * we do nothing. Otherwise, we will have to read the new sector. + */ + + if (fs->fs_currentsector != sector) + { + /* We will need to read the new sector. First, flush the cached + * sector if it is dirty. + */ + + ret = fat_fscacheflush(fs); + if (ret < 0) + { + return ret; + } + + /* Then read the specified sector into the cache */ + + ret = fat_hwread(fs, fs->fs_buffer, sector, 1); + if (ret < 0) + { + return ret; + } + + /* Update the cached sector number */ + + fs->fs_currentsector = sector; + } + + return OK; +} + +/**************************************************************************** + * Name: fat_ffcacheflush + * + * Desciption: Flush any dirty sectors as necessary + * + ****************************************************************************/ + +int fat_ffcacheflush(struct fat_mountpt_s *fs, struct fat_file_s *ff) +{ + int ret; + + /* Check if the ff_buffer is dirty. In this case, we will write back the + * contents of ff_buffer. + */ + + if (ff->ff_bflags && (FFBUFF_DIRTY|FFBUFF_VALID) == (FFBUFF_DIRTY|FFBUFF_VALID)) + { + /* Write the dirty sector */ + + ret = fat_hwwrite(fs, ff->ff_buffer, ff->ff_currentsector, 1); + if (ret < 0) + { + return ret; + } + + /* No longer dirty */ + + ff->ff_bflags &= ~FFBUFF_DIRTY; + } + + return OK; +} + +/**************************************************************************** + * Name: fat_ffcacheread + * + * Desciption: Read the specified sector into the sector cache, flushing any + * existing dirty sectors as necessary. + * + ****************************************************************************/ + +int fat_ffcacheread(struct fat_mountpt_s *fs, struct fat_file_s *ff, size_t sector) +{ + int ret; + + /* ff->ff_currentsector holds the current sector that is buffered in + * ff->ff_buffer. If the requested sector is the same as this sector, then + * we do nothing. Otherwise, we will have to read the new sector. + */ + + if (ff->ff_currentsector != sector || (ff->ff_bflags & FFBUFF_VALID) == 0) + { + /* We will need to read the new sector. First, flush the cached + * sector if it is dirty. + */ + + ret = fat_ffcacheflush(fs, ff); + if (ret < 0) + { + return ret; + } + + /* Then read the specified sector into the cache */ + + ret = fat_hwread(fs, ff->ff_buffer, sector, 1); + if (ret < 0) + { + return ret; + } + + /* Update the cached sector number */ + + ff->ff_currentsector = sector; + ff->ff_bflags |= FFBUFF_VALID; + } + return OK; +} + +/**************************************************************************** + * Name: fat_ffcacheread + * + * Desciption: Invalidate the current file buffer contents + * + ****************************************************************************/ + +int fat_ffcacheinvalidate(struct fat_mountpt_s *fs, struct fat_file_s *ff) +{ + int ret; + + /* Is there anything valid in the buffer now? */ + + if ((ff->ff_bflags & FFBUFF_VALID) != 0) + { + /* We will invalidate the buffered sector */ + + ret = fat_ffcacheflush(fs, ff); + if (ret < 0) + { + return ret; + } + + /* Then discard the current cache contents */ + + ff->ff_bflags &= ~FFBUFF_VALID; + } + return OK; +} + +/**************************************************************************** + * Name: fat_updatefsinfo + * + * Desciption: Flush evertyhing buffered for the mountpoint and update + * the FSINFO sector, if appropriate + * + ****************************************************************************/ + +int fat_updatefsinfo(struct fat_mountpt_s *fs) +{ + int ret; + + /* Flush the fs_buffer if it is dirty */ + + ret = fat_fscacheflush(fs); + if (ret == OK) + { + /* The FSINFO sector only has to be update for the case of a FAT32 file + * system. Check if the file system type.. If this is a FAT32 file + * system then the fs_fsidirty flag will indicate if the FSINFO sector + * needs to be re-written. + */ + + if (fs->fs_type == FSTYPE_FAT32 && fs->fs_fsidirty) + { + /* Create an image of the FSINFO sector in the fs_buffer */ + + memset(fs->fs_buffer, 0, fs->fs_hwsectorsize); + FSI_PUTLEADSIG(fs->fs_buffer, 0x41615252); + FSI_PUTSTRUCTSIG(fs->fs_buffer, 0x61417272); + FSI_PUTFREECOUNT(fs->fs_buffer, fs->fs_fsifreecount); + FSI_PUTNXTFREE(fs->fs_buffer, fs->fs_fsinextfree); + FSI_PUTTRAILSIG(fs->fs_buffer, 0xaa550000); + + /* Then flush this to disk */ + + fs->fs_currentsector = fs->fs_fsinfo; + fs->fs_dirty = TRUE; + ret = fat_fscacheflush(fs); + + /* No longer dirty */ + + fs->fs_fsidirty = FALSE; + } + } + return ret; +} + +/**************************************************************************** + * Name: fat_nfreeclusters + * + * Desciption: Get the number of free clusters + * + ****************************************************************************/ + +int fat_nfreeclusters(struct fat_mountpt_s *fs, size_t *pfreeclusters) +{ + uint32 nfreeclusters; + + /* If number of the first free cluster is valid, then just return that value. */ + + if (fs->fs_fsifreecount <= fs->fs_nclusters - 2) + { + *pfreeclusters = fs->fs_fsifreecount; + return OK; + } + + /* Otherwise, we will have to count the number of free clusters */ + + nfreeclusters = 0; + if (fs->fs_type == FSTYPE_FAT12) + { + size_t sector; + + /* Examine every cluster in the fat */ + + for (sector = 2; sector < fs->fs_nclusters; sector++) + { + + /* If the cluster is unassigned, then increment the count of free clusters */ + + if ((uint16)fat_getcluster(fs, sector) == 0) + { + nfreeclusters++; + } + } + } + else + { + unsigned int cluster; + size_t fatsector; + unsigned int offset; + int ret; + + fatsector = fs->fs_fatbase; + offset = fs->fs_hwsectorsize; + + /* Examine each cluster in the fat */ + + for (cluster = fs->fs_nclusters; cluster > 0; cluster--) + { + /* If we are starting a new sector, then read the new sector in fs_buffer */ + + if (offset >= fs->fs_hwsectorsize) + { + ret = fat_fscacheread(fs, fatsector++); + if (ret < 0) + { + return ret; + } + + /* Reset the offset to the next FAT entry. + * Increment the sector number to read next time around. + */ + + offset = 0; + fatsector++; + } + + /* FAT16 and FAT32 differ only on the size of each cluster start + * sector number in the FAT. + */ + + if (fs->fs_type == FSTYPE_FAT16) + { + if (FAT_GETFAT16(fs->fs_buffer, offset) == 0) + { + nfreeclusters++; + } + offset += 2; + } + else + { + if (FAT_GETFAT32(fs->fs_buffer, offset) == 0) + { + nfreeclusters++; + } + + offset += 4; + } + } + } + + fs->fs_fsifreecount = nfreeclusters; + if (fs->fs_type == FSTYPE_FAT32) + { + fs->fs_fsidirty = TRUE; + } + + *pfreeclusters = nfreeclusters; + return OK; +} + -- cgit v1.2.3