aboutsummaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-09-14 21:33:19 -0700
committerpx4dev <px4@purgatory.org>2012-09-14 21:33:19 -0700
commita3f21d914038f249e5e141b31410cc8554d94623 (patch)
tree59e60563503a42fce283149f0ca265c21faa19e2 /nuttx/sched
parent53fe61a6211a86597834d5d8d7e90187f84717b0 (diff)
parentcfa24e37d6f153dbb5c7e2e0de6484719ea4a9b0 (diff)
downloadpx4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.tar.gz
px4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.tar.bz2
px4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.zip
Merge branch 'NuttX/master'
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig54
-rw-r--r--nuttx/sched/Makefile2
-rw-r--r--nuttx/sched/os_bringup.c24
-rw-r--r--nuttx/sched/prctl.c2
-rw-r--r--nuttx/sched/sched_free.c4
-rw-r--r--nuttx/sched/task_exithook.c2
-rw-r--r--nuttx/sched/work_cancel.c16
-rw-r--r--nuttx/sched/work_internal.h48
-rw-r--r--nuttx/sched/work_queue.c14
-rw-r--r--nuttx/sched/work_signal.c96
-rw-r--r--nuttx/sched/work_thread.c215
11 files changed, 328 insertions, 149 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index 37ce0ebd6..4f7149595 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -166,6 +166,39 @@ config SIG_SIGWORK
The signal number that will be used to wake-up the worker thread.
Default: 4
+config SCHED_LPWORK
+ bool "Enable a lower priority worker thread"
+ default n
+ depends on SCHED_WORKQUEUE
+ ---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)
+
+config SCHED_LPWORKPRIORITY
+ int "Lower priority worker thread priority"
+ default 50
+ depends on SCHED_LPWORK
+ ---help---
+ The execution priority of the lopwer priority worker thread. Default: 192
+
+config SCHED_LPWORKPERIOD
+ int "Lower priority worker thread period"
+ default 50000
+ depends on SCHED_LPWORK
+ ---help---
+ How often the lower priority worker thread checks for work in units
+ of microseconds. Default: 50*1000 (50 MS).
+
+config SCHED_LPWORKSTACKSIZE
+ int "Lower priority worker thread stack size"
+ default 2048
+ depends on SCHED_LPWORK
+ ---help---
+ The stack size allocated for the lower priority worker thread. Default: 2K.
+
config SCHED_WAITPID
bool "Enable waitpid() API"
default n
@@ -203,7 +236,7 @@ config SCHED_ONEXIT_MAX
number that you require.
config USER_ENTRYPOINT
- string "Appliation entry point"
+ string "Application entry point"
default "user_start"
---help---
The name of the entry point for user applications. For the example
@@ -348,20 +381,6 @@ config PREALLOC_TIMERS
comment "Stack and heap information"
-config BOOT_RUNFROMFLASH
- bool "boot run from flash"
- default n
- ---help---
- Some configurations support XIP operation from FLASH but must copy
- initialized .data sections to RAM
-
-config BOOT_COPYTORAM
- bool "boot copy to ram"
- default n
- ---help---
- Some configurations boot in FLASH
- but copy themselves entirely into RAM for better performance.
-
config CUSTOM_STACK
bool "Enable custom stack"
default n
@@ -370,11 +389,6 @@ config CUSTOM_STACK
nuttx model. This is necessary for certain architectures that have
have hardware stacks (such as the 8051 family).
-config STACK_POINTER
- hex "The initial stack pointer"
- ---help---
- The initial stack pointer (arm7tdmi only).
-
config IDLETHREAD_STACKSIZE
int "Idle thread stack size"
default 1024
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index dfdc6f68b..1e0a55aea 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -141,7 +141,7 @@ TIMER_SRCS = timer_initialize.c timer_create.c timer_delete.c timer_getoverrun.c
endif
ifeq ($(CONFIG_SCHED_WORKQUEUE),y)
-WORK_SRCS = work_thread.c work_queue.c work_cancel.c
+WORK_SRCS = work_thread.c work_queue.c work_cancel.c work_signal.c
endif
ifeq ($(CONFIG_PAGING),y)
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/os_bringup.c
index d6d943137..ec6152891 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/os_bringup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/os_bringup.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* With extensions by:
@@ -47,6 +47,7 @@
#include <debug.h>
#include <nuttx/init.h>
+#include <nuttx/wqueue.h>
#include "os_internal.h"
#ifdef CONFIG_PAGING
@@ -149,10 +150,23 @@ int os_bringup(void)
#ifdef CONFIG_SCHED_WORKQUEUE
svdbg("Starting worker thread\n");
- g_worker = KERNEL_THREAD("work", CONFIG_SCHED_WORKPRIORITY,
- CONFIG_SCHED_WORKSTACKSIZE,
- (main_t)work_thread, (const char **)NULL);
- ASSERT(g_worker != ERROR);
+ g_work[HPWORK].pid = KERNEL_THREAD("work0", CONFIG_SCHED_WORKPRIORITY,
+ CONFIG_SCHED_WORKSTACKSIZE,
+ (main_t)work_hpthread, (const char **)NULL);
+ ASSERT(g_work[HPWORK].pid != ERROR);
+
+ /* Start a lower priority worker thread for other, non-critical continuation
+ * tasks
+ */
+
+#ifdef CONFIG_SCHED_LPWORK
+ svdbg("Starting worker thread\n");
+
+ g_work[LPWORK].pid = KERNEL_THREAD("work1", CONFIG_SCHED_LPWORKPRIORITY,
+ CONFIG_SCHED_LPWORKSTACKSIZE,
+ (main_t)work_lpthread, (const char **)NULL);
+ ASSERT(g_work[LPWORK].pid != ERROR);
+#endif
#endif
/* Once the operating system has been initialized, the system must be
diff --git a/nuttx/sched/prctl.c b/nuttx/sched/prctl.c
index b340d0ec8..d71a0e174 100644
--- a/nuttx/sched/prctl.c
+++ b/nuttx/sched/prctl.c
@@ -91,7 +91,7 @@ int prctl(int option, ...)
{
/* Get the prctl arguments */
- char *name = va_arg(ap, char *);
+ FAR char *name = va_arg(ap, FAR char *);
int pid = va_arg(ap, int);
FAR _TCB *tcb;
diff --git a/nuttx/sched/sched_free.c b/nuttx/sched/sched_free.c
index 4df77b109..e5e0bdacf 100644
--- a/nuttx/sched/sched_free.c
+++ b/nuttx/sched/sched_free.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_free.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -99,7 +99,7 @@ void sched_free(FAR void *address)
/* Signal the worker thread that is has some clean up to do */
#ifdef CONFIG_SCHED_WORKQUEUE
- work_signal();
+ work_signal(LPWORK);
#endif
irqrestore(saved_state);
}
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 63dc28aa0..e94476f2a 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -44,6 +44,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/sched.h>
#include <nuttx/fs/fs.h>
#include "os_internal.h"
@@ -180,6 +181,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
tcb->onexitfunc = NULL;
}
#endif
+}
#else
# define task_onexit(tcb,status)
#endif
diff --git a/nuttx/sched/work_cancel.c b/nuttx/sched/work_cancel.c
index 30b650826..55df86f44 100644
--- a/nuttx/sched/work_cancel.c
+++ b/nuttx/sched/work_cancel.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/work_cancel.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -74,6 +74,7 @@
/****************************************************************************
* Public Functions
****************************************************************************/
+
/****************************************************************************
* Name: work_cancel
*
@@ -83,6 +84,7 @@
* again.
*
* Input parameters:
+ * qid - The work queue ID
* work - The previously queue work structure to cancel
*
* Returned Value:
@@ -90,11 +92,12 @@
*
****************************************************************************/
-int work_cancel(struct work_s *work)
+int work_cancel(int qid, FAR struct work_s *work)
{
+ FAR struct wqueue_s *wqueue = &g_work[qid];
irqstate_t flags;
- DEBUGASSERT(work != NULL);
+ DEBUGASSERT(work != NULL && (unsigned)qid < NWORKERS);
/* Cancelling the work is simply a matter of removing the work structure
* from the work queue. This must be done with interrupts disabled because
@@ -106,18 +109,19 @@ int work_cancel(struct work_s *work)
{
/* A little test of the integrity of the work queue */
- DEBUGASSERT(work->dq.flink ||(FAR dq_entry_t *)work == g_work.tail);
- DEBUGASSERT(work->dq.blink ||(FAR dq_entry_t *)work == g_work.head);
+ 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 availalbe (i.e., the worker field is nullified).
*/
- dq_rem((FAR dq_entry_t *)work, &g_work);
+ dq_rem((FAR dq_entry_t *)work, &wqueue->q);
work->worker = NULL;
}
irqrestore(flags);
return OK;
}
+
#endif /* CONFIG_SCHED_WORKQUEUE */
diff --git a/nuttx/sched/work_internal.h b/nuttx/sched/work_internal.h
index 69b7bf547..7f6c1a937 100644
--- a/nuttx/sched/work_internal.h
+++ b/nuttx/sched/work_internal.h
@@ -51,51 +51,49 @@
/* Configuration ************************************************************/
-#ifndef CONFIG_SCHED_WORKPRIORITY
-# define CONFIG_SCHED_WORKPRIORITY 50
-#endif
-
-#ifndef CONFIG_SCHED_WORKPERIOD
-# define CONFIG_SCHED_WORKPERIOD (50*1000) /* 50 milliseconds */
-#endif
-
-#ifndef CONFIG_SCHED_WORKSTACKSIZE
-# define CONFIG_SCHED_WORKSTACKSIZE CONFIG_IDLETHREAD_STACKSIZE
-#endif
-
#ifdef CONFIG_DISABLE_SIGNALS
# warning "Worker thread support requires signals"
#endif
+#ifdef CONFIG_SCHED_LPWORK
+# define NWORKERS 2
+#else
+# define NWORKERS 1
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
+/* This structure defines the state on one work queue */
+
+struct wqueue_s
+{
+ pid_t pid; /* The task ID of the worker thread */
+ struct dq_queue_s q; /* The queue of pending work */
+};
+
/****************************************************************************
* Public Data
****************************************************************************/
-/* The queue of pending work */
-
-extern struct dq_queue_s g_work;
+/* The state of each work queue */
-/* The task ID of the worker thread */
-
-extern pid_t g_worker;
+extern struct wqueue_s g_work[NWORKERS];
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
- * Name: work_thread
+ * Name: work_hpthread and work_lpthread
*
* Description:
- * This is the main worker thread that performs actions placed on the work
- * queue. It also performs periodic garbage collection (that is performed
- * by the idle thread if CONFIG_SCHED_WORKQUEUE is not defined).
+ * 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).
*
* Input parameters:
* argc, argv (not used)
@@ -105,7 +103,11 @@ extern pid_t g_worker;
*
****************************************************************************/
-int work_thread(int argc, char *argv[]);
+int work_hpthread(int argc, char *argv[]);
+
+#ifdef CONFIG_SCHED_LPWORK
+int work_lpthread(int argc, char *argv[]);
+#endif
#endif /* __ASSEMBLY__ */
#endif /* CONFIG_SCHED_WORKQUEUE */
diff --git a/nuttx/sched/work_queue.c b/nuttx/sched/work_queue.c
index beeac168d..075f08a4d 100644
--- a/nuttx/sched/work_queue.c
+++ b/nuttx/sched/work_queue.c
@@ -76,6 +76,7 @@
/****************************************************************************
* Public Functions
****************************************************************************/
+
/****************************************************************************
* Name: work_queue
*
@@ -91,6 +92,7 @@
* 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.
@@ -104,11 +106,13 @@
*
****************************************************************************/
-int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint32_t delay)
+int work_queue(int qid, FAR struct work_s *work, worker_t worker,
+ FAR void *arg, uint32_t delay)
{
+ FAR struct wqueue_s *wqueue = &g_work[qid];
irqstate_t flags;
- DEBUGASSERT(work != NULL);
+ DEBUGASSERT(work != NULL && (unsigned)qid < NWORKERS);
/* First, initialize the work structure */
@@ -123,8 +127,10 @@ int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint32_t del
flags = irqsave();
work->qtime = clock_systimer(); /* Time work queued */
- dq_addlast((FAR dq_entry_t *)work, &g_work);
- work_signal(); /* Wake up the worker thread */
+
+ dq_addlast((FAR dq_entry_t *)work, &wqueue->q);
+ kill(wqueue->pid, SIGWORK); /* Wake up the worker thread */
+
irqrestore(flags);
return OK;
}
diff --git a/nuttx/sched/work_signal.c b/nuttx/sched/work_signal.c
new file mode 100644
index 000000000..6e6838c69
--- /dev/null
+++ b/nuttx/sched/work_signal.c
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * sched/work_signal.c
+ *
+ * Copyright (C) 2009-2012 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 <signal.h>
+#include <assert.h>
+
+#include <nuttx/wqueue.h>
+
+#include "work_internal.h"
+
+#ifdef CONFIG_SCHED_WORKQUEUE
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: work_signal
+ *
+ * Description:
+ * Signal the worker thread to process the work queue now. This function
+ * is used internally by the work logic but could also be used by the
+ * user to force an immediate re-assessment of pending work.
+ *
+ * Input parameters:
+ * qid - The work queue ID
+ *
+ * Returned Value:
+ * Zero on success, a negated errno on failure
+ *
+ ****************************************************************************/
+
+int work_signal(int qid)
+{
+ DEBUGASSERT((unsigned)qid < NWORKERS);
+ return kill(g_work[qid].pid, SIGWORK);
+}
+
+#endif /* CONFIG_SCHED_WORKQUEUE */
diff --git a/nuttx/sched/work_thread.c b/nuttx/sched/work_thread.c
index fe14ae5e5..abd86f771 100644
--- a/nuttx/sched/work_thread.c
+++ b/nuttx/sched/work_thread.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/work_thread.c
*
- * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -67,15 +67,9 @@
* Public Variables
****************************************************************************/
-/* The queue of pending work */
+/* The state of each work queue */
-struct dq_queue_s g_work;
-
-/* The task ID of the worker thread */
-
-#ifdef CONFIG_SCHED_WORKQUEUE
-pid_t g_worker;
-#endif
+struct wqueue_s g_work[NWORKERS];
/****************************************************************************
* Private Variables
@@ -86,130 +80,177 @@ pid_t g_worker;
****************************************************************************/
/****************************************************************************
- * Public Functions
- ****************************************************************************/
-/****************************************************************************
- * Name: work_thread
+ * Name: work_process
*
* Description:
- * This is the main worker thread that performs actions placed on the work
- * list. It also performs periodic garbage collection (that is performed
- * by the idle thread if CONFIG_SCHED_WORKQUEUE is not defined).
+ * This is the logic that performs actions placed on any work list.
*
* Input parameters:
- * argc, argv (not used)
+ * wqueue - Describes the work queue to be processed
*
* Returned Value:
- * Does not return
+ * None
*
****************************************************************************/
-int work_thread(int argc, char *argv[])
+static void work_process(FAR struct wqueue_s *wqueue)
{
volatile FAR struct work_s *work;
worker_t worker;
+ irqstate_t flags;
FAR void *arg;
uint32_t elapsed;
uint32_t remaining;
uint32_t next;
- int usec;
- irqstate_t flags;
- /* Loop forever */
+ /* Then process queued work. We need to keep interrupts disabled while
+ * we process items in the work list.
+ */
- usec = CONFIG_SCHED_WORKPERIOD;
+ next = CONFIG_SCHED_WORKPERIOD / USEC_PER_TICK;
flags = irqsave();
- for (;;)
+ work = (FAR struct work_s *)wqueue->q.head;
+ while (work)
{
- /* Wait awhile to check the work list. We will wait here until either
- * the time elapses or until we are awakened by a signal.
+ /* 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.
*/
- usleep(usec);
- irqrestore(flags);
+ elapsed = clock_systimer() - work->qtime;
+ if (elapsed >= work->delay)
+ {
+ /* Remove the ready-to-execute work from the list */
- /* First, perform garbage collection. This cleans-up memory de-allocations
- * that were queued because they could not be freed in that execution
- * context (for example, if the memory was freed from an interrupt handler).
- * NOTE: If the work thread is disabled, this clean-up is performed by
- * the IDLE thread (at a very, very lower priority).
- */
+ (void)dq_rem((struct dq_entry_s *)work, &wqueue->q);
- sched_garbagecollection();
+ /* Extract the work description from the entry (in case the work
+ * instance by the re-used after it has been de-queued).
+ */
- /* Then process queued work. We need to keep interrupts disabled while
- * we process items in the work list.
- */
+ worker = work->worker;
+ arg = work->arg;
+
+ /* Mark the work as no longer being queued */
+
+ 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!
+ */
+
+ irqrestore(flags);
+ worker(arg);
- next = CONFIG_SCHED_WORKPERIOD / USEC_PER_TICK;
- flags = irqsave();
- work = (FAR struct work_s *)g_work.head;
- while (work)
+ /* Now, unfortunately, since we re-enabled interrupts we don't
+ * know the state of the work list and we will have to start
+ * back at the head of the list.
+ */
+
+ flags = irqsave();
+ work = (FAR struct work_s *)wqueue->q.head;
+ }
+ else
{
- /* 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.
+ /* This one is not ready.. will it be ready before the next
+ * scheduled wakeup interval?
*/
- elapsed = clock_systimer() - work->qtime;
- if (elapsed >= work->delay)
+ remaining = elapsed - work->delay;
+ if (remaining < next)
{
- /* Remove the ready-to-execute work from the list */
+ /* Yes.. Then schedule to wake up when the work is ready */
- (void)dq_rem((struct dq_entry_s *)work, &g_work);
+ next = remaining;
+ }
+
+ /* Then try the next in the list. */
- /* Extract the work description from the entry (in case the work
- * instance by the re-used after it has been de-queued).
- */
+ work = (FAR struct work_s *)work->dq.flink;
+ }
+ }
- worker = work->worker;
- arg = work->arg;
+ /* Wait awhile to check the work list. We will wait here until either
+ * the time elapses or until we are awakened by a signal.
+ */
- /* Mark the work as no longer being queued */
+ usleep(next * USEC_PER_TICK);
+ irqrestore(flags);
+}
- work->worker = NULL;
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: work_hpthread and work_lpthread
+ *
+ * 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).
+ *
+ * Input parameters:
+ * argc, argv (not used)
+ *
+ * Returned Value:
+ * Does not return
+ *
+ ****************************************************************************/
- /* Do the work. Re-enable interrupts while the work is being
- * performed... we don't have any idea how long that will take!
- */
+int work_hpthread(int argc, char *argv[])
+{
+ /* Loop forever */
- irqrestore(flags);
- worker(arg);
+ for (;;)
+ {
+ /* First, perform garbage collection. This cleans-up memory de-allocations
+ * that were queued because they could not be freed in that execution
+ * context (for example, if the memory was freed from an interrupt handler).
+ * NOTE: If the work thread is disabled, this clean-up is performed by
+ * the IDLE thread (at a very, very lower priority).
+ */
- /* Now, unfortunately, since we re-enabled interrupts we don't
- * know the state of the work list and we will have to start
- * back at the head of the list.
- */
+#ifdef CONFIG_SCHED_LPWORK
+ sched_garbagecollection();
+#endif
- flags = irqsave();
- work = (FAR struct work_s *)g_work.head;
- }
- else
- {
- /* This one is not ready.. will it be ready before the next
- * scheduled wakeup interval?
- */
+ /* Then process queued work. We need to keep interrupts disabled while
+ * we process items in the work list.
+ */
+
+ work_process(&g_work[HPWORK]);
+ }
- remaining = elapsed - work->delay;
- if (remaining < next)
- {
- /* Yes.. Then schedule to wake up when the work is ready */
+ return OK; /* To keep some compilers happy */
+}
- next = remaining;
- }
-
- /* Then try the next in the list. */
+#ifdef CONFIG_SCHED_LPWORK
+int work_lpthread(int argc, char *argv[])
+{
+ /* Loop forever */
- work = (FAR struct work_s *)work->dq.flink;
- }
- }
+ for (;;)
+ {
+ /* First, perform garbage collection. This cleans-up memory de-allocations
+ * that were queued because they could not be freed in that execution
+ * context (for example, if the memory was freed from an interrupt handler).
+ * NOTE: If the work thread is disabled, this clean-up is performed by
+ * the IDLE thread (at a very, very lower priority).
+ */
- /* Now calculate the microsecond delay we should wait */
+ sched_garbagecollection();
- usec = next * USEC_PER_TICK;
+ /* Then process queued work. We need to keep interrupts disabled while
+ * we process items in the work list.
+ */
+
+ work_process(&g_work[LPWORK]);
}
return OK; /* To keep some compilers happy */
}
+
+#endif /* CONFIG_SCHED_LPWORK */
+
#endif /* CONFIG_SCHED_WORKQUEUE */