summaryrefslogtreecommitdiff
path: root/nuttx/libc
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/libc')
-rw-r--r--nuttx/libc/Kconfig113
-rw-r--r--nuttx/libc/wqueue/Make.defs4
-rw-r--r--nuttx/libc/wqueue/work_thread.c66
-rw-r--r--nuttx/libc/wqueue/work_usrstart.c118
4 files changed, 295 insertions, 6 deletions
diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig
index 3aee837c3..a549ced45 100644
--- a/nuttx/libc/Kconfig
+++ b/nuttx/libc/Kconfig
@@ -346,7 +346,118 @@ config ARCH_BZERO
endif
-comment "Non-standard Helper Functions"
+comment "Non-standard Library Support"
+
+config SCHED_WORKQUEUE
+ bool "Enable worker thread"
+ default n
+ depends on !DISABLE_SIGNALS
+ ---help---
+ Create a dedicated "worker" thread to handle delayed processing from interrupt
+ handlers. This feature is required for some drivers but, if there are no
+ complaints, can be safely disabled. The worker thread also performs
+ garbage collection -- completing any delayed memory deallocations from
+ interrupt handlers. If the worker thread is disabled, then that clean up will
+ be performed by the IDLE thread instead (which runs at the lowest of priority
+ and may not be appropriate if memory reclamation is of high priority).
+
+if SCHED_WORKQUEUE
+
+config SCHED_HPWORK
+ bool "High priority (kernel) worker thread"
+ default y
+ ---help---
+ If SCHED_WORKQUEUE is defined, then a single, high priority work queue is
+ created by default. This high priority worker thread is intended to serve
+ as the "bottom half" for driver interrupt handling.
+
+if SCHED_HPWORK
+config SCHED_WORKPRIORITY
+ int "High priority worker thread priority"
+ default 192
+ ---help---
+ The execution priority of the worker thread. Default: 192
+
+config SCHED_WORKPERIOD
+ int "High priority worker thread period"
+ default 50000
+ ---help---
+ How often the worker thread checks for work in units of microseconds.
+ Default: 50*1000 (50 MS).
+
+config SCHED_WORKSTACKSIZE
+ int "High priority worker thread stack size"
+ default 2048
+ depends on SCHED_WORKQUEUE
+ ---help---
+ The stack size allocated for the worker thread. Default: 2K.
+
+config SCHED_LPWORK
+ bool "Low priority (kernel) worker thread"
+ default n
+ ---help---
+ If SCHED_WORKQUEUE is defined, then a single work queue is created by
+ default. If SCHED_LPWORK is also defined then an additional, lower-
+ priority work queue will also be created. This lower priority work
+ queue is better suited for more extended processing (such as file system
+ clean-up operations)
+
+if SCHED_LPWORK
+
+config SCHED_LPWORKPRIORITY
+ int "Low priority worker thread priority"
+ default 50
+ ---help---
+ The execution priority of the lopwer priority worker thread. Default: 192
+
+config SCHED_LPWORKPERIOD
+ int "Low priority worker thread period"
+ default 50000
+ ---help---
+ How often the lower priority worker thread checks for work in units
+ of microseconds. Default: 50*1000 (50 MS).
+
+config SCHED_LPWORKSTACKSIZE
+ int "Low priority worker thread stack size"
+ default 2048
+ ---help---
+ The stack size allocated for the lower priority worker thread. Default: 2K.
+
+endif # SCHED_LPWORK
+endif # SCHED_HPWORK
+
+if NUTTX_KERNEL
+
+config SCHED_USRWORK
+ bool "User mode worker thread"
+ default n
+ ---help---
+ User space work queues can also be made available for deferred processing in the NuttX kernel build.
+
+if SCHED_USRWORK
+
+config SCHED_LPWORKPRIORITY
+ int "User mode priority worker thread priority"
+ default 50
+ ---help---
+ The execution priority of the lopwer priority worker thread. Default: 192
+
+config SCHED_LPWORKPERIOD
+ int "User mode worker thread period"
+ default 50000
+ ---help---
+ How often the lower priority worker thread checks for work in units
+ of microseconds. Default: 50*1000 (50 MS).
+
+config SCHED_LPWORKSTACKSIZE
+ int "User mode worker thread stack size"
+ default 2048
+ ---help---
+ The stack size allocated for the lower priority worker thread. Default: 2K.
+
+endif # SCHED_USRWORK
+endif # NUTTX_KERNEL
+endif # SCHED_WORKQUEUE
config LIB_KBDCODEC
bool "Keyboard CODEC"
diff --git a/nuttx/libc/wqueue/Make.defs b/nuttx/libc/wqueue/Make.defs
index 1a13bcf78..fca63a8a6 100644
--- a/nuttx/libc/wqueue/Make.defs
+++ b/nuttx/libc/wqueue/Make.defs
@@ -39,6 +39,10 @@ ifeq ($(CONFIG_SCHED_WORKQUEUE),y)
CSRCS += work_thread.c work_queue.c work_cancel.c work_signal.c
+ifeq ($(CONFIG_NUTTX_KERNEL),y)
+CSRCS += work_usrstart.c
+endif
+
# Add the wqueue directory to the build
DEPPATH += --dep-path wqueue
diff --git a/nuttx/libc/wqueue/work_thread.c b/nuttx/libc/wqueue/work_thread.c
index 32dff9c8c..febcd0ae8 100644
--- a/nuttx/libc/wqueue/work_thread.c
+++ b/nuttx/libc/wqueue/work_thread.c
@@ -65,10 +65,30 @@
* Public Variables
****************************************************************************/
-/* The state of each work queue */
+/* The state of each work queue. */
+
+#ifdef CONFIG_NUTTX_KERNEL
+
+ /* Play some games in the kernel mode build to assure that different
+ * naming is used for the global work queue data structures. This may
+ * not be necessary but it safer.
+ *
+ * In this case g_work is #define'd to be either g_kernelwork or
+ * g_usrwork in include/nuttx/wqueue.h
+ */
+
+# ifdef __KERNEL__
+struct wqueue_s g_kernelwork[NWORKERS];
+# else
+struct wqueue_s g_usrwork[NWORKERS];
+# endif
+
+#else /* CONFIG_NUTTX_KERNEL */
struct wqueue_s g_work[NWORKERS];
+#endif /* CONFIG_NUTTX_KERNEL */
+
/****************************************************************************
* Private Variables
****************************************************************************/
@@ -181,12 +201,24 @@ static void work_process(FAR struct wqueue_s *wqueue)
* Public Functions
****************************************************************************/
/****************************************************************************
- * Name: work_hpthread and work_lpthread
+ * Name: work_hpthread, work_lpthread, and work_usrthread
*
* Description:
- * These are the main worker threads that performs actions placed on the
- * work lists. One thread also performs periodic garbage collection (that
- * is performed by the idle thread if CONFIG_SCHED_WORKQUEUE is not defined).
+ * These are the worker threads that performs actions placed on the work
+ * lists.
+ *
+ * work_hpthread and work_lpthread: These are the kernel mode work queues
+ * (also build in the flat build). One of these threads also performs
+ * periodic garbage collection (that is otherwise performed by the idle
+ * thread if CONFIG_SCHED_WORKQUEUE is not defined).
+ *
+ * These worker threads are started by the OS during normal bringup.
+ *
+ * work_usrthread: This is a user mode work queue. It must be started
+ * by application code by calling work_usrstart().
+ *
+ * All of these entrypoints are referenced by OS internally and should not
+ * not be accessed by application logic.
*
* Input parameters:
* argc, argv (not used)
@@ -196,6 +228,8 @@ static void work_process(FAR struct wqueue_s *wqueue)
*
****************************************************************************/
+#ifdef CONFIG_SCHED_HPWORK
+
int work_hpthread(int argc, char *argv[])
{
/* Loop forever */
@@ -224,6 +258,7 @@ int work_hpthread(int argc, char *argv[])
}
#ifdef CONFIG_SCHED_LPWORK
+
int work_lpthread(int argc, char *argv[])
{
/* Loop forever */
@@ -250,5 +285,26 @@ int work_lpthread(int argc, char *argv[])
}
#endif /* CONFIG_SCHED_LPWORK */
+#endif /* CONFIG_SCHED_HPWORK */
+
+#ifdef CONFIG_SCHED_USRWORK
+
+int work_usrthread(int argc, char *argv[])
+{
+ /* Loop forever */
+
+ for (;;)
+ {
+ /* Then process queued work. We need to keep interrupts disabled while
+ * we process items in the work list.
+ */
+
+ work_process(&g_work[USRWORK]);
+ }
+
+ return OK; /* To keep some compilers happy */
+}
+
+#endif /* CONFIG_SCHED_USRWORK */
#endif /* CONFIG_SCHED_WORKQUEUE */
diff --git a/nuttx/libc/wqueue/work_usrstart.c b/nuttx/libc/wqueue/work_usrstart.c
new file mode 100644
index 000000000..b472afc8d
--- /dev/null
+++ b/nuttx/libc/wqueue/work_usrstart.c
@@ -0,0 +1,118 @@
+/****************************************************************************
+ * libc/wqueue/work_usrstart.c
+ *
+ * Copyright (C) 2013 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 <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/wqueue.h>
+
+#if defined(CONFIG_SCHED_WORKQUEUE) && defined(CONFIG_SCHED_USRWORK)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: work_usrstart
+ *
+ * Description:
+ * Start the user mode work queue.
+ *
+ * Input parameters:
+ * None
+ *
+ * Returned Value:
+ * The task ID of the worker thread is returned on success. A negated
+ * errno value is returned on failure.
+ *
+ ****************************************************************************/
+
+int work_usrstart(void)
+{
+ int errcode;
+
+ DEBUGASSERT(g_usrwork[USRWORK] == NULL);
+
+ /* Start a lower priority worker thread for other, non-critical continuation
+ * tasks
+ */
+
+ svdbg("Starting user-mode worker thread\n");
+
+ g_usrwork[USRWORK].pid = TASK_CREATE("usrwork",
+ CONFIG_SCHED_USRWORKPRIORITY,
+ CONFIG_SCHED_USRWORKSTACKSIZE,
+ (main_t)work_usrthread,
+ (FAR char * const *)NULL);
+
+ errcode = errno;
+ ASSERT(g_usrwork[USRWORK].pid > 0);
+ if (g_usrwork[USRWORK].pid < 0)
+ {
+ sdbg("task_create failed: %d\n", errcode);
+ return -errcode;
+ }
+
+ return g_usrwork[USRWORK].pid;
+}
+
+#endif /* CONFIG_SCHED_WORKQUEUE && CONFIG_SCHED_USRWORK */