summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-06-30 17:05:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-06-30 17:05:44 +0000
commit0bd9051049e45b1d8e3d79c544993f4055f247fb (patch)
tree9fdb70976d886c68d4fbdc2d93cf71f20c69f551 /nuttx/sched
parent50be6bb8bf81d1b83d3274005a3e55a2871f6e8f (diff)
downloadpx4-nuttx-0bd9051049e45b1d8e3d79c544993f4055f247fb.tar.gz
px4-nuttx-0bd9051049e45b1d8e3d79c544993f4055f247fb.tar.bz2
px4-nuttx-0bd9051049e45b1d8e3d79c544993f4055f247fb.zip
Add basic tasking support for environment variables
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@291 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile5
-rw-r--r--nuttx/sched/env_clearenv.c83
-rw-r--r--nuttx/sched/env_dup.c127
-rw-r--r--nuttx/sched/env_dupenv.c108
-rw-r--r--nuttx/sched/env_getenvironptr.c92
-rw-r--r--nuttx/sched/env_internal.h88
-rw-r--r--nuttx/sched/env_release.c122
-rw-r--r--nuttx/sched/env_share.c115
-rw-r--r--nuttx/sched/pthread_create.c5
-rw-r--r--nuttx/sched/sched_releasetcb.c5
-rw-r--r--nuttx/sched/task_create.c5
11 files changed, 755 insertions, 0 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index c007feaf4..97c59201e 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -55,6 +55,8 @@ SCHED_SRCS = sched_setparam.c sched_getparam.c \
sched_yield.c sched_rrgetinterval.c sched_foreach.c \
sched_getprioritymax.c sched_getprioritymin.c \
sched_lock.c sched_unlock.c sched_lockcount.c
+ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c \
+ env_clearenv.c
WDOG_SRCS = wd_initialize.c wd_create.c wd_start.c wd_cancel.c wd_delete.c \
wd_gettime.c
TIME_SRCS = sched_processtimer.c
@@ -128,6 +130,9 @@ endif
ifneq ($(CONFIG_DISABLE_MQUEUE),y)
CSRCS += $(MQUEUE_SRCS)
endif
+ifneq ($(CONFIG_DISABLE_ENVIRON),y)
+CSRCS += $(ENV_SRCS)
+endif
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c
new file mode 100644
index 000000000..1181596ea
--- /dev/null
+++ b/nuttx/sched/env_clearenv.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * env_clearenv.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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 <stdlib.h>
+#include "os_internal.h"
+#include "env_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: clearenv
+ *
+ * Description:
+ * The clearenv() function clears the environment of all name-value pairs
+ * and sets the value of the external variable environ to NULL.
+
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * Not called from an interrupt handler
+ *
+ ****************************************************************************/
+
+int clearenv(void)
+{
+ return env_release((FAR _TCB*)g_readytorun.head);
+}
+
+#endif /* CONFIG_DISABLE_ENVIRON */
+
+
+
diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c
new file mode 100644
index 000000000..0ee1cbc81
--- /dev/null
+++ b/nuttx/sched/env_dup.c
@@ -0,0 +1,127 @@
+/****************************************************************************
+ * env_dup.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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 <string.h>
+#include <errno.h>
+#include "os_internal.h"
+#include "env_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: env_dup
+ *
+ * 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:
+ * ptcb The tcb to receive the newly allocated copy of the parspecifiedent
+ * TCB's environment structure with reference count equal to one
+ *
+ * Return Value:
+ * zero on success
+ *
+ * Assumptions:
+ * Not called from an interrupt handler.
+ *
+ ****************************************************************************/
+
+int env_dup(FAR _TCB *ptcb)
+{
+ int ret = OK;
+ if (!ptcb )
+ {
+ ret = -EINVAL;
+ }
+ else
+ {
+ FAR _TCB *parent = (FAR _TCB*)g_readytorun.head;
+ 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 (parent->envp)
+ {
+ /* Yes..The parent task has an environment, duplicate it */
+
+ size_t envlen = ptcb->envp->ev_alloc;
+ envp = (environ_t*)malloc(SIZEOF_ENVIRON_T( envlen ));
+ if (!envp)
+ {
+ ret = -ENOMEM;
+ }
+ else
+ {
+ envp->ev_crefs = 1;
+ envp->ev_alloc = envlen;
+ memcmp( envp->ev_env, ptcb->envp->ev_env, envlen );
+ }
+ }
+
+ /* Save the cloned environment in the new TCB */
+
+ ptcb->envp = envp;
+ sched_unlock();
+ }
+ return ret;
+}
+
+#endif /* CONFIG_DISABLE_ENVIRON */
+
+
+
diff --git a/nuttx/sched/env_dupenv.c b/nuttx/sched/env_dupenv.c
new file mode 100644
index 000000000..748af878c
--- /dev/null
+++ b/nuttx/sched/env_dupenv.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ * env_dupenv.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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 <stdlib.h>
+#include "os_internal.h"
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: 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*)malloc(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_getenvironptr.c b/nuttx/sched/env_getenvironptr.c
new file mode 100644
index 000000000..4c01250b4
--- /dev/null
+++ b/nuttx/sched/env_getenvironptr.c
@@ -0,0 +1,92 @@
+/****************************************************************************
+ * env_getenvironptr.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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 <stdlib.h>
+#include "os_internal.h"
+
+#undef get_environ_ptr
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: get_environ_ptr
+ *
+ * Description:
+ * Return a pointer to the thread specific environ variable.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * A pointer to the per-thread environ variable.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+FAR char **get_environ_ptr( void )
+{
+ /* Return a reference to the thread-private environ in the TCB.*/
+
+ FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head;
+ if (ptcb->envp)
+ {
+ return &ptcb->envp->ev_env;
+ }
+ else
+ {
+ return NULL;
+ }
+}
+
+#endif /* CONFIG_DISABLE_ENVIRON */
+
+
+
diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h
new file mode 100644
index 000000000..5961362df
--- /dev/null
+++ b/nuttx/sched/env_internal.h
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * env_internal.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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 __ENV_INTERNAL_H
+#define __ENV_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/sched.h>
+#include "os_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#ifdef CONFIG_DISABLE_ENVIRON
+# define env_dup(ptcb) (0)
+# define env_share(ptcb) (0)
+# define env_release(ptcb) (0)
+#endif
+
+/****************************************************************************
+ * Public Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#ifndef CONFIG_DISABLE_ENVIRON
+EXTERN int env_dup(FAR _TCB *ptcb);
+EXTERN int env_share(FAR _TCB *ptcb);
+EXTERN int env_release(FAR _TCB *ptcb);
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ENV_INTERNAL_H */
+
diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c
new file mode 100644
index 000000000..96490588e
--- /dev/null
+++ b/nuttx/sched/env_release.c
@@ -0,0 +1,122 @@
+/****************************************************************************
+ * env_clearenv.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: 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.
+
+ * Parameters:
+ * ptcb Identifies the TCB containing the environment structure
+ *
+ * Return Value:
+ * zero on success
+ *
+ * Assumptions:
+ * Not called from an interrupt handler
+ *
+ ****************************************************************************/
+
+int env_release(FAR _TCB *ptcb)
+{
+ int ret = OK;
+ 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 */
+
+ if ( envp->ev_crefs <= 1)
+ {
+ /* Decrementing the reference count will destroy the environment */
+
+ sched_free( envp ); /* plain free() should be fine here */
+ }
+ 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;
+ }
+ sched_unlock();
+ }
+ return ret;
+}
+
+#endif /* CONFIG_DISABLE_ENVIRON */
+
+
+
diff --git a/nuttx/sched/env_share.c b/nuttx/sched/env_share.c
new file mode 100644
index 000000000..a1c740aa7
--- /dev/null
+++ b/nuttx/sched/env_share.c
@@ -0,0 +1,115 @@
+/****************************************************************************
+ * env_share.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt 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
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: 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++;
+ }
+
+ /* Then share the environment */
+
+ ptcb->envp = envp;
+ sched_unlock();
+ }
+ return ret;
+}
+
+#endif /* CONFIG_DISABLE_ENVIRON */
+
+
+
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index 998867349..24768664b 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -49,6 +49,7 @@
#include <nuttx/arch.h>
#include "os_internal.h"
#include "clock_internal.h"
+#include "env_internal.h"
#include "pthread_internal.h"
/************************************************************
@@ -273,6 +274,10 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
return ERROR;
}
+ /* Share the parent's envionment */
+
+ (void)env_share(ptcb);
+
/* Allocate a detachable structure to support pthread_join logic */
pjoin = (FAR join_t*)kzmalloc(sizeof(join_t));
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 5d3c8fd90..95f533c20 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -46,6 +46,7 @@
#include <nuttx/arch.h>
#include "os_internal.h"
#include "timer_internal.h"
+#include "env_internal.h"
/************************************************************
* Private Functions
@@ -150,6 +151,10 @@ int sched_releasetcb(FAR _TCB *tcb)
ret = sched_releasefiles(tcb);
+ /* Release environment variables */
+
+ (void)env_release(tcb);
+
/* And, finally, release the TCB itself */
sched_free(tcb);
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 008cc378a..ee0e86c6e 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -44,6 +44,7 @@
#include <debug.h>
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "env_internal.h"
/************************************************************
* Definitions
@@ -137,6 +138,10 @@ int task_create(const char *name, int priority,
}
#endif
+ /* Clone the parent's task environment */
+
+ (void)env_dup(tcb);
+
/* Allocate the stack for the TCB */
#ifndef CONFIG_CUSTOM_STACK