aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-25 23:21:27 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-25 23:21:27 +0000
commit239e2808cca6ee4c356d087bc83889fc57e64307 (patch)
treefd3a16f87e715df6729c7966a230f93214e98e20 /nuttx
parentfdaa22ed2d565e49983e956bc056f1e0797bd9a9 (diff)
downloadpx4-firmware-239e2808cca6ee4c356d087bc83889fc57e64307.tar.gz
px4-firmware-239e2808cca6ee4c356d087bc83889fc57e64307.tar.bz2
px4-firmware-239e2808cca6ee4c356d087bc83889fc57e64307.zip
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
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/include/nuttx/sched.h43
-rw-r--r--nuttx/sched/Makefile2
-rw-r--r--nuttx/sched/env_clearenv.c5
-rw-r--r--nuttx/sched/env_dup.c26
-rw-r--r--nuttx/sched/env_findvar.c33
-rw-r--r--nuttx/sched/env_getenv.c14
-rw-r--r--nuttx/sched/env_internal.h32
-rw-r--r--nuttx/sched/env_release.c68
-rw-r--r--nuttx/sched/env_removevar.c56
-rw-r--r--nuttx/sched/env_setenv.c59
-rw-r--r--nuttx/sched/env_share.c117
-rw-r--r--nuttx/sched/env_unsetenv.c62
-rw-r--r--nuttx/sched/group_create.c24
-rw-r--r--nuttx/sched/group_internal.h (renamed from nuttx/sched/env_dupenv.c)112
-rw-r--r--nuttx/sched/group_join.c5
-rw-r--r--nuttx/sched/group_leave.c20
-rw-r--r--nuttx/sched/group_signal.c2
-rw-r--r--nuttx/sched/os_internal.h38
-rw-r--r--nuttx/sched/os_start.c5
-rw-r--r--nuttx/sched/pthread_create.c6
-rw-r--r--nuttx/sched/sched_releasetcb.c6
-rw-r--r--nuttx/sched/sched_waitid.c1
-rw-r--r--nuttx/sched/sched_waitpid.c1
-rw-r--r--nuttx/sched/sig_action.c1
-rw-r--r--nuttx/sched/task_childstatus.c1
-rw-r--r--nuttx/sched/task_create.c6
-rw-r--r--nuttx/sched/task_exithook.c1
-rw-r--r--nuttx/sched/task_init.c13
-rw-r--r--nuttx/sched/task_posixspawn.c1
-rw-r--r--nuttx/sched/task_reparent.c1
-rw-r--r--nuttx/sched/task_setup.c1
-rw-r--r--nuttx/sched/task_vfork.c6
33 files changed, 295 insertions, 475 deletions
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 <gnutt@nuttx.org>
*
* 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_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 <gnutt@nuttx.org>
*
* 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 <gnutt@nuttx.org>
*
* 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 <gnutt@nuttx.org>
*
* 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 <gnutt@nuttx.org>
*
* 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 <gnutt@nuttx.org>
*
* 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 <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#ifndef CONFIG_DISABLE_ENVIRON
-
-#include <sched.h>
-#include <errno.h>
-
-#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 <gnutt@nuttx.org>
*
* 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 <nuttx/kmalloc.h>
+#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/env_dupenv.c b/nuttx/sched/group_internal.h
index 32bf6a433..aa8476e3c 100644
--- a/nuttx/sched/env_dupenv.c
+++ b/nuttx/sched/group_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * eched/env_dupenv.c
+ * sched/group_internal.h
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,80 +33,72 @@
*
****************************************************************************/
+#ifndef __SCHED_GROUP_INERNAL_H
+#define __SCHED_GROUP_INERNAL_H
+
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
-#ifndef CONFIG_DISABLE_ENVIRON
-
#include <sys/types.h>
+#include <stdbool.h>
+#include <queue.h>
#include <sched.h>
#include <nuttx/kmalloc.h>
-#include "os_internal.h"
-
/****************************************************************************
- * Private Data
+ * Pre-processor Definitions
****************************************************************************/
/****************************************************************************
- * Public Functions
+ * Public Type Definitions
****************************************************************************/
/****************************************************************************
- * 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.
- *
+ * Global Variables
****************************************************************************/
-
-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 */
-
-
-
+/****************************************************************************
+ * 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 <nuttx/kmalloc.h>
-#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 <errno.h>
#include <debug.h>
-#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 <signal.h>
#include <debug.h>
+#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 <gnutt@nuttx.org>
*
* 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 <nuttx/arch.h>
#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 <nuttx/arch.h>
#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 <nuttx/sched.h>
#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 <nuttx/sched.h>
#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 <errno.h>
#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 <debug.h>
#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 <nuttx/kmalloc.h>
#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 <nuttx/fs/fs.h>
#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 <nuttx/arch.h>
#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 <nuttx/spawn.h>
#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 <errno.h>
#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 <nuttx/arch.h>
#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 <nuttx/sched.h>
#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