summaryrefslogtreecommitdiff
path: root/nuttx/fs
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-10-05 15:33:31 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-10-05 15:33:31 -0600
commit5daa95bae187d09a50bc2663ee6291eb7c46b5dd (patch)
tree582ffeedb8a5aa6ed4b6d3da6ff4cf47eb475b1d /nuttx/fs
parent2bbdd8cc73bea765bf9464e3316c1b8a5cd8a47e (diff)
downloadpx4-nuttx-5daa95bae187d09a50bc2663ee6291eb7c46b5dd.tar.gz
px4-nuttx-5daa95bae187d09a50bc2663ee6291eb7c46b5dd.tar.bz2
px4-nuttx-5daa95bae187d09a50bc2663ee6291eb7c46b5dd.zip
Move all file operations from libc/aio to fs/aio. These will need to be kernel routines in order to handler issues with using file descriptors on worker thread
Diffstat (limited to 'nuttx/fs')
-rw-r--r--nuttx/fs/Kconfig1
-rw-r--r--nuttx/fs/Makefile1
-rw-r--r--nuttx/fs/aio/Make.defs46
-rw-r--r--nuttx/fs/aio/aio.h91
-rw-r--r--nuttx/fs/aio/aio_cancel.c167
-rw-r--r--nuttx/fs/aio/aio_fsync.c228
-rw-r--r--nuttx/fs/aio/aio_read.c276
-rw-r--r--nuttx/fs/aio/aio_signal.c148
-rw-r--r--nuttx/fs/aio/aio_write.c307
9 files changed, 1265 insertions, 0 deletions
diff --git a/nuttx/fs/Kconfig b/nuttx/fs/Kconfig
index 9165814dc..85de5acd6 100644
--- a/nuttx/fs/Kconfig
+++ b/nuttx/fs/Kconfig
@@ -48,6 +48,7 @@ config FS_WRITABLE
bool
default n
+source fs/aio/Kconfig
source fs/semaphore/Kconfig
source fs/mqueue/Kconfig
source fs/shm/Kconfig
diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
index 2d3a97422..92f1a9400 100644
--- a/nuttx/fs/Makefile
+++ b/nuttx/fs/Makefile
@@ -47,6 +47,7 @@ include inode/Make.defs
include vfs/Make.defs
include driver/Make.defs
include dirent/Make.defs
+include aio/Make.defs
include mmap/Make.defs
# OS resources
diff --git a/nuttx/fs/aio/Make.defs b/nuttx/fs/aio/Make.defs
new file mode 100644
index 000000000..c1d0bea8a
--- /dev/null
+++ b/nuttx/fs/aio/Make.defs
@@ -0,0 +1,46 @@
+############################################################################
+# fs/aio/Make.defs
+#
+# Copyright (C) 2014 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+ifeq ($(CONFIG_LIBC_AIO),y)
+
+# Add the asynchronous I/O C files to the build
+
+CSRCS += aio_cancel.c aio_fsync.c aio_read.c aio_signal.c aio_write.c
+
+# Add the asynchronous I/O directory to the build
+
+DEPPATH += --dep-path aio
+VPATH += :aio
+endif
diff --git a/nuttx/fs/aio/aio.h b/nuttx/fs/aio/aio.h
new file mode 100644
index 000000000..a7a179171
--- /dev/null
+++ b/nuttx/fs/aio/aio.h
@@ -0,0 +1,91 @@
+/****************************************************************************
+ * fs/aio/aio.h
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __FS_AIO_AIO_H
+#define __FS_AIO_AIO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <aio.h>
+#include <nuttx/wqueue.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_signal
+ *
+ * Description:
+ * Signal the client that an I/O has completed.
+ *
+ * Input Parameters:
+ * aiocbp - Pointer to the asynchronous I/O state structure that includes
+ * information about how to signal the client
+ *
+ * Returned Value:
+ * Zero (OK) if the client was successfully signalled. Otherwise, a
+ * negated errno value is returned.
+ *
+ ****************************************************************************/
+
+int aio_signal(FAR struct aiocb *aiocbp);
+
+#endif /* __FS_AIO_AIO_H */
diff --git a/nuttx/fs/aio/aio_cancel.c b/nuttx/fs/aio/aio_cancel.c
new file mode 100644
index 000000000..7e6c17d1e
--- /dev/null
+++ b/nuttx/fs/aio/aio_cancel.c
@@ -0,0 +1,167 @@
+/****************************************************************************
+ * fs/aio/aio_cancel.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <aio.h>
+#include <sched.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/wqueue.h>
+
+#include "aio/aio.h"
+
+#ifdef CONFIG_LIBC_AIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_read
+ *
+ * Description:
+ * The aio_cancel() function attempts to cancel one or more asynchronous
+ * I/O requests currently outstanding against file descriptor 'fildes'.
+ * The aiocbp argument points to the asynchronous I/O control block for
+ * a particular request to be cancelled..
+ *
+ * Normal asynchronous notification will occur for asynchronous I/O
+ * operations that are successfully cancelled. If there are requests that
+ * cannot be cancelled, then the normal asynchronous completion process
+ * will take place for those requests when they are completed.
+ *
+ * For requested operations that are successfully cancelled, the associated
+ * error status will be set to ECANCELED and the return status will be -1.
+ * For requested operations that are not successfully cancelled, the aiocbp
+ * will not be modified by aio_cancel().
+ *
+ * Input Parameters:
+ * fildes - Not used in this implmentation
+ * aiocbp - Points to the asynchronous I/O control block for a particular
+ * request to be cancelled.
+ *
+ * Returned Value:
+ * The aio_cancel() function will return the value AIO_CANCELED if the
+ * requested operation(s) were cancelled. The value AIO_NOTCANCELED will
+ * be returned if at least one of the requested operation(s) cannot be
+ * cancelled because it is in progress. In this case, the state of the
+ * other operations, if any, referenced in the call to aio_cancel() is
+ * not indicated by the return value of aio_cancel(). The application
+ * may determine the state of affairs for these operations by using
+ * aio_error(). The value AIO_ALLDONE is returned if all of the
+ * operations have already completed. Otherwise, the function will return
+ * -1 and set errno to indicate the error.
+ *
+ * POSIX Compliance
+ * By standard, this function support the value of NULL for aiocbp. If
+ * aiocbp is NULL, then all outstanding cancelable asynchronous I/O
+ * requests against fildes will be cancelled. In this implementation,
+ * nothing is done if aiocbp is NULL and the fildes parameter is always
+ * ignored. ENOSYS will be returned.
+ *
+ ****************************************************************************/
+
+int aio_cancel(int fildes, FAR struct aiocb *aiocbp)
+{
+ int status;
+ int ret;
+
+ /* Ignore NULL AIO control blocks (see "POSIX Compliance" above) */
+
+ if (aiocbp)
+ {
+ set_errno(ENOSYS);
+ return ERROR;
+ }
+
+ /* Lock the scheduler so that no I/O events can complete on the worker
+ * thread until we set complete this operation.
+ */
+
+ sched_lock();
+
+ /* Check if the I/O has completed */
+
+ if (aiocbp->aio_result == -EINPROGRESS)
+ {
+ /* No ... attempt to cancel the I/O. There are two possibilities: (1)
+ * the work has already been started and is no longer queued, or (2)
+ * the work has not been started and is still in the work queue. Only
+ * the second case can be cancelled. work_cancel() will return
+ * -ENOENT in the first case.
+ */
+
+ status = work_cancel(LPWORK, &aiocbp->aio_work);
+ ret = status >= 0 ? AIO_CANCELED : AIO_NOTCANCELED;
+ }
+ else
+ {
+ /* The I/O has already completed */
+
+ ret = AIO_ALLDONE;
+ }
+
+ sched_unlock();
+ return ret;
+}
+
+#endif /* CONFIG_LIBC_AIO */
diff --git a/nuttx/fs/aio/aio_fsync.c b/nuttx/fs/aio/aio_fsync.c
new file mode 100644
index 000000000..f4441d5df
--- /dev/null
+++ b/nuttx/fs/aio/aio_fsync.c
@@ -0,0 +1,228 @@
+/****************************************************************************
+ * fs/aio/aio_fsync.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <unistd.h>
+#include <aio.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/wqueue.h>
+
+#include "aio/aio.h"
+
+#ifdef CONFIG_LIBC_AIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_fsync_worker
+ *
+ * Description:
+ * This function executes on the worker thread and performs the
+ * asynchronous I/O operation.
+ *
+ * Input Parameters:
+ * arg - Worker argument. In this case, a pointer to an instance of
+ * struct aiocb cast to void *.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void aio_fsync_worker(FAR void *arg)
+{
+ FAR struct aiocb *aiocbp = (FAR struct aiocb *)arg;
+ DEBUGASSERT(arg);
+ int ret;
+
+ /* Perform the fsync using aio_fildes */
+
+ ret = fsync(aiocbp->aio_fildes);
+ if (ret < 0)
+ {
+ int errcode = get_errno();
+ fdbg("ERROR: fsync failed: %d\n", errode);
+ DEBUGASSERT(errcode > 0);
+ aiocbp->aio_result = -errcode;
+ }
+ else
+ {
+ aiocbp->aio_result = OK;
+ }
+
+ /* Signal the client */
+
+ (void)aio_signal(aiocbp);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_fsync
+ *
+ * Description:
+ * The aio_fsync() function asynchronously forces all I/O operations
+ * associated with the file indicated by the file descriptor aio_fildes
+ * member of the aiocb structure referenced by the aiocbp argument and
+ * queued at the time of the call to aio_fsync() to the synchronized
+ * I/O completion state. The function call will return when the
+ * synchronization request has been initiated or queued to the file or
+ * device (even when the data cannot be synchronized immediately).
+ *
+ * If op is O_DSYNC, all currently queued I/O operations will be
+ * completed as if by a call to fdatasync(); that is, as defined for
+ * synchronized I/O data integrity completion. If op is O_SYNC, all
+ * currently queued I/O operations will be completed as if by a call to
+ * fsync(); that is, as defined for synchronized I/O file integrity
+ * completion. If the aio_fsync() function fails, or if the operation
+ * queued by aio_fsync() fails, then, as for fsync() and fdatasync(),
+ * outstanding I/O operations are not guaranteed to have been completed.
+ * [See "POSIX Compliance" below]
+ *
+ * If aio_fsync() succeeds, then it is only the I/O that was queued at
+ * the time of the call to aio_fsync() that is guaranteed to be forced
+ * to the relevant completion state. The completion of subsequent I/O
+ * on the file descriptor is not guaranteed to be completed in a
+ * synchronized fashion.
+ *
+ * The aiocbp argument refers to an asynchronous I/O control block. The
+ * aiocbp value may be used as an argument to aio_error() and aio_return()
+ * in order to determine the error status and return status, respectively,
+ * of the asynchronous operation while it is proceeding. When the request
+ * is queued, the error status for the operation is [EINPROGRESS]. When
+ * all data has been successfully transferred, the error status will be
+ * reset to reflect the success or failure of the operation. If the
+ * operation does not complete successfully, the error status for the
+ * operation will be set to indicate the error. The aio_sigevent member
+ * determines the asynchronous notification to occur when all operations
+ * have achieved synchronized I/O completion. All other members of the
+ * structure referenced by aiocbp are ignored. If the control block
+ * referenced by aiocbp becomes an illegal address prior to asynchronous
+ * I/O completion, then the behavior is undefined.
+ *
+ * If the aio_fsync() function fails or aiocbp indicates an error condition,
+ * data is not guaranteed to have been successfully transferred.
+ *
+ * Input Parameters:
+ * op - Should be either O_SYNC or O_DSYNC. Ignored in this implementation.
+ * aiocbp - A pointer to an instance of struct aiocb
+ *
+ * Returned Value:
+ * The aio_fsync() function will return the value 0 if the I/O operation is
+ * successfully queued; otherwise, the function will return the value -1 and
+ * set errno to indicate the error.
+ *
+ * The aio_fsync() function will fail if:
+ *
+ * EAGAIN - The requested asynchronous operation was not queued due to
+ * temporary resource limitations.
+ * EBADF - The aio_fildes member of the aiocb structure referenced by
+ * the aiocbp argument is not a valid file descriptor open for writing.
+ * EINVAL - This implementation does not support synchronized I/O for
+ * this file.
+ * EINVAL - A value of op other than O_DSYNC or O_SYNC was specified.
+ *
+ * In the event that any of the queued I/O operations fail, aio_fsync()
+ * will return the error condition defined for read() and write(). The
+ * error is returned in the error status for the asynchronous fsync()
+ * operation, which can be retrieved using aio_error().
+ *
+ * POSIX Compliance
+ * - NuttX does not currently make any distinction between O_DYSNC and O_SYNC.
+ * Hence, the 'op' argument is ignored altogether.
+ * - Most errors required in the standard are not detected at this point.
+ * There are no pre-queuing checks for the validity of the operation.
+ *
+ ****************************************************************************/
+
+int aio_fsync(int op, FAR struct aiocb *aiocbp)
+{
+ int ret;
+
+ DEBUGASSERT(op == O_SYNC /* || op == O_DSYNC */);
+ DEBUGASSERT(aiocbp);
+
+ /* The result -EINPROGRESS means that the transfer has not yet completed */
+
+ aiocbp->aio_result = -EINPROGRESS;
+ aiocbp->aio_priv = NULL;
+
+ /* Save the ID of the calling, client thread */
+
+ aiocbp->aio_pid = getpid();
+
+ /* Defer the work to the worker thread */
+
+ ret = work_queue(LPWORK, &aiocbp->aio_work, aio_fsync_worker, aiocbp, 0);
+ if (ret < 0)
+ {
+ aiocbp->aio_result = ret;
+ set_errno(ret);
+ return ERROR;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_LIBC_AIO */
diff --git a/nuttx/fs/aio/aio_read.c b/nuttx/fs/aio/aio_read.c
new file mode 100644
index 000000000..90c6a024a
--- /dev/null
+++ b/nuttx/fs/aio/aio_read.c
@@ -0,0 +1,276 @@
+/****************************************************************************
+ * fs/aio/aio_read.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <unistd.h>
+#include <sched.h>
+#include <aio.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/wqueue.h>
+
+#include "aio/aio.h"
+
+#ifdef CONFIG_LIBC_AIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_read_worker
+ *
+ * Description:
+ * This function executes on the worker thread and performs the
+ * asynchronous I/O operation.
+ *
+ * Input Parameters:
+ * arg - Worker argument. In this case, a pointer to an instance of
+ * struct aiocb cast to void *.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void aio_read_worker(FAR void *arg)
+{
+ FAR struct aiocb *aiocbp = (FAR struct aiocb *)arg;
+ DEBUGASSERT(arg);
+ ssize_t nread;
+
+ /* Perform the read using:
+ *
+ * aio_fildes - File descriptor
+ * 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);
+
+ /* Set the result of the read */
+
+ if (nread < 0)
+ {
+ int errcode = get_errno();
+ fdbg("ERROR: pread failed: %d\n", errode);
+ DEBUGASSERT(errcode > 0);
+ aiocbp->aio_result = -errcode;
+ }
+ else
+ {
+ aiocbp->aio_result = nread;
+ }
+
+ /* Signal the client */
+
+ (void)aio_signal(aiocbp);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_read
+ *
+ * Description:
+ * The aio_read() function reads aiocbp->aio_nbytes from the file
+ * associated with aiocbp->aio_fildes into the buffer pointed to by
+ * aiocbp->aio_buf. The function call will return when the read request
+ * has been initiated or queued to the file or device (even when the data
+ * cannot be delivered immediately).
+ *
+ * The aiocbp value may be used as an argument to aio_error() and
+ * aio_return() in order to determine the error status and return status,
+ * respectively, of the asynchronous operation while it is proceeding. If
+ * an error condition is encountered during queuing, the function call
+ * will return without having initiated or queued the request. The
+ * requested operation takes place at the absolute position in the file as
+ * given by aio_offset, as if lseek() were called immediately prior to the
+ * operation with an offset equal to aio_offset and a whence equal to
+ * SEEK_SET. After a successful call to enqueue an asynchronous I/O
+ * operation, the value of the file offset for the file is unspecified.
+ *
+ * The aiocbp->aio_lio_opcode field will be ignored by aio_read().
+ *
+ * The aiocbp argument points to an aiocb structure. If the buffer pointed
+ * to by aiocbp->aio_buf or the control block pointed to by aiocbp becomes
+ * an illegal address prior to asynchronous I/O completion, then the
+ * behavior is undefined.
+ *
+ * Simultaneous asynchronous operations using the same aiocbp produce
+ * undefined results.
+ *
+ * For any system action that changes the process memory space while an
+ * synchronous I/O is outstanding to the address range being changed, the
+ * result of that action is undefined.
+ *
+ * Input Parameters:
+ * aiocbp - A pointer to an instance of struct aiocb
+ *
+ * Returned Value:
+ *
+ * The aio_read() function will return the value zero if the I/O operation
+ * is successfully queued; otherwise, the function will return the value
+ * -1 and set errno to indicate the error. The aio_read() function will
+ * ail if:
+ *
+ * EAGAIN - The requested asynchronous I/O operation was not queued due to
+ * system resource limitations.
+ *
+ * Each of the following conditions may be detected synchronously at the
+ * time of the call to aio_read(), or asynchronously. If any of the
+ * conditions below are detected synchronously, the aio_read() function
+ * will return -1 and set errno to the corresponding value. If any of the
+ * conditions below are detected asynchronously, the return status of the
+ * asynchronous operation is set to -1, and the error status of the
+ * asynchronous operation is set to the corresponding value.
+ *
+ * EBADF - The aiocbp->aio_fildes argument is not a valid file descriptor
+ * open for reading.
+ * EINVAL - The file offset value implied by aiocbp->aio_offset would be
+ * invalid, aiocbp->aio_reqprio is not a valid value, or
+ * aiocbp->aio_nbytes is an invalid value.
+ *
+ * In the case that the aio_read() successfully queues the I/O operation
+ * but the operation is subsequently cancelled or encounters an error, the
+ * return status of the asynchronous operation is one of the values
+ * normally returned by the read() function call. In addition, the error
+ * status of the asynchronous operation is set to one of the error
+ * statuses normally set by the read() function call, or one of the
+ * following values:
+ *
+ * EBADF - The aiocbp->aio_fildes argument is not a valid file descriptor
+ * open for reading.
+ * ECANCELED - The requested I/O was cancelled before the I/O completed
+ * due to an explicit aio_cancel() request.
+ * EINVAL - The file offset value implied by aiocbp->aio_offset would be
+ * invalid.
+ *
+ * The following condition may be detected synchronously or asynchronously:
+ *
+ * EOVERFLOW - The file is a regular file, aiobcp->aio_nbytes is greater
+ * than 0, and the starting offset in aiobcp->aio_offset is before the
+ * end-of-file and is at or beyond the offset maximum in the open file
+ * description associated with aiocbp->aio_fildes.
+ *
+ * POSIX Compliance:
+ * - The POSIX specification of asynchronous I/O implies that a thread is
+ * created for each I/O operation. The standard requires that if
+ * prioritized I/O is supported for this file, then the asynchronous
+ * operation will be submitted at a priority equal to a base scheduling
+ * priority minus aiocbp->aio_reqprio. If Thread Execution Scheduling is
+ * not supported, then the base scheduling priority is that of the calling
+ * thread.
+ *
+ * My initial gut feeling is the creating a new thread on each asynchronous
+ * I/O operation would not be a good use of resources in a deeply embedded
+ * system. So I decided to execute all asynchronous I/O on a low-priority
+ * or user-space worker thread. There are two negative consequences of this
+ * decision that need to be revisited:
+ *
+ * 1) The worker thread runs at a fixed priority making it impossible to
+ * meet the POSIX requirement for asynchronous I/O. That standard
+ * specifically requires varying priority.
+ * 2) On the worker thread, each I/O will still be performed synchronously,
+ * one at a time. This is not a violation of the POSIX requirement,
+ * but one would think there could be opportunities for concurrent I/O.
+ *
+ * In reality, in a small embedded system, there will probably only be one
+ * real file system and, in this case, the I/O will be performed sequentially
+ * anyway. Most simple embedded hardware will not support any concurrent
+ * accesses.
+ *
+ * - Most errors required in the standard are not detected at this point.
+ * There are no pre-queuing checks for the validity of the operation.
+ *
+ ****************************************************************************/
+
+int aio_read(FAR struct aiocb *aiocbp)
+{
+ int ret;
+
+ DEBUGASSERT(aiocbp);
+
+ /* The result -EINPROGRESS means that the transfer has not yet completed */
+
+ aiocbp->aio_result = -EINPROGRESS;
+ aiocbp->aio_priv = NULL;
+
+ /* Save the ID of the calling, client thread */
+
+ aiocbp->aio_pid = getpid();
+
+ /* Defer the work to the worker thread */
+
+ ret = work_queue(LPWORK, &aiocbp->aio_work, aio_read_worker, aiocbp, 0);
+ if (ret < 0)
+ {
+ aiocbp->aio_result = ret;
+ set_errno(ret);
+ return ERROR;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_LIBC_AIO */
diff --git a/nuttx/fs/aio/aio_signal.c b/nuttx/fs/aio/aio_signal.c
new file mode 100644
index 000000000..60cb0be77
--- /dev/null
+++ b/nuttx/fs/aio/aio_signal.c
@@ -0,0 +1,148 @@
+/****************************************************************************
+ * fs/aio/aio_signal.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sched.h>
+#include <signal.h>
+#include <aio.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "aio/aio.h"
+
+#ifdef CONFIG_LIBC_AIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: aio_signal
+ *
+ * Description:
+ * Signal the client that an I/O has completed.
+ *
+ * Input Parameters:
+ * aiocbp - Pointer to the asynchronous I/O state structure that includes
+ * information about how to signal the client
+ *
+ * Returned Value:
+ * Zero (OK) if the client was successfully signalled. Otherwise, a
+ * negated errno value is returned.
+ *
+ * Assumptions:
+ * This function runs only in the context of the worker thread.
+ *
+ ****************************************************************************/
+
+int aio_signal(FAR struct aiocb *aiocbp)
+{
+ int errcode;
+ int status;
+ int ret;
+
+ DEBUGASSERT(aiocbp);
+
+ ret = OK; /* Assume success */
+
+ /* Signal the client */
+
+ if (aiocbp->aio_sigevent.sigev_notify == SIGEV_SIGNAL)
+ {
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ status = sigqueue(aiocbp->aio_pid, aiocbp->aio_sigevent.sigev_signo,
+ aiocbp->aio_sigevent.sigev_value);
+#else
+ status = sigqueue(aiocbp->aio_pid, aiocbp->aio_sigevent.sigev_sign,
+ aiocbp->aio_sigevent.sigev_value.sival_ptr);
+#endif
+ if (ret < 0)
+ {
+ errcode = get_errno();
+ fdbg("ERROR: sigqueue failed: %d\n", errcode);
+ ret = ERROR;
+ }
+ }
+
+ /* Send the poll signal in any event in case the caller is waiting
+ * on sig_suspend();
+ */
+
+ status = kill(aiocbp->aio_pid, SIGPOLL);
+ if (status && ret == OK)
+ {
+ errcode = get_errno();
+ fdbg("ERROR: kill failed: %d\n", errcode);
+ ret = ERROR;
+ }
+
+ /* Make sure that errno is set correctly on return */
+
+ if (ret < 0)
+ {
+ set_errno(errcode);
+ return ERROR;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_LIBC_AIO */
diff --git a/nuttx/fs/aio/aio_write.c b/nuttx/fs/aio/aio_write.c
new file mode 100644
index 000000000..51a470964
--- /dev/null
+++ b/nuttx/fs/aio/aio_write.c
@@ -0,0 +1,307 @@
+/****************************************************************************
+ * fs/aio/aio_write.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <unistd.h>
+#include <fcntl.h>
+#include <sched.h>
+#include <aio.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/wqueue.h>
+
+#include "aio/aio.h"
+
+#ifdef CONFIG_LIBC_AIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_write_worker
+ *
+ * Description:
+ * This function executes on the worker thread and performs the
+ * asynchronous I/O operation.
+ *
+ * Input Parameters:
+ * arg - Worker argument. In this case, a pointer to an instance of
+ * struct aiocb cast to void *.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void aio_write_worker(FAR void *arg)
+{
+ FAR struct aiocb *aiocbp = (FAR struct aiocb *)arg;
+ DEBUGASSERT(arg);
+ ssize_t nwritten;
+ int oflags;
+
+ /* Call fcntl(F_GETFL) to get the file open mode. */
+
+ oflags = fcntl(aiocbp->aio_fildes, F_GETFL);
+ if (oflags < 0)
+ {
+ int errcode = get_errno();
+ fdbg("ERROR: fcntl failed: %d\n", errode);
+ aiocbp->aio_result = -errcode;
+ }
+ else
+ {
+ /* Perform the write using:
+ *
+ * aio_fildes - File descriptor
+ * aio_buf - Location of buffer
+ * aio_nbytes - Length of transfer
+ * aio_offset - File offset
+ */
+
+ /* Check if O_APPEND is set in the file open flags */
+
+ if ((oflags & O_APPEND) != 0)
+ {
+ /* Append to the current file position */
+
+ nwritten = write(aiocbp->aio_fildes,
+ (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);
+ }
+
+ /* Set the result of the write */
+
+ if (nwritten < 0)
+ {
+ int errcode = get_errno();
+ fdbg("ERROR: write/pwrite failed: %d\n", errode);
+ DEBUGASSERT(errcode > 0);
+ aiocbp->aio_result = -errcode;
+ }
+ else
+ {
+ aiocbp->aio_result = nwritten;
+ }
+ }
+
+ /* Signal the client */
+
+ (void)aio_signal(aiocbp);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_write
+ *
+ * Description:
+ * The aio_write() function writes aiocbp->aio_nbytes to the file
+ * associated with aiocbp->aio_fildes from the buffer pointed to by
+ * aiocbp->aio_buf. The function call will return when the write request
+ * has been initiated or queued to the file or device (even when the data
+ * cannot be delivered immediately).
+ *
+ * The aiocbp value may be used as an argument to aio_error() and
+ * aio_return() in order to determine the error status and return status,
+ * respectively, of the asynchronous operation while it is proceeding.
+ *
+ * The aiocbp argument points to an aiocb structure. If the buffer pointed
+ * to by aiocbp->aio_buf or the control block pointed to by aiocbp becomes
+ * an illegal address prior to asynchronous I/O completion, then the
+ * behavior is undefined.
+ *
+ * If O_APPEND is not set for the file descriptor aio_fildes, then the
+ * requested operation will take place at the absolute position in the file
+ * as given by aio_offset, as if lseek() were called immediately prior to the
+ * operation with an offset equal to aio_offset and a whence equal to SEEK_SET.
+ * If O_APPEND is set for the file descriptor, write operations append to the
+ * file in the same order as the calls were made. After a successful call to
+ * enqueue an asynchronous I/O operation, the value of the file offset for the
+ * file is unspecified.
+ *
+ * The aiocbp->aio_lio_opcode field will be ignored by aio_write().
+ *
+ * Simultaneous asynchronous operations using the same aiocbp produce
+ * undefined results.
+ *
+ * For any system action that changes the process memory space while an
+ * synchronous I/O is outstanding to the address range being changed, the
+ * result of that action is undefined.
+ *
+ * Input Parameters:
+ * aiocbp - A pointer to an instance of struct aiocb
+ *
+ * Returned Value:
+ *
+ * The aio_write() function will return the value zero if the I/O operation
+ * is successfully queued; otherwise, the function will return the value
+ * -1 and set errno to indicate the error. The aio_write() function will
+ * ail if:
+ *
+ * EAGAIN - The requested asynchronous I/O operation was not queued due to
+ * system resource limitations.
+ *
+ * Each of the following conditions may be detected synchronously at the
+ * time of the call to aio_write(), or asynchronously. If any of the
+ * conditions below are detected synchronously, the aio_write() function
+ * will return -1 and set errno to the corresponding value. If any of the
+ * conditions below are detected asynchronously, the return status of the
+ * asynchronous operation is set to -1, and the error status of the
+ * asynchronous operation is set to the corresponding value.
+ *
+ * EBADF - The aiocbp->aio_fildes argument is not a valid file descriptor
+ * open for writing.
+ * EINVAL - The file offset value implied by aiocbp->aio_offset would be
+ * invalid, aiocbp->aio_reqprio is not a valid value, or
+ * aiocbp->aio_nbytes is an invalid value.
+ *
+ * In the case that the aio_write() successfully queues the I/O operation
+ * but the operation is subsequently cancelled or encounters an error, the
+ * return status of the asynchronous operation is one of the values
+ * normally returned by the write() function call. In addition, the error
+ * status of the asynchronous operation is set to one of the error
+ * statuses normally set by the write() function call, or one of the
+ * following values:
+ *
+ * EBADF - The aiocbp->aio_fildes argument is not a valid file descriptor
+ * open for writing.
+ * EINVAL - The file offset value implied by aiocbp->aio_offset would be
+ * invalid.
+ * ECANCELED - The requested I/O was cancelled before the I/O completed
+ * due to an explicit aio_cancel() request.
+ *
+ * The following condition may be detected synchronously or asynchronously:
+ *
+ * EFBIG - The file is a regular file, aiobcp->aio_nbytes is greater
+ * than 0, and the starting offset in aiobcp->aio_offset is at or
+ * beyond the offset maximum in the open file description associated
+ * with aiocbp->aio_fildes.
+ *
+ * POSIX Compliance:
+ * - The POSIX specification of asynchronous I/O implies that a thread is
+ * created for each I/O operation. The standard requires that if
+ * prioritized I/O is supported for this file, then the asynchronous
+ * operation will be submitted at a priority equal to a base scheduling
+ * priority minus aiocbp->aio_reqprio. If Thread Execution Scheduling is
+ * not supported, then the base scheduling priority is that of the calling
+ * thread.
+ *
+ * My initial gut feeling is the creating a new thread on each asynchronous
+ * I/O operation would not be a good use of resources in a deeply embedded
+ * system. So I decided to execute all asynchronous I/O on a low-priority
+ * or user-space worker thread. There are two negative consequences of this
+ * decision that need to be revisited:
+ *
+ * 1) The worker thread runs at a fixed priority making it impossible to
+ * meet the POSIX requirement for asynchronous I/O. That standard
+ * specifically requires varying priority.
+ * 2) On the worker thread, each I/O will still be performed synchronously,
+ * one at a time. This is not a violation of the POSIX requirement,
+ * but one would think there could be opportunities for concurrent I/O.
+ *
+ * In reality, in a small embedded system, there will probably only be one
+ * real file system and, in this case, the I/O will be performed sequentially
+ * anyway. Most simple embedded hardware will not support any concurrent
+ * accesses.
+ *
+ * - Most errors required in the standard are not detected at this point.
+ * There are no pre-queuing checks for the validity of the operation.
+ *
+ ****************************************************************************/
+
+int aio_write(FAR struct aiocb *aiocbp)
+{
+ int ret;
+
+ DEBUGASSERT(aiocbp);
+
+ /* The result -EINPROGRESS means that the transfer has not yet completed */
+
+ aiocbp->aio_result = -EINPROGRESS;
+ aiocbp->aio_priv = NULL;
+
+ /* Save the ID of the calling, client thread */
+
+ aiocbp->aio_pid = getpid();
+
+ /* Defer the work to the worker thread */
+
+ ret = work_queue(LPWORK, &aiocbp->aio_work, aio_write_worker, aiocbp, 0);
+ if (ret < 0)
+ {
+ aiocbp->aio_result = ret;
+ set_errno(ret);
+ return ERROR;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_LIBC_AIO */