summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/TODO44
-rw-r--r--nuttx/include/nuttx/sched.h37
-rw-r--r--nuttx/sched/clock_abstime2ticks.c2
-rw-r--r--nuttx/sched/clock_initialize.c2
-rw-r--r--nuttx/sched/env_getenv.c4
-rw-r--r--nuttx/sched/env_getenvironptr.c4
-rw-r--r--nuttx/sched/env_setenv.c4
-rw-r--r--nuttx/sched/group_create.c33
-rw-r--r--nuttx/sched/group_internal.h12
-rw-r--r--nuttx/sched/group_join.c20
-rw-r--r--nuttx/sched/group_setupstreams.c3
-rw-r--r--nuttx/sched/group_setuptaskfiles.c3
-rw-r--r--nuttx/sched/os_start.c4
-rw-r--r--nuttx/sched/pthread_create.c4
-rw-r--r--nuttx/sched/sched_wait.c3
-rw-r--r--nuttx/sched/sched_waitid.c3
-rw-r--r--nuttx/sched/task_create.c4
-rw-r--r--nuttx/sched/task_exithook.c11
-rw-r--r--nuttx/sched/task_init.c4
20 files changed, 140 insertions, 66 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 1ec62c208..980885b00 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4130,4 +4130,9 @@
for pthreads. By dividing the TCB structure into these variants,
pthreads do not have to be burdened by task-specific data structures
(and vice versa).
+ * sched/task_exithook.c adn group_create.c: Fix an error, the
+ task within the task group may exit early leaving a pthread to
+ exit the task group last. In this case, we need to remember the
+ the PID of the main task in the task group and use that PID for
+ signalling SIGCHILD to the parent task group.
diff --git a/nuttx/TODO b/nuttx/TODO
index 3f26b852b..3e2413ded 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements.
nuttx/
- (11) Task/Scheduler (sched/)
+ (12) Task/Scheduler (sched/)
(1) Memory Managment (mm/)
(3) Signals (sched/, arch/)
(2) pthreads (sched/)
@@ -204,6 +204,48 @@ o Task/Scheduler (sched/)
incompatibilities could show up in porting some code).
Priority: Low
+ Title: SIGNALS IN TASK GROUPS WITH MANY PTHREADS
+ Description: Presumably when you single the task group you would signal
+ using the task ID of the task that created the group (in
+ practice, a different task should not know the IDs of the
+ internal threads created within the task group).
+
+ Here are some of the things that should happen, but don't
+ as of this writing:
+
+ - If a task group receives a signal then one and only one
+ indeterminate thread in the process which is not blocking
+ the signal should receive the signal.
+
+ - If a task group receives a signal and more than one thread
+ is waiting on that signal, then one and only one
+ indeterminate thread out of that waiting group will receive
+ the signal.
+
+ - If any signal which would normally cause the termination of
+ a process is sent to a thread it will result in the parent
+ process and all threads being terminated. (NuttX does not
+ support these default signal actions... that is really
+ another topic).
+
+ On creation a thread does correctly inherits the signal mask of the thread that created it.
+
+ You should be able to control which thread receives the signal
+ by control the signal mask. You should, for example, be able
+ to create a seperate thread whose sole purpose it is to catch
+ signals and respond to them. You can mask out certain signals
+ using sigprocmask() (or pthread_sigmask()). These signals
+ will be effectively disabled and will never be received in
+ these contexts. In the "signal processing" thread, enable the
+ blocked signals. This should now be the only thread who
+ receives the signals.
+
+ At present, the signal APIs will attempt to signal only the
+ thread that is the main task of the task group.
+ Status: Open.
+ Priority: Medium-high for spec compliance; but probably low for everyday
+ embedded applications.
+
o Memory Managment (mm/)
^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 02d44d829..47910fabe 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -77,22 +77,24 @@
*/
#else
-# if !defined(CONFIG_DISABLE_ENVIRON) /* Environment variables */
-# define HAVE_TASK_GROUP 1
-# elif defined(CONFIG_SCHED_ATEXIT) /* Group atexit() function */
-# define HAVE_TASK_GROUP 1
-# elif defined(CONFIG_SCHED_ONEXIT) /* Group on_exit() function */
-# define HAVE_TASK_GROUP 1
-# elif defined(CONFIG_SCHED_WAITPID) /* Group waitpid() function */
-# define HAVE_TASK_GROUP 1
-# elif CONFIG_NFILE_DESCRIPTORS > 0 /* File descriptors */
-# define HAVE_TASK_GROUP 1
-# elif CONFIG_NFILE_STREAMS > 0 /* Standard C buffered I/O */
-# define HAVE_TASK_GROUP 1
-# elif CONFIG_NSOCKET_DESCRIPTORS > 0 /* Sockets */
-# define HAVE_TASK_GROUP 1
-# elif !defined(CONFIG_DISABLE_MQUEUE) /* Message queues */
-# define HAVE_TASK_GROUP 1
+# if !defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_SCHED_HAVE_PARENT)
+# define HAVE_TASK_GROUP 1 /* pthreads with parent*/
+# elif !defined(CONFIG_DISABLE_ENVIRON)
+# define HAVE_TASK_GROUP 1 /* Environment variables */
+# elif defined(CONFIG_SCHED_ATEXIT)
+# define HAVE_TASK_GROUP 1 /* Group atexit() function */
+# elif defined(CONFIG_SCHED_ONEXIT)
+# define HAVE_TASK_GROUP 1 /* Group on_exit() function */
+# elif defined(CONFIG_SCHED_WAITPID)
+# define HAVE_TASK_GROUP 1 /* Group waitpid() function */
+# elif CONFIG_NFILE_DESCRIPTORS > 0
+# define HAVE_TASK_GROUP 1 /* File descriptors */
+# elif CONFIG_NFILE_STREAMS > 0
+# define HAVE_TASK_GROUP 1 /* Standard C buffered I/O */
+# elif CONFIG_NSOCKET_DESCRIPTORS > 0
+# define HAVE_TASK_GROUP 1 /* Sockets */
+# elif !defined(CONFIG_DISABLE_MQUEUE)
+# define HAVE_TASK_GROUP 1 /* Message queues */
# endif
#endif
@@ -294,6 +296,9 @@ struct task_group_s
gid_t tg_gid; /* The ID of this task group */
gid_t tg_pgid; /* The ID of the parent task group */
#endif
+#if !defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_SCHED_HAVE_PARENT)
+ pid_t tg_task; /* The ID of the task within the group */
+#endif
uint8_t tg_flags; /* See GROUP_FLAG_* definitions */
/* Group membership ***********************************************************/
diff --git a/nuttx/sched/clock_abstime2ticks.c b/nuttx/sched/clock_abstime2ticks.c
index 2d7f7f480..c55865635 100644
--- a/nuttx/sched/clock_abstime2ticks.c
+++ b/nuttx/sched/clock_abstime2ticks.c
@@ -120,7 +120,7 @@ int clock_abstime2ticks(clockid_t clockid, FAR const struct timespec *abstime,
reltime.tv_sec -= 1;
}
- /* Convert this relative time into microseconds.*/
+ /* Convert this relative time into microseconds. */
return clock_time2ticks(&reltime, ticks);
}
diff --git a/nuttx/sched/clock_initialize.c b/nuttx/sched/clock_initialize.c
index 2e146bb47..85a7294ab 100644
--- a/nuttx/sched/clock_initialize.c
+++ b/nuttx/sched/clock_initialize.c
@@ -179,7 +179,7 @@ static inline void clock_basetime(FAR struct timespec *tp)
static void clock_inittime(void)
{
- /* (Re-)initialize the time value to match the RTC*/
+ /* (Re-)initialize the time value to match the RTC */
clock_basetime(&g_basetime);
g_system_timer = 0;
diff --git a/nuttx/sched/env_getenv.c b/nuttx/sched/env_getenv.c
index 0414e23aa..0b847950a 100644
--- a/nuttx/sched/env_getenv.c
+++ b/nuttx/sched/env_getenv.c
@@ -91,7 +91,7 @@ FAR char *getenv(const char *name)
goto errout;
}
- /* Get a reference to the thread-private environ in the TCB.*/
+ /* Get a reference to the thread-private environ in the TCB. */
sched_lock();
rtcb = (FAR struct tcb_s*)g_readytorun.head;
@@ -131,5 +131,3 @@ errout:
#endif /* CONFIG_DISABLE_ENVIRON */
-
-
diff --git a/nuttx/sched/env_getenvironptr.c b/nuttx/sched/env_getenvironptr.c
index 91f3940b6..5808dc5dd 100644
--- a/nuttx/sched/env_getenvironptr.c
+++ b/nuttx/sched/env_getenvironptr.c
@@ -83,7 +83,7 @@ FAR char **get_environ_ptr( void )
#else
- /* Return a reference to the thread-private environ in the TCB.*/
+ /* Return a reference to the thread-private environ in the TCB. */
FAR struct tcb_s *ptcb = (FAR struct tcb_s*)g_readytorun.head;
if (ptcb->envp)
@@ -100,5 +100,3 @@ FAR char **get_environ_ptr( void )
#endif /* CONFIG_DISABLE_ENVIRON */
-
-
diff --git a/nuttx/sched/env_setenv.c b/nuttx/sched/env_setenv.c
index 772b01160..7ce3e1a1f 100644
--- a/nuttx/sched/env_setenv.c
+++ b/nuttx/sched/env_setenv.c
@@ -121,7 +121,7 @@ int setenv(FAR const char *name, FAR const char *value, int overwrite)
}
}
- /* Get a reference to the thread-private environ in the TCB.*/
+ /* Get a reference to the thread-private environ in the TCB. */
sched_lock();
rtcb = (FAR struct tcb_s*)g_readytorun.head;
@@ -203,5 +203,3 @@ errout:
#endif /* CONFIG_DISABLE_ENVIRON */
-
-
diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c
index 414fe1824..ccf2e7519 100644
--- a/nuttx/sched/group_create.c
+++ b/nuttx/sched/group_create.c
@@ -174,12 +174,12 @@ void group_assigngid(FAR struct task_group_s *group)
*
*****************************************************************************/
-int group_allocate(FAR struct tcb_s *tcb)
+int group_allocate(FAR struct task_tcb_s *tcb)
{
FAR struct task_group_s *group;
int ret;
- DEBUGASSERT(tcb && !tcb->group);
+ DEBUGASSERT(tcb && !tcb->cmn.group);
/* Allocate the group structure and assign it to the TCB */
@@ -191,7 +191,7 @@ int group_allocate(FAR struct tcb_s *tcb)
/* Attach the group to the TCB */
- tcb->group = group;
+ tcb->cmn.group = group;
/* Assign the group a unique ID. If g_gidcounter were to wrap before we
* finish with task creation, that would be a problem.
@@ -207,7 +207,7 @@ int group_allocate(FAR struct tcb_s *tcb)
if (ret < 0)
{
kfree(group);
- tcb->group = NULL;
+ tcb->cmn.group = NULL;
return ret;
}
@@ -241,15 +241,15 @@ int group_allocate(FAR struct tcb_s *tcb)
*
*****************************************************************************/
-int group_initialize(FAR struct tcb_s *tcb)
+int group_initialize(FAR struct task_tcb_s *tcb)
{
FAR struct task_group_s *group;
#ifdef HAVE_GROUP_MEMBERS
irqstate_t flags;
#endif
- DEBUGASSERT(tcb && tcb->group);
- group = tcb->group;
+ DEBUGASSERT(tcb && tcb->cmn.group);
+ group = tcb->cmn.group;
#ifdef HAVE_GROUP_MEMBERS
/* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */
@@ -261,9 +261,9 @@ int group_initialize(FAR struct tcb_s *tcb)
return -ENOMEM;
}
- /* Assign the PID of this new task as a member of the group*/
+ /* Assign the PID of this new task as a member of the group. */
- group->tg_members[0] = tcb->pid;
+ group->tg_members[0] = tcb->cmn.pid;
/* Initialize the non-zero elements of group structure and assign it to
* the tcb.
@@ -280,8 +280,21 @@ int group_initialize(FAR struct tcb_s *tcb)
#endif
- group->tg_nmembers = 1; /* Number of members in the group */
+ /* Save the ID of the main task within the group of threads. This needed
+ * for things like SIGCHILD. It ID is also saved in the TCB of the main
+ * task but is also retained in the group which may persist after the main
+ * task has exited.
+ */
+
+#if !defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_SCHED_HAVE_PARENT)
+ group->tg_task = tcb->cmn.pid;
+#endif
+
+ /* Mark that there is one member in the group, the main task */
+
+ group->tg_nmembers = 1;
return OK;
}
#endif /* HAVE_TASK_GROUP */
+
diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h
index e79f96e8c..f29cb53de 100644
--- a/nuttx/sched/group_internal.h
+++ b/nuttx/sched/group_internal.h
@@ -76,16 +76,18 @@ extern FAR struct task_group_s *g_grouphead;
/* Task group data structure management */
#ifdef HAVE_TASK_GROUP
-int group_allocate(FAR struct tcb_s *tcb);
-int group_initialize(FAR struct tcb_s *tcb);
-int group_bind(FAR struct tcb_s *tcb);
-int group_join(FAR struct tcb_s *tcb);
+int group_allocate(FAR struct task_tcb_s *tcb);
+int group_initialize(FAR struct task_tcb_s *tcb);
+#ifndef CONFIG_DISABLE_PTHREAD
+int group_bind(FAR struct pthread_tcb_s *tcb);
+int group_join(FAR struct pthread_tcb_s *tcb);
+#endif
void group_leave(FAR struct tcb_s *tcb);
#ifdef HAVE_GROUP_MEMBERS
FAR struct task_group_s *group_find(gid_t gid);
int group_addmember(FAR struct task_group_s *group, pid_t pid);
-int group_removemember(FAR struct task_group_s *group, pid_t pid);
+int group_removemember(FAR struct task_group_s *group, pid_t pid);
#endif
/* Convenience functions */
diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c
index 564fbe7e9..f6babb871 100644
--- a/nuttx/sched/group_join.c
+++ b/nuttx/sched/group_join.c
@@ -49,7 +49,7 @@
#include "group_internal.h"
#include "env_internal.h"
-#ifdef HAVE_TASK_GROUP
+#if defined(HAVE_TASK_GROUP) && !defined(CONFIG_DISABLE_PTHREAD)
/*****************************************************************************
* Pre-processor Definitions
@@ -99,15 +99,15 @@
*
*****************************************************************************/
-int group_bind(FAR struct tcb_s *tcb)
+int group_bind(FAR struct pthread_tcb_s *tcb)
{
FAR struct tcb_s *ptcb = (FAR struct tcb_s *)g_readytorun.head;
- DEBUGASSERT(ptcb && tcb && ptcb->group && !tcb->group);
+ DEBUGASSERT(ptcb && tcb && ptcb->group && !tcb->cmn.group);
/* Copy the group reference from the parent to the child */
- tcb->group = ptcb->group;
+ tcb->cmn.group = ptcb->group;
return OK;
}
@@ -136,24 +136,24 @@ int group_bind(FAR struct tcb_s *tcb)
*
*****************************************************************************/
-int group_join(FAR struct tcb_s *tcb)
+int group_join(FAR struct pthread_tcb_s *tcb)
{
FAR struct task_group_s *group;
#ifdef HAVE_GROUP_MEMBERS
int ret;
#endif
- DEBUGASSERT(tcb && tcb->group &&
- tcb->group->tg_nmembers < UINT8_MAX);
+ DEBUGASSERT(tcb && tcb->cmn.group &&
+ tcb->cmn.group->tg_nmembers < UINT8_MAX);
/* Get the group from the TCB */
- group = tcb->group;
+ group = tcb->cmn.group;
#ifdef HAVE_GROUP_MEMBERS
/* Add the member to the group */
- ret = group_addmember(group, tcb->pid);
+ ret = group_addmember(group, tcb->cmn.pid);
if (ret < 0)
{
return ret;
@@ -224,4 +224,4 @@ int group_addmember(FAR struct task_group_s *group, pid_t pid)
}
#endif /* HAVE_GROUP_MEMBERS */
-#endif /* HAVE_TASK_GROUP */
+#endif /* HAVE_TASK_GROUP && !CONFIG_DISABLE_PTHREAD */
diff --git a/nuttx/sched/group_setupstreams.c b/nuttx/sched/group_setupstreams.c
index 217decd57..4a9fa5762 100644
--- a/nuttx/sched/group_setupstreams.c
+++ b/nuttx/sched/group_setupstreams.c
@@ -96,4 +96,5 @@ int group_setupstreams(FAR struct task_tcb_s *tcb)
}
#endif /* CONFIG_NFILE_STREAMS > 0 */
-#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
diff --git a/nuttx/sched/group_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c
index 269485ea4..6809f9784 100644
--- a/nuttx/sched/group_setuptaskfiles.c
+++ b/nuttx/sched/group_setuptaskfiles.c
@@ -246,4 +246,5 @@ int group_setuptaskfiles(FAR struct task_tcb_s *tcb)
#endif
}
-#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 */
+
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index ace475ba1..86b40bfbb 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -330,7 +330,7 @@ void os_start(void)
/* Allocate the IDLE group and suppress child status. */
#ifdef HAVE_TASK_GROUP
- (void)group_allocate(&g_idletcb.cmn);
+ (void)group_allocate(&g_idletcb);
#endif
/* Initialize the interrupt handling subsystem (if included) */
@@ -456,7 +456,7 @@ void os_start(void)
*/
#ifdef HAVE_TASK_GROUP
- (void)group_initialize(&g_idletcb.cmn);
+ (void)group_initialize(&g_idletcb);
g_idletcb.cmn.group->tg_flags = GROUP_FLAG_NOCLDWAIT;
#endif
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index 70b5ceb49..696e2c06c 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -255,7 +255,7 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
*/
#ifdef HAVE_TASK_GROUP
- ret = group_bind((FAR struct tcb_s *)ptcb);
+ ret = group_bind(ptcb);
if (ret < 0)
{
errcode = ENOMEM;
@@ -354,7 +354,7 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Join the parent's task group */
#ifdef HAVE_TASK_GROUP
- ret = group_join((FAR struct tcb_s *)ptcb);
+ ret = group_join(ptcb);
if (ret < 0)
{
errcode = ENOMEM;
diff --git a/nuttx/sched/sched_wait.c b/nuttx/sched/sched_wait.c
index 813d4f842..9a6265e70 100644
--- a/nuttx/sched/sched_wait.c
+++ b/nuttx/sched/sched_wait.c
@@ -87,4 +87,5 @@ pid_t wait(FAR int *stat_loc)
return waitpid((pid_t)-1, stat_loc, 0);
}
-#endif /* CONFIG_SCHED_WAITPID && CONFIG_SCHED_HAVE_PARENT*/
+#endif /* CONFIG_SCHED_WAITPID && CONFIG_SCHED_HAVE_PARENT */
+
diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c
index e75cf4987..545353e8b 100644
--- a/nuttx/sched/sched_waitid.c
+++ b/nuttx/sched/sched_waitid.c
@@ -405,4 +405,5 @@ errout:
return ERROR;
}
-#endif /* CONFIG_SCHED_WAITPID && CONFIG_SCHED_HAVE_PARENT*/
+#endif /* CONFIG_SCHED_WAITPID && CONFIG_SCHED_HAVE_PARENT */
+
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 30fc1354f..15bdebdb9 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -123,7 +123,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
/* Allocate a new task group */
#ifdef HAVE_TASK_GROUP
- ret = group_allocate((FAR struct tcb_s *)tcb);
+ ret = group_allocate(tcb);
if (ret < 0)
{
errcode = -ret;
@@ -169,7 +169,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
/* Now we have enough in place that we can join the group */
#ifdef HAVE_TASK_GROUP
- ret = group_initialize((FAR struct tcb_s *)tcb);
+ ret = group_initialize(tcb);
if (ret < 0)
{
errcode = -ret;
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 1c2137545..688c25c44 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -343,7 +343,11 @@ static inline void task_sigchild(gid_t pgid, FAR struct tcb_s *ctcb, int status)
info.si_signo = SIGCHLD;
info.si_code = CLD_EXITED;
info.si_value.sival_ptr = NULL;
+#ifndef CONFIG_DISABLE_PTHREAD
+ info.si_pid = chgrp->tg_task;
+#else
info.si_pid = ctcb->pid;
+#endif
info.si_status = status;
/* Send the signal. We need to use this internal interface so that we
@@ -356,7 +360,8 @@ static inline void task_sigchild(gid_t pgid, FAR struct tcb_s *ctcb, int status)
#else /* HAVE_GROUP_MEMBERS */
-static inline void task_sigchild(FAR struct tcb_s *ptcb, FAR struct tcb_s *ctcb, int status)
+static inline void task_sigchild(FAR struct tcb_s *ptcb,
+ FAR struct tcb_s *ctcb, int status)
{
siginfo_t info;
@@ -391,7 +396,11 @@ static inline void task_sigchild(FAR struct tcb_s *ptcb, FAR struct tcb_s *ctcb,
info.si_signo = SIGCHLD;
info.si_code = CLD_EXITED;
info.si_value.sival_ptr = NULL;
+#ifndef CONFIG_DISABLE_PTHREAD
+ info.si_pid = chgrp->tg_task;
+#else
info.si_pid = ctcb->pid;
+#endif
info.si_status = status;
/* Send the signal. We need to use this internal interface so that we
diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c
index 802d0748d..79189f6cc 100644
--- a/nuttx/sched/task_init.c
+++ b/nuttx/sched/task_init.c
@@ -134,7 +134,7 @@ int task_init(FAR struct tcb_s *tcb, const char *name, int priority,
/* Create a new task group */
#ifdef HAVE_TASK_GROUP
- ret = group_allocate(tcb);
+ ret = group_allocate(ttcb);
if (ret < 0)
{
errcode = -ret;
@@ -176,7 +176,7 @@ int task_init(FAR struct tcb_s *tcb, const char *name, int priority,
/* Now we have enough in place that we can join the group */
#ifdef HAVE_TASK_GROUP
- ret = group_initialize(tcb);
+ ret = group_initialize(ttcb);
if (ret < 0)
{
errcode = -ret;