From d35fa6bacd380d6adc2f836c145d2d38ea8e4f58 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 6 Oct 2014 10:53:25 -0600 Subject: Major structure of file system functions to better support asynchronous I/O. Respository should not be trusted until I have a chance to verify everything --- nuttx/fs/aio/aio.h | 5 +- nuttx/fs/aio/aio_fsync.c | 17 ++++-- nuttx/fs/aio/aio_read.c | 18 ++++-- nuttx/fs/aio/aio_write.c | 46 +++++++++++---- nuttx/fs/aio/aioc_contain.c | 17 +++++- nuttx/fs/inode/fs_files.c | 4 +- nuttx/fs/vfs/Make.defs | 8 +-- nuttx/fs/vfs/fs_dup.c | 8 +-- nuttx/fs/vfs/fs_dup2.c | 4 +- nuttx/fs/vfs/fs_dupfd.c | 137 ++++++++++++++++++++++++++++++++++++++++++++ nuttx/fs/vfs/fs_dupfd2.c | 117 +++++++++++++++++++++++++++++++++++++ nuttx/fs/vfs/fs_fcntl.c | 44 ++++++++------ nuttx/fs/vfs/fs_fdopen.c | 18 ++++-- nuttx/fs/vfs/fs_filedup.c | 119 -------------------------------------- nuttx/fs/vfs/fs_filedup2.c | 121 -------------------------------------- nuttx/fs/vfs/fs_fsync.c | 56 +++++++++++------- nuttx/fs/vfs/fs_getfilep.c | 112 ++++++++++++++++++++++++++++++++++++ nuttx/fs/vfs/fs_ioctl.c | 16 +++--- nuttx/fs/vfs/fs_lseek.c | 26 +++------ nuttx/fs/vfs/fs_open.c | 32 ++++++----- nuttx/fs/vfs/fs_poll.c | 20 ++++--- nuttx/fs/vfs/fs_pread.c | 92 +++++++++++++++++++---------- nuttx/fs/vfs/fs_pwrite.c | 88 +++++++++++++++++++--------- nuttx/fs/vfs/fs_read.c | 28 +++++---- nuttx/fs/vfs/fs_sendfile.c | 17 ++++-- nuttx/fs/vfs/fs_write.c | 65 +++++++++++---------- 26 files changed, 756 insertions(+), 479 deletions(-) create mode 100644 nuttx/fs/vfs/fs_dupfd.c create mode 100644 nuttx/fs/vfs/fs_dupfd2.c delete mode 100644 nuttx/fs/vfs/fs_filedup.c delete mode 100644 nuttx/fs/vfs/fs_filedup2.c create mode 100644 nuttx/fs/vfs/fs_getfilep.c (limited to 'nuttx/fs') diff --git a/nuttx/fs/aio/aio.h b/nuttx/fs/aio/aio.h index 0716b09bc..e6b85cc62 100644 --- a/nuttx/fs/aio/aio.h +++ b/nuttx/fs/aio/aio.h @@ -67,10 +67,12 @@ * pre-allocated, the number pre-allocated controlled by CONFIG_FS_NAIOC. */ +struct file; struct aio_container_s { dq_entry_t aioc_link; /* Supports a doubly linked list */ FAR struct aiocb *aioc_aiocbp; /* The contained AIO control block */ + FAR struct file *aioc_filep; /* File structure to use with the I/O */ struct work_s aioc_work; /* Used to defer I/O to the work thread */ pid_t aioc_pid; /* ID of the waiting task */ uint8_t aioc_prio; /* Priority of the waiting task */ @@ -182,7 +184,8 @@ void aioc_free(FAR struct aio_container_s *aioc); * Returned Value: * A reference to the new AIO control block container. This function * will not fail but will wait if necessary for the resources to perform - * this operation. + * this operation. NULL will be returned on certain errors with the + * errno value already set appropriately. * ****************************************************************************/ diff --git a/nuttx/fs/aio/aio_fsync.c b/nuttx/fs/aio/aio_fsync.c index 3df22bec6..25573df45 100644 --- a/nuttx/fs/aio/aio_fsync.c +++ b/nuttx/fs/aio/aio_fsync.c @@ -46,6 +46,7 @@ #include #include +#include #include "aio/aio.h" @@ -103,9 +104,9 @@ static void aio_fsync_worker(FAR void *arg) pid = aioc->aioc_pid; aiocbp = aioc_decant(aioc); - /* Perform the fsync using aio_fildes */ + /* Perform the fsync using aioc_filep */ - ret = fsync(aiocbp->aio_fildes); + ret = file_fsync(aioc->aioc_filep); if (ret < 0) { int errcode = get_errno(); @@ -218,12 +219,18 @@ int aio_fsync(int op, FAR struct aiocb *aiocbp) aiocbp->aio_result = -EINPROGRESS; aiocbp->aio_priv = NULL; - /* Create a container for the AIO control block. This will not fail but - * may cause us to block if there are insufficient resources to satisfy - * the request. + /* Create a container for the AIO control block. This may cause us to + * block if there are insufficient resources to satisfy the request. */ aioc = aio_contain(aiocbp); + if (!aioc) + { + /* The errno has already been set (probably EBADF) */ + + aiocbp->aio_result = -get_errno(); + return ERROR; + } /* Defer the work to the worker thread */ diff --git a/nuttx/fs/aio/aio_read.c b/nuttx/fs/aio/aio_read.c index c627a0d87..5ee7db119 100644 --- a/nuttx/fs/aio/aio_read.c +++ b/nuttx/fs/aio/aio_read.c @@ -106,14 +106,14 @@ static void aio_read_worker(FAR void *arg) /* Perform the read using: * - * aio_fildes - File descriptor + * aioc_filep - File structure pointer * aio_buf - Location of buffer * aio_nbytes - Length of transfer * aio_offset - File offset */ - nread = pread(aiocbp->aio_fildes, (FAR void *)aiocbp->aio_buf, - aiocbp->aio_nbytes, aiocbp->aio_offset); + nread = file_pread(aioc->aioc_filep, (FAR void *)aiocbp->aio_buf, + aiocbp->aio_nbytes, aiocbp->aio_offset); /* Set the result of the read */ @@ -266,12 +266,18 @@ int aio_read(FAR struct aiocb *aiocbp) aiocbp->aio_result = -EINPROGRESS; aiocbp->aio_priv = NULL; - /* Create a container for the AIO control block. This will not fail but - * may cause us to block if there are insufficient resources to satisfy - * the request. + /* Create a container for the AIO control block. This may cause us to + * block if there are insufficient resources to satisfy the request. */ aioc = aio_contain(aiocbp); + if (!aioc) + { + /* The errno has already been set (probably EBADF) */ + + aiocbp->aio_result = -get_errno(); + return ERROR; + } /* Defer the work to the worker thread */ diff --git a/nuttx/fs/aio/aio_write.c b/nuttx/fs/aio/aio_write.c index 2b1233e25..86f45c61d 100644 --- a/nuttx/fs/aio/aio_write.c +++ b/nuttx/fs/aio/aio_write.c @@ -39,6 +39,7 @@ #include +#include #include #include #include @@ -73,6 +74,21 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: file_fcntl + ****************************************************************************/ + +static inline int file_fcntl(FAR struct file *filep, int cmd, ...) +{ + va_list ap; + int ret; + + va_start(ap, cmd); + ret = file_vfcntl(filep, cmd, ap); + va_end(ap); + return ret; +} + /**************************************************************************** * Name: aio_write_worker * @@ -108,7 +124,7 @@ static void aio_write_worker(FAR void *arg) /* Call fcntl(F_GETFL) to get the file open mode. */ - oflags = fcntl(aiocbp->aio_fildes, F_GETFL); + oflags = file_fcntl(aioc->aioc_filep, F_GETFL); if (oflags < 0) { int errcode = get_errno(); @@ -119,7 +135,7 @@ static void aio_write_worker(FAR void *arg) { /* Perform the write using: * - * aio_fildes - File descriptor + * aioc_filep - File descriptor * aio_buf - Location of buffer * aio_nbytes - Length of transfer * aio_offset - File offset @@ -131,16 +147,16 @@ static void aio_write_worker(FAR void *arg) { /* Append to the current file position */ - nwritten = write(aiocbp->aio_fildes, - (FAR const void *)aiocbp->aio_buf, - aiocbp->aio_nbytes); + nwritten = file_write(aioc->aioc_filep, + (FAR const void *)aiocbp->aio_buf, + aiocbp->aio_nbytes); } else { - nwritten = pwrite(aiocbp->aio_fildes, - (FAR const void *)aiocbp->aio_buf, - aiocbp->aio_nbytes, - aiocbp->aio_offset); + nwritten = file_pwrite(aioc->aioc_filep, + (FAR const void *)aiocbp->aio_buf, + aiocbp->aio_nbytes, + aiocbp->aio_offset); } /* Set the result of the write */ @@ -297,12 +313,18 @@ int aio_write(FAR struct aiocb *aiocbp) aiocbp->aio_result = -EINPROGRESS; aiocbp->aio_priv = NULL; - /* Create a container for the AIO control block. This will not fail but - * may cause us to block if there are insufficient resources to satisfy - * the request. + /* Create a container for the AIO control block. This may cause us to + * block if there are insufficient resources to satisfy the request. */ aioc = aio_contain(aiocbp); + if (!aioc) + { + /* The errno has already been set (probably EBADF) */ + + aiocbp->aio_result = -get_errno(); + return ERROR; + } /* Defer the work to the worker thread */ diff --git a/nuttx/fs/aio/aioc_contain.c b/nuttx/fs/aio/aioc_contain.c index e608a8659..34842bd21 100644 --- a/nuttx/fs/aio/aioc_contain.c +++ b/nuttx/fs/aio/aioc_contain.c @@ -41,6 +41,8 @@ #include +#include + #include "aio/aio.h" #ifdef CONFIG_FS_AIO @@ -80,15 +82,27 @@ * Returned Value: * A reference to the new AIO control block container. This function * will not fail but will wait if necessary for the resources to perform - * this operation. + * this operation. NULL will be returned on certain errors with the + * errno value already set appropriately. * ****************************************************************************/ FAR struct aio_container_s *aio_contain(FAR struct aiocb *aiocbp) { FAR struct aio_container_s *aioc; + FAR struct file *filep; struct sched_param param; + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(aiocbp->aio_fildes); + if (!filep) + { + /* The errno value has already been set */ + + return NULL; + } + /* Allocate the AIO control block container, waiting for one to become * available if necessary. This should never fail. */ @@ -100,6 +114,7 @@ FAR struct aio_container_s *aio_contain(FAR struct aiocb *aiocbp) memset(aioc, 0, sizeof(struct aio_container_s)); aioc->aioc_aiocbp = aiocbp; + aioc->aioc_filep = filep; aioc->aioc_pid = getpid(); DEBUGVERIFY(sched_getparam (aioc->aioc_pid, ¶m)); diff --git a/nuttx/fs/inode/fs_files.c b/nuttx/fs/inode/fs_files.c index f39ea8b81..4f82b1512 100644 --- a/nuttx/fs/inode/fs_files.c +++ b/nuttx/fs/inode/fs_files.c @@ -200,7 +200,7 @@ void files_releaselist(FAR struct filelist *list) } /**************************************************************************** - * Name: files_dup + * Name: file_dup2 * * Description: * Assign an inode to a specific files structure. This is the heart of @@ -208,7 +208,7 @@ void files_releaselist(FAR struct filelist *list) * ****************************************************************************/ -int files_dup(FAR struct file *filep1, FAR struct file *filep2) +int file_dup2(FAR struct file *filep1, FAR struct file *filep2) { FAR struct filelist *list; FAR struct inode *inode; diff --git a/nuttx/fs/vfs/Make.defs b/nuttx/fs/vfs/Make.defs index 583aaf070..1780eabd6 100644 --- a/nuttx/fs/vfs/Make.defs +++ b/nuttx/fs/vfs/Make.defs @@ -69,10 +69,10 @@ else # Common file/socket descriptor support -CSRCS += fs_close.c fs_dup.c fs_dup2.c fs_fcntl.c fs_filedup.c fs_filedup2.c -CSRCS += fs_fsync.c fs_ioctl.c fs_lseek.c fs_mkdir.c fs_open.c fs_poll.c -CSRCS += fs_read.c fs_rename.c fs_rmdir.c fs_stat.c fs_statfs.c fs_select.c -CSRCS += fs_unlink.c fs_write.c +CSRCS += fs_close.c fs_dup.c fs_dup2.c fs_fcntl.c fs_dupfd.c fs_dupfd2.c +CSRCS += fs_fsync.c fs_getfilep.c fs_ioctl.c fs_lseek.c fs_mkdir.c fs_open.c +CSRCS += fs_poll.c fs_read.c fs_rename.c fs_rmdir.c fs_stat.c fs_statfs.c +CSRCS += fs_select.c fs_unlink.c fs_write.c # Support for positional file access diff --git a/nuttx/fs/vfs/fs_dup.c b/nuttx/fs/vfs/fs_dup.c index 2c4dd785d..5981dc8cd 100644 --- a/nuttx/fs/vfs/fs_dup.c +++ b/nuttx/fs/vfs/fs_dup.c @@ -68,7 +68,7 @@ int dup(int fd) { - int ret = OK; + int ret = OK; /* Check the range of the descriptor to see if we got a file or a socket * descriptor. */ @@ -79,19 +79,19 @@ int dup(int fd) /* Its a valid file descriptor.. dup the file descriptor using any * other file descriptor*/ - ret = file_dup(fd, 0); + ret = fs_dupfd(fd, 0); } else #endif { - /* Not a vailid file descriptor. Did we get a valid socket descriptor? */ + /* Not a valid file descriptor. Did we get a valid socket descriptor? */ #if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 if ((unsigned int)fd < (CONFIG_NFILE_DESCRIPTORS+CONFIG_NSOCKET_DESCRIPTORS)) { /* Yes.. dup the socket descriptor */ - ret = net_dup(fd, CONFIG_NFILE_DESCRIPTORS); + ret = net_dupsd(fd, CONFIG_NFILE_DESCRIPTORS); } else #endif diff --git a/nuttx/fs/vfs/fs_dup2.c b/nuttx/fs/vfs/fs_dup2.c index ff6eabdb4..3164e0b2f 100644 --- a/nuttx/fs/vfs/fs_dup2.c +++ b/nuttx/fs/vfs/fs_dup2.c @@ -87,7 +87,7 @@ int dup2(int fd1, int fd2) { /* Yes.. dup the socket descriptor */ - return net_dup2(fd1, fd2); + return net_dupsd2(fd1, fd2); } else { @@ -101,7 +101,7 @@ int dup2(int fd1, int fd2) { /* Its a valid file descriptor.. dup the file descriptor */ - return file_dup2(fd1, fd2); + return fs_dupfd2(fd1, fd2); } } diff --git a/nuttx/fs/vfs/fs_dupfd.c b/nuttx/fs/vfs/fs_dupfd.c new file mode 100644 index 000000000..5d319641d --- /dev/null +++ b/nuttx/fs/vfs/fs_dupfd.c @@ -0,0 +1,137 @@ +/**************************************************************************** + * fs/vfs/fs_dupfd.c + * + * Copyright (C) 2007-2009, 2011-2014 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "inode/inode.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define DUP_ISOPEN(filep) (filep->f_inode != NULL) + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: file_dup + * + * Description: + * Equivalent to the non-standard fs_dupfd() function except that it + * accepts a struct file instance instead of a file descriptor. Currently + * used only by file_vfcntl(); + * + ****************************************************************************/ + +int file_dup(FAR struct file *filep, int minfd) +{ + int fd2; + + /* Verify that fd is a valid, open file descriptor */ + + if (!DUP_ISOPEN(filep)) + { + set_errno(EBADF); + return ERROR; + } + + /* Increment the reference count on the contained inode */ + + inode_addref(filep->f_inode); + + /* Then allocate a new file descriptor for the inode */ + + fd2 = files_allocate(filep->f_inode, filep->f_oflags, filep->f_pos, minfd); + if (fd2 < 0) + { + set_errno(EMFILE); + inode_release(filep->f_inode); + return ERROR; + } + + return fd2; +} + +/**************************************************************************** + * Name: fs_dupfd OR dup + * + * Description: + * Clone a file descriptor 'fd' to an arbitray descriptor number (any value + * greater than or equal to 'minfd'). If socket descriptors are + * implemented, then this is called by dup() for the case of file + * descriptors. If socket descriptors are not implemented, then this + * function IS dup(). + * + ****************************************************************************/ + +int fs_dupfd(int fd, int minfd) +{ + FAR struct file *filep; + + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } + + /* Let file_dup() do the real work */ + + return file_dup(filep, minfd); +} + +#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */ + diff --git a/nuttx/fs/vfs/fs_dupfd2.c b/nuttx/fs/vfs/fs_dupfd2.c new file mode 100644 index 000000000..6043430bd --- /dev/null +++ b/nuttx/fs/vfs/fs_dupfd2.c @@ -0,0 +1,117 @@ +/**************************************************************************** + * fs/vfs/fs_dupfd2.c + * + * Copyright (C) 2007-2009, 2011-2014 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "inode/inode.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define DUP_ISOPEN(filep) (filep->f_inode != NULL) + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fs_dupfd2 OR dup2 + * + * Description: + * Clone a file descriptor to a specific descriptor number. If socket + * descriptors are implemented, then this is called by dup2() for the + * case of file descriptors. If socket descriptors are not implemented, + * then this function IS dup2(). + * + ****************************************************************************/ + +#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 +int fs_dupfd2(int fd1, int fd2) +#else +int dup2(int fd1, int fd2) +#endif +{ + FAR struct file *filep1; + FAR struct file *filep2; + + /* Get the file structures corresponding to the file descriptors. */ + + filep1 = fs_getfilep(fd1); + filep2 = fs_getfilep(fd2); + + if (!filep1 || !filep2) + { + /* The errno value has already been set */ + + return ERROR; + } + + /* Verify that fd1 is a valid, open file descriptor */ + + if (!DUP_ISOPEN(filep1)) + { + set_errno(EBADF); + return ERROR; + } + + /* Handle a special case */ + + if (fd1 == fd2) + { + return fd1; + } + + /* Perform the dup2 operation */ + + return file_dup2(filep1, filep2); +} + +#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */ + diff --git a/nuttx/fs/vfs/fs_fcntl.c b/nuttx/fs/vfs/fs_fcntl.c index 6e4ebefb1..f4d67ae45 100644 --- a/nuttx/fs/vfs/fs_fcntl.c +++ b/nuttx/fs/vfs/fs_fcntl.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/vfs/fs_fcntl.c * - * Copyright (C) 2009, 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2009, 2012-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -58,26 +58,28 @@ * Private Functions ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ + /**************************************************************************** * Name: file_vfcntl + * + * Description: + * Similar to the standard vfcntl function except that is accepts a struct + * struct file instance instead of a file descriptor. Currently used + * only by aio_fcntl(); + * ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -static inline int file_vfcntl(int fd, int cmd, va_list ap) +int file_vfcntl(FAR struct file *filep, int cmd, va_list ap) { - FAR struct filelist *list; - FAR struct file *filep; int err = 0; int ret = OK; - /* Get the thread-specific file list */ - - list = sched_getfiles(); - DEBUGASSERT(list); - /* Was this file opened ? */ - filep = &list->fl_files[fd]; if (!filep->f_inode) { err = EBADF; @@ -98,7 +100,7 @@ static inline int file_vfcntl(int fd, int cmd, va_list ap) */ { - ret = file_dup(fd, va_arg(ap, int)); + ret = file_dup(filep, va_arg(ap, int)); } break; @@ -216,16 +218,13 @@ errout: } #endif /* CONFIG_NFILE_DESCRIPTORS > 0 */ -/**************************************************************************** - * Global Functions - ****************************************************************************/ - /**************************************************************************** * Name: fcntl ****************************************************************************/ int fcntl(int fd, int cmd, ...) { + FAR struct file *filep; va_list ap; int ret; @@ -238,9 +237,19 @@ int fcntl(int fd, int cmd, ...) #if CONFIG_NFILE_DESCRIPTORS > 0 if ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS) { - /* Yes.. defer file operations to file_vfcntl() */ + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ - ret = file_vfcntl(fd, cmd, ap); + return ERROR; + } + + /* Let file_vfcntl() do the real work */ + + ret = file_vfcntl(filep, cmd, ap); } else #endif @@ -266,4 +275,3 @@ int fcntl(int fd, int cmd, ...) va_end(ap); return ret; } - diff --git a/nuttx/fs/vfs/fs_fdopen.c b/nuttx/fs/vfs/fs_fdopen.c index ece6f0fe9..882337da1 100644 --- a/nuttx/fs/vfs/fs_fdopen.c +++ b/nuttx/fs/vfs/fs_fdopen.c @@ -65,22 +65,28 @@ #if CONFIG_NFILE_DESCRIPTORS > 0 static inline int fs_checkfd(FAR struct tcb_s *tcb, int fd, int oflags) { - FAR struct filelist *flist; - FAR struct inode *inode; + FAR struct file *filep; + FAR struct inode *inode; DEBUGASSERT(tcb && tcb->group); - /* Get the file list from the task group */ + /* Get the file structure corresponding to the file descriptor. */ - flist = &tcb->group->tg_filelist; + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } /* Get the inode associated with the file descriptor. This should * normally be the case if fd >= 0. But not in the case where the - * called attempts to explictly stdin with fdopen(0) but stdin has + * called attempts to explicitly stdin with fdopen(0) but stdin has * been closed. */ - inode = flist->fl_files[fd].f_inode; + inode = filep->f_inode; if (!inode) { /* No inode -- descriptor does not correspond to an open file */ diff --git a/nuttx/fs/vfs/fs_filedup.c b/nuttx/fs/vfs/fs_filedup.c deleted file mode 100644 index f474a096e..000000000 --- a/nuttx/fs/vfs/fs_filedup.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * fs/vfs/fs_filedup.c - * - * Copyright (C) 2007-2009, 2011-2013 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -#include "inode/inode.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define DUP_ISOPEN(fd, list) \ - ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS && \ - list->fl_files[fd].f_inode != NULL) - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: file_dup OR dup - * - * Description: - * Clone a file descriptor 'fd' to an arbitray descriptor number (any value - * greater than or equal to 'minfd'). If socket descriptors are - * implemented, then this is called by dup() for the case of file - * descriptors. If socket descriptors are not implemented, then this - * function IS dup(). - * - ****************************************************************************/ - -int file_dup(int fd, int minfd) -{ - FAR struct filelist *list; - int fd2; - - /* Get the thread-specific file list */ - - list = sched_getfiles(); - DEBUGASSERT(list); - - /* Verify that fd is a valid, open file descriptor */ - - if (!DUP_ISOPEN(fd, list)) - { - set_errno(EBADF); - return ERROR; - } - - /* Increment the reference count on the contained inode */ - - inode_addref(list->fl_files[fd].f_inode); - - /* Then allocate a new file descriptor for the inode */ - - fd2 = files_allocate(list->fl_files[fd].f_inode, - list->fl_files[fd].f_oflags, - list->fl_files[fd].f_pos, - minfd); - if (fd2 < 0) - { - set_errno(EMFILE); - inode_release(list->fl_files[fd].f_inode); - return ERROR; - } - - return fd2; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */ - diff --git a/nuttx/fs/vfs/fs_filedup2.c b/nuttx/fs/vfs/fs_filedup2.c deleted file mode 100644 index 73b29c32e..000000000 --- a/nuttx/fs/vfs/fs_filedup2.c +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * fs/vfs/fs_filedup2.c - * - * Copyright (C) 2007-2009, 2011-2013 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include "inode/inode.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define DUP_ISOPEN(fd, list) \ - ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS && \ - list->fl_files[fd].f_inode != NULL) - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Global Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: file_dup2 OR dup2 - * - * Description: - * Clone a file descriptor to a specific descriptor number. If socket - * descriptors are implemented, then this is called by dup2() for the - * case of file descriptors. If socket descriptors are not implemented, - * then this function IS dup2(). - * - ****************************************************************************/ - -#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 -int file_dup2(int fd1, int fd2) -#else -int dup2(int fd1, int fd2) -#endif -{ - FAR struct filelist *list; - - /* Get the thread-specific file list */ - - list = sched_getfiles(); - if (!list) - { - set_errno(EMFILE); - return ERROR; - } - - /* Verify that fd is a valid, open file descriptor */ - - if (!DUP_ISOPEN(fd1, list)) - { - set_errno(EBADF); - return ERROR; - } - - /* Handle a special case */ - - if (fd1 == fd2) - { - return fd1; - } - - /* Verify fd2 */ - - if ((unsigned int)fd2 >= CONFIG_NFILE_DESCRIPTORS) - { - set_errno(EBADF); - return ERROR; - } - - return files_dup(&list->fl_files[fd1], &list->fl_files[fd2]); -} - -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */ - diff --git a/nuttx/fs/vfs/fs_fsync.c b/nuttx/fs/vfs/fs_fsync.c index d608cda5f..24e184142 100644 --- a/nuttx/fs/vfs/fs_fsync.c +++ b/nuttx/fs/vfs/fs_fsync.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/vfs/fs_fsync.c * - * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2013-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -70,36 +70,22 @@ ****************************************************************************/ /**************************************************************************** - * Name: fsync + * Name: file_fsync * * Description: - * This func simply binds inode sync methods to the sync system call. + * Equivalent to the standard fsync() function except that is accepts a + * struct file instance instead of a file descriptor. Currently used + * only by aio_fsync(); * ****************************************************************************/ -int fsync(int fd) +int file_fsync(FAR struct file *filep) { - FAR struct filelist *list; - FAR struct file *filep; - struct inode *inode; - int ret; - - /* Get the thread-specific file list */ - - list = sched_getfiles(); - DEBUGASSERT(list); - - /* Did we get a valid file descriptor? */ - - if ((unsigned int)fd >= CONFIG_NFILE_DESCRIPTORS) - { - ret = EBADF; - goto errout; - } + struct inode *inode; + int ret; /* Was this file opened for write access? */ - filep = &list->fl_files[fd]; if ((filep->f_oflags & O_WROK) == 0) { ret = EBADF; @@ -134,3 +120,29 @@ errout: return ERROR; } +/**************************************************************************** + * Name: fsync + * + * Description: + * This func simply binds inode sync methods to the sync system call. + * + ****************************************************************************/ + +int fsync(int fd) +{ + FAR struct file *filep; + + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } + + /* Perform the fsync operation */ + + return file_fsync(filep); +} diff --git a/nuttx/fs/vfs/fs_getfilep.c b/nuttx/fs/vfs/fs_getfilep.c new file mode 100644 index 000000000..165d00434 --- /dev/null +++ b/nuttx/fs/vfs/fs_getfilep.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * fs/vfs/fs_getfilep.c + * + * Copyright (C) 2014 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include +#include +#include +#include + +#include "inode/inode.h" + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fs_getfilep + * + * Description: + * Given a file descriptor, return the corresponding instance of struct + * file. NOTE that this function will currently fail if it is provided + * with a socket descriptor. + * + * Parameters: + * fd - The file descriptor + * + * Return: + * A point to the corresponding struct file instance is returned on + * success. On failure, NULL is returned and the errno value is + * set appropriately (EBADF). + * + ****************************************************************************/ + +FAR struct file *fs_getfilep(int fd) +{ + FAR struct filelist *list; + int errcode; + + if ((unsigned int)fd >= CONFIG_NFILE_DESCRIPTORS) + { + errcode = EBADF; + goto errout; + } + + /* The descriptor is in a valid range to file descriptor... Get the + * thread-specific file list. + */ + + list = sched_getfiles(); + + /* The file list can be NULL under one obscure cornercase: When memory + * management debug output is enabled. Then there may be attempts to + * write to stdout from malloc before the group data has been allocated. + */ + + if (!list) + { + errcode = EAGAIN; + goto errout; + } + + /* And return the file pointer from the list */ + + return &list->fl_files[fd]; + +errout: + set_errno(errcode); + return NULL; +} diff --git a/nuttx/fs/vfs/fs_ioctl.c b/nuttx/fs/vfs/fs_ioctl.c index b0a7ad786..c0165cf7b 100644 --- a/nuttx/fs/vfs/fs_ioctl.c +++ b/nuttx/fs/vfs/fs_ioctl.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/vfs/fs_ioctl.c * - * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2010, 2012-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -89,7 +89,6 @@ int ioctl(int fd, int req, unsigned long arg) { int err; #if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct filelist *list; FAR struct file *filep; FAR struct inode *inode; int ret = OK; @@ -115,16 +114,19 @@ int ioctl(int fd, int req, unsigned long arg) } #if CONFIG_NFILE_DESCRIPTORS > 0 - /* Get the thread-specific file list */ + /* Get the file structure corresponding to the file descriptor. */ - list = sched_getfiles(); - DEBUGASSERT(list); + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } /* Is a driver registered? Does it support the ioctl method? */ - filep = &list->fl_files[fd]; inode = filep->f_inode; - if (inode && inode->u.i_ops && inode->u.i_ops->ioctl) { /* Yes, then let it perform the ioctl */ diff --git a/nuttx/fs/vfs/fs_lseek.c b/nuttx/fs/vfs/fs_lseek.c index a4a45b5fd..7136d2ce1 100644 --- a/nuttx/fs/vfs/fs_lseek.c +++ b/nuttx/fs/vfs/fs_lseek.c @@ -50,7 +50,7 @@ #if CONFIG_NFILE_DESCRIPTORS > 0 /**************************************************************************** - * Global Functions + * Public Functions ****************************************************************************/ /**************************************************************************** @@ -71,9 +71,6 @@ * ****************************************************************************/ -#ifndef CONFIG_NET_SENDFILE -static inline -#endif off_t file_seek(FAR struct file *filep, off_t offset, int whence) { FAR struct inode *inode; @@ -172,26 +169,21 @@ errout: off_t lseek(int fd, off_t offset, int whence) { - FAR struct filelist *list; + FAR struct file *filep; - /* Did we get a valid file descriptor? */ + /* Get the file structure corresponding to the file descriptor. */ - if ((unsigned int)fd >= CONFIG_NFILE_DESCRIPTORS) + filep = fs_getfilep(fd); + if (!filep) { - set_errno(EBADF); + /* The errno value has already been set */ + return (off_t)ERROR; } - else - { - /* Get the thread-specific file list */ - - list = sched_getfiles(); - DEBUGASSERT(list); - /* Then let file_seek do the real work */ + /* Then let file_seek do the real work */ - return file_seek(&list->fl_files[fd], offset, whence); - } + return file_seek(filep, offset, whence); } #endif diff --git a/nuttx/fs/vfs/fs_open.c b/nuttx/fs/vfs/fs_open.c index 4c0596e7f..fd6562ac3 100644 --- a/nuttx/fs/vfs/fs_open.c +++ b/nuttx/fs/vfs/fs_open.c @@ -91,19 +91,14 @@ int inode_checkflags(FAR struct inode *inode, int oflags) int open(const char *path, int oflags, ...) { - FAR struct filelist *list; - FAR struct inode *inode; - FAR const char *relpath = NULL; + FAR struct file *filep; + FAR struct inode *inode; + FAR const char *relpath = NULL; #if defined(CONFIG_FILE_MODE) || !defined(CONFIG_DISABLE_MOUNTPOINT) - mode_t mode = 0666; + mode_t mode = 0666; #endif - int ret; - int fd; - - /* Get the thread-specific file list */ - - list = sched_getfiles(); - DEBUGASSERT(list); + int ret; + int fd; #ifdef CONFIG_FILE_MODE # ifdef CONFIG_CPP_HAVE_WARNING @@ -168,6 +163,16 @@ int open(const char *path, int oflags, ...) goto errout_with_inode; } + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } + /* Perform the driver open operation. NOTE that the open method may be * called many times. The driver/mountpoint logic should handled this * because it may also be closed that many times. @@ -179,13 +184,12 @@ int open(const char *path, int oflags, ...) #ifndef CONFIG_DISABLE_MOUNTPOINT if (INODE_IS_MOUNTPT(inode)) { - ret = inode->u.i_mops->open((FAR struct file*)&list->fl_files[fd], - relpath, oflags, mode); + ret = inode->u.i_mops->open(filep, relpath, oflags, mode); } else #endif { - ret = inode->u.i_ops->open((FAR struct file*)&list->fl_files[fd]); + ret = inode->u.i_ops->open(filep); } } diff --git a/nuttx/fs/vfs/fs_poll.c b/nuttx/fs/vfs/fs_poll.c index 701508917..3bdc817ca 100644 --- a/nuttx/fs/vfs/fs_poll.c +++ b/nuttx/fs/vfs/fs_poll.c @@ -97,10 +97,9 @@ static void poll_semtake(FAR sem_t *sem) #if CONFIG_NFILE_DESCRIPTORS > 0 static int poll_fdsetup(int fd, FAR struct pollfd *fds, bool setup) { - FAR struct filelist *list; - FAR struct file *filep; - FAR struct inode *inode; - int ret = -ENOSYS; + FAR struct file *filep; + FAR struct inode *inode; + int ret = -ENOSYS; /* Check for a valid file descriptor */ @@ -120,18 +119,21 @@ static int poll_fdsetup(int fd, FAR struct pollfd *fds, bool setup) } } - /* Get the thread-specific file list */ + /* Get the file pointer corresponding to this file descriptor */ - list = sched_getfiles(); - DEBUGASSERT(list); + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } /* Is a driver registered? Does it support the poll method? * If not, return -ENOSYS */ - filep = &list->fl_files[fd]; inode = filep->f_inode; - if (inode && inode->u.i_ops && inode->u.i_ops->poll) { /* Yes, then setup the poll */ diff --git a/nuttx/fs/vfs/fs_pread.c b/nuttx/fs/vfs/fs_pread.c index 3e4943439..e80efe66a 100644 --- a/nuttx/fs/vfs/fs_pread.c +++ b/nuttx/fs/vfs/fs_pread.c @@ -43,6 +43,8 @@ #include #include +#include + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -52,56 +54,38 @@ ****************************************************************************/ /**************************************************************************** - * Name: pread + * Name: file_pread * * Description: - * The pread() function performs the same action as read(), except that it - * reads from a given position in the file without changing the file - * pointer. The first three arguments to pread() are the same as read() - * with the addition of a fourth argument offset for the desired position - * inside the file. An attempt to perform a pread() on a file that is - * incapable of seeking results in an error. - * - * NOTE: This function could have been wholly implemented within libc but - * it is not. Why? Because if pread were implemented in libc, it would - * require four system calls. If it is implemented within the kernel, - * only three. - * - * Parameters: - * file File structure instance - * buf User-provided to save the data - * nbytes The maximum size of the user-provided buffer - * offset The file offset - * - * Return: - * The positive non-zero number of bytes read on success, 0 on if an - * end-of-file condition, or -1 on failure with errno set appropriately. - * See read() return values + * Equivalent to the standard pread function except that is accepts a + * struct file instance instead of a file descriptor. Currently used + * only by aio_read(); * ****************************************************************************/ -ssize_t pread(int fd, FAR void *buf, size_t nbytes, off_t offset) +ssize_t file_pread(FAR struct file *filep, FAR void *buf, size_t nbytes, + off_t offset) { off_t savepos; off_t pos; ssize_t ret; int errcode; - /* Perform the lseek to the current position. This will not move the + /* Perform the seek to the current position. This will not move the * file pointer, but will return its current setting */ - savepos = lseek(fd, 0, SEEK_CUR); + savepos = file_seek(filep, 0, SEEK_CUR); if (savepos == (off_t)-1) { - /* lseek might fail if this if the media is not seekable */ + /* file_seek might fail if this if the media is not seekable */ return ERROR; } /* Then seek to the correct position in the file */ - pos = lseek(fd, offset, SEEK_SET); + pos = file_seek(filep, offset, SEEK_SET); if (pos == (off_t)-1) { /* This might fail is the offset is beyond the end of file */ @@ -111,12 +95,12 @@ ssize_t pread(int fd, FAR void *buf, size_t nbytes, off_t offset) /* Then perform the read operation */ - ret = read(fd, buf, nbytes); + ret = file_read(filep, buf, nbytes); errcode = get_errno(); /* Restore the file position */ - pos = lseek(fd, savepos, SEEK_SET); + pos = file_seek(filep, savepos, SEEK_SET); if (pos == (off_t)-1 && ret >= 0) { /* This really should not fail */ @@ -127,3 +111,51 @@ ssize_t pread(int fd, FAR void *buf, size_t nbytes, off_t offset) set_errno(errcode); return ret; } + +/**************************************************************************** + * Name: pread + * + * Description: + * The pread() function performs the same action as read(), except that it + * reads from a given position in the file without changing the file + * pointer. The first three arguments to pread() are the same as read() + * with the addition of a fourth argument offset for the desired position + * inside the file. An attempt to perform a pread() on a file that is + * incapable of seeking results in an error. + * + * NOTE: This function could have been wholly implemented within libc but + * it is not. Why? Because if pread were implemented in libc, it would + * require four system calls. If it is implemented within the kernel, + * only three. + * + * Parameters: + * file File structure instance + * buf User-provided to save the data + * nbytes The maximum size of the user-provided buffer + * offset The file offset + * + * Return: + * The positive non-zero number of bytes read on success, 0 on if an + * end-of-file condition, or -1 on failure with errno set appropriately. + * See read() return values + * + ****************************************************************************/ + +ssize_t pread(int fd, FAR void *buf, size_t nbytes, off_t offset) +{ + FAR struct file *filep; + + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return (ssize_t)ERROR; + } + + /* Let file_pread do the real work */ + + return file_pread(filep, buf, nbytes, offset); +} diff --git a/nuttx/fs/vfs/fs_pwrite.c b/nuttx/fs/vfs/fs_pwrite.c index e7c1cf700..43630c455 100644 --- a/nuttx/fs/vfs/fs_pwrite.c +++ b/nuttx/fs/vfs/fs_pwrite.c @@ -43,6 +43,8 @@ #include #include +#include + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -52,54 +54,38 @@ ****************************************************************************/ /**************************************************************************** - * Name: pwrite + * Name: file_pwrite * * Description: - * The pwrite() function performs the same action as write(), except that - * it writes into a given position without changing the file pointer. The - * first three arguments to pwrite() are the same as write() with the - * addition of a fourth argument offset for the desired position inside - * the file. - * - * NOTE: This function could have been wholly implemented within libc but - * it is not. Why? Because if pwrite were implemented in libc, it would - * require four system calls. If it is implemented within the kernel, - * only three. - * - * Parameters: - * fd file descriptor (or socket descriptor) to write to - * buf Data to write - * nbytes Length of data to write - * - * Return: - * The positive non-zero number of bytes read on success, 0 on if an - * end-of-file condition, or -1 on failure with errno set appropriately. - * See write() return values + * Equivalent to the standard pwrite function except that is accepts a + * struct file instance instead of a file descriptor. Currently used + * only by aio_write(); * ****************************************************************************/ -ssize_t pwrite(int fd, FAR const void *buf, size_t nbytes, off_t offset) +ssize_t file_pwrite(FAR struct file *filep, FAR const void *buf, + size_t nbytes, off_t offset) { off_t savepos; off_t pos; ssize_t ret; int errcode; - /* Perform the lseek to the current position. This will not move the + /* Perform the seek to the current position. This will not move the * file pointer, but will return its current setting */ - savepos = lseek(fd, 0, SEEK_CUR); + savepos = file_seek(filep, 0, SEEK_CUR); if (savepos == (off_t)-1) { - /* lseek might fail if this if the media is not seekable */ + /* file_seek might fail if this if the media is not seekable */ return ERROR; } /* Then seek to the correct position in the file */ - pos = lseek(fd, offset, SEEK_SET); + pos = file_seek(filep, offset, SEEK_SET); if (pos == (off_t)-1) { /* This might fail is the offset is beyond the end of file */ @@ -109,12 +95,12 @@ ssize_t pwrite(int fd, FAR const void *buf, size_t nbytes, off_t offset) /* Then perform the write operation */ - ret = write(fd, buf, nbytes); + ret = file_write(filep, buf, nbytes); errcode = get_errno(); /* Restore the file position */ - pos = lseek(fd, savepos, SEEK_SET); + pos = file_seek(filep, savepos, SEEK_SET); if (pos == (off_t)-1 && ret >= 0) { /* This really should not fail */ @@ -125,3 +111,49 @@ ssize_t pwrite(int fd, FAR const void *buf, size_t nbytes, off_t offset) set_errno(errcode); return ret; } + +/**************************************************************************** + * Name: pwrite + * + * Description: + * The pwrite() function performs the same action as write(), except that + * it writes into a given position without changing the file pointer. The + * first three arguments to pwrite() are the same as write() with the + * addition of a fourth argument offset for the desired position inside + * the file. + * + * NOTE: This function could have been wholly implemented within libc but + * it is not. Why? Because if pwrite were implemented in libc, it would + * require four system calls. If it is implemented within the kernel, + * only three. + * + * Parameters: + * fd file descriptor (or socket descriptor) to write to + * buf Data to write + * nbytes Length of data to write + * + * Return: + * The positive non-zero number of bytes read on success, 0 on if an + * end-of-file condition, or -1 on failure with errno set appropriately. + * See write() return values + * + ****************************************************************************/ + +ssize_t pwrite(int fd, FAR const void *buf, size_t nbytes, off_t offset) +{ + FAR struct file *filep; + + /* Get the file structure corresponding to the file descriptor. */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return (ssize_t)ERROR; + } + + /* Let file_pread do the real work */ + + return file_pwrite(filep, buf, nbytes, offset); +} diff --git a/nuttx/fs/vfs/fs_read.c b/nuttx/fs/vfs/fs_read.c index d9b7ed23a..c5cdc701e 100644 --- a/nuttx/fs/vfs/fs_read.c +++ b/nuttx/fs/vfs/fs_read.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/vfs/fs_read.c * - * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -73,10 +73,6 @@ * ****************************************************************************/ -#if CONFIG_NFILE_DESCRIPTORS > 0 -#ifndef CONFIG_NET_SENDFILE -static inline -#endif ssize_t file_read(FAR struct file *filep, FAR void *buf, size_t nbytes) { FAR struct inode *inode; @@ -120,7 +116,6 @@ ssize_t file_read(FAR struct file *filep, FAR void *buf, size_t nbytes) return ret; } -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */ /**************************************************************************** * Name: read @@ -141,10 +136,6 @@ ssize_t file_read(FAR struct file *filep, FAR void *buf, size_t nbytes) ssize_t read(int fd, FAR void *buf, size_t nbytes) { -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct filelist *list; -#endif - /* Did we get a valid file descriptor? */ #if CONFIG_NFILE_DESCRIPTORS > 0 @@ -168,16 +159,23 @@ ssize_t read(int fd, FAR void *buf, size_t nbytes) #if CONFIG_NFILE_DESCRIPTORS > 0 else { - /* Thee descriptor is in a valid range to file descriptor... do the - * read. Get the thread-specific file list. + FAR struct file *filep; + + /* The descriptor is in a valid range to file descriptor... do the + * read. First, get the file structure. */ - list = sched_getfiles(); - DEBUGASSERT(list); + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } /* Then let file_read do all of the work */ - return file_read(&list->fl_files[fd], buf, nbytes); + return file_read(filep, buf, nbytes); } #endif } diff --git a/nuttx/fs/vfs/fs_sendfile.c b/nuttx/fs/vfs/fs_sendfile.c index e5d935696..05c3d976e 100644 --- a/nuttx/fs/vfs/fs_sendfile.c +++ b/nuttx/fs/vfs/fs_sendfile.c @@ -127,18 +127,23 @@ ssize_t sendfile(int outfd, int infd, off_t *offset, size_t count) if ((unsigned int)outfd >= CONFIG_NFILE_DESCRIPTORS && (unsigned int)infd < CONFIG_NFILE_DESCRIPTORS) { - FAR struct filelist *list; + FAR struct file *filep; - /* This appears to be a file-to-socket transfer. Get the thread- - * specific file list. + /* This appears to be a file-to-socket transfer. Get the file + * structure. */ - list = sched_getfiles(); - DEBUGASSERT(list); + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } /* Then let net_sendfile do the work. */ - return net_sendfile(outfd, &list->fl_files[infd], offset, count); + return net_sendfile(outfd, filep, offset, count); } else #endif diff --git a/nuttx/fs/vfs/fs_write.c b/nuttx/fs/vfs/fs_write.c index 1c0ab8ea1..830e56dcc 100644 --- a/nuttx/fs/vfs/fs_write.c +++ b/nuttx/fs/vfs/fs_write.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/vfs/fs_write.c * - * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012-2014 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -55,33 +55,28 @@ * Private Functions ****************************************************************************/ -#if CONFIG_NFILE_DESCRIPTORS > 0 -static inline ssize_t file_write(int fd, FAR const void *buf, size_t nbytes) +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: file_write + * + * Description: + * Equivalent to the standard write() function except that is accepts a + * struct file instance instead of a file descriptor. Currently used + * only by aio_write(); + * + ****************************************************************************/ + +ssize_t file_write(FAR struct file *filep, FAR const void *buf, size_t nbytes) { - FAR struct filelist *list; - FAR struct file *filep; FAR struct inode *inode; int ret; int err; - /* Get the thread-specific file list */ - - list = sched_getfiles(); - - /* The file list can be NULL under one obscure cornercase: When memory - * management debug output is enabled. Then there may be attempts to - * write to stdout from malloc before the group data has been allocated. - */ - - if (!list) - { - err = EAGAIN; - goto errout; - } - /* Was this file opened for write access? */ - filep = &list->fl_files[fd]; if ((filep->f_oflags & O_WROK) == 0) { err = EBADF; @@ -112,11 +107,6 @@ errout: set_errno(err); return ERROR; } -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ /*************************************************************************** * Name: write @@ -170,6 +160,10 @@ errout: ssize_t write(int fd, FAR const void *buf, size_t nbytes) { +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct file *filep; +#endif + /* Did we get a valid file descriptor? */ #if CONFIG_NFILE_DESCRIPTORS > 0 @@ -186,10 +180,21 @@ ssize_t write(int fd, FAR const void *buf, size_t nbytes) #endif } - /* The descriptor is in the right range to be a file descriptor... write to the file */ - #if CONFIG_NFILE_DESCRIPTORS > 0 - return file_write(fd, buf, nbytes); + /* The descriptor is in the right range to be a file descriptor... write + * to the file. + */ + + filep = fs_getfilep(fd); + if (!filep) + { + /* The errno value has already been set */ + + return ERROR; + } + + /* Perform the write operation using the file descriptor as an index */ + + return file_write(filep, buf, nbytes); #endif } - -- cgit v1.2.3