From e95efd5d2a08dcb62c8c635089e4fe146965db45 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 17:23:38 +0000 Subject: Add framework to support task groups git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5562 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/sched/sched_releasetcb.c | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) (limited to 'nuttx/sched/sched_releasetcb.c') diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 0557c829b..50505f579 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_releasetcb.c * - * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -177,6 +177,11 @@ int sched_releasetcb(FAR _TCB *tcb) ret = up_addrenv_release(tcb); #endif + /* Leave the group (if we did not already leady in task_exithook.c) */ + +#ifdef HAVE_TASK_GROUP + group_leave(tcb); +#endif /* And, finally, release the TCB itself */ sched_free(tcb); -- cgit v1.2.3 From 239e2808cca6ee4c356d087bc83889fc57e64307 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 23:21:27 +0000 Subject: Move environment variables in the task group structure git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5565 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/include/nuttx/sched.h | 43 +++++++-------- nuttx/sched/Makefile | 2 +- nuttx/sched/env_clearenv.c | 5 +- nuttx/sched/env_dup.c | 26 +++++---- nuttx/sched/env_dupenv.c | 112 --------------------------------------- nuttx/sched/env_findvar.c | 33 +++++------- nuttx/sched/env_getenv.c | 14 ++--- nuttx/sched/env_internal.h | 32 ++++++----- nuttx/sched/env_release.c | 68 +++++++++--------------- nuttx/sched/env_removevar.c | 56 ++++++++++---------- nuttx/sched/env_setenv.c | 59 ++++++++++----------- nuttx/sched/env_share.c | 117 ----------------------------------------- nuttx/sched/env_unsetenv.c | 62 +++++++++------------- nuttx/sched/group_create.c | 24 ++++++++- nuttx/sched/group_internal.h | 104 ++++++++++++++++++++++++++++++++++++ nuttx/sched/group_join.c | 5 +- nuttx/sched/group_leave.c | 20 +++++-- nuttx/sched/group_signal.c | 2 + nuttx/sched/os_internal.h | 38 ++----------- nuttx/sched/os_start.c | 5 +- nuttx/sched/pthread_create.c | 6 +-- nuttx/sched/sched_releasetcb.c | 6 +-- nuttx/sched/sched_waitid.c | 1 + nuttx/sched/sched_waitpid.c | 1 + nuttx/sched/sig_action.c | 1 + nuttx/sched/task_childstatus.c | 1 + nuttx/sched/task_create.c | 6 +-- nuttx/sched/task_exithook.c | 1 + nuttx/sched/task_init.c | 13 ++--- nuttx/sched/task_posixspawn.c | 1 + nuttx/sched/task_reparent.c | 1 + nuttx/sched/task_setup.c | 1 + nuttx/sched/task_vfork.c | 6 +-- 34 files changed, 347 insertions(+), 527 deletions(-) delete mode 100644 nuttx/sched/env_dupenv.c delete mode 100644 nuttx/sched/env_share.c create mode 100644 nuttx/sched/group_internal.h (limited to 'nuttx/sched/sched_releasetcb.c') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f033fc9ba..f23a3ed73 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4029,4 +4029,6 @@ support for task groups. * sched/group_signal.c and task_exithook.c: Send signal to all members for the parent task group. + * include/nuttx/sched.h and sched/env_*.c: Move environment + variables into task group structure. diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 2795751ab..dd33b4570 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -68,6 +68,11 @@ # define HAVE_GROUP_MEMBERS 1 #endif +#if !defined(CONFIG_DISABLE_ENVIRON) +# undef HAVE_TASK_GROUP +# define HAVE_TASK_GROUP 1 +#endif + /* In any event, we don't need group members if support for pthreads is disabled */ #ifdef CONFIG_DISABLE_PTHREAD @@ -178,21 +183,6 @@ typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg); typedef struct msgq_s msgq_t; -/* struct environ_s **************************************************************/ -/* The structure used to maintain environment variables */ - -#ifndef CONFIG_DISABLE_ENVIRON -struct environ_s -{ - unsigned int ev_crefs; /* Reference count used when environment - * is shared by threads */ - size_t ev_alloc; /* Number of bytes allocated in environment */ - char ev_env[1]; /* Environment strings */ -}; -typedef struct environ_s environ_t; -# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1) -#endif - /* struct child_status_s *********************************************************/ /* This structure is used to maintin information about child tasks. * pthreads work differently, they have join information. This is @@ -263,11 +253,14 @@ struct dspace_s #ifdef HAVE_TASK_GROUP struct task_group_s { - uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ - uint8_t tg_nmembers; /* Number of members in the group */ + uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ + + /* Group membership ***********************************************************/ + + uint8_t tg_nmembers; /* Number of members in the group */ #ifdef HAVE_GROUP_MEMBERS - uint8_t tg_mxmembers; /* Number of members in allocation */ - FAR pid_t *tg_members; /* Members of the group */ + uint8_t tg_mxmembers; /* Number of members in allocation */ + FAR pid_t *tg_members; /* Members of the group */ #endif /* Child exit status **********************************************************/ @@ -276,8 +269,12 @@ struct task_group_s FAR struct child_status_s *tg_children; /* Head of a list of child status */ #endif - /* Environment varibles *******************************************************/ - /* Not yet (see type environ_t) */ + /* Environment variables ******************************************************/ + +#ifndef CONFIG_DISABLE_ENVIRON + size_t tg_envsize; /* Size of environment string allocation */ + FAR char *tg_envp; /* Allocated environment strings */ +#endif /* PIC data space and address environments */ /* Not yet (see struct dspace_s) */ @@ -373,10 +370,6 @@ struct _TCB uint8_t init_priority; /* Initial priority of the task */ char *argv[CONFIG_MAX_TASK_ARGS+1]; /* Name+start-up parameters */ -#ifndef CONFIG_DISABLE_ENVIRON - FAR environ_t *envp; /* Environment variables */ -#endif - /* Stack-Related Fields *******************************************************/ #ifndef CONFIG_CUSTOM_STACK diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index bbf513f34..6a0b99144 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -93,7 +93,7 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y) GRP_SRCS += group_signal.c endif -ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c +ENV_SRCS = env_getenvironptr.c env_dup.c env_release.c ENV_SRCS += env_findvar.c env_removevar.c ENV_SRCS += env_clearenv.c env_getenv.c env_putenv.c env_setenv.c env_unsetenv.c diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c index 75890f3bc..a9e9f5efd 100644 --- a/nuttx/sched/env_clearenv.c +++ b/nuttx/sched/env_clearenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_clearenv.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -74,7 +74,8 @@ int clearenv(void) { - return env_release((FAR _TCB*)g_readytorun.head); + env_release((FAR _TCB*)g_readytorun.head); + return OK; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c index 30c0b7773..479f7cae7 100644 --- a/nuttx/sched/env_dup.c +++ b/nuttx/sched/env_dup.c @@ -68,7 +68,7 @@ * exact duplicate of the parent task's environment. * * Parameters: - * ptcb The tcb to receive the newly allocated copy of the parent + * ctcb The child tcb to receive the newly allocated copy of the parent * TCB's environment structure with reference count equal to one * * Return Value: @@ -79,13 +79,14 @@ * ****************************************************************************/ -int env_dup(FAR _TCB *ptcb) +int env_dup(FAR _TCB *ctcb) { - FAR _TCB *parent = (FAR _TCB*)g_readytorun.head; - environ_t *envp = NULL; + FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head; + FAR char *envp = NULL; + size_t envlen; int ret = OK; - DEBUGASSERT(ptcb); + DEBUGASSERT(ctcb && ptcb && ctcb->group && ptcb->group); /* Pre-emption must be disabled throughout the following because the * environment may be shared. @@ -95,27 +96,24 @@ int env_dup(FAR _TCB *ptcb) /* Does the parent task have an environment? */ - if (parent->envp) + if (ptcb->group && ptcb->group->tg_envp) { /* Yes..The parent task has an environment, duplicate it */ - size_t envlen = parent->envp->ev_alloc; - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(envlen)); + envlen = ptcb->group->tg_envsize; + envp = (FAR char *)kmalloc(envlen); if (!envp) { ret = -ENOMEM; } else { - envp->ev_crefs = 1; - envp->ev_alloc = envlen; - memcpy(envp->ev_env, parent->envp->ev_env, envlen); + ctcb->group->tg_envsize = envlen; + ctcb->group->tg_envp = envp; + memcpy(envp, ptcb->group->tg_envp, envlen); } } - /* Save the cloned environment in the new TCB */ - - ptcb->envp = envp; sched_unlock(); return ret; } diff --git a/nuttx/sched/env_dupenv.c b/nuttx/sched/env_dupenv.c deleted file mode 100644 index 32bf6a433..000000000 --- a/nuttx/sched/env_dupenv.c +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * eched/env_dupenv.c - * - * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#ifndef CONFIG_DISABLE_ENVIRON - -#include -#include - -#include - -#include "os_internal.h" - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: dupenv - * - * Description: - * Copy the internal environment structure of a task. This is the action - * that is performed when a new task is created: The new task has a private, - * exact duplicate of the parent task's environment. - * - * Parameters: - * None - * - * Return Value: - * A pointer to a newly allocated copy of the specified TCB's environment - * structure with reference count equal to one. - * - * Assumptions: - * Not called from an interrupt handler. - * - ****************************************************************************/ - -FAR environ_t *dupenv(FAR _TCB *ptcb) -{ - environ_t *envp = NULL; - - /* Pre-emption must be disabled throughout the following because the - * environment may be shared. - */ - - sched_lock(); - - /* Does the parent task have an environment? */ - - if (ptcb->envp) - { - /* Yes..The parent task has an environment, duplicate it */ - - size_t envlen = ptcb->envp->ev_alloc - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen )); - if (envp) - { - envp->ev_crefs = 1; - envp->ev_alloc = envlen; - memcmp( envp->ev_env, ptcb->envp->ev_env, envlen ); - } - } - - sched_unlock(); - return envp; -} - -#endif /* CONFIG_DISABLE_ENVIRON */ - - - diff --git a/nuttx/sched/env_findvar.c b/nuttx/sched/env_findvar.c index a8e94180c..a744c6c3a 100644 --- a/nuttx/sched/env_findvar.c +++ b/nuttx/sched/env_findvar.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_findvar.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,7 +85,7 @@ static bool env_cmpname(const char *pszname, const char *peqname) * specified name. * * Parameters: - * envp The environment structre to be searched. + * group The task group containging environment array to be searched. * pname The variable name to find * * Return Value: @@ -97,32 +97,25 @@ static bool env_cmpname(const char *pszname, const char *peqname) * ****************************************************************************/ -FAR char *env_findvar(environ_t *envp, const char *pname) +FAR char *env_findvar(FAR struct task_group_s *group, const char *pname) { - char *ret = NULL; + char *ptr; + char *end; /* Verify input parameters */ - if (envp && pname) - { - char *ptr; - char *end = &envp->ev_env[envp->ev_alloc]; - - /* Search for a name=value string with matching name */ + DEBUGASSERT(group && pname); - for (ptr = envp->ev_env; - ptr < end && !env_cmpname( pname, ptr); - ptr += (strlen(ptr) + 1)); + /* Search for a name=value string with matching name */ - /* Check for success */ + end = &group->tg_envp[group->tg_envsize]; + for (ptr = group->tg_envp; + ptr < end && !env_cmpname(pname, ptr); + ptr += (strlen(ptr) + 1)); - if (ptr < end) - { - ret = ptr; - } - } + /* Check for success */ - return ret; + return (ptr < end) ? ptr : NULL; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/env_getenv.c b/nuttx/sched/env_getenv.c index ee8d798b1..4709bc380 100644 --- a/nuttx/sched/env_getenv.c +++ b/nuttx/sched/env_getenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * env_getenv.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -77,10 +77,10 @@ FAR char *getenv(const char *name) { - FAR _TCB *rtcb; - FAR environ_t *envp; - FAR char *pvar; - FAR char *pvalue = NULL; + FAR _TCB *rtcb; + FAR struct task_group_s *group; + FAR char *pvar; + FAR char *pvalue = NULL; int ret = OK; /* Verify that a string was passed */ @@ -95,11 +95,11 @@ FAR char *getenv(const char *name) sched_lock(); rtcb = (FAR _TCB*)g_readytorun.head; - envp = rtcb->envp; + group = rtcb->group; /* Check if the variable exists */ - if ( !envp || (pvar = env_findvar(envp, name)) == NULL) + if ( !group || (pvar = env_findvar(group, name)) == NULL) { ret = ENOENT; goto errout_with_lock; diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h index 5370da059..6f1097c0b 100644 --- a/nuttx/sched/env_internal.h +++ b/nuttx/sched/env_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_internal.h * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -50,9 +50,8 @@ #ifdef CONFIG_DISABLE_ENVIRON # define env_dup(ptcb) (0) -# define env_share(ptcb) (0) # define env_release(ptcb) (0) -#endif +#else /**************************************************************************** * Public Type Declarations @@ -62,34 +61,33 @@ * Public Variables ****************************************************************************/ -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - #ifdef __cplusplus #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif -#ifndef CONFIG_DISABLE_ENVIRON -/* functions used by the task/pthread creation and destruction logic */ +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ -EXTERN int env_dup(FAR _TCB *ptcb); -EXTERN int env_share(FAR _TCB *ptcb); -EXTERN int env_release(FAR _TCB *ptcb); +/* Functions used by the task/pthread creation and destruction logic */ -/* functions used internally by the environment handling logic */ +int env_dup(FAR _TCB *ctcb); +void env_release(FAR _TCB *tcb); -EXTERN FAR char *env_findvar(environ_t *envp, const char *pname); -EXTERN int env_removevar(environ_t *envp, char *pvar); -#endif +/* Functions used internally by the environment handling logic */ + +FAR char *env_findvar(FAR struct task_group_s *group, FAR const char *pname); +int env_removevar(FAR struct task_group_s *group, FAR char *pvar); #undef EXTERN #ifdef __cplusplus } #endif +#endif /* !CONFIG_DISABLE_ENVIRON */ #endif /* __SCHED_ENV_INTERNAL_H */ diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c index 8bc8d2205..4de55c388 100644 --- a/nuttx/sched/env_release.c +++ b/nuttx/sched/env_release.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/env_clearenv.c + * sched/env_release.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -58,65 +58,45 @@ * Name: env_release * * Description: - * The env_release() function clears the environment of all name-value - * pairs and sets the value of the external variable environ to NULL. + * env_release() is called only from group_leave() when the last member of + * a task group exits. The env_release() function clears the environment + * of all name-value pairs and sets the value of the external variable + * environ to NULL. * * Parameters: - * ptcb Identifies the TCB containing the environment structure + * tcb Identifies the TCB containing the environment structure to be + * released. * * Return Value: - * zero on success + * None * * Assumptions: * Not called from an interrupt handler * ****************************************************************************/ -int env_release(FAR _TCB *ptcb) +void env_release(FAR _TCB *tcb) { - int ret = OK; + FAR struct task_group_s *group; - if (!ptcb) - { - ret = -EINVAL; - } - else - { - FAR environ_t *envp; - - /* Examine the environ data in the TCB. Preemption is disabled because the - * the environment could be shared among threads. - */ - - sched_lock(); - envp = ptcb->envp; - if (ptcb->envp) - { - /* Check the reference count on the environment structure */ + DEBUGASSERT(tcb && tcb->group); + group = tcb->group; - if (envp->ev_crefs <= 1) - { - /* Decrementing the reference count will destroy the environment */ + /* Free any allocate environment strings */ - sched_free(envp); - } - else - { - /* The environment will persist after decrementing the reference - * count */ - - envp->ev_crefs--; - } - - /* In any case, the environment is no longer accessible on this thread */ - - ptcb->envp = NULL; - } + if (group->tg_envp) + { + /* Free the environment */ - sched_unlock(); + sched_free(group->tg_envp); } - return ret; + /* In any event, make sure that all environment-related varialbles in the + * task group structure are reset to initial values. + */ + + group->tg_envsize = 0; + group->tg_envp = NULL; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/env_removevar.c b/nuttx/sched/env_removevar.c index e96aa7a37..811e6079e 100644 --- a/nuttx/sched/env_removevar.c +++ b/nuttx/sched/env_removevar.c @@ -59,7 +59,7 @@ * Remove the referenced name=value pair from the environment * * Parameters: - * envp The environment containing the name=value pair + * group The task group with the environment containing the name=value pair * pvar A pointer to the name=value pair in the restroom * * Return Value: @@ -72,42 +72,44 @@ * ****************************************************************************/ -int env_removevar(environ_t *envp, char *pvar) +int env_removevar(FAR struct task_group_s *group, FAR char *pvar) { + FAR char *end; /* Pointer to the end+1 of the environment */ + int alloc; /* Size of the allocated environment */ int ret = ERROR; - if (envp && pvar) - { - /* Verify that the pointer lies within the environment region */ - int alloc = envp->ev_alloc; /* Size of the allocated environment */ - char *end = &envp->ev_env[alloc]; /* Pointer to the end+1 of the environment */ + DEBUGASSERT(group && pvar); - if (pvar >= envp->ev_env && pvar < end) - { - /* Set up for the removal */ + /* Verify that the pointer lies within the environment region */ - int len = strlen(pvar) + 1; /* Length of name=value string to remove */ - char *src = &pvar[len]; /* Address of name=value string after */ - char *dest = pvar; /* Location to move the next string */ - int count = end - src; /* Number of bytes to move (might be zero) */ + alloc = group->tg_envsize; /* Size of the allocated environment */ + end = &group->tg_envp[alloc]; /* Pointer to the end+1 of the environment */ - /* Move all of the environment strings after the removed one 'down.' - * this is inefficient, but robably not high duty. - */ + if (pvar >= group->tg_envp && pvar < end) + { + /* Set up for the removal */ - while (count-- > 0) - { - *dest++ = *src++; - } + int len = strlen(pvar) + 1; /* Length of name=value string to remove */ + char *src = &pvar[len]; /* Address of name=value string after */ + char *dest = pvar; /* Location to move the next string */ + int count = end - src; /* Number of bytes to move (might be zero) */ - /* Then set to the new allocation size. The caller is expected to - * call realloc at some point but we don't do that here because the - * caller may add more stuff to the environment. - */ + /* Move all of the environment strings after the removed one 'down.' + * this is inefficient, but robably not high duty. + */ - envp->ev_alloc -= len; - ret = OK; + while (count-- > 0) + { + *dest++ = *src++; } + + /* Then set to the new allocation size. The caller is expected to + * call realloc at some point but we don't do that here because the + * caller may add more stuff to the environment. + */ + + group->tg_envsize -= len; + ret = OK; } return ret; diff --git a/nuttx/sched/env_setenv.c b/nuttx/sched/env_setenv.c index c186241ef..cfde71604 100644 --- a/nuttx/sched/env_setenv.c +++ b/nuttx/sched/env_setenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_setenv.c * - * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -83,12 +83,14 @@ * ****************************************************************************/ -int setenv(const char *name, const char *value, int overwrite) +int setenv(FAR const char *name, FAR const char *value, int overwrite) { - FAR _TCB *rtcb; - FAR environ_t *envp; - FAR char *pvar; - int varlen; + FAR _TCB *rtcb; + FAR struct task_group_s *group; + FAR char *pvar; + FAR char *newenvp; + int newsize; + int varlen; int ret = OK; /* Verify input parameter */ @@ -122,14 +124,15 @@ int setenv(const char *name, const char *value, int overwrite) /* Get a reference to the thread-private environ in the TCB.*/ sched_lock(); - rtcb = (FAR _TCB*)g_readytorun.head; - envp = rtcb->envp; + rtcb = (FAR _TCB*)g_readytorun.head; + group = rtcb->group; + DEBUGASSERT(group); - /* Check if the variable alreay exists */ + /* Check if the variable already exists */ - if ( envp && (pvar = env_findvar(envp, name)) != NULL) + if (group->tg_envp && (pvar = env_findvar(group, name)) != NULL) { - /* It does! Do we have permission to overwrite the existing value? */ + /* It does! Do we have permission to overwrite the existing value? */ if (!overwrite) { @@ -144,7 +147,7 @@ int setenv(const char *name, const char *value, int overwrite) * the environment buffer; this will happen below. */ - (void)env_removevar(envp, pvar); + (void)env_removevar(group, pvar); } /* Get the size of the new name=value string. The +2 is for the '=' and for @@ -155,43 +158,39 @@ int setenv(const char *name, const char *value, int overwrite) /* Then allocate or reallocate the environment buffer */ - if (envp) + if (group->tg_envp) { - int alloc = envp->ev_alloc; - environ_t *tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc + varlen)); - if (!tmp) + newsize = group->tg_envsize + varlen; + newenvp = (FAR char *)krealloc(group->tg_envp, newsize); + if (!newenvp) { ret = ENOMEM; goto errout_with_lock; } - envp = tmp; - envp->ev_alloc = alloc + varlen; - pvar = &envp->ev_env[alloc]; + pvar = &newenvp[group->tg_envsize]; } else { - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(varlen)); - if (!envp) + newsize = varlen; + newenvp = (FAR char *)kmalloc(varlen); + if (!newenvp) { ret = ENOMEM; goto errout_with_lock; } - envp->ev_crefs = 1; - envp->ev_alloc = varlen; - pvar = envp->ev_env; + pvar = newenvp; } - /* Now, put the new name=value string into the environment buffer */ + /* Save the new buffer and size */ - sprintf(pvar, "%s=%s", name, value); + group->tg_envp = newenvp; + group->tg_envsize = newsize; - /* Save the new environment pointer (it might have changed due to allocation or - * reallocation. - */ + /* Now, put the new name=value string into the environment buffer */ - rtcb->envp = envp; + sprintf(pvar, "%s=%s", name, value); sched_unlock(); return OK; diff --git a/nuttx/sched/env_share.c b/nuttx/sched/env_share.c deleted file mode 100644 index 5f37a0219..000000000 --- a/nuttx/sched/env_share.c +++ /dev/null @@ -1,117 +0,0 @@ -/**************************************************************************** - * sched/env_share.c - * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#ifndef CONFIG_DISABLE_ENVIRON - -#include -#include - -#include "os_internal.h" -#include "env_internal.h" - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: env_share - * - * Description: - * Increment the reference count on the internal environment structure of - * a task. This is the action that is performed when a new pthread is - * created: The new pthread shares the environment with its parent. - * - * Parameters: - * ptcb The new TCB to receive the shared environment. - * - * Return Value: - * A pointer to a specified TCB's environment structure with an incremented - * reference count. - * - * Assumptions: - * Not called from an interrupt handler. - * - ****************************************************************************/ - -int env_share(FAR _TCB *ptcb) -{ - int ret = OK; - if (!ptcb) - { - ret = -EINVAL; - } - else - { - FAR _TCB *parent = (FAR _TCB*)g_readytorun.head; - environ_t *envp = parent->envp; - - /* Pre-emption must be disabled throughout the following because the - * environment is shared. - */ - - sched_lock(); - - /* Does the parent task have an environment? */ - - if (envp) - { - /* Yes.. increment the reference count on the environment */ - - envp->ev_crefs++; - } - - /* Then share the environment */ - - ptcb->envp = envp; - sched_unlock(); - } - - return ret; -} - -#endif /* CONFIG_DISABLE_ENVIRON */ - - - diff --git a/nuttx/sched/env_unsetenv.c b/nuttx/sched/env_unsetenv.c index 52469fac9..8206a4ece 100644 --- a/nuttx/sched/env_unsetenv.c +++ b/nuttx/sched/env_unsetenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_unsetenv.c * - * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -75,61 +75,47 @@ * ****************************************************************************/ -int unsetenv(const char *name) +int unsetenv(FAR const char *name) { - FAR _TCB *rtcb; - FAR environ_t *envp; - FAR char *pvar; + FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + FAR struct task_group_s *group = rtcb->group; + FAR char *pvar; + FAR char *newenvp; + int newsize; int ret = OK; - /* Verify input parameter */ - - if (!name) - { - ret = EINVAL; - goto errout; - } - - /* Get a reference to the thread-private environ in the TCB.*/ - - sched_lock(); - rtcb = (FAR _TCB*)g_readytorun.head; - envp = rtcb->envp; + DEBUGASSERT(name && group); /* Check if the variable exists */ - if ( envp && (pvar = env_findvar(envp, name)) != NULL) + sched_lock(); + if (group && (pvar = env_findvar(group, name)) != NULL) { - int alloc; - environ_t *tmp; - /* It does! Remove the name=value pair from the environment. */ - (void)env_removevar(envp, pvar); + (void)env_removevar(group, pvar); /* Reallocate the new environment buffer */ - alloc = envp->ev_alloc; - tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc)); - if (!tmp) + newsize = group->tg_envsize; + newenvp = (FAR char *)krealloc(group->tg_envp, newsize); + if (!newenvp) { - ret = ENOMEM; - goto errout_with_lock; + set_errno(ENOMEM); + ret = ERROR; } + else + { + /* Save the new environment pointer (it might have changed due to + * reallocation. + */ - /* Save the new environment pointer (it might have changed due to reallocation. */ - - rtcb->envp = tmp; + group->tg_envp = newenvp; + } } sched_unlock(); - return OK; - -errout_with_lock: - sched_unlock(); -errout: - errno = ret; - return ERROR; + return ret; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index 4612ae8c5..da91fa065 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -46,6 +46,9 @@ #include +#include "group_internal.h" +#include "env_internal.h" + #ifdef HAVE_TASK_GROUP /***************************************************************************** @@ -97,12 +100,29 @@ int group_allocate(FAR _TCB *tcb) { + int ret; + DEBUGASSERT(tcb && !tcb->group); /* Allocate the group structure and assign it to the TCB */ tcb->group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s)); - return tcb->group ? OK : -ENOMEM; + if (!tcb->group) + { + return -ENOMEM; + } + + /* Duplicate the parent tasks envionment */ + + ret = env_dup(tcb); + if (ret < 0) + { + kfree(tcb->group); + tcb->group = NULL; + return ret; + } + + return OK; } /***************************************************************************** @@ -128,12 +148,12 @@ int group_allocate(FAR _TCB *tcb) int group_initialize(FAR _TCB *tcb) { -#ifdef HAVE_GROUP_MEMBERS FAR struct task_group_s *group; DEBUGASSERT(tcb && tcb->group); group = tcb->group; +#ifdef HAVE_GROUP_MEMBERS /* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */ group->tg_members = (FAR pid_t *)kmalloc(GROUP_INITIAL_MEMBERS*sizeof(pid_t)); diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h new file mode 100644 index 000000000..aa8476e3c --- /dev/null +++ b/nuttx/sched/group_internal.h @@ -0,0 +1,104 @@ +/**************************************************************************** + * sched/group_internal.h + * + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_GROUP_INERNAL_H +#define __SCHED_GROUP_INERNAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ +/* Task group data structure management */ + +#ifdef HAVE_TASK_GROUP +int group_allocate(FAR _TCB *tcb); +int group_initialize(FAR _TCB *tcb); +int group_bind(FAR _TCB *tcb); +int group_join(FAR _TCB *tcb); +void group_leave(FAR _TCB *tcb); +#ifndef CONFIG_DISABLE_SIGNALS +int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); +#else +# define group_signal(tcb,info) (0) +#endif +#else +# define group_allocate(tcb) (0) +# define group_initialize(tcb) (0) +# define group_bind(tcb) (0) +# define group_join(tcb) (0) +# define group_leave(tcb) +# define group_signal(tcb,info) (0) +#endif /* HAVE_TASK_GROUP */ + +/* Parent/child data management */ + +#ifdef CONFIG_SCHED_HAVE_PARENT +int task_reparent(pid_t ppid, pid_t chpid); + +#ifdef CONFIG_SCHED_CHILD_STATUS +FAR struct child_status_s *task_allocchild(void); +void task_freechild(FAR struct child_status_s *status); +void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child); +FAR struct child_status_s *task_exitchild(FAR _TCB *tcb); +FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid); +FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid); +void task_removechildren(FAR _TCB *tcb); +#endif +#endif /* CONFIG_SCHED_HAVE_PARENT */ + +#endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c index 9dcea6599..077c45763 100644 --- a/nuttx/sched/group_join.c +++ b/nuttx/sched/group_join.c @@ -46,7 +46,8 @@ #include -#include "os_internal.h" +#include "group_internal.h" +#include "env_internal.h" #ifdef HAVE_TASK_GROUP @@ -137,7 +138,6 @@ int group_bind(FAR _TCB *tcb) int group_join(FAR _TCB *tcb) { -#ifdef HAVE_GROUP_MEMBERS FAR struct task_group_s *group; DEBUGASSERT(tcb && tcb->group && @@ -147,6 +147,7 @@ int group_join(FAR _TCB *tcb) group = tcb->group; +#ifdef HAVE_GROUP_MEMBERS /* Will we need to extend the size of the array of groups? */ if (group->tg_nmembers >= group->tg_mxmembers) diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 223af1556..d5fa9dbaf 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -44,7 +44,8 @@ #include #include -#include "os_internal.h" +#include "group_internal.h" +#include "env_internal.h" #ifdef HAVE_TASK_GROUP @@ -92,7 +93,6 @@ void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; - int i; DEBUGASSERT(tcb); @@ -102,6 +102,8 @@ void group_leave(FAR _TCB *tcb) if (group) { #ifdef HAVE_GROUP_MEMBERS + int i; + /* Find the member in the array of members and remove it */ for (i = 0; i < group->tg_nmembers; i++) @@ -142,8 +144,14 @@ void group_leave(FAR _TCB *tcb) /* Release all of the resource contained within the group */ /* Free all un-reaped child exit status */ - task_removechildren(tcb); +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) + task_removechildren(tcb); +#endif + /* Release all shared environment variables */ +#ifndef CONFIG_DISABLE_ENVIRON + env_release(tcb); +#endif /* Release the group container itself */ sched_free(group); @@ -166,8 +174,14 @@ void group_leave(FAR _TCB *tcb) /* Release all of the resource contained within the group */ /* Free all un-reaped child exit status */ +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) task_removechildren(tcb); +#endif + /* Release all shared environment variables */ +#ifndef CONFIG_DISABLE_ENVIRON + env_release(tcb); +#endif /* Release the group container itself */ sched_free(group); diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c index 68912fe00..5020ec436 100644 --- a/nuttx/sched/group_signal.c +++ b/nuttx/sched/group_signal.c @@ -44,6 +44,8 @@ #include #include +#include "os_internal.h" +#include "group_internal.h" #include "sig_internal.h" #if defined(HAVE_TASK_GROUP) && !defined(CONFIG_DISABLE_SIGNALS) diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 599be25bb..e3d0fd48f 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -262,6 +262,9 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES]; ****************************************************************************/ int os_bringup(void); +#ifdef CONFIG_SCHED_CHILD_STATUS +void weak_function task_initialize(void); +#endif void task_start(void); int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main, uint8_t ttype); @@ -269,41 +272,6 @@ int task_argsetup(FAR _TCB *tcb, FAR const char *name, FAR const char *argv[]); void task_exithook(FAR _TCB *tcb, int status); int task_deletecurrent(void); -#ifdef CONFIG_SCHED_HAVE_PARENT -int task_reparent(pid_t ppid, pid_t chpid); - -#ifdef HAVE_TASK_GROUP -int group_allocate(FAR _TCB *tcb); -int group_initialize(FAR _TCB *tcb); -int group_bind(FAR _TCB *tcb); -int group_join(FAR _TCB *tcb); -void group_leave(FAR _TCB *tcb); -#ifndef CONFIG_DISABLE_SIGNALS -int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); -#else -# define group_signal(tcb,info) (0) -#endif -#else -# define group_allocate(tcb) (0) -# define group_initialize(tcb) (0) -# define group_bind(tcb) (0) -# define group_join(tcb) (0) -# define group_leave(tcb) -# define group_signal(tcb,info) (0) -#endif - -#ifdef CONFIG_SCHED_CHILD_STATUS -void weak_function task_initialize(void); -FAR struct child_status_s *task_allocchild(void); -void task_freechild(FAR struct child_status_s *status); -void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child); -FAR struct child_status_s *task_exitchild(FAR _TCB *tcb); -FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid); -FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid); -void task_removechildren(FAR _TCB *tcb); -#endif -#endif - #ifndef CONFIG_CUSTOM_STACK int kernel_thread(FAR const char *name, int priority, int stack_size, main_t entry, FAR const char *argv[]); diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index 3aecc7efb..b2551d2a3 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/os_start.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -63,6 +63,9 @@ #include "clock_internal.h" #include "timer_internal.h" #include "irq_internal.h" +#ifdef HAVE_TASK_GROUP +#include "group_internal.h" +#endif /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c index 89a2feb00..9fd6a4a61 100644 --- a/nuttx/sched/pthread_create.c +++ b/nuttx/sched/pthread_create.c @@ -53,8 +53,8 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "clock_internal.h" -#include "env_internal.h" #include "pthread_internal.h" /**************************************************************************** @@ -305,10 +305,6 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, goto errout_with_tcb; } - /* Share the parent's envionment */ - - (void)env_share(ptcb); - /* Allocate a detachable structure to support pthread_join logic */ pjoin = (FAR join_t*)kzalloc(sizeof(join_t)); diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 50505f579..00d4c2c0c 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -45,8 +45,8 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "timer_internal.h" -#include "env_internal.h" /************************************************************************ * Private Functions @@ -167,10 +167,6 @@ int sched_releasetcb(FAR _TCB *tcb) ret = sched_releasefiles(tcb); - /* Release environment variables */ - - (void)env_release(tcb); - /* Release this thread's reference to the address environment */ #ifdef CONFIG_ADDRENV diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index e47e3c38c..41e488f90 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -46,6 +46,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #if defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT) diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index 2d0fe2e48..4af7f7ef3 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -47,6 +47,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #ifdef CONFIG_SCHED_WAITPID diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c index b307c1fb6..fe72cc22d 100644 --- a/nuttx/sched/sig_action.c +++ b/nuttx/sched/sig_action.c @@ -46,6 +46,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "sig_internal.h" /**************************************************************************** diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c index aff2bdf3a..c0df3d534 100644 --- a/nuttx/sched/task_childstatus.c +++ b/nuttx/sched/task_childstatus.c @@ -44,6 +44,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c index bb309444b..85c0f5e92 100644 --- a/nuttx/sched/task_create.c +++ b/nuttx/sched/task_create.c @@ -48,7 +48,7 @@ #include #include "os_internal.h" -#include "env_internal.h" +#include "group_internal.h" /**************************************************************************** * Definitions @@ -142,10 +142,6 @@ static int thread_create(const char *name, uint8_t ttype, int priority, } #endif - /* Clone the parent's task environment */ - - (void)env_dup(tcb); - /* Allocate the stack for the TCB */ #ifndef CONFIG_CUSTOM_STACK diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 2d596978f..cbada851a 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -49,6 +49,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "sig_internal.h" /**************************************************************************** diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c index 6ae643948..8dfd8b7f6 100644 --- a/nuttx/sched/task_init.c +++ b/nuttx/sched/task_init.c @@ -47,7 +47,7 @@ #include #include "os_internal.h" -#include "env_internal.h" +#include "group_internal.h" /**************************************************************************** * Definitions @@ -145,10 +145,6 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, } #endif - /* Clone the parent's task environment */ - - (void)env_dup(tcb); - /* Configure the user provided stack region */ #ifndef CONFIG_CUSTOM_STACK @@ -162,7 +158,7 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, if (ret < OK) { errcode = -ret; - goto errout_with_env; + goto errout_with_group; } /* Setup to pass parameters to the new task */ @@ -176,14 +172,11 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, if (ret < 0) { errcode = -ret; - goto errout_with_env; + goto errout_with_group; } #endif return OK; -errout_with_env: - env_release(tcb); - errout_with_group: #ifdef HAVE_TASK_GROUP group_leave(tcb); diff --git a/nuttx/sched/task_posixspawn.c b/nuttx/sched/task_posixspawn.c index 7bb9c9a4d..e9ad1fc45 100644 --- a/nuttx/sched/task_posixspawn.c +++ b/nuttx/sched/task_posixspawn.c @@ -54,6 +54,7 @@ #include #include "os_internal.h" +#include "group_internal.h" /**************************************************************************** * Private Types diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c index 0b502dcce..1193c9a7f 100644 --- a/nuttx/sched/task_reparent.c +++ b/nuttx/sched/task_reparent.c @@ -42,6 +42,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #ifdef CONFIG_SCHED_HAVE_PARENT diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index 7675c7481..b66f3cc7c 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -49,6 +49,7 @@ #include #include "os_internal.h" +#include "group_internal.h" /**************************************************************************** * Definitions diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c index fece4c596..3f058bdec 100644 --- a/nuttx/sched/task_vfork.c +++ b/nuttx/sched/task_vfork.c @@ -48,7 +48,7 @@ #include #include "os_internal.h" -#include "env_internal.h" +#include "group_internal.h" /**************************************************************************** * Pre-processor Definitions @@ -132,10 +132,6 @@ FAR _TCB *task_vforksetup(start_t retaddr) } #endif - /* Clone the parent's task environment */ - - (void)env_dup(child); - /* Get the priority of the parent task */ #ifdef CONFIG_PRIORITY_INHERITANCE -- cgit v1.2.3 From 5b6482a22bb8b656e3d70a6efc5ae2c77ed2a58b Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 20:17:29 +0000 Subject: Move file data from TCB to task group git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5567 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/TODO | 23 +---- nuttx/arch/arm/src/common/up_exit.c | 8 +- nuttx/arch/avr/src/common/up_exit.c | 8 +- nuttx/arch/hc/src/common/up_exit.c | 8 +- nuttx/arch/mips/src/common/up_exit.c | 8 +- nuttx/arch/sh/src/common/up_exit.c | 9 +- nuttx/arch/x86/src/common/up_exit.c | 6 +- nuttx/arch/z16/src/common/up_exit.c | 11 +- nuttx/arch/z80/src/common/up_exit.c | 9 +- nuttx/fs/fs_fdopen.c | 8 +- nuttx/fs/fs_files.c | 101 ++++--------------- nuttx/include/nuttx/fs/fs.h | 89 +++++++---------- nuttx/include/nuttx/sched.h | 42 +++++--- nuttx/sched/group_leave.c | 16 ++- nuttx/sched/sched_getfiles.c | 5 +- nuttx/sched/sched_releasefiles.c | 13 ++- nuttx/sched/sched_releasetcb.c | 4 - nuttx/sched/sched_setupidlefiles.c | 15 +-- nuttx/sched/sched_setuppthreadfiles.c | 8 -- nuttx/sched/sched_setuptaskfiles.c | 49 +++++---- nuttx/sched/task_exithook.c | 182 +++++++++++++++++++++------------- 22 files changed, 288 insertions(+), 336 deletions(-) (limited to 'nuttx/sched/sched_releasetcb.c') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 858f82819..ae7105b89 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4034,3 +4034,5 @@ * sched/: Lots of file changed. Don't keep the parent task's task ID in the child task's TCB. Instead, keep the parent task group IN the child task's task group. + * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h: + Move file data from TCB to task group structure. diff --git a/nuttx/TODO b/nuttx/TODO index d6bd18d12..cb99f1bf7 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 24, 2013) +NuttX TODO List (Last updated January 26, 2013) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements. nuttx/ - (11) Task/Scheduler (sched/) + (10) Task/Scheduler (sched/) (2) Memory Managment (mm/) (3) Signals (sched/, arch/) (2) pthreads (sched/) @@ -161,25 +161,6 @@ o Task/Scheduler (sched/) Status: Open Priority: Medium Low for now - Title: IMPROVED TASK CONTROL BLOCK STRUCTURE - Description: All task resources that are shared amongst threads have - their own "break-away", reference-counted structure. The - Task Control Block (TCB) of each thread holds a reference - to each breakaway structure (see include/nuttx/sched.h). - It would be more efficent to have one reference counted - structure that holds all of the shared resources. - - These are the current shared structures: - - Environment varaibles (struct environ_s) - - PIC data space and address environments (struct dspace_s) - - File descriptors (struct filelist) - - FILE streams (struct streamlist) - - Sockets (struct socketlist) - Status: Open - Priority: Low. This is an enhancement. It would slight reduce - memory usage but would also increase coupling. These - resources are nicely modular now. - Title: ISSUES WITH atexit() AND on_exit() Description: These functions execute with the following bad properties: diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c index 6f6d54f76..5b469fd03 100644 --- a/nuttx/arch/arm/src/common/up_exit.c +++ b/nuttx/arch/arm/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 201-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/avr/src/common/up_exit.c b/nuttx/arch/avr/src/common/up_exit.c index 0a8cc0d18..0813754a0 100644 --- a/nuttx/arch/avr/src/common/up_exit.c +++ b/nuttx/arch/avr/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/common/up_exit.c * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/hc/src/common/up_exit.c b/nuttx/arch/hc/src/common/up_exit.c index 7cd16b438..5313a1172 100644 --- a/nuttx/arch/hc/src/common/up_exit.c +++ b/nuttx/arch/hc/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/mips/src/common/up_exit.c b/nuttx/arch/mips/src/common/up_exit.c index 876b486b6..5a7b68a99 100644 --- a/nuttx/arch/mips/src/common/up_exit.c +++ b/nuttx/arch/mips/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/src/common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -87,12 +87,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c index 84a44a705..af270b335 100644 --- a/nuttx/arch/sh/src/common/up_exit.c +++ b/nuttx/arch/sh/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -81,16 +81,15 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #endif sdbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c index e3d27b0af..6a98c7dd0 100644 --- a/nuttx/arch/x86/src/common/up_exit.c +++ b/nuttx/arch/x86/src/common/up_exit.c @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c index 41f058347..ad0c55eed 100644 --- a/nuttx/arch/z16/src/common/up_exit.c +++ b/nuttx/arch/z16/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -81,17 +81,16 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) int i; #endif - dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - lldbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { lldbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index 85ddd841e..50289f52b 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -82,17 +82,16 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) int i; #endif - dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - lldbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { lldbg(" fd=%d refcount=%d\n", diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c index fd6aa88a8..629083c77 100644 --- a/nuttx/fs/fs_fdopen.c +++ b/nuttx/fs/fs_fdopen.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/fs_fdopen.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -68,9 +68,11 @@ static inline int fs_checkfd(FAR _TCB *tcb, int fd, int oflags) FAR struct filelist *flist; FAR struct inode *inode; - /* Get the file list from the TCB */ + DEBUGASSERT(tcb && tcb->group); - flist = tcb->filelist; + /* Get the file list from the task group */ + + flist = &tcb->group->tg_filelist; /* Get the inode associated with the file descriptor. This should * normally be the case if fd >= 0. But not in the case where the diff --git a/nuttx/fs/fs_files.c b/nuttx/fs/fs_files.c index 06addb1ef..c68ec7e73 100644 --- a/nuttx/fs/fs_files.c +++ b/nuttx/fs/fs_files.c @@ -155,56 +155,19 @@ void files_initialize(void) } /**************************************************************************** - * Name: files_alloclist + * Name: files_initlist * - * Description: Allocate a list of files for a new task + * Description: Initializes the list of files for a new task * ****************************************************************************/ -FAR struct filelist *files_alloclist(void) +void files_initlist(FAR struct filelist *list) { - FAR struct filelist *list; - list = (FAR struct filelist*)kzalloc(sizeof(struct filelist)); - if (list) - { - /* Start with a reference count of one */ - - list->fl_crefs = 1; - - /* Initialize the list access mutex */ + DEBUGASSERT(list); - (void)sem_init(&list->fl_sem, 0, 1); - } + /* Initialize the list access mutex */ - return list; -} - -/**************************************************************************** - * Name: files_addreflist - * - * Description: - * Increase the reference count on a file list - * - ****************************************************************************/ - -int files_addreflist(FAR struct filelist *list) -{ - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - list->fl_crefs++; - irqrestore(flags); - } - - return OK; + (void)sem_init(&list->fl_sem, 0, 1); } /**************************************************************************** @@ -215,51 +178,25 @@ int files_addreflist(FAR struct filelist *list) * ****************************************************************************/ -int files_releaselist(FAR struct filelist *list) +void files_releaselist(FAR struct filelist *list) { - int crefs; - if (list) - { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - crefs = --(list->fl_crefs); - irqrestore(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { - int i; + int i; - /* Close each file descriptor .. Normally, you would need - * take the list semaphore, but it is safe to ignore the - * semaphore in this context because there are no references - */ + DEBUGASSERT(list); - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) - { - (void)_files_close(&list->fl_files[i]); - } - - /* Destroy the semaphore and release the filelist */ + /* Close each file descriptor .. Normally, you would need take the list + * semaphore, but it is safe to ignore the semaphore in this context because + * there should not be any references in this context. + */ - (void)sem_destroy(&list->fl_sem); - sched_free(list); - } + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + { + (void)_files_close(&list->fl_files[i]); } - return OK; + /* Destroy the semaphore */ + + (void)sem_destroy(&list->fl_sem); } /**************************************************************************** diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 327bf37ca..02855460c 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -240,7 +240,6 @@ struct file struct filelist { sem_t fl_sem; /* Manage access to the file list */ - int16_t fl_crefs; /* Reference count */ struct file fl_files[CONFIG_NFILE_DESCRIPTORS]; }; #endif @@ -318,7 +317,8 @@ typedef int (*foreach_mountpoint_t)(FAR const char *mountpoint, #undef EXTERN #if defined(__cplusplus) #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif @@ -333,7 +333,7 @@ extern "C" { * ****************************************************************************/ -EXTERN void weak_function fs_initialize(void); +void weak_function fs_initialize(void); /* fs_foreachmountpoint.c ***************************************************/ /**************************************************************************** @@ -357,7 +357,7 @@ EXTERN void weak_function fs_initialize(void); ****************************************************************************/ #ifndef CONFIG_DISABLE_MOUNTPOUNT -EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); +int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); #endif /* fs_registerdriver.c ******************************************************/ @@ -384,9 +384,8 @@ EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); * ****************************************************************************/ -EXTERN int register_driver(const char *path, - const struct file_operations *fops, - mode_t mode, void *priv); +int register_driver(FAR const char *path, FAR const struct file_operations *fops, + mode_t mode, FAR void *priv); /* fs_registerblockdriver.c *************************************************/ /**************************************************************************** @@ -412,9 +411,9 @@ EXTERN int register_driver(const char *path, * ****************************************************************************/ -EXTERN int register_blockdriver(const char *path, - const struct block_operations *bops, - mode_t mode, void *priv); +int register_blockdriver(FAR const char *path, + FAR const struct block_operations *bops, mode_t mode, + FAR void *priv); /* fs_unregisterdriver.c ****************************************************/ /**************************************************************************** @@ -425,7 +424,7 @@ EXTERN int register_blockdriver(const char *path, * ****************************************************************************/ -EXTERN int unregister_driver(const char *path); +int unregister_driver(const char *path); /* fs_unregisterblockdriver.c ***********************************************/ /**************************************************************************** @@ -436,7 +435,7 @@ EXTERN int unregister_driver(const char *path); * ****************************************************************************/ -EXTERN int unregister_blockdriver(const char *path); +int unregister_blockdriver(const char *path); /* fs_open.c ****************************************************************/ /**************************************************************************** @@ -447,30 +446,19 @@ EXTERN int unregister_blockdriver(const char *path); * ****************************************************************************/ -EXTERN int inode_checkflags(FAR struct inode *inode, int oflags); +int inode_checkflags(FAR struct inode *inode, int oflags); /* fs_files.c ***************************************************************/ /**************************************************************************** - * Name: files_alloclist - * - * Description: Allocate a list of files for a new task - * - ****************************************************************************/ - -#if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN FAR struct filelist *files_alloclist(void); -#endif - -/**************************************************************************** - * Name: files_addreflist + * Name: files_initlist * * Description: - * Increase the reference count on a file list + * Initializes the list of files for a new task * ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_addreflist(FAR struct filelist *list); +void files_initlist(FAR struct filelist *list); #endif /**************************************************************************** @@ -482,7 +470,7 @@ EXTERN int files_addreflist(FAR struct filelist *list); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_releaselist(FAR struct filelist *list); +void files_releaselist(FAR struct filelist *list); #endif /**************************************************************************** @@ -495,7 +483,7 @@ EXTERN int files_releaselist(FAR struct filelist *list); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2); +int files_dup(FAR struct file *filep1, FAR struct file *filep2); #endif /* fs_filedup.c *************************************************************/ @@ -515,7 +503,7 @@ EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int file_dup(int fd, int minfd); +int file_dup(int fd, int minfd); #endif /* fs_filedup2.c ************************************************************/ @@ -535,7 +523,7 @@ EXTERN int file_dup(int fd, int minfd); #if CONFIG_NFILE_DESCRIPTORS > 0 #if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 -EXTERN int file_dup2(int fd1, int fd2); +int file_dup2(int fd1, int fd2); #else # define file_dup2(fd1, fd2) dup2(fd1, fd2) #endif @@ -566,8 +554,8 @@ EXTERN int file_dup2(int fd1, int fd2); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int open_blockdriver(FAR const char *pathname, int mountflags, - FAR struct inode **ppinode); +int open_blockdriver(FAR const char *pathname, int mountflags, + FAR struct inode **ppinode); #endif /* fs_closeblockdriver.c ****************************************************/ @@ -589,7 +577,7 @@ EXTERN int open_blockdriver(FAR const char *pathname, int mountflags, ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int close_blockdriver(FAR struct inode *inode); +int close_blockdriver(FAR struct inode *inode); #endif /* fs_fdopen.c **************************************************************/ @@ -609,7 +597,7 @@ typedef struct _TCB _TCB; #define __TCB_DEFINED__ #endif -EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); +FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); #endif /* lib/stdio/lib_fflush.c **************************************************/ @@ -623,7 +611,7 @@ EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); ****************************************************************************/ #if CONFIG_NFILE_STREAMS > 0 -EXTERN int lib_flushall(FAR struct streamlist *list); +int lib_flushall(FAR struct streamlist *list); #endif /* drivers/dev_null.c *******************************************************/ @@ -635,7 +623,7 @@ EXTERN int lib_flushall(FAR struct streamlist *list); * ****************************************************************************/ -EXTERN void devnull_register(void); +void devnull_register(void); /* drivers/dev_zero.c *******************************************************/ /**************************************************************************** @@ -646,7 +634,7 @@ EXTERN void devnull_register(void); * ****************************************************************************/ -EXTERN void devzero_register(void); +void devzero_register(void); /* drivers/loop.c ***********************************************************/ /**************************************************************************** @@ -658,8 +646,8 @@ EXTERN void devzero_register(void); * ****************************************************************************/ -EXTERN int losetup(FAR const char *devname, FAR const char *filename, - uint16_t sectsize, off_t offset, bool readonly); +int losetup(FAR const char *devname, FAR const char *filename, + uint16_t sectsize, off_t offset, bool readonly); /**************************************************************************** * Name: loteardown @@ -669,7 +657,7 @@ EXTERN int losetup(FAR const char *devname, FAR const char *filename, * ****************************************************************************/ -EXTERN int loteardown(FAR const char *devname); +int loteardown(FAR const char *devname); /* drivers/bch/bchdev_register.c ********************************************/ /**************************************************************************** @@ -681,8 +669,8 @@ EXTERN int loteardown(FAR const char *devname); * ****************************************************************************/ -EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev, - bool readonly); +int bchdev_register(FAR const char *blkdev, FAR const char *chardev, + bool readonly); /* drivers/bch/bchdev_unregister.c ******************************************/ /**************************************************************************** @@ -694,7 +682,7 @@ EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev, * ****************************************************************************/ -EXTERN int bchdev_unregister(FAR const char *chardev); +int bchdev_unregister(FAR const char *chardev); /* Low level, direct access. NOTE: low-level access and character driver access * are incompatible. One and only one access method should be implemented. @@ -710,8 +698,7 @@ EXTERN int bchdev_unregister(FAR const char *chardev); * ****************************************************************************/ -EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly, - FAR void **handle); +int bchlib_setup(FAR const char *blkdev, bool readonly, FAR void **handle); /* drivers/bch/bchlib_teardown.c ********************************************/ /**************************************************************************** @@ -723,7 +710,7 @@ EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly, * ****************************************************************************/ -EXTERN int bchlib_teardown(FAR void *handle); +int bchlib_teardown(FAR void *handle); /* drivers/bch/bchlib_read.c ************************************************/ /**************************************************************************** @@ -735,8 +722,8 @@ EXTERN int bchlib_teardown(FAR void *handle); * ****************************************************************************/ -EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, - size_t len); +ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, + size_t len); /* drivers/bch/bchlib_write.c ***********************************************/ /**************************************************************************** @@ -748,8 +735,8 @@ EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, * ****************************************************************************/ -EXTERN ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, - size_t offset, size_t len); +ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, size_t offset, + size_t len); #undef EXTERN #if defined(__cplusplus) diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 8ebb7db4c..1580a80d3 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -52,6 +52,7 @@ #include #include +#include #include /******************************************************************************** @@ -63,14 +64,24 @@ #undef HAVE_TASK_GROUP #undef HAVE_GROUP_MEMBERS +/* We need a group an group members if we are supportint the parent/child + * relationship. + */ + #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) -# define HAVE_TASK_GROUP 1 -# define HAVE_GROUP_MEMBERS 1 -#endif +# define HAVE_TASK_GROUP 1 +# define HAVE_GROUP_MEMBERS 1 -#if !defined(CONFIG_DISABLE_ENVIRON) -# undef HAVE_TASK_GROUP -# define HAVE_TASK_GROUP 1 +/* We need a group (but not members) if any other resources are shared within + * a task group. + */ + +#else +# if !defined(CONFIG_DISABLE_ENVIRON) +# define HAVE_TASK_GROUP 1 +# elif CONFIG_NFILE_DESCRIPTORS > 0 +# define HAVE_TASK_GROUP 1 +# endif #endif /* In any event, we don't need group members if support for pthreads is disabled */ @@ -79,7 +90,7 @@ # undef HAVE_GROUP_MEMBERS #endif -/* Task Management Definitins ***************************************************/ +/* Task Management Definitions **************************************************/ /* This is the maximum number of times that a lock can be set */ @@ -282,16 +293,19 @@ struct task_group_s FAR char *tg_envp; /* Allocated environment strings */ #endif - /* PIC data space and address environments */ + /* PIC data space and address environments ************************************/ /* Not yet (see struct dspace_s) */ - /* File descriptors */ - /* Not yet (see struct filelist) */ + /* File descriptors ***********************************************************/ - /* FILE streams */ +#if CONFIG_NFILE_DESCRIPTORS > 0 + struct filelist tg_filelist; /* Maps file descriptor to file */ +#endif + + /* FILE streams ***************************************************************/ /* Not yet (see streamlist) */ - /* Sockets */ + /* Sockets ********************************************************************/ /* Not yet (see struct socketlist) */ }; #endif @@ -433,10 +447,6 @@ struct _TCB /* File system support ********************************************************/ -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct filelist *filelist; /* Maps file descriptor to file */ -#endif - #if CONFIG_NFILE_STREAMS > 0 FAR struct streamlist *streams; /* Holds C buffered I/O info */ #endif diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index add424185..f5dca1829 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -176,6 +176,13 @@ void group_leave(FAR _TCB *tcb) #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) group_removechildren(tcb->group); +#endif + /* Free all file-related resources now. We really need to close + * files as soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 + (void)sched_releasefiles(tcb); #endif /* Release all shared environment variables */ @@ -231,7 +238,14 @@ void group_leave(FAR _TCB *tcb) #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) group_removechildren(tcb->group); #endif - /* Release all shared environment variables */ + /* Free all file-related resources now. We really need to close + * files as soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 + (void)sched_releasefiles(tcb); +#endif + /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON env_release(tcb); diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c index 256b4cb6b..eca4ba3ff 100644 --- a/nuttx/sched/sched_getfiles.c +++ b/nuttx/sched/sched_getfiles.c @@ -70,7 +70,10 @@ FAR struct filelist *sched_getfiles(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->filelist; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_filelist; } #endif /* CONFIG_NFILE_DESCRIPTORS */ diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/sched_releasefiles.c index a3ef71af4..4be92f4eb 100644 --- a/nuttx/sched/sched_releasefiles.c +++ b/nuttx/sched/sched_releasefiles.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_releasefiles.c * - * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -78,13 +78,12 @@ int sched_releasefiles(_TCB *tcb) if (tcb) { #if CONFIG_NFILE_DESCRIPTORS > 0 - /* Free the file descriptor list */ + FAR struct task_group_s *group = tcb->group; + DEBUGASSERT(group); - if (tcb->filelist) - { - files_releaselist(tcb->filelist); - tcb->filelist = NULL; - } + /* Free resources used by the file descriptor list */ + + files_releaselist(&group->tg_filelist); #if CONFIG_NFILE_STREAMS > 0 /* Free the stream list */ diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 00d4c2c0c..02f7170c2 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -163,10 +163,6 @@ int sched_releasetcb(FAR _TCB *tcb) } } - /* Release any allocated file structures */ - - ret = sched_releasefiles(tcb); - /* Release this thread's reference to the address environment */ #ifdef CONFIG_ADDRENV diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c index ae814e1a6..4bbd4d3b7 100644 --- a/nuttx/sched/sched_setupidlefiles.c +++ b/nuttx/sched/sched_setupidlefiles.c @@ -79,18 +79,21 @@ int sched_setupidlefiles(FAR _TCB *tcb) { +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; +#endif #if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) int fd; #endif - /* Allocate file descriptors for the TCB */ +#if CONFIG_NFILE_DESCRIPTORS > 0 + DEBUGASSERT(group); +#endif + + /* Initialize file descriptors for the TCB */ #if CONFIG_NFILE_DESCRIPTORS > 0 - tcb->filelist = files_alloclist(); - if (!tcb->filelist) - { - return -ENOMEM; - } + files_initlist(&group->tg_filelist); #endif /* Allocate socket descriptors for the TCB */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c index 648d9273e..78d6cbfec 100644 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ b/nuttx/sched/sched_setuppthreadfiles.c @@ -79,14 +79,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; -#if CONFIG_NFILE_DESCRIPTORS > 0 - /* The child thread inherits the parent file descriptors */ - - tcb->filelist = rtcb->filelist; - files_addreflist(tcb->filelist); - -#endif /* CONFIG_NFILE_DESCRIPTORS */ - #if CONFIG_NSOCKET_DESCRIPTORS > 0 /* The child thread inherits the parent socket descriptors */ diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c index d01b8d4cd..9e44147e9 100644 --- a/nuttx/sched/sched_setuptaskfiles.c +++ b/nuttx/sched/sched_setuptaskfiles.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_setuptaskfiles.c * - * Copyright (C) 2007-2008, 2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -93,34 +93,33 @@ static inline void sched_dupfiles(FAR _TCB *tcb) FAR struct file *child; int i; + DEBUGASSERT(tcb && tcb->group && rtcb->group); + /* Duplicate the file descriptors. This will be either all of the * file descriptors or just the first three (stdin, stdout, and stderr) * if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set * accordingly above. */ - if (rtcb->filelist) - { - /* Get pointers to the parent and child task file lists */ + /* Get pointers to the parent and child task file lists */ - parent = rtcb->filelist->fl_files; - child = tcb->filelist->fl_files; + parent = rtcb->group->tg_filelist.fl_files; + child = tcb->group->tg_filelist.fl_files; - /* Check each file in the parent file list */ + /* Check each file in the parent file list */ - for (i = 0; i < NFDS_TOCLONE; i++) - { - /* Check if this file is opened by the parent. We can tell if - * if the file is open because it contain a reference to a non-NULL - * i-node structure. - */ + for (i = 0; i < NFDS_TOCLONE; i++) + { + /* Check if this file is opened by the parent. We can tell if + * if the file is open because it contain a reference to a non-NULL + * i-node structure. + */ - if (parent[i].f_inode) - { - /* Yes... duplicate it for the child */ + if (parent[i].f_inode) + { + /* Yes... duplicate it for the child */ - (void)files_dup(&parent[i], &child[i]); - } + (void)files_dup(&parent[i], &child[i]); } } } @@ -209,14 +208,14 @@ static inline void sched_dupsockets(FAR _TCB *tcb) int sched_setuptaskfiles(FAR _TCB *tcb) { - /* Allocate file descriptors for the TCB */ - #if CONFIG_NFILE_DESCRIPTORS > 0 - tcb->filelist = files_alloclist(); - if (!tcb->filelist) - { - return -ENOMEM; - } + FAR struct task_group_s *group = tcb->group; + + DEBUGASSERT(group); + + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); #endif /* Allocate socket descriptors for the TCB */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 3fdf08bf7..5a2b9e57e 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -177,6 +177,89 @@ static inline void task_onexit(FAR _TCB *tcb, int status) # define task_onexit(tcb,status) #endif +/**************************************************************************** + * Name: task_exitstatus + * + * Description: + * Report exit status when main task of a task group exits + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static inline void task_exitstatus(FAR struct task_group_s *group, int status) +{ + FAR struct child_status_s *child; + + /* Check if the parent task group has suppressed retention of + * child exit status information. + */ + + if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(group, getpid()); + DEBUGASSERT(child); + if (child) + { +#ifndef HAVE_GROUP_MEMBERS + /* No group members? Save the exit status */ + + child->ch_status = status; +#endif + /* Save the exit status.. For the case of HAVE_GROUP_MEMBERS, + * the child status will be as exited until the last member + * of the task group exits. + */ + + child->ch_status = status; + } + } +} +#else + +# define task_exitstatus(group,status) + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + +/**************************************************************************** + * Name: task_groupexit + * + * Description: + * Mark that the final thread of a child task group as exited. + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static inline void task_groupexit(FAR struct task_group_s *group) +{ + FAR struct child_status_s *child; + + /* Check if the parent task group has suppressed retention of child exit + * status information. + */ + + if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(group, getpid()); + DEBUGASSERT(child); + if (child) + { + /* Mark that all members of the child task group has exit'ed */ + + child->ch_flags |= CHILD_FLAG_EXITED; + } + } +} + +#else + +# define task_groupexit(group) + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + /**************************************************************************** * Name: task_sigchild * @@ -195,55 +278,41 @@ static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status) DEBUGASSERT(chgrp); - /* Only the final exiting thread in a task group should generate SIGCHLD. */ + /* Get the parent task group. It is possible that all of the members of + * the parent task group have exited. This would not be an error. In + * this case, the child task group has been orphaned. + */ - if (chgrp->tg_nmembers == 1) + pgrp = group_find(chgrp->tg_pgid); + if (!pgrp) { - /* Get the parent task group */ - - pgrp = group_find(chgrp->tg_pgid); - - /* It is possible that all of the members of the parent task group - * have exited. This would not be an error. In this case, the - * child task group has been orphaned. + /* Set the task group ID to an invalid group ID. The dead parent + * task group ID could get reused some time in the future. */ - if (!pgrp) - { - /* Set the task group ID to an invalid group ID. The dead parent - * task group ID could get reused some time in the future. - */ - - chgrp->tg_pgid = INVALID_GROUP_ID; - return; - } - -#ifdef CONFIG_SCHED_CHILD_STATUS - /* Check if the parent task group has suppressed retention of child exit - * status information. Only 'tasks' report exit status, not pthreads. - * pthreads have a different mechanism. - */ - - if ((pgrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) - { - FAR struct child_status_s *child; + chgrp->tg_pgid = INVALID_GROUP_ID; + return; + } - /* No.. Find the exit status entry for this task in the parent TCB */ + /* Save the exit status now if this is the main thread of the task group + * that is exiting. Only the exiting main task of a task group carries + * interpretable exit Check if this is the main task that is exiting. + */ - child = group_findchild(pgrp, getpid()); - DEBUGASSERT(child); - if (child) - { - /* Mark that the child has exit'ed */ + if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) + { + task_exitstatus(pgrp, status); + } - child->ch_flags |= CHILD_FLAG_EXITED; + /* But only the final exiting thread in a task group, whatever it is, + * should generate SIGCHLD. + */ - /* Save the exit status */ + if (chgrp->tg_nmembers == 1) + { + /* Mark that all of the threads in the task group have exited */ - child->ch_status = status; - } - } -#endif /* CONFIG_SCHED_CHILD_STATUS */ + task_groupexit(pgrp); /* Create the siginfo structure. We don't actually know the cause. * That is a bug. Let's just say that the child task just exit-ted @@ -278,30 +347,9 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) { #ifdef CONFIG_SCHED_CHILD_STATUS - /* Check if the parent task group has suppressed retention of child exit - * status information. Only 'tasks' report exit status, not pthreads. - * pthreads have a different mechanism. - */ + /* Save the exit status now of the main thread */ - if ((ptcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) - { - FAR struct child_status_s *child; - - /* No.. Find the exit status entry for this task in the parent TCB */ - - child = group_findchild(ptcb->group, getpid()); - DEBUGASSERT(child); - if (child) - { - /* Mark that the child has exit'ed */ - - child->ch_flags |= CHILD_FLAG_EXITED; - - /* Save the exit status */ - - child->ch_status = status; - } - } + task_exitstatus(ptcb->group, status); #else /* CONFIG_SCHED_CHILD_STATUS */ @@ -506,14 +554,6 @@ void task_exithook(FAR _TCB *tcb, int status) group_leave(tcb); #endif - /* Free all file-related resources now. This gets called again - * just be be certain when the TCB is delallocated. However, we - * really need to close files as soon as possible while we still - * have a functioning task. - */ - - (void)sched_releasefiles(tcb); - /* Deallocate anything left in the TCB's queues */ #ifndef CONFIG_DISABLE_SIGNALS -- cgit v1.2.3