summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-10-10 14:52:04 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-10-10 14:52:04 -0600
commita55c76b88fc937600c55d12b86f8e475ffb844b3 (patch)
tree946708e432ec06b2650c6b3b2c18975fa51303a8
parentf1ce005747fef1426ddc6a6564e78429afd66455 (diff)
downloadpx4-nuttx-a55c76b88fc937600c55d12b86f8e475ffb844b3.tar.gz
px4-nuttx-a55c76b88fc937600c55d12b86f8e475ffb844b3.tar.bz2
px4-nuttx-a55c76b88fc937600c55d12b86f8e475ffb844b3.zip
User-mode work queue logic should not disable interrupts
-rw-r--r--nuttx/include/nuttx/wqueue.h36
-rw-r--r--nuttx/libc/Kconfig2
-rw-r--r--nuttx/libc/wqueue/Make.defs22
-rw-r--r--nuttx/libc/wqueue/work_cancel.c26
-rw-r--r--nuttx/libc/wqueue/work_lock.c139
-rw-r--r--nuttx/libc/wqueue/work_queue.c38
-rw-r--r--nuttx/libc/wqueue/work_signal.c7
-rw-r--r--nuttx/libc/wqueue/work_usrthread.c291
-rw-r--r--nuttx/libc/wqueue/wqueue.h53
-rw-r--r--nuttx/sched/wqueue/Make.defs2
-rw-r--r--nuttx/sched/wqueue/kwork_cancel.c57
-rw-r--r--nuttx/sched/wqueue/kwork_process.c (renamed from nuttx/libc/wqueue/work_process.c)2
-rw-r--r--nuttx/sched/wqueue/kwork_queue.c61
-rw-r--r--nuttx/sched/wqueue/wqueue.h19
14 files changed, 654 insertions, 101 deletions
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
index 918a25afe..b2d51cb0f 100644
--- a/nuttx/include/nuttx/wqueue.h
+++ b/nuttx/include/nuttx/wqueue.h
@@ -340,25 +340,6 @@ extern "C"
****************************************************************************/
/****************************************************************************
- * Name: work_process
- *
- * Description:
- * This is the logic that performs actions placed on any work list. This
- * logic is the common underlying logic to all work queues. This logic is
- * part of the internal implementation of each work queue; it should not
- * be called from application level logic.
- *
- * Input parameters:
- * wqueue - Describes the work queue to be processed
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-void work_process(FAR struct wqueue_s *wqueue);
-
-/****************************************************************************
* Name: work_usrstart
*
* Description:
@@ -378,7 +359,7 @@ int work_usrstart(void);
#endif
/****************************************************************************
- * Name: work_queue and work_qqueue
+ * Name: work_queue
*
* Description:
* Queue work to be performed at a later time. All queued work will be
@@ -391,11 +372,6 @@ int work_usrstart(void);
* from the queue, or (2) work_cancel() has been called to cancel the work
* and remove it from the work queue.
*
- * work_queue() is the application interface. It simply maps the qid to
- * the correct work queue and calls work_qqueue().
- * work_qqueue() is the common cancellation logic that operates on the
- * particular work queue selected by work_queue().
- *
* Input parameters:
* qid - The work queue ID
* work - The work structure to queue
@@ -413,22 +389,15 @@ int work_usrstart(void);
int work_queue(int qid, FAR struct work_s *work, worker_t worker,
FAR void *arg, uint32_t delay);
-int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
- worker_t worker, FAR void *arg, uint32_t delay);
/****************************************************************************
- * Name: work_cancel and work_qcancel;
+ * Name: work_cancel
*
* Description:
* Cancel previously queued work. This removes work from the work queue.
* After work has been cancelled, it may be re-queue by calling work_queue()
* again.
*
- * work_cancel() is the application interface. It simply maps the qid to
- * the correct work queue and calls work_qcancel().
- * work_qcancel() is the common cancellation logic that operates on the
- * particular work queue selected by work_cancel().
- *
* Input parameters:
* qid - The work queue ID
* work - The previously queue work structure to cancel
@@ -441,7 +410,6 @@ int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
*
****************************************************************************/
-int work_qcancel(FAR struct wqueue_s *wqueue, FAR struct work_s *work);
int work_cancel(int qid, FAR struct work_s *work);
/****************************************************************************
diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig
index d899bae0d..76ece0222 100644
--- a/nuttx/libc/Kconfig
+++ b/nuttx/libc/Kconfig
@@ -540,7 +540,7 @@ config SCHED_LPWORKSTACKSIZE
endif # SCHED_LPWORK
-if BUILD_PROTECTED
+if BUILD_PROTECTED || BUILD_KERNEL
config SCHED_USRWORK
bool "User mode worker thread"
diff --git a/nuttx/libc/wqueue/Make.defs b/nuttx/libc/wqueue/Make.defs
index 2b953626e..36a2ccc98 100644
--- a/nuttx/libc/wqueue/Make.defs
+++ b/nuttx/libc/wqueue/Make.defs
@@ -37,15 +37,25 @@ ifeq ($(CONFIG_SCHED_WORKQUEUE),y)
# Add the work queue C files to the build
-CSRCS += work_process.c work_queue.c work_cancel.c work_signal.c
+WORK_CSRCS += work_usrthread.c work_queue.c work_cancel.c work_signal.c
+WORK_CSRCS += work_lock.c
+
+# Protected mode
ifeq ($(CONFIG_BUILD_PROTECTED),y)
-CSRCS += work_usrthread.c
+CSRCS += $(WORK_CSRCS)
+
+# Add the wqueue directory to the build
+
+DEPPATH += --dep-path wqueue
+VPATH += :wqueue
+
else
+
+# Kernel mode
+
ifeq ($(CONFIG_BUILD_KERNEL),y)
-CSRCS += work_usrthread.c
-endif
-endif
+CSRCS += $(WORK_CSRCS)
# Add the wqueue directory to the build
@@ -53,3 +63,5 @@ DEPPATH += --dep-path wqueue
VPATH += :wqueue
endif
+endif
+endif
diff --git a/nuttx/libc/wqueue/work_cancel.c b/nuttx/libc/wqueue/work_cancel.c
index 9484918c5..fa04f6ca9 100644
--- a/nuttx/libc/wqueue/work_cancel.c
+++ b/nuttx/libc/wqueue/work_cancel.c
@@ -48,7 +48,8 @@
#include "wqueue/wqueue.h"
-#ifdef CONFIG_SCHED_WORKQUEUE
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK) && \
+ !defined(__KERNEL__)
/****************************************************************************
* Pre-processor Definitions
@@ -71,10 +72,6 @@
****************************************************************************/
/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
* Name: work_qcancel
*
* Description:
@@ -95,19 +92,21 @@
*
****************************************************************************/
-int work_qcancel(FAR struct wqueue_s *wqueue, FAR struct work_s *work)
+static int work_qcancel(FAR struct wqueue_s *wqueue, FAR struct work_s *work)
{
- irqstate_t flags;
int ret = -ENOENT;
DEBUGASSERT(work != NULL);
+ /* Get exclusive access to the work queue */
+
+ while (work_lock() < 0);
+
/* Cancelling the work is simply a matter of removing the work structure
* from the work queue. This must be done with interrupts disabled because
* new work is typically added to the work queue from interrupt handlers.
*/
- flags = irqsave();
if (work->worker != NULL)
{
/* A little test of the integrity of the work queue */
@@ -124,11 +123,15 @@ int work_qcancel(FAR struct wqueue_s *wqueue, FAR struct work_s *work)
ret = OK;
}
- irqrestore(flags);
+ work_unlock();
return ret;
}
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: work_cancel
*
* Description:
@@ -148,8 +151,6 @@ int work_qcancel(FAR struct wqueue_s *wqueue, FAR struct work_s *work)
*
****************************************************************************/
-#if defined(CONFIG_SCHED_USRWORK) && !defined(__KERNEL__)
-
int work_cancel(int qid, FAR struct work_s *work)
{
if (qid == USRWORK)
@@ -162,5 +163,4 @@ int work_cancel(int qid, FAR struct work_s *work)
}
}
-#endif /* CONFIG_SCHED_USRWORK && !__KERNEL__ */
-#endif /* CONFIG_SCHED_WORKQUEUE */
+#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_USRWORK && !__KERNEL__ */
diff --git a/nuttx/libc/wqueue/work_lock.c b/nuttx/libc/wqueue/work_lock.c
new file mode 100644
index 000000000..8c39a2bbb
--- /dev/null
+++ b/nuttx/libc/wqueue/work_lock.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * libc/wqueue/work_lock.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 <pthread.h>
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+
+#include "wqueue/wqueue.h"
+
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK) && \
+ !defined(__KERNEL__)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: work_lock
+ *
+ * Description:
+ * Lock the user-mode work queue.
+ *
+ * Input parameters:
+ * None
+ *
+ * Returned Value:
+ * Zero (OK) on success, a negated errno on failure. This error may be
+ * reported:
+ *
+ * -EINTR - Wait was interrupted by a signal
+ *
+ ****************************************************************************/
+
+int work_lock(void)
+{
+ int ret;
+
+#ifdef CONFIG_BUILD_PROTECTED
+ int ret = sem_wait(&g_usrsem);
+ if (ret < 0)
+ {
+ DEBUGASSERT(errno == EINTR);
+ return -EINTR;
+ }
+#else
+ ret = pthread_mutex_lock(&g_usrmutex);
+ if (ret != 0)
+ {
+ DEBUGASSERT(ret == EINTR);
+ return -EINTR;
+ }
+#endif
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: work_unlock
+ *
+ * Description:
+ * Unlock the user-mode work queue.
+ *
+ * Input parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void work_unlock(void)
+{
+#ifdef CONFIG_BUILD_PROTECTED
+ (void)sem_post(&g_usrsem);
+#else
+ (void)pthread_mutex_unlock(&g_usrmutex);
+#endif
+}
+
+#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_USRWORK && !__KERNEL__*/
diff --git a/nuttx/libc/wqueue/work_queue.c b/nuttx/libc/wqueue/work_queue.c
index 3abba1599..a17d8d14b 100644
--- a/nuttx/libc/wqueue/work_queue.c
+++ b/nuttx/libc/wqueue/work_queue.c
@@ -40,17 +40,18 @@
#include <nuttx/config.h>
#include <stdint.h>
-#include <queue.h>
+#include <signal.h>
#include <assert.h>
+#include <queue.h>
#include <errno.h>
-#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <nuttx/wqueue.h>
#include "wqueue/wqueue.h"
-#ifdef CONFIG_SCHED_WORKQUEUE
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK) && \
+ !defined(__KERNEL__)
/****************************************************************************
* Pre-processor Definitions
@@ -73,10 +74,6 @@
****************************************************************************/
/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
* Name: work_qqueue
*
* Description:
@@ -105,11 +102,9 @@
*
****************************************************************************/
-int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
- worker_t worker, FAR void *arg, uint32_t delay)
+static int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
+ worker_t worker, FAR void *arg, uint32_t delay)
{
- irqstate_t flags;
-
DEBUGASSERT(work != NULL);
/* First, initialize the work structure */
@@ -118,22 +113,26 @@ int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
work->arg = arg; /* Callback argument */
work->delay = delay; /* Delay until work performed */
- /* Now, time-tag that entry and put it in the work queue. This must be
- * done with interrupts disabled. This permits this function to be called
- * from with task logic or interrupt handlers.
- */
+ /* Get exclusive access to the work queue */
+
+ while (work_lock() < 0);
+
+ /* Now, time-tag that entry and put it in the work queue. */
- flags = irqsave();
work->qtime = clock_systimer(); /* Time work queued */
dq_addlast((FAR dq_entry_t *)work, &wqueue->q);
kill(wqueue->pid[0], SIGWORK); /* Wake up the worker thread */
- irqrestore(flags);
+ work_unlock();
return OK;
}
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Name: work_queue
*
* Description:
@@ -162,8 +161,6 @@ int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
*
****************************************************************************/
-#if defined(CONFIG_SCHED_USRWORK) && !defined(__KERNEL__)
-
int work_queue(int qid, FAR struct work_s *work, worker_t worker,
FAR void *arg, uint32_t delay)
{
@@ -177,5 +174,4 @@ int work_queue(int qid, FAR struct work_s *work, worker_t worker,
}
}
-#endif /* CONFIG_SCHED_USRWORK && !__KERNEL__ */
-#endif /* CONFIG_SCHED_WORKQUEUE */
+#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_USRWORK && !__KERNEL__ */
diff --git a/nuttx/libc/wqueue/work_signal.c b/nuttx/libc/wqueue/work_signal.c
index 288c89877..813b9e8d6 100644
--- a/nuttx/libc/wqueue/work_signal.c
+++ b/nuttx/libc/wqueue/work_signal.c
@@ -40,6 +40,7 @@
#include <nuttx/config.h>
#include <signal.h>
+#include <errno.h>
#include <nuttx/wqueue.h>
@@ -100,13 +101,15 @@ int work_signal(int qid)
if (ret < 0)
{
int errcode = errno;
- return -errcode;
+ ret = -errcode;
}
}
else
{
- return -EINVAL;
+ ret = -EINVAL;
}
+
+ return ret;
}
#endif /* CONFIG_SCHED_USRWORK && !__KERNEL__ */
diff --git a/nuttx/libc/wqueue/work_usrthread.c b/nuttx/libc/wqueue/work_usrthread.c
index dfa67735f..0b4606e2e 100644
--- a/nuttx/libc/wqueue/work_usrthread.c
+++ b/nuttx/libc/wqueue/work_usrthread.c
@@ -39,13 +39,19 @@
#include <nuttx/config.h>
+#include <stdint.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <sched.h>
#include <errno.h>
+#include <assert.h>
#include <queue.h>
-#include <debug.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
+#include "wqueue/wqueue.h"
+
#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK) && \
!defined(__KERNEL__)
@@ -53,9 +59,19 @@
* Pre-processor Definitions
****************************************************************************/
-/* The state of the user mode work queue. */
+/* Use CLOCK_MONOTONIC if it is available. CLOCK_REALTIME can cause bad
+ * delays if the time is changed.
+ */
+
+#ifdef CONFIG_CLOCK_MONOTONIC
+# define WORK_CLOCK CLOCK_MONOTONIC
+#else
+# define WORK_CLOCK CLOCK_REALTIME
+#endif
-extern struct wqueue_s g_usrwork;
+#ifndef MIN
+# define MIN(a,b) ((a) < (b) ? (a) : (b))
+#endif
/****************************************************************************
* Private Type Declarations
@@ -65,6 +81,18 @@ extern struct wqueue_s g_usrwork;
* Public Data
****************************************************************************/
+/* The state of the user mode work queue. */
+
+struct wqueue_s g_usrwork;
+
+/* This semaphore supports exclusive access to the user-mode work queue */
+
+#ifdef CONFIG_BUILD_PROTECTED
+extern sem_t g_usrsem;
+#else
+extern pthread_mutex_t g_usrmutex;
+#endif
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -74,6 +102,179 @@ extern struct wqueue_s g_usrwork;
****************************************************************************/
/****************************************************************************
+ * Name: work_process
+ *
+ * Description:
+ * This is the logic that performs actions placed on any work list. This
+ * logic is the common underlying logic to all work queues. This logic is
+ * part of the internal implementation of each work queue; it should not
+ * be called from application level logic.
+ *
+ * Input parameters:
+ * wqueue - Describes the work queue to be processed
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void work_process(FAR struct wqueue_s *wqueue)
+{
+ volatile FAR struct work_s *work;
+ worker_t worker;
+ FAR void *arg;
+ uint32_t elapsed;
+ uint32_t remaining;
+ uint32_t stick;
+ uint32_t ctick;
+ uint32_t next;
+ int ret;
+
+ /* Then process queued work. Lock the work queue while we process items
+ * in the work list.
+ */
+
+ next = wqueue->delay;
+ ret = work_lock();
+ if (ret < 0)
+ {
+ /* Break out earlier if we were awakened by a signal */
+
+ return;
+ }
+
+ /* Get the time that we started this polling cycle in clock ticks. */
+
+ stick = clock_systimer();
+
+ /* And check each entry in the work queue. Since we have locked the
+ * work queue we know: (1) we will not be suspended unless we do
+ * so ourselves, and (2) there will be no changes to the work queue
+ */
+
+ work = (FAR struct work_s *)wqueue->q.head;
+ while (work)
+ {
+ DEBUGASSERT(wqueue->wq_sem.count > 0);
+
+ /* Is this work ready? It is ready if there is no delay or if
+ * the delay has elapsed. qtime is the time that the work was added
+ * to the work queue. It will always be greater than or equal to
+ * zero. Therefore a delay of zero will always execute immediately.
+ */
+
+ ctick = clock_systimer();
+ elapsed = ctick - work->qtime;
+ if (elapsed >= work->delay)
+ {
+ /* Remove the ready-to-execute work from the list */
+
+ (void)dq_rem((struct dq_entry_s *)work, &wqueue->q);
+
+ /* Extract the work description from the entry (in case the work
+ * instance by the re-used after it has been de-queued).
+ */
+
+ worker = work->worker;
+
+ /* Check for a race condition where the work may be nullified
+ * before it is removed from the queue.
+ */
+
+ if (worker != NULL)
+ {
+ /* Extract the work argument (before unlocking the work queue) */
+
+ arg = work->arg;
+
+ /* Mark the work as no longer being queued */
+
+ work->worker = NULL;
+
+ /* Do the work. Unlock the the work queue while the work is being
+ * performed... we don't have any idea how long this will take!
+ */
+
+ work_unlock();
+ worker(arg);
+
+ /* Now, unfortunately, since we unlocked the work queue we don't
+ * know the state of the work list and we will have to start
+ * back at the head of the list.
+ */
+
+ ret = work_lock();
+ if (ret < 0)
+ {
+ /* Break out earlier if we were awakened by a signal */
+
+ return;
+ }
+
+ work = (FAR struct work_s *)wqueue->q.head;
+ }
+ else
+ {
+ /* Cancelled.. Just move to the next work in the list with
+ * the work queue still locked.
+ */
+
+ work = (FAR struct work_s *)work->dq.flink;
+ }
+ }
+ else
+ {
+ /* This one is not ready.. will it be ready before the next
+ * scheduled wakeup interval?
+ *
+ * NOTE that elapsed is relative to the the current time,
+ * not the time of beginning of this queue processing pass.
+ * So it may need an adjustment.
+ */
+
+ elapsed += (ctick - stick);
+ remaining = elapsed - work->delay;
+ if (remaining < next)
+ {
+ /* Yes.. Then schedule to wake up when the work is ready */
+
+ next = remaining;
+ }
+
+ /* Then try the next in the list. */
+
+ work = (FAR struct work_s *)work->dq.flink;
+ }
+ }
+
+ /* Get the delay (in clock ticks) since we started the sampling */
+
+ elapsed = clock_systimer() - work->qtime;
+ if (elapsed <= wqueue->delay)
+ {
+ /* How must time would we need to delay to get to the end of the
+ * sampling period? The amount of time we delay should be the smaller
+ * of the time to the end of the sampling period and the time to the
+ * next work expiry.
+ */
+
+ remaining = wqueue->delay - elapsed;
+ next = MIN(next, remaining);
+ if (next > 0)
+ {
+ /* Wait awhile to check the work list. We will wait here until
+ * either the time elapses or until we are awakened by a signal.
+ * Interrupts will be re-enabled while we wait.
+ */
+
+ usleep(next * USEC_PER_TICK);
+ }
+ }
+
+ work_unlock();
+}
+
+/****************************************************************************
* Name: work_usrthread
*
* Description:
@@ -92,24 +293,32 @@ extern struct wqueue_s g_usrwork;
*
****************************************************************************/
+#ifdef CONFIG_BUILD_PROTECTED
static int work_usrthread(int argc, char *argv[])
+#else
+static pthread_addr_t work_usrthread(pthread_addr_t arg)
+#endif
{
/* Loop forever */
for (;;)
{
- /* Then process queued work. We need to keep interrupts disabled while
- * we process items in the work list.
+ /* Then process queued work. We need to keep the work queue locked
+ * while we process items in the work list.
*/
work_process(&g_usrwork);
}
+#ifdef CONFIG_BUILD_PROTECTED
return OK; /* To keep some compilers happy */
+#else
+ return NULL; /* To keep some compilers happy */
+#endif
}
/****************************************************************************
- * Private Functions
+ * Public Functions
****************************************************************************/
/****************************************************************************
@@ -134,27 +343,65 @@ int work_usrstart(void)
g_usrwork.delay = CONFIG_SCHED_USRWORKPERIOD / USEC_PER_TICK;
dq_init(&g_usrwork.q);
- /* Start a user-mode worker thread for use by applications. */
+#ifdef CONFIG_BUILD_PROTECTED
+ {
+ /* Set up the work queue lock */
- svdbg("Starting user-mode worker thread\n");
+ (void)sem_init(&g_usrsem, 0, 1);
- g_usrwork.pid[0] = task_create("uwork",
- CONFIG_SCHED_USRWORKPRIORITY,
- CONFIG_SCHED_USRWORKSTACKSIZE,
- (main_t)work_usrthread,
- (FAR char * const *)NULL);
+ /* Start a user-mode worker thread for use by applications. */
- DEBUGASSERT(g_usrwork.pid[0] > 0);
- if (g_usrwork.pid[0] < 0)
- {
- int errcode = errno;
- DEBUGASSERT(errcode > 0);
+ g_usrwork.pid[0] = task_create("uwork",
+ CONFIG_SCHED_USRWORKPRIORITY,
+ CONFIG_SCHED_USRWORKSTACKSIZE,
+ (main_t)work_usrthread,
+ (FAR char * const *)NULL);
- sdbg("task_create failed: %d\n", errcode);
- return -errcode;
- }
+ DEBUGASSERT(g_usrwork.pid[0] > 0);
+ if (g_usrwork.pid[0] < 0)
+ {
+ int errcode = errno;
+ DEBUGASSERT(errcode > 0);
+ return -errcode;
+ }
+
+ return g_usrwork.pid[0];
+ }
+#else
+ {
+ pthread_t usrwork;
+ pthread_attr_t attr;
+ struct sched_param param;
+ int status;
+
+ /* Set up the work queue lock */
+
+ (void)pthread_mutex_init(&g_usrmutex, NULL);
+
+ /* Start a user-mode worker thread for use by applications. */
+
+ (void)pthread_attr_init(&attr);
+ (void)pthread_attr_setstacksize(&attr, CONFIG_SCHED_USRWORKSTACKSIZE);
+
+ param.sched_priority = CONFIG_SCHED_USRWORKPRIORITY;
+ (void)pthread_attr_setschedparam(&attr, &param);
+
+ status = pthread_create(&usrwork, &attr, work_usrthread, NULL);
+ if (status != 0)
+ {
+ return -status;
+ }
+
+ /* Detach because the return value and completion status will not be
+ * requested.
+ */
+
+ (void)pthread_detach(usrwork);
- return g_usrwork.pid[0];
+ g_usrwork.pid[0] = (pid_t)usrwork;
+ return g_usrwork.pid[0];
+ }
+#endif
}
#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_USRWORK && !__KERNEL__*/
diff --git a/nuttx/libc/wqueue/wqueue.h b/nuttx/libc/wqueue/wqueue.h
index 9f6d2dde5..9fcbabdb8 100644
--- a/nuttx/libc/wqueue/wqueue.h
+++ b/nuttx/libc/wqueue/wqueue.h
@@ -42,6 +42,11 @@
#include <nuttx/config.h>
+#include <semaphore.h>
+#include <pthread.h>
+
+#include <nuttx/wqueue.h>
+
#ifdef CONFIG_SCHED_WORKQUEUE
/****************************************************************************
@@ -57,15 +62,61 @@
****************************************************************************/
#if defined(CONFIG_SCHED_USRWORK) && !defined(__KERNEL__)
-
/* The state of the user mode work queue */
extern struct wqueue_s g_usrwork;
+
+/* This semaphore/mutex supports exclusive access to the user-mode work queue */
+
+#ifdef CONFIG_BUILD_PROTECTED
+extern sem_t g_usrsem;
+#else
+extern pthread_mutex_t g_usrmutex;
+#endif
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
+/****************************************************************************
+ * Name: work_lock
+ *
+ * Description:
+ * Lock the user-mode work queue.
+ *
+ * Input parameters:
+ * None
+ *
+ * Returned Value:
+ * Zero (OK) on success, a negated errno on failure. This error may be
+ * reported:
+ *
+ * -EINTR - Wait was interrupted by a signal
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_SCHED_USRWORK) && !defined(__KERNEL__)
+int work_lock(void);
+#endif
+
+/****************************************************************************
+ * Name: work_unlock
+ *
+ * Description:
+ * Unlock the user-mode work queue.
+ *
+ * Input parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_SCHED_USRWORK) && !defined(__KERNEL__)
+void work_unlock(void);
+#endif
+
#endif /* CONFIG_SCHED_WORKQUEUE */
#endif /* __LIBC_WQUEUE_WQUEUE_H */
diff --git a/nuttx/sched/wqueue/Make.defs b/nuttx/sched/wqueue/Make.defs
index 4a375926a..54efbbd7d 100644
--- a/nuttx/sched/wqueue/Make.defs
+++ b/nuttx/sched/wqueue/Make.defs
@@ -37,7 +37,7 @@
ifeq ($(CONFIG_SCHED_WORKQUEUE),y)
-CSRCS += kwork_queue.c kwork_cancel.c kwork_signal.c
+CSRCS += kwork_queue.c kwork_process.c kwork_cancel.c kwork_signal.c
# Add high priority work queue files
diff --git a/nuttx/sched/wqueue/kwork_cancel.c b/nuttx/sched/wqueue/kwork_cancel.c
index e8a44acf2..589389c52 100644
--- a/nuttx/sched/wqueue/kwork_cancel.c
+++ b/nuttx/sched/wqueue/kwork_cancel.c
@@ -39,8 +39,11 @@
#include <nuttx/config.h>
+#include <queue.h>
+#include <assert.h>
#include <errno.h>
+#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include "wqueue/wqueue.h"
@@ -68,6 +71,60 @@
****************************************************************************/
/****************************************************************************
+ * Name: work_qcancel
+ *
+ * Description:
+ * Cancel previously queued work. This removes work from the work queue.
+ * After work has been cancelled, it may be re-queue by calling work_queue()
+ * again.
+ *
+ * Input parameters:
+ * qid - The work queue ID
+ * work - The previously queue work structure to cancel
+ *
+ * Returned Value:
+ * Zero (OK) on success, a negated errno on failure. This error may be
+ * reported:
+ *
+ * -ENOENT - There is no such work queued.
+ * -EINVAL - An invalid work queue was specified
+ *
+ ****************************************************************************/
+
+static int work_qcancel(FAR struct wqueue_s *wqueue, FAR struct work_s *work)
+{
+ irqstate_t flags;
+ int ret = -ENOENT;
+
+ DEBUGASSERT(work != NULL);
+
+ /* Cancelling the work is simply a matter of removing the work structure
+ * from the work queue. This must be done with interrupts disabled because
+ * new work is typically added to the work queue from interrupt handlers.
+ */
+
+ flags = irqsave();
+ if (work->worker != NULL)
+ {
+ /* A little test of the integrity of the work queue */
+
+ DEBUGASSERT(work->dq.flink || (FAR dq_entry_t *)work == wqueue->q.tail);
+ DEBUGASSERT(work->dq.blink || (FAR dq_entry_t *)work == wqueue->q.head);
+
+ /* Remove the entry from the work queue and make sure that it is
+ * mark as available (i.e., the worker field is nullified).
+ */
+
+ dq_rem((FAR dq_entry_t *)work, &wqueue->q);
+ work->worker = NULL;
+ ret = OK;
+ }
+
+ irqrestore(flags);
+ return ret;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
diff --git a/nuttx/libc/wqueue/work_process.c b/nuttx/sched/wqueue/kwork_process.c
index 92cfd5c87..1e878dc43 100644
--- a/nuttx/libc/wqueue/work_process.c
+++ b/nuttx/sched/wqueue/kwork_process.c
@@ -173,7 +173,7 @@ void work_process(FAR struct wqueue_s *wqueue)
work->worker = NULL;
/* Do the work. Re-enable interrupts while the work is being
- * performed... we don't have any idea how long that will take!
+ * performed... we don't have any idea how long this will take!
*/
irqrestore(flags);
diff --git a/nuttx/sched/wqueue/kwork_queue.c b/nuttx/sched/wqueue/kwork_queue.c
index 9a979f947..e385d76b7 100644
--- a/nuttx/sched/wqueue/kwork_queue.c
+++ b/nuttx/sched/wqueue/kwork_queue.c
@@ -40,8 +40,12 @@
#include <nuttx/config.h>
#include <stdint.h>
+#include <queue.h>
+#include <assert.h>
#include <errno.h>
+#include <nuttx/arch.h>
+#include <nuttx/clock.h>
#include <nuttx/wqueue.h>
#include "wqueue/wqueue.h"
@@ -69,6 +73,63 @@
****************************************************************************/
/****************************************************************************
+ * Name: work_qqueue
+ *
+ * Description:
+ * Queue work to be performed at a later time. All queued work will be
+ * performed on the worker thread of of execution (not the caller's).
+ *
+ * The work structure is allocated by caller, but completely managed by
+ * the work queue logic. The caller should never modify the contents of
+ * the work queue structure; the caller should not call work_queue()
+ * again until either (1) the previous work has been performed and removed
+ * from the queue, or (2) work_cancel() has been called to cancel the work
+ * and remove it from the work queue.
+ *
+ * Input parameters:
+ * qid - The work queue ID (index)
+ * work - The work structure to queue
+ * worker - The worker callback to be invoked. The callback will invoked
+ * on the worker thread of execution.
+ * arg - The argument that will be passed to the workder callback when
+ * int is invoked.
+ * delay - Delay (in clock ticks) from the time queue until the worker
+ * is invoked. Zero means to perform the work immediately.
+ *
+ * Returned Value:
+ * Zero on success, a negated errno on failure
+ *
+ ****************************************************************************/
+
+static int work_qqueue(FAR struct wqueue_s *wqueue, FAR struct work_s *work,
+ worker_t worker, FAR void *arg, uint32_t delay)
+{
+ irqstate_t flags;
+
+ DEBUGASSERT(work != NULL);
+
+ /* First, initialize the work structure */
+
+ work->worker = worker; /* Work callback */
+ work->arg = arg; /* Callback argument */
+ work->delay = delay; /* Delay until work performed */
+
+ /* Now, time-tag that entry and put it in the work queue. This must be
+ * done with interrupts disabled. This permits this function to be called
+ * from with task logic or interrupt handlers.
+ */
+
+ flags = irqsave();
+ work->qtime = clock_systimer(); /* Time work queued */
+
+ dq_addlast((FAR dq_entry_t *)work, &wqueue->q);
+ kill(wqueue->pid[0], SIGWORK); /* Wake up the worker thread */
+
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
diff --git a/nuttx/sched/wqueue/wqueue.h b/nuttx/sched/wqueue/wqueue.h
index 0c95b8501..530775072 100644
--- a/nuttx/sched/wqueue/wqueue.h
+++ b/nuttx/sched/wqueue/wqueue.h
@@ -123,5 +123,24 @@ int work_hpstart(void);
int work_lpstart(void);
#endif
+/****************************************************************************
+ * Name: work_process
+ *
+ * Description:
+ * This is the logic that performs actions placed on any work list. This
+ * logic is the common underlying logic to all work queues. This logic is
+ * part of the internal implementation of each work queue; it should not
+ * be called from application level logic.
+ *
+ * Input parameters:
+ * wqueue - Describes the work queue to be processed
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void work_process(FAR struct wqueue_s *wqueue);
+
#endif /* CONFIG_SCHED_WORKQUEUE */
#endif /* __SCHED_WQUEUE_WQUEUE_H */