summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/drivers/rwbuffer.c40
-rw-r--r--nuttx/include/nuttx/rwbuffer.h40
-rwxr-xr-xnuttx/include/nuttx/wqueue.h142
-rw-r--r--nuttx/sched/Makefile6
-rwxr-xr-xnuttx/sched/work_cancel.c110
-rwxr-xr-xnuttx/sched/work_internal.h73
-rwxr-xr-xnuttx/sched/work_queue.c123
7 files changed, 490 insertions, 44 deletions
diff --git a/nuttx/drivers/rwbuffer.c b/nuttx/drivers/rwbuffer.c
index 62b17c90b..440e8da83 100644
--- a/nuttx/drivers/rwbuffer.c
+++ b/nuttx/drivers/rwbuffer.c
@@ -43,11 +43,12 @@
#include <stdlib.h>
#include <string.h>
#include <time.h>
+#include <assert.h>
#include <semaphore.h>
#include <errno.h>
-#include <wdog.h>
#include <debug.h>
+#include <nuttx/wqueue.h>
#include <nuttx/rwbuffer.h>
#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
@@ -176,43 +177,42 @@ static void rwb_wrflush(struct rwbuffer_s *rwb)
* Name: rwb_wrtimeout
****************************************************************************/
-static void rwb_wrtimeout(int argc, uint32 irwb)
+static void rwb_wrtimeout(FAR void *arg)
{
/* The following assumes that the size of a pointer is 4-bytes or less */
- FAR struct rwbuffer_s *rwb = (struct rwbuffer_s *)irwb;
+ FAR struct rwbuffer_s *rwb = (struct rwbuffer_s *)arg;
+ DEBUGASSERT(rwb != NULL);
/* If a timeout elpases with with write buffer activity, this watchdog
- * handler function will be evoked. This function will schedule to flush
- * the write buffer. NOTE: This function runs in the context of the timer
- * interrupt handler!
+ * handler function will be evoked on the thread of execution of the
+ * worker thread.
*/
- DEBUGASSERT(argc == 1);
-#warning "REVISIT: Missing logic"
+ rwb_wrflush(rwb);
}
/****************************************************************************
- * Name: rwb_wrstarttimer
+ * Name: rwb_wrstarttimeout
****************************************************************************/
-static void rwb_wrstarttimer(FAR struct rwbuffer_s *rwb)
+static void rwb_wrstarttimeout(FAR struct rwbuffer_s *rwb)
{
/* CONFIG_FS_WRDELAY provides the delay period in milliseconds. CLK_TCK
* provides the clock tick of the system (frequency in Hz).
*/
int ticks = (CONFIG_FS_WRDELAY + CLK_TCK/2) / CLK_TCK;
- (void)wd_start(rwb->wdog, ticks, (wdentry_t)rwb_wrtimeout, 1, (uint32)rwb);
+ (void)work_queue(&rwb->work, rwb_wrtimeout, (FAR void *)rwb, ticks);
}
/****************************************************************************
- * Name: rwb_wrcanceltimer
+ * Name: rwb_wrcanceltimeout
****************************************************************************/
-static inline void rwb_wrcanceltimer(struct rwbuffer_s *rwb)
+static inline void rwb_wrcanceltimeout(struct rwbuffer_s *rwb)
{
- wd_cancel(rwb->wdog);
+ (void)work_cancel(&rwb->work);
}
/****************************************************************************
@@ -228,7 +228,7 @@ static ssize_t rwb_writebuffer(FAR struct rwbuffer_s *rwb,
/* Write writebuffer Logic */
- rwb_wrcanceltimer(rwb);
+ rwb_wrcanceltimeout(rwb);
/* First: Should we flush out our cache? */
@@ -266,7 +266,7 @@ static ssize_t rwb_writebuffer(FAR struct rwbuffer_s *rwb,
rwb->wrnbytes += nbytes;
rwb->wrexpectedblock = rwb->wrblockstart + rwb->wrnbytes;
- rwb_wrstarttimer(rwb);
+ rwb_wrstarttimeout(rwb);
return nbytes;
}
#endif
@@ -395,12 +395,6 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
sem_init(&rwb->wrsem, 0, 1);
- /* Create a timer that will be used to flush buffered write data
- * after a delay with no activity.
- */
-
- rwb->wdog = wd_create();
-
/* Initialize write buffer parameters */
rwb_resetwrbuffer(rwb);
@@ -451,8 +445,8 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
void rwb_uninitialize(FAR struct rwbuffer_s *rwb)
{
#ifdef CONFIG_FS_WRITEBUFFER
+ rwb_wrcanceltimeout(rwb);
sem_destroy(&rwb->wrsem);
- wd_delete(rwb->wdog);
if (rwb->wrbuffer)
{
free(rwb->wrbuffer);
diff --git a/nuttx/include/nuttx/rwbuffer.h b/nuttx/include/nuttx/rwbuffer.h
index 8a9a22d35..4e9d24d45 100644
--- a/nuttx/include/nuttx/rwbuffer.h
+++ b/nuttx/include/nuttx/rwbuffer.h
@@ -48,7 +48,7 @@
#include <sys/types.h>
#include <semaphore.h>
-#include <wdog.h>
+#include <nuttx/wqueue.h>
#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD)
@@ -102,17 +102,17 @@ struct rwbuffer_s
/* Supported geometry */
- uint16 blocksize; /* The size of one block */
- size_t nblocks; /* The total number blocks supported */
- void *dev; /* Device state passed to callout functions */
+ uint16 blocksize; /* The size of one block */
+ size_t nblocks; /* The total number blocks supported */
+ void *dev; /* Device state passed to callout functions */
#ifdef CONFIG_FS_WRITEBUFFER
- uint16 wrblocks; /* The number of blocks to buffer in memory */
- rwbflush_t wrflush; /* Callout to flush the write buffer */
+ uint16 wrblocks; /* The number of blocks to buffer in memory */
+ rwbflush_t wrflush; /* Callout to flush the write buffer */
#endif
#ifdef CONFIG_FS_READAHEAD
- uint16 rhblocks; /* The number of blocks to buffer in memory */
- rwbreload_t rhreload; /* Callout to reload the read-ahead buffer */
+ uint16 rhblocks; /* The number of blocks to buffer in memory */
+ rwbreload_t rhreload; /* Callout to reload the read-ahead buffer */
#endif
/********************************************************************/
@@ -121,23 +121,23 @@ struct rwbuffer_s
/* This is the state of the write buffer */
#ifdef CONFIG_FS_WRITEBUFFER
- sem_t wrsem; /* Enforces exclusive access to the write buffer */
- WDOG_ID wdog; /* Watchdog fires after delay with no activity */
- ubyte *wrbuffer; /* Allocated write buffer */
- size_t wrnbytes; /* Bytes in write buffer */
- off_t wrblockstart; /* First block in write buffer */
- off_t wrexpectedblock; /* Next block expected */
- size_t wrallocsize; /* Size of allocated write buffer */
+ sem_t wrsem; /* Enforces exclusive access to the write buffer */
+ struct work_s work; /* Delayed work to flush buffer after adelay with no activity */
+ ubyte *wrbuffer; /* Allocated write buffer */
+ size_t wrnbytes; /* Bytes in write buffer */
+ off_t wrblockstart; /* First block in write buffer */
+ off_t wrexpectedblock; /* Next block expected */
+ size_t wrallocsize; /* Size of allocated write buffer */
#endif
/* This is the state of the read-ahead buffer */
#ifdef CONFIG_FS_READAHEAD
- sem_t rhsem; /* Enforces exclusive access to the write buffer */
- ubyte *rhbuffer; /* Allocated read-ahead buffer */
- size_t rhnbytes; /* Blocks in read-ahead buffer */
- off_t rhblockstart; /* First block in read-ahead buffer */
- size_t rhallocsize; /* Size of allocated read-ahead buffer */
+ sem_t rhsem; /* Enforces exclusive access to the write buffer */
+ ubyte *rhbuffer; /* Allocated read-ahead buffer */
+ size_t rhnbytes; /* Blocks in read-ahead buffer */
+ off_t rhblockstart; /* First block in read-ahead buffer */
+ size_t rhallocsize; /* Size of allocated read-ahead buffer */
#endif
};
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
new file mode 100755
index 000000000..5b6a3651e
--- /dev/null
+++ b/nuttx/include/nuttx/wqueue.h
@@ -0,0 +1,142 @@
+/****************************************************************************
+ * include/nuttx/wqueue.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 __INCLUDE_NUTTX_WQUEUE_H
+#define __INCLUDE_NUTTX_WQUEUE_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <queue.h>
+
+#ifdef CONFIG_SCHED_WORKQUEUE
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* Defines the work callback */
+
+typedef FAR void (*worker_t)(FAR void *arg);
+
+/* Defines one entry in the work queue. The user only needs this structure
+ * in order to declare instances of the work structure. Handling of all
+ * fields is performed by the work APIs
+ */
+
+struct work_s
+{
+ struct dq_entry_s dq; /* Implements a doubly linked list */
+ worker_t worker; /* Work callback */
+ FAR void *arg; /* Callback argument */
+ uint32 qtime; /* Time work queued */
+ uint32 delay; /* Delay until work performed */
+};
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* The task ID of the worker thread */
+
+EXTERN pid_t g_worker;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: work_queue
+ *
+ * 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).
+ *
+ * Input parameters:
+ * 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
+ *
+ ****************************************************************************/
+
+EXTERN int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint32 delay);
+
+/****************************************************************************
+ * Name: work_cancel
+ *
+ * Description:
+ * Cancel previously queued work.
+ *
+ * Input parameters:
+ * work - The previously queue work structure to cancel
+ *
+ * Returned Value:
+ * Zero on success, a negated errno on failure
+ *
+ ****************************************************************************/
+
+EXTERN int work_cancel(struct work_s *work);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_SCHED_WORKQUEUE */
+#endif /* __INCLUDE_NUTTX_WQUEUE_H */
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 84609a021..3a2512662 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -135,10 +135,14 @@ TIMER_SRCS = timer_initialize.c timer_create.c timer_delete.c timer_getoverrun.c
timer_gettime.c timer_settime.c timer_release.c
endif
+ifeq ($(CONFIG_SCHED_WORKQUEUE),y)
+WORK_SRCS = work_queue.c work_cancel.c
+endif
+
IRQ_SRCS = irq_initialize.c irq_attach.c irq_dispatch.c irq_unexpectedisr.c
CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(SCHED_SRCS) $(WDOG_SRCS) $(TIME_SRCS) \
- $(SEM_SRCS) $(TIMER_SRCS) $(IRQ_SRCS)
+ $(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(IRQ_SRCS)
ifneq ($(CONFIG_DISABLE_CLOCK),y)
CSRCS += $(CLOCK_SRCS)
endif
diff --git a/nuttx/sched/work_cancel.c b/nuttx/sched/work_cancel.c
new file mode 100755
index 000000000..1a5cce312
--- /dev/null
+++ b/nuttx/sched/work_cancel.c
@@ -0,0 +1,110 @@
+/****************************************************************************
+ * sched/work_cancel.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <sys/types.h>
+
+#include <queue.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.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_cancel
+ *
+ * Description:
+ * Cancel previously queued work.
+ *
+ * Input parameters:
+ * work - The previously queue work structure to cancel
+ *
+ * Returned Value:
+ * Zero on success, a negated errno on failure
+ *
+ ****************************************************************************/
+
+int work_cancel(struct work_s *work)
+{
+ irqstate_t flags;
+
+ 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();
+ DEBUGASSERT(work->flink || (FAR dq_entry_t *)work == g_work.head);
+ DEBUGASSERT(work->blink || (FAR dq_entry_t *)work == g_work.tail);
+ dq_rem((FAR dq_entry_t *)work, &g_work);
+ irqrestore(flags);
+ return OK;
+}
+#endif /* CONFIG_SCHED_WORKQUEUE */
diff --git a/nuttx/sched/work_internal.h b/nuttx/sched/work_internal.h
new file mode 100755
index 000000000..e86ee0ac2
--- /dev/null
+++ b/nuttx/sched/work_internal.h
@@ -0,0 +1,73 @@
+/****************************************************************************
+ * sched/work_internal.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 __SCHED_WORK_INTERNAL_H
+#define __SCHED_WORK_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <queue.h>
+
+#ifdef CONFIG_SCHED_WORKQUEUE
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* The queue of pending work */
+
+extern struct dq_queue_s g_work;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_SCHED_WORKQUEUE */
+#endif /* __SCHED_WORK_INTERNAL_H */
diff --git a/nuttx/sched/work_queue.c b/nuttx/sched/work_queue.c
new file mode 100755
index 000000000..9e8c44e52
--- /dev/null
+++ b/nuttx/sched/work_queue.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ * sched/work_queue.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <sys/types.h>
+
+#include <queue.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/clock.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_queue
+ *
+ * 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).
+ *
+ * Input parameters:
+ * 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
+ *
+ ****************************************************************************/
+
+int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint32 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 = g_system_timer; /* Time work queued */
+ dq_addlast((FAR dq_entry_t *)work, &g_work);
+ irqrestore(flags);
+ return OK;
+}
+#endif /* CONFIG_SCHED_WORKQUEUE */