summaryrefslogtreecommitdiff
path: root/nuttx/fs
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-10-07 08:24:50 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-10-07 08:24:50 -0600
commitd1348ca8c0212943ce01e255e621013fb8f6a2bf (patch)
tree867be0eda197bae60fd4cb04622c303ead20f080 /nuttx/fs
parent5550f5f3caaf93a780f59af88050112bb9afb151 (diff)
downloadpx4-nuttx-d1348ca8c0212943ce01e255e621013fb8f6a2bf.tar.gz
px4-nuttx-d1348ca8c0212943ce01e255e621013fb8f6a2bf.tar.bz2
px4-nuttx-d1348ca8c0212943ce01e255e621013fb8f6a2bf.zip
The Asynch I/O implementation now satisfies POSIX priority requirements; it uses the new low priority worker thread interfaces to adjust the priority of the worker thread according to the priority of the client thread
Diffstat (limited to 'nuttx/fs')
-rw-r--r--nuttx/fs/aio/Make.defs4
-rw-r--r--nuttx/fs/aio/aio.h20
-rw-r--r--nuttx/fs/aio/aio_fsync.c19
-rw-r--r--nuttx/fs/aio/aio_queue.c126
-rw-r--r--nuttx/fs/aio/aio_read.c20
-rw-r--r--nuttx/fs/aio/aio_write.c20
6 files changed, 193 insertions, 16 deletions
diff --git a/nuttx/fs/aio/Make.defs b/nuttx/fs/aio/Make.defs
index 46a747707..9f30f24e1 100644
--- a/nuttx/fs/aio/Make.defs
+++ b/nuttx/fs/aio/Make.defs
@@ -37,8 +37,8 @@ ifeq ($(CONFIG_FS_AIO),y)
# Add the asynchronous I/O C files to the build
-CSRCS += aio_cancel.c aioc_contain.c aio_fsync.c aio_initialize.c aio_read.c
-CSRCS += aio_signal.c aio_write.c
+CSRCS += aio_cancel.c aioc_contain.c aio_fsync.c aio_initialize.c
+CSRCS += aio_queue.c aio_read.c aio_signal.c aio_write.c
# Add the asynchronous I/O directory to the build
diff --git a/nuttx/fs/aio/aio.h b/nuttx/fs/aio/aio.h
index 54bfe03e1..85a5161cb 100644
--- a/nuttx/fs/aio/aio.h
+++ b/nuttx/fs/aio/aio.h
@@ -76,7 +76,9 @@ struct aio_container_s
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 */
+#ifdef CONFIG_PRIORITY_INHERITANCE
uint8_t aioc_prio; /* Priority of the waiting task */
+#endif
};
/****************************************************************************
@@ -212,6 +214,24 @@ FAR struct aio_container_s *aio_contain(FAR struct aiocb *aiocbp);
FAR struct aiocb *aioc_decant(FAR struct aio_container_s *aioc);
/****************************************************************************
+ * Name: aio_queue
+ *
+ * Description:
+ * Schedule the asynchronous I/O on the low priority work queue
+ *
+ * Input Parameters:
+ * arg - Worker argument. In this case, a pointer to an instance of
+ * struct aiocb cast to void *.
+ *
+ * Returned Value:
+ * Zero (OK) on success. Otherwise, -1 is returned and the errno is set
+ * appropriately.
+ *
+ ****************************************************************************/
+
+int aio_queue(FAR struct aio_container_s *aioc, worker_t worker);
+
+/****************************************************************************
* Name: aio_signal
*
* Description:
diff --git a/nuttx/fs/aio/aio_fsync.c b/nuttx/fs/aio/aio_fsync.c
index 2c92a7a56..8aed8bdd1 100644
--- a/nuttx/fs/aio/aio_fsync.c
+++ b/nuttx/fs/aio/aio_fsync.c
@@ -46,7 +46,6 @@
#include <errno.h>
#include <debug.h>
-#include <nuttx/wqueue.h>
#include <nuttx/fs/fs.h>
#include "aio/aio.h"
@@ -94,6 +93,9 @@ static void aio_fsync_worker(FAR void *arg)
FAR struct aio_container_s *aioc = (FAR struct aio_container_s *)arg;
FAR struct aiocb *aiocbp;
pid_t pid;
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ uint8_t prio;
+#endif
int ret;
/* Get the information from the container, decant the AIO control block,
@@ -103,6 +105,9 @@ static void aio_fsync_worker(FAR void *arg)
DEBUGASSERT(aioc && aioc->aioc_aiocbp);
pid = aioc->aioc_pid;
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ prio = aioc->aioc_prio;
+#endif
aiocbp = aioc_decant(aioc);
/* Perform the fsync using aioc_filep */
@@ -123,6 +128,12 @@ static void aio_fsync_worker(FAR void *arg)
/* Signal the client */
(void)aio_signal(pid, aiocbp);
+
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ /* Restore the low priority worker thread default priority */
+
+ lpwork_restorepriority(prio);
+#endif
}
/****************************************************************************
@@ -235,11 +246,11 @@ int aio_fsync(int op, FAR struct aiocb *aiocbp)
/* Defer the work to the worker thread */
- ret = work_queue(LPWORK, &aioc->aioc_work, aio_fsync_worker, aioc, 0);
+ ret = aio_queue(aioc, aio_fsync_worker);
if (ret < 0)
{
- aiocbp->aio_result = ret;
- set_errno(ret);
+ /* The result and the errno have already been set */
+
return ERROR;
}
diff --git a/nuttx/fs/aio/aio_queue.c b/nuttx/fs/aio/aio_queue.c
new file mode 100644
index 000000000..34cb31df0
--- /dev/null
+++ b/nuttx/fs/aio/aio_queue.c
@@ -0,0 +1,126 @@
+/****************************************************************************
+ * fs/aio/aio_queue.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 <aio.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/wqueue.h>
+
+#include "aio/aio.h"
+
+#ifdef CONFIG_FS_AIO
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: aio_queue
+ *
+ * Description:
+ * Schedule the asynchronous I/O on the low priority work queue
+ *
+ * Input Parameters:
+ * arg - Worker argument. In this case, a pointer to an instance of
+ * struct aiocb cast to void *.
+ *
+ * Returned Value:
+ * Zero (OK) on success. Otherwise, -1 is returned and the errno is set
+ * appropriately.
+ *
+ ****************************************************************************/
+
+int aio_queue(FAR struct aio_container_s *aioc, worker_t worker)
+{
+ int ret;
+
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ /* Prohibit context switches until we complete the queuing */
+
+ sched_lock();
+
+ /* Make sure that the low-priority worker thread is running at at least
+ * the priority specified for this action.
+ */
+
+ lpwork_boostpriority(aioc->aioc_prio);
+#endif
+
+ /* Schedule the work on the low priority worker thread */
+
+ ret = work_queue(LPWORK, &aioc->aioc_work, worker, aioc, 0);
+ if (ret < 0)
+ {
+ FAR struct aiocb *aiocbp = aioc->aioc_aiocbp;
+ DEBUGASSERT(aiocbp);
+
+ aiocbp->aio_result = ret;
+ set_errno(-ret);
+ ret = ERROR;
+ }
+
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ /* Now the low-priority work queue might run at its new priority */
+
+ sched_unlock();
+#endif
+ return ret;
+}
+
+#endif /* CONFIG_FS_AIO */
diff --git a/nuttx/fs/aio/aio_read.c b/nuttx/fs/aio/aio_read.c
index 5ee7db119..a4982532b 100644
--- a/nuttx/fs/aio/aio_read.c
+++ b/nuttx/fs/aio/aio_read.c
@@ -46,8 +46,6 @@
#include <errno.h>
#include <debug.h>
-#include <nuttx/wqueue.h>
-
#include "aio/aio.h"
#ifdef CONFIG_FS_AIO
@@ -93,6 +91,9 @@ static void aio_read_worker(FAR void *arg)
FAR struct aio_container_s *aioc = (FAR struct aio_container_s *)arg;
FAR struct aiocb *aiocbp;
pid_t pid;
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ uint8_t prio;
+#endif
ssize_t nread;
/* Get the information from the container, decant the AIO control block,
@@ -102,6 +103,9 @@ static void aio_read_worker(FAR void *arg)
DEBUGASSERT(aioc && aioc->aioc_aiocbp);
pid = aioc->aioc_pid;
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ prio = aioc->aioc_prio;
+#endif
aiocbp = aioc_decant(aioc);
/* Perform the read using:
@@ -132,6 +136,12 @@ static void aio_read_worker(FAR void *arg)
/* Signal the client */
(void)aio_signal(pid, aiocbp);
+
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ /* Restore the low priority worker thread default priority */
+
+ lpwork_restorepriority(prio);
+#endif
}
/****************************************************************************
@@ -281,11 +291,11 @@ int aio_read(FAR struct aiocb *aiocbp)
/* Defer the work to the worker thread */
- ret = work_queue(LPWORK, &aioc->aioc_work, aio_read_worker, aioc, 0);
+ ret = aio_queue(aioc, aio_read_worker);
if (ret < 0)
{
- aiocbp->aio_result = ret;
- set_errno(ret);
+ /* The result and the errno have already been set */
+
return ERROR;
}
diff --git a/nuttx/fs/aio/aio_write.c b/nuttx/fs/aio/aio_write.c
index 86f45c61d..db1daa2c6 100644
--- a/nuttx/fs/aio/aio_write.c
+++ b/nuttx/fs/aio/aio_write.c
@@ -48,8 +48,6 @@
#include <errno.h>
#include <debug.h>
-#include <nuttx/wqueue.h>
-
#include "aio/aio.h"
#ifdef CONFIG_FS_AIO
@@ -110,6 +108,9 @@ static void aio_write_worker(FAR void *arg)
FAR struct aio_container_s *aioc = (FAR struct aio_container_s *)arg;
FAR struct aiocb *aiocbp;
pid_t pid;
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ uint8_t prio;
+#endif
ssize_t nwritten;
int oflags;
@@ -120,6 +121,9 @@ static void aio_write_worker(FAR void *arg)
DEBUGASSERT(aioc && aioc->aioc_aiocbp);
pid = aioc->aioc_pid;
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ prio = aioc->aioc_prio;
+#endif
aiocbp = aioc_decant(aioc);
/* Call fcntl(F_GETFL) to get the file open mode. */
@@ -177,6 +181,12 @@ static void aio_write_worker(FAR void *arg)
/* Signal the client */
(void)aio_signal(pid, aiocbp);
+
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ /* Restore the low priority worker thread default priority */
+
+ lpwork_restorepriority(prio);
+#endif
}
/****************************************************************************
@@ -328,11 +338,11 @@ int aio_write(FAR struct aiocb *aiocbp)
/* Defer the work to the worker thread */
- ret = work_queue(LPWORK, &aioc->aioc_work, aio_write_worker, aioc, 0);
+ ret = aio_queue(aioc, aio_write_worker);
if (ret < 0)
{
- aiocbp->aio_result = ret;
- set_errno(ret);
+ /* The result and the errno have already been set */
+
return ERROR;
}