summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-27 15:52:58 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-27 15:52:58 +0000
commit2f2cd79e084223f644af5bb88ff19fd4f739f8b7 (patch)
treedebe53d5a4c8d5a904b5487d632995bbab5a11a2 /nuttx/sched
parent46d5183722a1aac256357f1a054575c6d5ab9a9f (diff)
downloadpx4-nuttx-2f2cd79e084223f644af5bb88ff19fd4f739f8b7.tar.gz
px4-nuttx-2f2cd79e084223f644af5bb88ff19fd4f739f8b7.tar.bz2
px4-nuttx-2f2cd79e084223f644af5bb88ff19fd4f739f8b7.zip
Add a start hook that can be setup to call a function in the context of a new thread before the new threads main() has been called.
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5571 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig10
-rw-r--r--nuttx/sched/Makefile4
-rw-r--r--nuttx/sched/group_setupidlefiles.c1
-rw-r--r--nuttx/sched/group_setupstreams.c2
-rw-r--r--nuttx/sched/group_setuptaskfiles.c5
-rw-r--r--nuttx/sched/task_start.c9
-rw-r--r--nuttx/sched/task_starthook.c100
7 files changed, 129 insertions, 2 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index 7745c2c25..097dd1993 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -296,6 +296,16 @@ config SCHED_WAITPID
compliant) and will enable the waitid() and wait() interfaces as
well.
+config SCHED_STARTHOOK
+ bool "Enable startup hook"
+ default n
+ ---help---
+ Enable a non-standard, internal OS API call task_starthook().
+ task_starthook() registers a function that will be called on task
+ startup before that actual task entry point is called. The
+ starthook is useful, for example, for setting up automatic
+ configuration of C++ constructors.
+
config SCHED_ATEXIT
bool "Enable atexit() API"
default n
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 7710ae058..961560176 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -54,6 +54,10 @@ TSK_SRCS += task_posixspawn.c
endif
endif
+ifeq ($(CONFIG_SCHED_STARTHOOK),y)
+TSK_SRCS += task_starthook.c
+endif
+
SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c
SCHED_SRCS += sched_setscheduler.c sched_getscheduler.c
SCHED_SRCS += sched_yield.c sched_rrgetinterval.c sched_foreach.c
diff --git a/nuttx/sched/group_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c
index 98cc7885e..ceb9f3e2c 100644
--- a/nuttx/sched/group_setupidlefiles.c
+++ b/nuttx/sched/group_setupidlefiles.c
@@ -50,6 +50,7 @@
#include <nuttx/net/net.h>
#include "os_internal.h"
+#include "group_internal.h"
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
diff --git a/nuttx/sched/group_setupstreams.c b/nuttx/sched/group_setupstreams.c
index 88e266280..08399ae41 100644
--- a/nuttx/sched/group_setupstreams.c
+++ b/nuttx/sched/group_setupstreams.c
@@ -46,6 +46,8 @@
#include <nuttx/net/net.h>
#include <nuttx/lib.h>
+#include "group_internal.h"
+
/* Make sure that there are file or socket descriptors in the system and
* that some number of streams have been configured.
*/
diff --git a/nuttx/sched/group_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c
index d52adcfee..e2e7d4634 100644
--- a/nuttx/sched/group_setuptaskfiles.c
+++ b/nuttx/sched/group_setuptaskfiles.c
@@ -46,6 +46,7 @@
#include <nuttx/net/net.h>
#include "os_internal.h"
+#include "group_internal.h"
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
@@ -159,8 +160,8 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
/* Get pointers to the parent and child task socket lists */
- parent = rtcb->group->tg_sockets->sl_sockets;
- child = tcb->group->tg_sockets->sl_sockets;
+ parent = rtcb->group->tg_socketlist.sl_sockets;
+ child = tcb->group->tg_socketlist.sl_sockets;
/* Check each socket in the parent socket list */
diff --git a/nuttx/sched/task_start.c b/nuttx/sched/task_start.c
index a9cc38dfc..5a32a5dd8 100644
--- a/nuttx/sched/task_start.c
+++ b/nuttx/sched/task_start.c
@@ -94,6 +94,15 @@ void task_start(void)
FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
int argc;
+ /* Execute the start hook if one has been registered */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+ if (tcb->starthook)
+ {
+ tcb->starthook(tcb->starthookarg);
+ }
+#endif
+
/* Count how many non-null arguments we are passing */
for (argc = 1; argc <= CONFIG_MAX_TASK_ARGS; argc++)
diff --git a/nuttx/sched/task_starthook.c b/nuttx/sched/task_starthook.c
new file mode 100644
index 000000000..1cb29349f
--- /dev/null
+++ b/nuttx/sched/task_starthook.c
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * sched/task_start.c
+ *
+ * Copyright (C) 2007-2010 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 <nuttx/sched.h>
+
+#ifdef CONFIG_SCHED_STARTHOOK
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: task_starthook
+ *
+ * Description:
+ * Configure a start hook... a function that will be called on the thread
+ * of the new task before the new task's main entry point is called.
+ * The start hook is useful, for example, for setting up automatic
+ * configuration of C++ constructors.
+ *
+ * Inputs:
+ * tcb - The new, unstarted task task that needs the start hook
+ * starthook - The pointer to the start hook function
+ * arg - The argument to pass to the start hook function.
+ *
+ * Return:
+ * None
+ *
+ ****************************************************************************/
+
+void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg)
+{
+ DEBUGASSERT(tcb);
+ tcb->starthook = starthook;
+ tcb->starthookarg = arg;
+}
+
+#endif /* CONFIG_SCHED_STARTHOOK */