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/sched/group_internal.h | 104 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 104 insertions(+) create mode 100644 nuttx/sched/group_internal.h (limited to 'nuttx/sched/group_internal.h') 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 */ -- cgit v1.2.3 From a1aa13f62853491f8bd96a3dea0f0427fa83ad05 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 17:28:20 +0000 Subject: 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. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5566 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 +- nuttx/include/nuttx/sched.h | 12 +- nuttx/sched/Makefile | 16 +- nuttx/sched/group_childstatus.c | 441 ++++++++++++++++++++++++++++++++++++++++ nuttx/sched/group_create.c | 99 ++++++++- nuttx/sched/group_find.c | 125 ++++++++++++ nuttx/sched/group_internal.h | 71 +++++-- nuttx/sched/group_join.c | 48 ++++- nuttx/sched/group_leave.c | 212 ++++++++++++++----- nuttx/sched/group_signal.c | 40 +++- nuttx/sched/sched_waitid.c | 22 +- nuttx/sched/sched_waitpid.c | 40 ++-- nuttx/sched/sig_action.c | 2 +- nuttx/sched/task_childstatus.c | 440 --------------------------------------- nuttx/sched/task_exithook.c | 175 ++++++++++++---- nuttx/sched/task_reparent.c | 156 +++++++++++++- nuttx/sched/task_setup.c | 32 ++- 17 files changed, 1322 insertions(+), 613 deletions(-) create mode 100644 nuttx/sched/group_childstatus.c create mode 100644 nuttx/sched/group_find.c delete mode 100644 nuttx/sched/task_childstatus.c (limited to 'nuttx/sched/group_internal.h') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f23a3ed73..858f82819 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4031,4 +4031,6 @@ members for the parent task group. * include/nuttx/sched.h and sched/env_*.c: Move environment variables into task group structure. - + * 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. diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index dd33b4570..8ebb7db4c 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -95,6 +95,7 @@ #define TCB_FLAG_NONCANCELABLE (1 << 2) /* Bit 2: Pthread is non-cancelable */ #define TCB_FLAG_CANCEL_PENDING (1 << 3) /* Bit 3: Pthread cancel is pending */ #define TCB_FLAG_ROUND_ROBIN (1 << 4) /* Bit 4: Round robin sched enabled */ +#define TCB_FLAG_EXIT_PROCESSING (1 << 5) /* Bit 5: Exitting */ /* Values for struct task_group tg_flags */ @@ -253,6 +254,11 @@ struct dspace_s #ifdef HAVE_TASK_GROUP struct task_group_s { +#ifdef HAVE_GROUP_MEMBERS + struct task_group_s *flink; /* Supports a singly linked list */ + gid_t tg_gid; /* The ID of this task group */ + gid_t tg_pgid; /* The ID of the parent task group */ +#endif uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ /* Group membership ***********************************************************/ @@ -311,12 +317,16 @@ struct _TCB /* Task Management Fields *****************************************************/ pid_t pid; /* This is the ID of the thread */ + #ifdef CONFIG_SCHED_HAVE_PARENT /* Support parent-child relationship */ - pid_t parent; /* This is the ID of the parent thread */ +#ifndef HAVE_GROUP_MEMBERS /* Don't know pids of group members */ + pid_t ppid; /* This is the ID of the parent thread */ #ifndef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */ uint16_t nchildren; /* This is the number active children */ #endif #endif +#endif /* CONFIG_SCHED_HAVE_PARENT */ + start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 6a0b99144..d059152e0 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -73,13 +73,6 @@ ifeq ($(CONFIG_PRIORITY_INHERITANCE),y) SCHED_SRCS += sched_reprioritize.c endif -ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) -SCHED_SRCS += task_reparent.c -ifeq ($(CONFIG_SCHED_CHILD_STATUS),y) -SCHED_SRCS += task_childstatus.c -endif -endif - ifeq ($(CONFIG_SCHED_WAITPID),y) SCHED_SRCS += sched_waitpid.c ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) @@ -87,7 +80,14 @@ SCHED_SRCS += sched_waitid.c sched_wait.c endif endif -GRP_SRCS = group_create.c group_join.c group_leave.c +GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c + +ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) +GRP_SRCS += task_reparent.c +ifeq ($(CONFIG_SCHED_CHILD_STATUS),y) +GRP_SRCS += group_childstatus.c +endif +endif ifneq ($(CONFIG_DISABLE_SIGNALS),y) GRP_SRCS += group_signal.c diff --git a/nuttx/sched/group_childstatus.c b/nuttx/sched/group_childstatus.c new file mode 100644 index 000000000..ef42b6c34 --- /dev/null +++ b/nuttx/sched/group_childstatus.c @@ -0,0 +1,441 @@ +/***************************************************************************** + * sched/group_childstatus.c + * + * Copyright (C) 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. + * + *****************************************************************************/ + +/***************************************************************************** + * Included Files + *****************************************************************************/ + +#include + +#include +#include +#include + +#include "os_internal.h" +#include "group_internal.h" + +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ +/* Note that there cannot be more that CONFIG_MAX_TASKS tasks in total. + * However, the number of child status structures may need to be significantly + * larger because this number includes the maximum number of tasks that are + * running PLUS the number of tasks that have exit'ed without having their + * exit status reaped (via wait(), waitid(), or waitpid()). + * + * Obviously, if tasks spawn children indefinitely and never have the exit + * status reaped, then you have a memory leak! + */ + +#if !defined(CONFIG_PREALLOC_CHILDSTATUS) || CONFIG_PREALLOC_CHILDSTATUS == 0 +# undef CONFIG_PREALLOC_CHILDSTATUS +# define CONFIG_PREALLOC_CHILDSTATUS (2*CONFIG_MAX_TASKS) +#endif + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_CHILDSTATUS +#endif + +/***************************************************************************** + * Private Types + *****************************************************************************/ +/* Globals are maintained in a structure to minimize name collisions. */ + +struct child_pool_s +{ + struct child_status_s alloc[CONFIG_PREALLOC_CHILDSTATUS]; + FAR struct child_status_s *freelist; +}; + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +static struct child_pool_s g_child_pool; + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_dumpchildren + * + * Description: + * Dump all of the children when the part TCB list is modified. + * + * Parameters: + * group - The task group containing the child status. + * + * Return Value: + * None. + * + * Assumptions: + * Called early in initialization. No special precautions are required. + * + *****************************************************************************/ + +#ifdef CONFIG_DEBUG_CHILDSTATUS +static void group_dumpchildren(FAR struct task_group_s *group, + FAR const char *msg) +{ + FAR struct child_status_s *child; + int i; + + dbg("Task group=%p: %s\n", group, msg); + for (i = 0, child = group->tg_children; child; i++, child = child->flink) + { + dbg(" %d. ch_flags=%02x ch_pid=%d ch_status=%d\n", + i, child->ch_flags, child->ch_pid, child->ch_status); + } +} +#else +# define group_dumpchildren(t,m) +#endif + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: task_initialize + * + * Description: + * Initialize task related status. At present, this includes only the + * initialize of the child status pool. + * + * Parameters: + * None. + * + * Return Value: + * None. + * + * Assumptions: + * Called early in initialization. No special precautions are required. + * + *****************************************************************************/ + +void task_initialize(void) +{ + FAR struct child_status_s *curr; + FAR struct child_status_s *prev; + int i; + + /* Save all of the child status structures in a free list */ + + prev = &g_child_pool.alloc[0]; + g_child_pool.freelist = prev; + for (i = 0; i < CONFIG_PREALLOC_CHILDSTATUS; i++) + { + curr = &g_child_pool.alloc[i]; + prev->flink = curr; + prev = curr; + } +} + +/***************************************************************************** + * Name: group_allocchild + * + * Description: + * Allocate a child status structure by removing the next entry from a + * free list. + * + * Parameters: + * None. + * + * Return Value: + * On success, a non-NULL pointer to a child status structure. NULL is + * returned if there are no remaining, pre-allocated child status structures. + * + * Assumptions: + * Called during task creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +FAR struct child_status_s *group_allocchild(void) +{ + FAR struct child_status_s *ret; + + /* Return the status block at the head of the free list */ + + ret = g_child_pool.freelist; + if (ret) + { + g_child_pool.freelist = ret->flink; + ret->flink = NULL; + } + + return ret; +} + +/***************************************************************************** + * Name: group_freechild + * + * Description: + * Release a child status structure by returning it to a free list. + * + * Parameters: + * status - The child status structure to be freed. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +void group_freechild(FAR struct child_status_s *child) +{ + /* Return the child status structure to the free list */ + + if (child) + { + child->flink = g_child_pool.freelist; + g_child_pool.freelist = child; + } +} + +/***************************************************************************** + * Name: group_addchild + * + * Description: + * Add a child status structure in the given TCB. + * + * Parameters: + * group - The task group for the child status. + * child - The structure to be added + * + * Return Value: + * N + * + * Assumptions: + * Called during task creation processing in a safe context. No special + * precautions are required here. + * + *****************************************************************************/ + +void group_addchild(FAR struct task_group_s *group, + FAR struct child_status_s *child) +{ + /* Add the entry into the TCB list of children */ + + child->flink = group->tg_children; + group->tg_children = child; + + group_dumpchildren(group, "group_addchild"); +} + +/***************************************************************************** + * Name: group_findchild + * + * Description: + * Find a child status structure in the given task group. A reference to + * the child structure is returned, but the child remains the the group's + * list of children. + * + * Parameters: + * group - The ID of the parent task group to containing the child status. + * pid - The ID of the child to find. + * + * Return Value: + * On success, a non-NULL pointer to a child status structure. NULL is + * returned if there is child status structure for that pid in the TCB. + * + * Assumptions: + * Called during SIGCHLD processing in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +FAR struct child_status_s *group_findchild(FAR struct task_group_s *group, + pid_t pid) +{ + FAR struct child_status_s *child; + + DEBUGASSERT(group); + + /* Find the status structure with the matching PID */ + + for (child = group->tg_children; child; child = child->flink) + { + if (child->ch_pid == pid) + { + return child; + } + } + + return NULL; +} + +/***************************************************************************** + * Name: group_exitchild + * + * Description: + * Search for any child that has exitted. + * + * Parameters: + * tcb - The TCB of the parent task to containing the child status. + * + * Return Value: + * On success, a non-NULL pointer to a child status structure for the + * exited child. NULL is returned if not child has exited. + * + * Assumptions: + * Called during SIGCHLD processing in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group) +{ + FAR struct child_status_s *child; + + /* Find the status structure of any child task that has exitted. */ + + for (child = group->tg_children; child; child = child->flink) + { + if ((child->ch_flags & CHILD_FLAG_EXITED) != 0) + { + return child; + } + } + + return NULL; +} + +/***************************************************************************** + * Name: group_removechild + * + * Description: + * Remove one child structure from a task group. The child is removed, but + * is not yet freed. group_freechild must be called in order to free the + * child status structure. + * + * Parameters: + * group - The task group containing the child status. + * pid - The ID of the child to find. + * + * Return Value: + * On success, a non-NULL pointer to a child status structure. NULL is + * returned if there is child status structure for that pid in the TCB. + * + * Assumptions: + * Called during SIGCHLD processing in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, + pid_t pid) +{ + FAR struct child_status_s *curr; + FAR struct child_status_s *prev; + + DEBUGASSERT(group); + + /* Find the status structure with the matching PID */ + + for (prev = NULL, curr = group->tg_children; + curr; + prev = curr, curr = curr->flink) + { + if (curr->ch_pid == pid) + { + break; + } + } + + /* Did we find it? If so, remove it from the group. */ + + if (curr) + { + /* Do we remove it from mid-list? Or from the head of the list? */ + + if (prev) + { + prev->flink = curr->flink; + } + else + { + group->tg_children = curr->flink; + } + + curr->flink = NULL; + group_dumpchildren(group, "group_removechild"); + } + + return curr; +} + +/***************************************************************************** + * Name: group_removechildren + * + * Description: + * Remove and free all child structure from the task group. + * + * Parameters: + * group - The task group containing the child status. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task exit processing in a safe context. No special + * precautions are required here. + * + *****************************************************************************/ + +void group_removechildren(FAR struct task_group_s *group) +{ + FAR struct child_status_s *curr; + FAR struct child_status_s *next; + + /* Remove all child structures for the TCB and return them to the freelist */ + + for (curr = group->tg_children; curr; curr = next) + { + next = curr->flink; + group_freechild(curr); + } + + group->tg_children = NULL; + group_dumpchildren(group, "group_removechildren"); +} + +#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index da91fa065..768641be1 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -1,5 +1,5 @@ /***************************************************************************** - * sched/group_allocate.c + * sched/group_create.c * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -65,11 +65,87 @@ /***************************************************************************** * Private Data *****************************************************************************/ +/* This is counter that is used to generate unique task group IDs */ + +#ifdef HAVE_GROUP_MEMBERS +static gid_t g_gidcounter; +#endif + +/***************************************************************************** + * Public Data + *****************************************************************************/ +/* This is the head of a list of all group members */ + +#ifdef HAVE_GROUP_MEMBERS +FAR struct task_group_s *g_grouphead; +#endif /***************************************************************************** * Private Functions *****************************************************************************/ +/***************************************************************************** + * Name: group_assigngid + * + * Description: + * Create a unique group ID. + * + * Parameters: + * tcb - The tcb in need of the task group. + * + * Return Value: + * None + * + * Assumptions: + * Called during task creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +void group_assigngid(FAR struct task_group_s *group) +{ + irqstate_t flags; + gid_t gid; + + /* Pre-emption should already be enabled, but lets be paranoid careful */ + + sched_lock(); + + /* Loop until we create a unique ID */ + + for (;;) + { + /* Increment the ID counter. This is global data so be extra paraoid. */ + + flags = irqsave(); + gid = ++g_gidcounter; + + /* Check for overflow */ + + if (gid <= 0) + { + g_gidcounter = 1; + irqrestore(flags); + } + else + { + /* Does a task group with this ID already exist? */ + + irqrestore(flags); + if (group_find(gid) == NULL) + { + /* Now assign this ID to the group and return */ + + group->tg_gid = gid; + sched_unlock(); + return; + } + } + } +} +#endif /* HAVE_GROUP_MEMBERS */ + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -112,6 +188,14 @@ int group_allocate(FAR _TCB *tcb) return -ENOMEM; } + /* Assign the group a unique ID. If g_gidcounter were to wrap before we + * finish with task creation, that would be a problem. + */ + +#ifdef HAVE_GROUP_MEMBERS + group_assigngid(tcb->group); +#endif + /* Duplicate the parent tasks envionment */ ret = env_dup(tcb); @@ -149,6 +233,9 @@ int group_allocate(FAR _TCB *tcb) int group_initialize(FAR _TCB *tcb) { FAR struct task_group_s *group; +#ifdef HAVE_GROUP_MEMBERS + irqstate_t flags; +#endif DEBUGASSERT(tcb && tcb->group); group = tcb->group; @@ -172,9 +259,17 @@ int group_initialize(FAR _TCB *tcb) */ group->tg_mxmembers = GROUP_INITIAL_MEMBERS; /* Number of members in allocation */ + + /* Add the initialized entry to the list of groups */ + + flags = irqsave(); + group->flink = g_grouphead; + g_grouphead = group; + irqrestore(flags); + #endif - group->tg_nmembers = 1; /* Number of members in the group */ + group->tg_nmembers = 1; /* Number of members in the group */ return OK; } diff --git a/nuttx/sched/group_find.c b/nuttx/sched/group_find.c new file mode 100644 index 000000000..eb3989223 --- /dev/null +++ b/nuttx/sched/group_find.c @@ -0,0 +1,125 @@ +/***************************************************************************** + * sched/group_find.c + * + * Copyright (C) 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. + * + *****************************************************************************/ + +/***************************************************************************** + * Included Files + *****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#include "group_internal.h" +#include "env_internal.h" + +#ifdef HAVE_TASK_GROUP + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ + +/***************************************************************************** + * Private Types + *****************************************************************************/ + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +/***************************************************************************** + * Public Data + *****************************************************************************/ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_find + * + * Description: + * Given a group ID, find the group task structure with that ID. IDs are + * used instead of pointers to group structures. This is done because a + * group can disappear at any time leaving a stale pointer; an ID is cleaner + * because if the group disappears, this function will fail gracefully. + * + * Parameters: + * gid - The group ID to find. + * + * Return Value: + * On success, a pointer to the group task structure is returned. This + * function can fail only if there is no group that corresponds to the + * groupd ID. + * + * Assumptions: + * Called during when signally tasks in a safe context. No special + * precautions should be required here. However, extra care is taken when + * accessing the global g_grouphead list. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +FAR struct task_group_s *group_find(gid_t gid) +{ + FAR struct task_group_s *group; + irqstate_t flags; + + /* Find the status structure with the matching PID */ + + flags = irqsave(); + for (group = g_grouphead; group; group = group->flink) + { + if (group->tg_gid == gid) + { + irqrestore(flags); + return group; + } + } + + irqrestore(flags); + return NULL; +} +#endif + +#endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index aa8476e3c..b78b38453 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -52,37 +52,62 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ +/* Any negative GID is invalid. */ + +#define INVALID_GROUP_ID (pid_t)-1 +#define IS_INVALID_GID(gid) ((int)(gid) < 0) /**************************************************************************** * Public Type Definitions ****************************************************************************/ /**************************************************************************** - * Global Variables + * Public Data ****************************************************************************/ +/* This is the head of a list of all group members */ + +#ifdef HAVE_GROUP_MEMBERS +extern FAR struct task_group_s *g_grouphead; +#endif + /**************************************************************************** * 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); +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); + +#ifdef HAVE_GROUP_MEMBERS +FAR struct task_group_s *group_find(gid_t gid); +int group_addmember(FAR struct task_group_s *group, pid_t pid); +int group_removemember(FAR struct task_group_s *group, pid_t pid); +#else +# define group_find(gid) (NULL) +# define group_addmember(group,pid) (0) +# define group_removemember(group,pid) (1) +#endif + #ifndef CONFIG_DISABLE_SIGNALS -int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); +int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info); #else -# define group_signal(tcb,info) (0) +# 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) +# 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_find(gid) (NULL) +# define group_addmember(group,pid) (0) +# define group_removemember(group,pid) (1) +# define group_signal(tcb,info) (0) #endif /* HAVE_TASK_GROUP */ /* Parent/child data management */ @@ -91,14 +116,18 @@ int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); 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 +FAR struct child_status_s *group_allocchild(void); +void group_freechild(FAR struct child_status_s *status); +void group_addchild(FAR struct task_group_s *group, + FAR struct child_status_s *child); +FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group); +FAR struct child_status_s *group_findchild(FAR struct task_group_s *group, + pid_t pid); +FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, + pid_t pid); +void group_removechildren(FAR struct task_group_s *group); + +#endif /* CONFIG_SCHED_CHILD_STATUS */ #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 077c45763..70319b3a1 100644 --- a/nuttx/sched/group_join.c +++ b/nuttx/sched/group_join.c @@ -139,6 +139,9 @@ int group_bind(FAR _TCB *tcb) int group_join(FAR _TCB *tcb) { FAR struct task_group_s *group; +#ifdef HAVE_GROUP_MEMBERS + int ret; +#endif DEBUGASSERT(tcb && tcb->group && tcb->group->tg_nmembers < UINT8_MAX); @@ -146,8 +149,45 @@ int group_join(FAR _TCB *tcb) /* Get the group from the TCB */ group = tcb->group; - + #ifdef HAVE_GROUP_MEMBERS + /* Add the member to the group */ + + ret = group_addmember(group, tcb->pid); + if (ret < 0) + { + return ret; + } +#endif + + group->tg_nmembers++; + return OK; +} + +/***************************************************************************** + * Name: group_addmember + * + * Description: + * Add a new member to a group. + * + * Parameters: + * group - The task group to add the new member + * pid - The new member + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during thread creation and during reparenting in a safe context. + * No special precautions are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +int group_addmember(FAR struct task_group_s *group, pid_t pid) +{ + DEBUGASSERT(group && group->tg_nmembers < UINT8_MAX); + /* Will we need to extend the size of the array of groups? */ if (group->tg_nmembers >= group->tg_mxmembers) @@ -179,11 +219,9 @@ int group_join(FAR _TCB *tcb) /* Assign this new pid to the group. */ - group->tg_members[group->tg_nmembers] = tcb->pid; -#endif - - group->tg_nmembers++; + group->tg_members[group->tg_nmembers] = pid; return OK; } +#endif /* HAVE_GROUP_MEMBERS */ #endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index d5fa9dbaf..add424185 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -65,6 +65,65 @@ * Private Functions *****************************************************************************/ +/***************************************************************************** + * Name: group_remove + * + * Description: + * Remove a group from the list of groups. + * + * Parameters: + * group - The group to be removed. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task deletion in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +void group_remove(FAR struct task_group_s *group) +{ + FAR struct task_group_s *curr; + FAR struct task_group_s *prev; + irqstate_t flags; + + /* Let's be especially careful while access the global task group list. + * This is probably un-necessary. + */ + + flags = irqsave(); + + /* Find the task group structure */ + + for (prev = NULL, curr = g_grouphead; + curr && curr != group; + prev = curr, curr = curr->flink); + + /* Did we find it? If so, remove it from the list. */ + + if (curr) + { + /* Do we remove it from mid-list? Or from the head of the list? */ + + if (prev) + { + prev->flink = curr->flink; + } + else + { + g_grouphead = curr->flink; + } + + curr->flink = NULL; + } + + irqrestore(flags); +} +#endif + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -90,6 +149,8 @@ * *****************************************************************************/ +#ifdef HAVE_GROUP_MEMBERS + void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; @@ -101,64 +162,57 @@ void group_leave(FAR _TCB *tcb) group = tcb->group; if (group) { -#ifdef HAVE_GROUP_MEMBERS - int i; + /* Remove the member from group */ - /* Find the member in the array of members and remove it */ + int ret = group_removemember(group, tcb->pid); + DEBUGASSERT(ret >= 0); - for (i = 0; i < group->tg_nmembers; i++) - { - /* Does this member have the matching pid */ - - if (group->tg_members[i] == tcb->pid) - { - /* Yes.. break out of the loop. We don't do the actual - * removal here, instead we re-test i and do the adjustments - * outside of the loop. We do this because we want the - * DEBUGASSERT to work properly. - */ - - break; - } - } - - /* Now, test if we found the task in the array of members. */ + /* Is the group now empty? */ - DEBUGASSERT(i < group->tg_nmembers); - if (i < group->tg_nmembers) + if (ret == 0) { - /* Yes..Is this the last member of the group? */ - - if (group->tg_nmembers > 1) - { - /* No.. remove the member from the array of members */ - - group->tg_members[i] = group->tg_members[group->tg_nmembers - 1]; - group->tg_nmembers--; - } - - /* Yes.. that was the last member remaining in the group */ - - else - { - /* Release all of the resource contained within the group */ - /* Free all un-reaped child exit status */ + /* 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); + group_removechildren(tcb->group); #endif - /* Release all shared environment variables */ + /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); + env_release(tcb); #endif - /* Release the group container itself */ + /* Remove the group from the list of groups */ + + group_remove(group); + + /* Release the group container itself */ - sched_free(group); - } + sched_free(group); } -#else - /* Yes..Is this the last member of the group? */ + + /* In any event, we can detach the group from the TCB so that we won't + * do this again. + */ + + tcb->group = NULL; + } +} + +#else /* HAVE_GROUP_MEMBERS */ + +void group_leave(FAR _TCB *tcb) +{ + FAR struct task_group_s *group; + + DEBUGASSERT(tcb); + + /* Make sure that we have a group */ + + group = tcb->group; + if (group) + { + /* Yes, we have a group.. Is this the last member of the group? */ if (group->tg_nmembers > 1) { @@ -175,7 +229,7 @@ void group_leave(FAR _TCB *tcb) /* Free all un-reaped child exit status */ #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - task_removechildren(tcb); + group_removechildren(tcb->group); #endif /* Release all shared environment variables */ @@ -186,7 +240,6 @@ void group_leave(FAR _TCB *tcb) sched_free(group); } -#endif /* In any event, we can detach the group from the TCB so we won't do * this again. @@ -196,4 +249,67 @@ void group_leave(FAR _TCB *tcb) } } +#endif /* HAVE_GROUP_MEMBERS */ + +/***************************************************************************** + * Name: group_removemember + * + * Description: + * Remove a member from a group. + * + * Parameters: + * group - The group from which to remove the member. + * pid - The member to be removed. + * + * Return Value: + * On success, returns the number of members remaining in the group (>=0). + * Can fail only if the member is not found in the group. On failure, + * returns -ENOENT + * + * Assumptions: + * Called during task deletion and also from the reparenting logic, both + * in a safe context. No special precautions are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +int group_removemember(FAR struct task_group_s *group, pid_t pid) +{ + int i; + + DEBUGASSERT(group); + + /* Find the member in the array of members and remove it */ + + for (i = 0; i < group->tg_nmembers; i++) + { + /* Does this member have the matching pid */ + + if (group->tg_members[i] == pid) + { + /* Yes.. break out of the loop. We don't do the actual + * removal here, instead we re-test i and do the adjustments + * outside of the loop. We do this because we want the + * DEBUGASSERT to work properly. + */ + + break; + } + } + + /* Now, test if we found the task in the array of members. */ + + if (i < group->tg_nmembers) + { + /* Remove the member from the array of members */ + + group->tg_members[i] = group->tg_members[group->tg_nmembers - 1]; + group->tg_nmembers--; + return group->tg_nmembers; + } + + return -ENOENT; +} +#endif /* HAVE_GROUP_MEMBERS */ + #endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c index 5020ec436..009ab7a55 100644 --- a/nuttx/sched/group_signal.c +++ b/nuttx/sched/group_signal.c @@ -42,6 +42,7 @@ #include #include #include +#include #include #include "os_internal.h" @@ -74,10 +75,10 @@ * Name: group_signal * * Description: - * Send a signal to every member of the group to which task belongs. + * Send a signal to every member of the group. * * Parameters: - * tcb - The tcb of one task in the task group that needs to be signalled. + * group - The task group that needs to be signalled. * * Return Value: * 0 (OK) on success; a negated errno value on failure. @@ -88,15 +89,13 @@ * *****************************************************************************/ -int group_signal(FAR _TCB *tcb, FAR siginfo_t *info) +int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info) { #ifdef HAVE_GROUP_MEMBERS - FAR struct task_group_s *group; FAR _TCB *gtcb; int i; - DEBUGASSERT(tcb && tcb->group && info); - group = tcb->group; + DEBUGASSERT(group && info); /* Make sure that pre-emption is disabled to that we signal all of teh * members of the group before any of them actually run. @@ -130,8 +129,35 @@ int group_signal(FAR _TCB *tcb, FAR siginfo_t *info) sched_unlock(); return OK; #else - return sig_received(tcb, info); + return -ENOSYS; #endif } +/***************************************************************************** + * Name: group_signalmember + * + * Description: + * Send a signal to every member of the group to which task belongs. + * + * Parameters: + * tcb - The tcb of one task in the task group that needs to be signalled. + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during task terminatino in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +int group_signalmember(FAR _TCB *tcb, FAR siginfo_t *info) +{ +#ifdef HAVE_GROUP_MEMBERS + DEBUGASSERT(tcb); + return group_signal(tcb->group, info); +#else + return sig_received(tcb, info); +#endif +} #endif /* HAVE_TASK_GROUP && !CONFIG_DISABLE_SIGNALS */ diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index 41e488f90..9c24189c4 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -79,8 +79,8 @@ static void exited_child(FAR _TCB *rtcb, FAR struct child_status_s *child, /* Discard the child entry */ - (void)task_removechild(rtcb, child->ch_pid); - task_freechild(child); + (void)group_removechild(rtcb->group, child->ch_pid); + group_freechild(child); } #endif @@ -212,7 +212,11 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb((pid_t)id); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -224,7 +228,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { /* Check if this specific pid has allocated child status? */ - if (task_findchild(rtcb, (pid_t)id) == NULL) + if (group_findchild(rtcb->group, (pid_t)id) == NULL) { /* This specific pid is not a child */ @@ -246,7 +250,11 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb((pid_t)id); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -270,7 +278,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { /* We are waiting for any child to exit */ - if (retains && (child = task_exitchild(rtcb)) != NULL) + if (retains && (child = group_exitchild(rtcb->group)) != NULL) { /* A child has exited. Apparently we missed the signal. * Return the exit status and break out of the loop. @@ -287,7 +295,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { /* Yes ... Get the current status of the child task. */ - child = task_findchild(rtcb, (pid_t)id); + child = group_findchild(rtcb->group, (pid_t)id); DEBUGASSERT(child); /* Did the child exit? */ diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index 4af7f7ef3..0285c2673 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -172,16 +172,12 @@ * * Assumptions: * - *****************************************************************************/ - -/*************************************************************************** - * NOTE: This is a partially functional, experimental version of waitpid() + * Compatibility + * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not + * defined), then waitpid() is still available, but does not obey the + * restriction that the pid be a child of the caller. * - * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not - * defined), then waitpid() is still available, but does not obey the - * restriction that the pid be a child of the caller. - * - ***************************************************************************/ + *****************************************************************************/ #ifndef CONFIG_SCHED_HAVE_PARENT pid_t waitpid(pid_t pid, int *stat_loc, int options) @@ -325,7 +321,11 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb(pid); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -337,7 +337,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* Check if this specific pid has allocated child status? */ - if (task_findchild(rtcb, pid) == NULL) + if (group_findchild(rtcb->group, pid) == NULL) { err = ECHILD; goto errout_with_errno; @@ -357,7 +357,11 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb(pid); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -383,7 +387,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) */ DEBUGASSERT(!retains || rtcb->group->tg_children); - if (retains && (child = task_exitchild(rtcb)) != NULL) + if (retains && (child = group_exitchild(rtcb->group)) != NULL) { /* A child has exited. Apparently we missed the signal. * Return the saved exit status. @@ -395,8 +399,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Discard the child entry and break out of the loop */ - (void)task_removechild(rtcb, child->ch_pid); - task_freechild(child); + (void)group_removechild(rtcb->group, child->ch_pid); + group_freechild(child); break; } } @@ -407,7 +411,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* Get the current status of the child task. */ - child = task_findchild(rtcb, pid); + child = group_findchild(rtcb->group, pid); DEBUGASSERT(child); /* Did the child exit? */ @@ -420,8 +424,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Discard the child entry and break out of the loop */ - (void)task_removechild(rtcb, pid); - task_freechild(child); + (void)group_removechild(rtcb->group, pid); + group_freechild(child); break; } } diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c index fe72cc22d..5c00179dc 100644 --- a/nuttx/sched/sig_action.c +++ b/nuttx/sched/sig_action.c @@ -242,7 +242,7 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction * /* Free all pending exit status */ - task_removechildren(rtcb); + group_removechildren(rtcb->group); irqrestore(flags); } #endif diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c deleted file mode 100644 index c0df3d534..000000000 --- a/nuttx/sched/task_childstatus.c +++ /dev/null @@ -1,440 +0,0 @@ -/***************************************************************************** - * sched/task_childstatus.c - * - * Copyright (C) 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. - * - *****************************************************************************/ - -/***************************************************************************** - * Included Files - *****************************************************************************/ - -#include - -#include -#include -#include - -#include "os_internal.h" -#include "group_internal.h" - -#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - -/***************************************************************************** - * Pre-processor Definitions - *****************************************************************************/ -/* Note that there cannot be more that CONFIG_MAX_TASKS tasks in total. - * However, the number of child status structures may need to be significantly - * larger because this number includes the maximum number of tasks that are - * running PLUS the number of tasks that have exit'ed without having their - * exit status reaped (via wait(), waitid(), or waitpid()). - * - * Obviously, if tasks spawn children indefinitely and never have the exit - * status reaped, then you have a memory leak! - */ - -#if !defined(CONFIG_PREALLOC_CHILDSTATUS) || CONFIG_PREALLOC_CHILDSTATUS == 0 -# undef CONFIG_PREALLOC_CHILDSTATUS -# define CONFIG_PREALLOC_CHILDSTATUS (2*CONFIG_MAX_TASKS) -#endif - -#ifndef CONFIG_DEBUG -# undef CONFIG_DEBUG_CHILDSTATUS -#endif - -/***************************************************************************** - * Private Types - *****************************************************************************/ -/* Globals are maintained in a structure to minimize name collisions. */ - -struct child_pool_s -{ - struct child_status_s alloc[CONFIG_PREALLOC_CHILDSTATUS]; - FAR struct child_status_s *freelist; -}; - -/***************************************************************************** - * Private Data - *****************************************************************************/ - -static struct child_pool_s g_child_pool; - -/***************************************************************************** - * Private Functions - *****************************************************************************/ - -/***************************************************************************** - * Name: task_dumpchildren - * - * Description: - * Dump all of the children when the part TCB list is modified. - * - * Parameters: - * tcb - The parent TCB. - * - * Return Value: - * None. - * - * Assumptions: - * Called early in initialization. No special precautions are required. - * - *****************************************************************************/ - -#ifdef CONFIG_DEBUG_CHILDSTATUS -static void task_dumpchildren(FAR _TCB *tcb, FAR const char *msg) -{ - FAR struct child_status_s *child; - FAR struct task_group_s *group = tcb->group; - int i; - - dbg("Parent TCB=%p group=%p: %s\n", tcb, group, msg); - for (i = 0, child = group->tg_children; child; i++, child = child->flink) - { - dbg(" %d. ch_flags=%02x ch_pid=%d ch_status=%d\n", - i, child->ch_flags, child->ch_pid, child->ch_status); - } -} -#else -# define task_dumpchildren(t,m) -#endif - -/***************************************************************************** - * Public Functions - *****************************************************************************/ - -/***************************************************************************** - * Name: task_initialize - * - * Description: - * Initialize task related status. At present, this includes only the - * initialize of the child status pool. - * - * Parameters: - * None. - * - * Return Value: - * None. - * - * Assumptions: - * Called early in initialization. No special precautions are required. - * - *****************************************************************************/ - -void task_initialize(void) -{ - FAR struct child_status_s *curr; - FAR struct child_status_s *prev; - int i; - - /* Save all of the child status structures in a free list */ - - prev = &g_child_pool.alloc[0]; - g_child_pool.freelist = prev; - for (i = 0; i < CONFIG_PREALLOC_CHILDSTATUS; i++) - { - curr = &g_child_pool.alloc[i]; - prev->flink = curr; - prev = curr; - } -} - -/***************************************************************************** - * Name: task_allocchild - * - * Description: - * Allocate a child status structure by removing the next entry from a - * free list. - * - * Parameters: - * None. - * - * Return Value: - * On success, a non-NULL pointer to a child status structure. NULL is - * returned if there are no remaining, pre-allocated child status structures. - * - * Assumptions: - * Called during task creation in a safe context. No special precautions - * are required here. - * - *****************************************************************************/ - -FAR struct child_status_s *task_allocchild(void) -{ - FAR struct child_status_s *ret; - - /* Return the status block at the head of the free list */ - - ret = g_child_pool.freelist; - if (ret) - { - g_child_pool.freelist = ret->flink; - ret->flink = NULL; - } - - return ret; -} - -/***************************************************************************** - * Name: task_freechild - * - * Description: - * Release a child status structure by returning it to a free list. - * - * Parameters: - * status - The child status structure to be freed. - * - * Return Value: - * None. - * - * Assumptions: - * Called during task creation in a safe context. No special precautions - * are required here. - * - *****************************************************************************/ - -void task_freechild(FAR struct child_status_s *child) -{ - /* Return the child status structure to the free list */ - - if (child) - { - child->flink = g_child_pool.freelist; - g_child_pool.freelist = child; - } -} - -/***************************************************************************** - * Name: task_addchild - * - * Description: - * Add a child status structure in the given TCB. - * - * Parameters: - * tcb - The TCB of the parent task to containing the child status. - * child - The structure to be added - * - * Return Value: - * N - * - * Assumptions: - * Called during task creation processing in a safe context. No special - * precautions are required here. - * - *****************************************************************************/ - -void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child) -{ - FAR struct task_group_s *group = tcb->group; - - /* Add the entry into the TCB list of children */ - - child->flink = group->tg_children; - group->tg_children = child; - - task_dumpchildren(tcb, "task_addchild"); -} - -/***************************************************************************** - * Name: task_findchild - * - * Description: - * Find a child status structure in the given TCB. A reference to the - * child structure is returned, but the child remains the the TCB's list - * of children. - * - * Parameters: - * tcb - The TCB of the parent task to containing the child status. - * pid - The ID of the child to find. - * - * Return Value: - * On success, a non-NULL pointer to a child status structure. NULL is - * returned if there is child status structure for that pid in the TCB. - * - * Assumptions: - * Called during SIGCHLD processing in a safe context. No special precautions - * are required here. - * - *****************************************************************************/ - -FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid) -{ - FAR struct task_group_s *group = tcb->group; - FAR struct child_status_s *child; - - /* Find the status structure with the matching PID */ - - for (child = group->tg_children; child; child = child->flink) - { - if (child->ch_pid == pid) - { - return child; - } - } - - return NULL; -} - -/***************************************************************************** - * Name: task_exitchild - * - * Description: - * Search for any child that has exitted. - * - * Parameters: - * tcb - The TCB of the parent task to containing the child status. - * - * Return Value: - * On success, a non-NULL pointer to a child status structure for the - * exited child. NULL is returned if not child has exited. - * - * Assumptions: - * Called during SIGCHLD processing in a safe context. No special precautions - * are required here. - * - *****************************************************************************/ - -FAR struct child_status_s *task_exitchild(FAR _TCB *tcb) -{ - FAR struct task_group_s *group = tcb->group; - FAR struct child_status_s *child; - - /* Find the status structure of any child task that has exitted. */ - - for (child = group->tg_children; child; child = child->flink) - { - if ((child->ch_flags & CHILD_FLAG_EXITED) != 0) - { - return child; - } - } - - return NULL; -} - -/***************************************************************************** - * Name: task_removechild - * - * Description: - * Remove one child structure from the TCB. The child is removed, but is - * not yet freed. task_freechild must be called in order to free the child - * status structure. - * - * Parameters: - * tcb - The TCB of the parent task to containing the child status. - * pid - The ID of the child to find. - * - * Return Value: - * On success, a non-NULL pointer to a child status structure. NULL is - * returned if there is child status structure for that pid in the TCB. - * - * Assumptions: - * Called during SIGCHLD processing in a safe context. No special precautions - * are required here. - * - *****************************************************************************/ - -FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid) -{ - FAR struct task_group_s *group = tcb->group; - FAR struct child_status_s *curr; - FAR struct child_status_s *prev; - - /* Find the status structure with the matching PID */ - - for (prev = NULL, curr = group->tg_children; - curr; - prev = curr, curr = curr->flink) - { - if (curr->ch_pid == pid) - { - break; - } - } - - /* Did we find it? If so, remove it from the TCB. */ - - if (curr) - { - /* Do we remove it from mid-list? Or from the head of the list? */ - - if (prev) - { - prev->flink = curr->flink; - } - else - { - group->tg_children = curr->flink; - } - - curr->flink = NULL; - task_dumpchildren(tcb, "task_removechild"); - } - - return curr; -} - -/***************************************************************************** - * Name: task_removechildren - * - * Description: - * Remove and free all child structure from the TCB. - * - * Parameters: - * tcb - The TCB of the parent task to containing the child status. - * - * Return Value: - * None. - * - * Assumptions: - * Called during task exit processing in a safe context. No special - * precautions are required here. - * - *****************************************************************************/ - -void task_removechildren(FAR _TCB *tcb) -{ - FAR struct task_group_s *group = tcb->group; - FAR struct child_status_s *curr; - FAR struct child_status_s *next; - - /* Remove all child structures for the TCB and return them to the freelist */ - - for (curr = group->tg_children; curr; curr = next) - { - next = curr->flink; - task_freechild(curr); - } - - group->tg_children = NULL; - task_dumpchildren(tcb, "task_removechildren"); -} - -#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index cbada851a..3fdf08bf7 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -104,10 +104,7 @@ static inline void task_atexit(FAR _TCB *tcb) (*tcb->atexitfunc[index])(); - /* Nullify the atexit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the atext function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the atexit function to prevent its reuse. */ tcb->atexitfunc[index] = NULL; } @@ -120,10 +117,7 @@ static inline void task_atexit(FAR _TCB *tcb) (*tcb->atexitfunc)(); - /* Nullify the atexit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the atext function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the atexit function to prevent its reuse. */ tcb->atexitfunc = NULL; } @@ -161,10 +155,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status) (*tcb->onexitfunc[index])(status, tcb->onexitarg[index]); - /* Nullify the on_exit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the atext function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the on_exit function to prevent its reuse. */ tcb->onexitfunc[index] = NULL; } @@ -176,10 +167,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status) (*tcb->onexitfunc)(status, tcb->onexitarg); - /* Nullify the on_exit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the on_exit function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the on_exit function to prevent its reuse. */ tcb->onexitfunc = NULL; } @@ -198,20 +186,96 @@ static inline void task_onexit(FAR _TCB *tcb, int status) ****************************************************************************/ #ifdef CONFIG_SCHED_HAVE_PARENT +#ifdef HAVE_GROUP_MEMBERS +static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status) +{ + FAR struct task_group_s *chgrp = ctcb->group; + FAR struct task_group_s *pgrp; + siginfo_t info; + + DEBUGASSERT(chgrp); + + /* Only the final exiting thread in a task group should generate SIGCHLD. */ + + if (chgrp->tg_nmembers == 1) + { + /* 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. + */ + + 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; + + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(pgrp, 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; + } + } +#endif /* CONFIG_SCHED_CHILD_STATUS */ + + /* 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 + * for now. + */ + + info.si_signo = SIGCHLD; + info.si_code = CLD_EXITED; + info.si_value.sival_ptr = NULL; + info.si_pid = ctcb->pid; + info.si_status = status; + + /* Send the signal. We need to use this internal interface so that we + * can provide the correct si_code value with the signal. + */ + + (void)group_signal(pgrp, &info); + } +} + +#else /* HAVE_GROUP_MEMBERS */ + static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) { siginfo_t info; - /* Only the final exiting thread in a task group should generate SIGCHLD. - * If task groups are not supported then we will report SIGCHLD when the - * task exits. + /* If task groups are not supported then we will report SIGCHLD when the + * task exits. Unfortunately, there could still be threads in the group + * that are still running. */ -#ifdef CONFIG_SCHED_CHILD_STATUS - if (ctcb->group->tg_nmembers == 1) -#else if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) -#endif { #ifdef CONFIG_SCHED_CHILD_STATUS /* Check if the parent task group has suppressed retention of child exit @@ -225,7 +289,7 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) /* No.. Find the exit status entry for this task in the parent TCB */ - child = task_findchild(ptcb, getpid()); + child = group_findchild(ptcb->group, getpid()); DEBUGASSERT(child); if (child) { @@ -238,12 +302,15 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) child->ch_status = status; } } -#else + +#else /* CONFIG_SCHED_CHILD_STATUS */ + /* Decrement the number of children from this parent */ DEBUGASSERT(ptcb->nchildren > 0); ptcb->nchildren--; -#endif + +#endif /* CONFIG_SCHED_CHILD_STATUS */ /* 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 @@ -260,16 +327,16 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) * can provide the correct si_code value with the signal. */ -#ifdef HAVE_GROUP_MEMBERS - (void)group_signal(ptcb, &info); -#else (void)sig_received(ptcb, &info); -#endif } } -#else -# define task_sigchild(ptct,ctcb,status) -#endif + +#endif /* HAVE_GROUP_MEMBERS */ +#else /* CONFIG_SCHED_HAVE_PARENT */ + +# define task_sigchild(x,ctcb,status) + +#endif /* CONFIG_SCHED_HAVE_PARENT */ /**************************************************************************** * Name: task_leavegroup @@ -282,6 +349,18 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) #ifdef CONFIG_SCHED_HAVE_PARENT static inline void task_leavegroup(FAR _TCB *ctcb, int status) { +#ifdef HAVE_GROUP_MEMBERS + DEBUGASSERT(ctcb && ctcb->group); + + /* Keep things stationary throughout the following */ + + sched_lock(); + + /* Send SIGCHLD to all members of the parent's task group */ + + task_sigchild(ctcb->group->tg_pgid, ctcb, status); + sched_unlock(); +#else FAR _TCB *ptcb; /* Keep things stationary throughout the following */ @@ -289,12 +368,12 @@ static inline void task_leavegroup(FAR _TCB *ctcb, int status) sched_lock(); /* Get the TCB of the receiving, parent task. We do this early to - * handle multiple calls to task_leavegroup. ctcb->parent is set to an + * handle multiple calls to task_leavegroup. ctcb->ppid is set to an * invalid value below and the following call will fail if we are * called again. */ - ptcb = sched_gettcb(ctcb->parent); + ptcb = sched_gettcb(ctcb->ppid); if (!ptcb) { /* The parent no longer exists... bail */ @@ -307,14 +386,11 @@ static inline void task_leavegroup(FAR _TCB *ctcb, int status) task_sigchild(ptcb, ctcb, status); - /* Set the parent to an impossible PID. We do this because under certain - * conditions, task_exithook() can be called multiple times. If this - * function is called again, sched_gettcb() will fail on the invalid - * parent PID above and all will be well. - */ + /* Forget who our parent was */ - ctcb->parent = INVALID_PROCESS_ID; + ctcb->ppid = INVALID_PROCESS_ID; sched_unlock(); +#endif } #else # define task_leavegroup(ctcb,status) @@ -385,6 +461,16 @@ static inline void task_exitwakeup(FAR _TCB *tcb, int status) void task_exithook(FAR _TCB *tcb, int status) { + /* Under certain conditions, task_exithook() can be called multiple times. + * A bit in the TCB was set the first time this function was called. If + * that bit is set, then just ext doing nothing more.. + */ + + if ((tcb->flags & TCB_FLAG_EXIT_PROCESSING) != 0) + { + return; + } + /* If exit function(s) were registered, call them now before we do any un- * initialization. NOTE: In the case of task_delete(), the exit function * will *not* be called on the thread execution of the task being deleted! @@ -433,4 +519,11 @@ void task_exithook(FAR _TCB *tcb, int status) #ifndef CONFIG_DISABLE_SIGNALS sig_cleanup(tcb); /* Deallocate Signal lists */ #endif + + /* This function can be re-entered in certain cases. Set a flag + * bit in the TCB to not that we have already completed this exit + * processing. + */ + + tcb->flags |= TCB_FLAG_EXIT_PROCESSING; } diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c index 1193c9a7f..5bb62893f 100644 --- a/nuttx/sched/task_reparent.c +++ b/nuttx/sched/task_reparent.c @@ -70,6 +70,141 @@ * *****************************************************************************/ +#ifdef HAVE_GROUP_MEMBERS +int task_reparent(pid_t ppid, pid_t chpid) +{ +#ifdef CONFIG_SCHED_CHILD_STATUS + FAR struct child_status_s *child; +#endif + FAR struct task_group_s *chgrp; + FAR struct task_group_s *ogrp; + FAR struct task_group_s *pgrp; + _TCB *tcb; + gid_t ogid; + gid_t pgid; + irqstate_t flags; + int ret; + + /* Disable interrupts so that nothing can change in the relatinoship of + * the three task: Child, current parent, and new parent. + */ + + flags = irqsave(); + + /* Get the child tasks task group */ + + tcb = sched_gettcb(chpid); + if (!tcb) + { + ret = -ECHILD; + goto errout_with_ints; + } + + DEBUGASSERT(tcb->group); + chgrp = tcb->group; + + /* Get the GID of the old parent task's task group (ogid) */ + + ogid = chgrp->tg_pgid; + + /* Get the old parent task's task group (ogrp) */ + + ogrp = group_find(ogid); + if (!ogrp) + { + ret = -ESRCH; + goto errout_with_ints; + } + + /* If new parent task's PID (ppid) is zero, then new parent is the + * grandparent will be the new parent, i.e., the parent of the current + * parent task. + */ + + if (ppid == 0) + { + /* Get the grandparent task's task group (pgrp) */ + + pgid = ogrp->tg_pgid; + pgrp = group_find(pgid); + } + else + { + /* Get the new parent task's task group (pgrp) */ + + tcb = sched_gettcb(ppid); + if (!tcb) + { + ret = -ESRCH; + goto errout_with_ints; + } + + pgrp = tcb->group; + pgid = pgrp->tg_gid; + } + + if (!pgrp) + { + ret = -ESRCH; + goto errout_with_ints; + } + + /* Then reparent the child. Notice that we don't actually change the + * parent of the task. Rather, we change the parent task group for + * all members of the child's task group. + */ + + chgrp->tg_pgid = pgid; + +#ifdef CONFIG_SCHED_CHILD_STATUS + /* Remove the child status entry from old parent task group */ + + child = group_removechild(ogrp, chpid); + if (child) + { + /* Has the new parent's task group supressed child exit status? */ + + if ((pgrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Add the child status entry to the new parent's task group */ + + group_addchild(pgrp, child); + } + else + { + /* Yes.. Discard the child status entry */ + + group_freechild(child); + } + + /* Either case is a success */ + + ret = OK; + } + else + { + /* This would not be an error if the original parent's task group has + * suppressed child exit status. + */ + + ret = ((ogrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; + } + +#else /* CONFIG_SCHED_CHILD_STATUS */ + + DEBUGASSERT(otcb->nchildren > 0); + + otcb->nchildren--; /* The orignal parent now has one few children */ + ptcb->nchildren++; /* The new parent has one additional child */ + ret = OK; + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + +errout_with_ints: + irqrestore(flags); + return ret; +} +#else int task_reparent(pid_t ppid, pid_t chpid) { #ifdef CONFIG_SCHED_CHILD_STATUS @@ -99,7 +234,7 @@ int task_reparent(pid_t ppid, pid_t chpid) /* Get the PID of the child task's parent (opid) */ - opid = chtcb->parent; + opid = chtcb->ppid; /* Get the TCB of the child task's parent (otcb) */ @@ -117,7 +252,7 @@ int task_reparent(pid_t ppid, pid_t chpid) if (ppid == 0) { - ppid = otcb->parent; + ppid = otcb->ppid; } /* Get the new parent task's TCB (ptcb) */ @@ -131,12 +266,12 @@ int task_reparent(pid_t ppid, pid_t chpid) /* Then reparent the child */ - chtcb->parent = ppid; /* The task specified by ppid is the new parent */ + chtcb->ppid = ppid; /* The task specified by ppid is the new parent */ #ifdef CONFIG_SCHED_CHILD_STATUS /* Remove the child status entry from old parent TCB */ - child = task_removechild(otcb, chpid); + child = group_removechild(otcb->group, chpid); if (child) { /* Has the new parent's task group supressed child exit status? */ @@ -145,13 +280,13 @@ int task_reparent(pid_t ppid, pid_t chpid) { /* No.. Add the child status entry to the new parent's task group */ - task_addchild(ptcb, child); + group_addchild(ptcb->group, child); } else { /* Yes.. Discard the child status entry */ - task_freechild(child); + group_freechild(child); } /* Either case is a success */ @@ -166,17 +301,20 @@ int task_reparent(pid_t ppid, pid_t chpid) ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; } -#else + +#else /* CONFIG_SCHED_CHILD_STATUS */ + DEBUGASSERT(otcb->nchildren > 0); otcb->nchildren--; /* The orignal parent now has one few children */ ptcb->nchildren++; /* The new parent has one additional child */ ret = OK; -#endif + +#endif /* CONFIG_SCHED_CHILD_STATUS */ errout_with_ints: irqrestore(flags); return ret; } - +#endif #endif /* CONFIG_SCHED_HAVE_PARENT */ diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index b66f3cc7c..b770d46e6 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -172,12 +172,36 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; +#if defined(HAVE_GROUP_MEMBERS) || defined(CONFIG_SCHED_CHILD_STATUS) + DEBUGASSERT(tcb && tcb->group && rtcb->group); +#else +#endif + +#ifdef HAVE_GROUP_MEMBERS + /* Save the ID of the parent tasks' task group in the child's task group. + * Do nothing for pthreads. The parent and the child are both members of + * the same task group. + */ + + if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD) + { + /* This is a new task in a new task group, we have to copy the ID from + * the parent's task group structure to child's task group. + */ + + tcb->group->tg_pgid = rtcb->group->tg_gid; + } + +#else + DEBUGASSERT(tcb); + /* Save the parent task's ID in the child task's TCB. I am not sure if * this makes sense for the case of pthreads or not, but I don't think it * is harmful in any event. */ - tcb->parent = rtcb->pid; + tcb->ppid = rtcb->pid; +#endif #ifdef CONFIG_SCHED_CHILD_STATUS /* Tasks can also suppress retention of their child status by applying @@ -192,13 +216,13 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) * parent TCB. There should not be. */ - child = task_findchild(rtcb, tcb->pid); + child = group_findchild(rtcb->group, tcb->pid); DEBUGASSERT(!child); if (!child) { /* Allocate a new status structure */ - child = task_allocchild(); + child = group_allocchild(); } /* Did we successfully find/allocate the child status structure? */ @@ -214,7 +238,7 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) /* Add the entry into the TCB list of children */ - task_addchild(rtcb, child); + group_addchild(rtcb->group, child); } } #else -- cgit v1.2.3 From 3bec164b3ae1cd7f9b5dcec532e7d073be96d45d Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 21:01:19 +0000 Subject: Fix a recently introduced memory leak git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5568 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/sched/Makefile | 3 +- nuttx/sched/group_internal.h | 8 +++ nuttx/sched/group_leave.c | 107 ++++++++++++++++++++---------------- nuttx/sched/group_releasefiles.c | 113 +++++++++++++++++++++++++++++++++++++++ nuttx/sched/os_internal.h | 2 - nuttx/sched/sched_releasefiles.c | 113 --------------------------------------- 6 files changed, 185 insertions(+), 161 deletions(-) create mode 100644 nuttx/sched/group_releasefiles.c delete mode 100644 nuttx/sched/sched_releasefiles.c (limited to 'nuttx/sched/group_internal.h') diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index d059152e0..c8fe7cf69 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -41,7 +41,7 @@ AOBJS = $(ASRCS:.S=$(OBJEXT)) MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c MISC_SRCS += sched_garbage.c sched_setupstreams.c sched_getfiles.c sched_getsockets.c MISC_SRCS += sched_getstreams.c sched_setupidlefiles.c sched_setuptaskfiles.c -MISC_SRCS += sched_setuppthreadfiles.c sched_releasefiles.c +MISC_SRCS += sched_setuppthreadfiles.c TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c TSK_SRCS += task_start.c task_delete.c task_deletecurrent.c task_exithook.c @@ -81,6 +81,7 @@ endif endif GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c +GRP_SRCS += group_releasefiles.c ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) GRP_SRCS += task_reparent.c diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index b78b38453..39d0a2b7c 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -127,6 +127,14 @@ FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, pid_t pid); void group_removechildren(FAR struct task_group_s *group); +/* File/network resources */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 +int group_releasefiles(FAR _TCB *tcb); +#else +# define group_releasefiles(t) (OK) +#endif + #endif /* CONFIG_SCHED_CHILD_STATUS */ #endif /* CONFIG_SCHED_HAVE_PARENT */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index f5dca1829..158ba30b5 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -124,6 +124,64 @@ void group_remove(FAR struct task_group_s *group) } #endif +/***************************************************************************** + * Name: group_release + * + * Description: + * Release group resources after the last member has left the group. + * + * Parameters: + * group - The group to be removed. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task deletion in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +static inline void group_release(FAR _TCB *tcb, + FAR struct task_group_s *group) +{ + /* Free all un-reaped child exit status */ + +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) + group_removechildren(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 || CONFIG_NSOCKET_DESCRIPTORS > 0 + (void)group_releasefiles(tcb); +#endif + + /* Release all shared environment variables */ + +#ifndef CONFIG_DISABLE_ENVIRON + env_release(tcb); +#endif + + /* Remove the group from the list of groups */ + + group_remove(group); + + /* Release the members array */ + + if (group->tg_members) + { + sched_free(group->tg_members); + group->tg_members = NULL; + } + + /* Release the group container itself */ + + sched_free(group); +} + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -150,7 +208,6 @@ void group_remove(FAR struct task_group_s *group) *****************************************************************************/ #ifdef HAVE_GROUP_MEMBERS - void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; @@ -171,31 +228,9 @@ void group_leave(FAR _TCB *tcb) if (ret == 0) { - /* 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) - 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 */ + /* Release all of the resource held by the task group */ -#ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); -#endif - /* Remove the group from the list of groups */ - - group_remove(group); - - /* Release the group container itself */ - - sched_free(group); + group_release(tcb, group); } /* In any event, we can detach the group from the TCB so that we won't @@ -232,27 +267,9 @@ void group_leave(FAR _TCB *tcb) else { - /* 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) - 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 */ - -#ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); -#endif - /* Release the group container itself */ + /* Release all of the resource held by the task group */ - sched_free(group); + group_release(tcb, group); } /* In any event, we can detach the group from the TCB so we won't do diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c new file mode 100644 index 000000000..40bf373b4 --- /dev/null +++ b/nuttx/sched/group_releasefiles.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * sched/group_releasefiles.c + * + * 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 + * 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 + +#include +#include +#include +#include + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_releasefiles + * + * Description: + * Release file resources attached to a TCB. This file may be called + * multiple times as a task exists. It will be called as early as possible + * to support proper closing of complex drivers that may need to wait + * on external events. + * + * Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int group_releasefiles(_TCB *tcb) +{ + if (tcb) + { +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; + DEBUGASSERT(group); + + /* Free resources used by the file descriptor list */ + + files_releaselist(&group->tg_filelist); + +#if CONFIG_NFILE_STREAMS > 0 + /* Free the stream list */ + + if (tcb->streams) + { + lib_releaselist(tcb->streams); + tcb->streams = NULL; + } +#endif /* CONFIG_NFILE_STREAMS */ +#endif /* CONFIG_NFILE_DESCRIPTORS */ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Free the file descriptor list */ + + if (tcb->sockets) + { + net_releaselist(tcb->sockets); + tcb->sockets = NULL; + } +#endif /* CONFIG_NSOCKET_DESCRIPTORS */ + } + + return OK; +} + +#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index e3d0fd48f..5aa6487d0 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -105,7 +105,6 @@ enum os_crash_codes_e # define sched_setupidlefiles(t) (OK) # define sched_setuptaskfiles(t) (OK) # define sched_setuppthreadfiles(t) (OK) -# define sched_releasefiles(t) (OK) #endif /* One processor family supported by NuttX has a single, fixed hardware stack. @@ -301,7 +300,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb); #if CONFIG_NFILE_STREAMS > 0 int sched_setupstreams(FAR _TCB *tcb); #endif -int sched_releasefiles(FAR _TCB *tcb); #endif int sched_releasetcb(FAR _TCB *tcb); diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/sched_releasefiles.c deleted file mode 100644 index 4be92f4eb..000000000 --- a/nuttx/sched/sched_releasefiles.c +++ /dev/null @@ -1,113 +0,0 @@ -/**************************************************************************** - * sched/sched_releasefiles.c - * - * 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 - * 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 - -#include -#include -#include -#include - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_releasefiles - * - * Description: - * Release file resources attached to a TCB. This file may be called - * multiple times as a task exists. It will be called as early as possible - * to support proper closing of complex drivers that may need to wait - * on external events. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int sched_releasefiles(_TCB *tcb) -{ - if (tcb) - { -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = tcb->group; - DEBUGASSERT(group); - - /* Free resources used by the file descriptor list */ - - files_releaselist(&group->tg_filelist); - -#if CONFIG_NFILE_STREAMS > 0 - /* Free the stream list */ - - if (tcb->streams) - { - lib_releaselist(tcb->streams); - tcb->streams = NULL; - } -#endif /* CONFIG_NFILE_STREAMS */ -#endif /* CONFIG_NFILE_DESCRIPTORS */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - /* Free the file descriptor list */ - - if (tcb->sockets) - { - net_releaselist(tcb->sockets); - tcb->sockets = NULL; - } -#endif /* CONFIG_NSOCKET_DESCRIPTORS */ - } - - return OK; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ -- cgit v1.2.3 From b82c36961aa730fc39a9fc8eac17e2518128cb67 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 22:25:21 +0000 Subject: Move stream data from TCB to task group structure. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5569 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/arch/arm/src/common/up_exit.c | 42 +++++------ nuttx/arch/avr/src/common/up_exit.c | 42 +++++------ nuttx/arch/hc/src/common/up_exit.c | 42 +++++------ nuttx/arch/mips/src/common/up_exit.c | 42 +++++------ nuttx/arch/sh/src/common/up_exit.c | 42 +++++------ nuttx/arch/x86/src/common/up_exit.c | 44 +++++------ nuttx/arch/z16/src/common/up_exit.c | 42 +++++------ nuttx/arch/z80/src/common/up_exit.c | 44 +++++------ nuttx/fs/fs_fdopen.c | 5 +- nuttx/include/nuttx/fs/fs.h | 1 - nuttx/include/nuttx/lib.h | 9 +-- nuttx/include/nuttx/sched.h | 13 ++-- nuttx/libc/misc/lib_init.c | 134 ++++++++++------------------------ nuttx/libc/stdio/lib_libflushall.c | 2 +- nuttx/sched/group_internal.h | 27 +------ nuttx/sched/group_leave.c | 2 + nuttx/sched/group_releasefiles.c | 9 +-- nuttx/sched/sched_getfiles.c | 2 +- nuttx/sched/sched_getstreams.c | 7 +- nuttx/sched/sched_setuppthreadfiles.c | 9 --- nuttx/sched/sched_setupstreams.c | 35 +++++---- nuttx/sched/task_exithook.c | 2 +- 23 files changed, 242 insertions(+), 357 deletions(-) (limited to 'nuttx/sched/group_internal.h') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ae7105b89..b5933f620 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4036,3 +4036,5 @@ 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. + * libc/stdio/, sched/, include/nuttx/lib.h, and include/nutts/fs/fs.h: + Move stream data from TCB to task group structure. diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c index 5b469fd03..16f5c4442 100644 --- a/nuttx/arch/arm/src/common/up_exit.c +++ b/nuttx/arch/arm/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/avr/src/common/up_exit.c b/nuttx/arch/avr/src/common/up_exit.c index 0813754a0..68e33fde7 100644 --- a/nuttx/arch/avr/src/common/up_exit.c +++ b/nuttx/arch/avr/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/hc/src/common/up_exit.c b/nuttx/arch/hc/src/common/up_exit.c index 5313a1172..1c46875f8 100644 --- a/nuttx/arch/hc/src/common/up_exit.c +++ b/nuttx/arch/hc/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/mips/src/common/up_exit.c b/nuttx/arch/mips/src/common/up_exit.c index 5a7b68a99..e112364b4 100644 --- a/nuttx/arch/mips/src/common/up_exit.c +++ b/nuttx/arch/mips/src/common/up_exit.c @@ -77,7 +77,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -85,40 +89,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c index af270b335..705f49852 100644 --- a/nuttx/arch/sh/src/common/up_exit.c +++ b/nuttx/arch/sh/src/common/up_exit.c @@ -76,7 +76,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -84,40 +88,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c index 6a98c7dd0..dee6f7d49 100644 --- a/nuttx/arch/x86/src/common/up_exit.c +++ b/nuttx/arch/x86/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * 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 @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c index ad0c55eed..20b808360 100644 --- a/nuttx/arch/z16/src/common/up_exit.c +++ b/nuttx/arch/z16/src/common/up_exit.c @@ -77,7 +77,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -85,40 +89,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - lldbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + lldbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - lldbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - lldbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + lldbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - lldbg(" fd=%d\n", filep->fs_filedes); + lldbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index 50289f52b..603a0bfbe 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.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 @@ -78,7 +78,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -86,40 +90,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - lldbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + lldbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - lldbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - lldbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + lldbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - lldbg(" fd=%d\n", filep->fs_filedes); + lldbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c index 629083c77..d8a370482 100644 --- a/nuttx/fs/fs_fdopen.c +++ b/nuttx/fs/fs_fdopen.c @@ -144,6 +144,7 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb) { tcb = sched_self(); } + DEBUGASSERT(tcb && tcb->group); /* Verify that this is a valid file/socket descriptor and that the * requested access can be support. @@ -191,9 +192,9 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb) /* Get the stream list from the TCB */ - slist = tcb->streams; + slist = &tcb->group->tg_streamlist; - /* Find an unallocated FILE structure in the stream list */ + /* Find an unallocated FILE structure in the stream list */ ret = sem_wait(&slist->sl_sem); if (ret != OK) diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 02855460c..93ca2a334 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -293,7 +293,6 @@ struct file_struct struct streamlist { - int sl_crefs; /* Reference count */ sem_t sl_sem; /* For thread safety */ struct file_struct sl_streams[CONFIG_NFILE_STREAMS]; }; diff --git a/nuttx/include/nuttx/lib.h b/nuttx/include/nuttx/lib.h index 220af2030..3bc581e18 100644 --- a/nuttx/include/nuttx/lib.h +++ b/nuttx/include/nuttx/lib.h @@ -2,7 +2,7 @@ * include/nuttx/lib.h * Non-standard, internal APIs available in lib/. * - * 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 @@ -67,11 +67,10 @@ extern "C" { /* Functions contained in lib_init.c ****************************************/ -EXTERN void weak_function lib_initialize(void); +void weak_function lib_initialize(void); #if CONFIG_NFILE_STREAMS > 0 -EXTERN FAR struct streamlist *lib_alloclist(void); -EXTERN void lib_addreflist(FAR struct streamlist *list); -EXTERN void lib_releaselist(FAR struct streamlist *list); +void lib_streaminit(FAR struct streamlist *list); +void lib_releaselist(FAR struct streamlist *list); #endif #undef EXTERN diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 1580a80d3..a084d50ba 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -81,6 +81,8 @@ # define HAVE_TASK_GROUP 1 # elif CONFIG_NFILE_DESCRIPTORS > 0 # define HAVE_TASK_GROUP 1 +# elif CONFIG_NFILE_STREAMS > 0 +# define HAVE_TASK_GROUP 1 # endif #endif @@ -303,7 +305,10 @@ struct task_group_s #endif /* FILE streams ***************************************************************/ - /* Not yet (see streamlist) */ + +#if CONFIG_NFILE_STREAMS > 0 + struct streamlist tg_streamlist; /* Holds C buffered I/O info */ +#endif /* CONFIG_NFILE_STREAMS */ /* Sockets ********************************************************************/ /* Not yet (see struct socketlist) */ @@ -445,12 +450,6 @@ struct _TCB int pterrno; /* Current per-thread errno */ - /* File system support ********************************************************/ - -#if CONFIG_NFILE_STREAMS > 0 - FAR struct streamlist *streams; /* Holds C buffered I/O info */ -#endif - /* Network socket *************************************************************/ #if CONFIG_NSOCKET_DESCRIPTORS > 0 diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c index 6a120f7b1..434c46505 100644 --- a/nuttx/libc/misc/lib_init.c +++ b/nuttx/libc/misc/lib_init.c @@ -1,7 +1,7 @@ /************************************************************ * libc/misc/lib_init.c * - * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -76,69 +76,35 @@ void weak_const_function lib_initialize(void) } #if CONFIG_NFILE_STREAMS > 0 -/* The following function is called when a new TCB is allocated. It - * creates the streamlist instance that is stored in the TCB. +/* The following function is called when a new task is allocated. It + * intializes the streamlist instance that is stored in the task group. */ -FAR struct streamlist *lib_alloclist(void) +void lib_streaminit(FAR struct streamlist *list) { - FAR struct streamlist *list; - list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist)); - if (list) - { - int i; - - /* Start with a reference count of one */ - - list->sl_crefs = 1; + int i; - /* Initialize the list access mutex */ + /* Initialize the list access mutex */ - (void)sem_init(&list->sl_sem, 0, 1); + (void)sem_init(&list->sl_sem, 0, 1); - /* Initialize each FILE structure */ + /* Initialize each FILE structure */ - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Clear the IOB */ + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Clear the IOB */ - memset(&list->sl_streams[i], 0, sizeof(FILE)); + memset(&list->sl_streams[i], 0, sizeof(FILE)); - /* Indicate not opened */ + /* Indicate not opened */ - list->sl_streams[i].fs_filedes = -1; + list->sl_streams[i].fs_filedes = -1; - /* Initialize the stream semaphore to one to support one-at- - * a-time access to private data sets. - */ - - lib_sem_initialize(&list->sl_streams[i]); - } - } - return list; + /* Initialize the stream semaphore to one to support one-at- + * a-time access to private data sets. + */ -} - -/* This function is called when a TCB is closed (such as with - * pthread_create(). It increases the reference count on the stream - * list. - */ - -void lib_addreflist(FAR struct streamlist *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->sl_crefs++; - irqrestore(flags); + lib_sem_initialize(&list->sl_streams[i]); } } @@ -149,57 +115,33 @@ void lib_addreflist(FAR struct streamlist *list) void lib_releaselist(FAR struct streamlist *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->sl_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) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - int i; + int i; #endif - /* Destroy the semaphore and release the filelist */ - (void)sem_destroy(&list->sl_sem); + DEBUGASSERT(list); + + /* Destroy the semaphore and release the filelist */ - /* Release each stream in the list */ + (void)sem_destroy(&list->sl_sem); + + /* Release each stream in the list */ #if CONFIG_STDIO_BUFFER_SIZE > 0 - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Destroy the semaphore that protects the IO buffer */ - - (void)sem_destroy(&list->sl_streams[i].fs_sem); - - /* Release the IO buffer */ - if (list->sl_streams[i].fs_bufstart) - { - sched_free(list->sl_streams[i].fs_bufstart); - } - } -#endif - /* Finally, release the list itself */ + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Destroy the semaphore that protects the IO buffer */ - sched_free(list); - } - } + (void)sem_destroy(&list->sl_streams[i].fs_sem); + + /* Release the IO buffer */ + + if (list->sl_streams[i].fs_bufstart) + { + sched_free(list->sl_streams[i].fs_bufstart); + } + } +#endif } #endif /* CONFIG_NFILE_STREAMS */ diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c index 7ac3da7e0..22baed968 100644 --- a/nuttx/libc/stdio/lib_libflushall.c +++ b/nuttx/libc/stdio/lib_libflushall.c @@ -1,7 +1,7 @@ /**************************************************************************** * libc/stdio/lib_libflushall.c * - * Copyright (C) 2007-2009, 2011-2012 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 diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index 39d0a2b7c..e6e0dfd16 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -86,28 +86,11 @@ void group_leave(FAR _TCB *tcb); FAR struct task_group_s *group_find(gid_t gid); int group_addmember(FAR struct task_group_s *group, pid_t pid); int group_removemember(FAR struct task_group_s *group, pid_t pid); -#else -# define group_find(gid) (NULL) -# define group_addmember(group,pid) (0) -# define group_removemember(group,pid) (1) #endif #ifndef CONFIG_DISABLE_SIGNALS int group_signal(FAR struct task_group_s *group, 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_find(gid) (NULL) -# define group_addmember(group,pid) (0) -# define group_removemember(group,pid) (1) -# define group_signal(tcb,info) (0) #endif /* HAVE_TASK_GROUP */ /* Parent/child data management */ @@ -127,15 +110,13 @@ FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, pid_t pid); void group_removechildren(FAR struct task_group_s *group); +#endif /* CONFIG_SCHED_CHILD_STATUS */ +#endif /* CONFIG_SCHED_HAVE_PARENT */ + /* File/network resources */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int group_releasefiles(FAR _TCB *tcb); -#else -# define group_releasefiles(t) (OK) +int group_releasefiles(FAR _TCB *tcb); #endif -#endif /* CONFIG_SCHED_CHILD_STATUS */ -#endif /* CONFIG_SCHED_HAVE_PARENT */ - #endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 158ba30b5..70ef93666 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -165,6 +165,7 @@ static inline void group_release(FAR _TCB *tcb, env_release(tcb); #endif +#ifdef HAVE_GROUP_MEMBERS /* Remove the group from the list of groups */ group_remove(group); @@ -176,6 +177,7 @@ static inline void group_release(FAR _TCB *tcb, sched_free(group->tg_members); group->tg_members = NULL; } +#endif /* Release the group container itself */ diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c index 40bf373b4..b33415c76 100644 --- a/nuttx/sched/group_releasefiles.c +++ b/nuttx/sched/group_releasefiles.c @@ -80,7 +80,9 @@ int group_releasefiles(_TCB *tcb) #if CONFIG_NFILE_DESCRIPTORS > 0 FAR struct task_group_s *group = tcb->group; DEBUGASSERT(group); +#endif +#if CONFIG_NFILE_DESCRIPTORS > 0 /* Free resources used by the file descriptor list */ files_releaselist(&group->tg_filelist); @@ -88,11 +90,8 @@ int group_releasefiles(_TCB *tcb) #if CONFIG_NFILE_STREAMS > 0 /* Free the stream list */ - if (tcb->streams) - { - lib_releaselist(tcb->streams); - tcb->streams = NULL; - } + lib_releaselist(&group->tg_streamlist); + #endif /* CONFIG_NFILE_STREAMS */ #endif /* CONFIG_NFILE_DESCRIPTORS */ diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c index eca4ba3ff..17ca2bbf6 100644 --- a/nuttx/sched/sched_getfiles.c +++ b/nuttx/sched/sched_getfiles.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_getfiles.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 diff --git a/nuttx/sched/sched_getstreams.c b/nuttx/sched/sched_getstreams.c index f7c21ab4c..dab406e66 100644 --- a/nuttx/sched/sched_getstreams.c +++ b/nuttx/sched/sched_getstreams.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_getstreams.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 @@ -70,7 +70,10 @@ FAR struct streamlist *sched_getstreams(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->streams; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_streamlist; } #endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_NFILE_STREAMS */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c index 78d6cbfec..91d72fa7f 100644 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ b/nuttx/sched/sched_setuppthreadfiles.c @@ -77,8 +77,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) { - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - #if CONFIG_NSOCKET_DESCRIPTORS > 0 /* The child thread inherits the parent socket descriptors */ @@ -87,13 +85,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) #endif /* CONFIG_NSOCKET_DESCRIPTORS */ -#if CONFIG_NFILE_STREAMS > 0 - /* The child thread inherits the parent streams */ - - tcb->streams = rtcb->streams; - lib_addreflist(tcb->streams); - -#endif /* CONFIG_NFILE_STREAMS */ return OK; } diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c index 22895b047..fb2e4d0be 100644 --- a/nuttx/sched/sched_setupstreams.c +++ b/nuttx/sched/sched_setupstreams.c @@ -72,24 +72,23 @@ int sched_setupstreams(FAR _TCB *tcb) { - /* Allocate file streams for the TCB */ - - tcb->streams = lib_alloclist(); - if (tcb->streams) - { - /* fdopen to get the stdin, stdout and stderr streams. - * The following logic depends on the fact that the library - * layer will allocate FILEs in order. - * - * fd = 0 is stdin (read-only) - * fd = 1 is stdout (write-only, append) - * fd = 2 is stderr (write-only, append) - */ - - (void)fs_fdopen(0, O_RDONLY, tcb); - (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); - (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); - } + DEBUGASSERT(tcb && tcb->group); + + /* Initialize file streams for the task group */ + + lib_streaminit(&tcb->group->tg_streamlist); + + /* fdopen to get the stdin, stdout and stderr streams. The following logic + * depends on the fact that the library layer will allocate FILEs in order. + * + * fd = 0 is stdin (read-only) + * fd = 1 is stdout (write-only, append) + * fd = 2 is stderr (write-only, append) + */ + + (void)fs_fdopen(0, O_RDONLY, tcb); + (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); + (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); return OK; } diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 5a2b9e57e..889df25e0 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -543,7 +543,7 @@ void task_exithook(FAR _TCB *tcb, int status) */ #if CONFIG_NFILE_STREAMS > 0 - (void)lib_flushall(tcb->streams); + (void)lib_flushall(&tcb->group->tg_streamlist); #endif /* Leave the task group. Perhaps discarding any un-reaped child -- cgit v1.2.3 From 47b94bafa5045532f239ea57a3610873b1a71368 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 23:49:02 +0000 Subject: Move socket data from TCB to task group structure. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5570 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 6 +- nuttx/include/nuttx/net/net.h | 8 +- nuttx/include/nuttx/sched.h | 13 +- nuttx/net/net_sockets.c | 100 +++----------- nuttx/sched/Makefile | 6 +- nuttx/sched/env_clearenv.c | 5 +- nuttx/sched/env_dup.c | 12 +- nuttx/sched/env_internal.h | 8 +- nuttx/sched/env_release.c | 11 +- nuttx/sched/group_create.c | 2 +- nuttx/sched/group_internal.h | 8 +- nuttx/sched/group_leave.c | 34 +++-- nuttx/sched/group_releasefiles.c | 112 --------------- nuttx/sched/group_setupidlefiles.c | 147 ++++++++++++++++++++ nuttx/sched/group_setupstreams.c | 97 +++++++++++++ nuttx/sched/group_setuptaskfiles.c | 245 +++++++++++++++++++++++++++++++++ nuttx/sched/os_internal.h | 17 --- nuttx/sched/os_start.c | 2 +- nuttx/sched/pthread_create.c | 9 -- nuttx/sched/sched_getsockets.c | 7 +- nuttx/sched/sched_setupidlefiles.c | 151 --------------------- nuttx/sched/sched_setuppthreadfiles.c | 91 ------------- nuttx/sched/sched_setupstreams.c | 97 ------------- nuttx/sched/sched_setuptaskfiles.c | 248 ---------------------------------- nuttx/sched/task_create.c | 2 +- nuttx/sched/task_init.c | 2 +- nuttx/sched/task_vfork.c | 2 +- 27 files changed, 583 insertions(+), 859 deletions(-) delete mode 100644 nuttx/sched/group_releasefiles.c create mode 100644 nuttx/sched/group_setupidlefiles.c create mode 100644 nuttx/sched/group_setupstreams.c create mode 100644 nuttx/sched/group_setuptaskfiles.c delete mode 100644 nuttx/sched/sched_setupidlefiles.c delete mode 100644 nuttx/sched/sched_setuppthreadfiles.c delete mode 100644 nuttx/sched/sched_setupstreams.c delete mode 100644 nuttx/sched/sched_setuptaskfiles.c (limited to 'nuttx/sched/group_internal.h') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index b5933f620..255d69a3d 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4035,6 +4035,8 @@ 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. + Move file data from the TCB to the task group structure. * libc/stdio/, sched/, include/nuttx/lib.h, and include/nutts/fs/fs.h: - Move stream data from TCB to task group structure. + Move stream data from the TCB to the task group structure. + * net/, sched/, and include/nuttx/net/net.h: Move socket data + from the TCB to the task group structure. diff --git a/nuttx/include/nuttx/net/net.h b/nuttx/include/nuttx/net/net.h index b625b2fbe..d23fb8796 100644 --- a/nuttx/include/nuttx/net/net.h +++ b/nuttx/include/nuttx/net/net.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/net/net.h * - * Copyright (C) 2007, 2009-2012 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 @@ -106,7 +106,6 @@ struct socket struct socketlist { sem_t sl_sem; /* Manage access to the socket list */ - int16_t sl_crefs; /* Reference count */ struct socket sl_sockets[CONFIG_NSOCKET_DESCRIPTORS]; }; #endif @@ -145,9 +144,8 @@ int net_checksd(int fd, int oflags); */ void weak_function net_initialize(void); -FAR struct socketlist *net_alloclist(void); -int net_addreflist(FAR struct socketlist *list); -int net_releaselist(FAR struct socketlist *list); +void net_initlist(FAR struct socketlist *list); +void net_releaselist(FAR struct socketlist *list); /* Given a socket descriptor, return the underly NuttX-specific socket * structure. diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index a084d50ba..244455cd4 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -83,6 +83,8 @@ # define HAVE_TASK_GROUP 1 # elif CONFIG_NFILE_STREAMS > 0 # define HAVE_TASK_GROUP 1 +# elif CONFIG_NSOCKET_DESCRIPTORS > 0 +# define HAVE_TASK_GROUP 1 # endif #endif @@ -311,7 +313,10 @@ struct task_group_s #endif /* CONFIG_NFILE_STREAMS */ /* Sockets ********************************************************************/ - /* Not yet (see struct socketlist) */ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + struct socketlist tg_socketlist; /* Maps socket descriptor to socket */ +#endif }; #endif @@ -450,12 +455,6 @@ struct _TCB int pterrno; /* Current per-thread errno */ - /* Network socket *************************************************************/ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - FAR struct socketlist *sockets; /* Maps file descriptor to file */ -#endif - /* State save areas ***********************************************************/ /* The form and content of these fields are processor-specific. */ diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c index 81e48c121..ddb54c98c 100644 --- a/nuttx/net/net_sockets.c +++ b/nuttx/net/net_sockets.c @@ -116,99 +116,37 @@ void net_initialize(void) #if CONFIG_NSOCKET_DESCRIPTORS > 0 -/* Allocate a list of files for a new task */ +/* Initialize a list of sockets for a new task */ -FAR struct socketlist *net_alloclist(void) +void net_initlist(FAR struct socketlist *list) { - FAR struct socketlist *list; - list = (FAR struct socketlist*)kzalloc(sizeof(struct socketlist)); - if (list) - { - /* Start with a reference count of one */ - - list->sl_crefs = 1; - - /* Initialize the list access mutex */ + /* Initialize the list access mutex */ - (void)sem_init(&list->sl_sem, 0, 1); - } - return list; + (void)sem_init(&list->sl_sem, 0, 1); } -/* Increase the reference count on a file list */ +/* Release release resources held by the socket list */ -int net_addreflist(FAR struct socketlist *list) +void net_releaselist(FAR struct socketlist *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 uip_lock_t flags = uip_lock(); - list->sl_crefs++; - uip_unlock(flags); - } - return OK; -} + int ndx; -/* Release a reference to the file list */ + DEBUGASSERT(list); -int net_releaselist(FAR struct socketlist *list) -{ - int crefs; - int ndx; + /* Close each open socket in the list. */ - if (list) + for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++) { - /* 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. - */ - - uip_lock_t flags = uip_lock(); - crefs = --(list->sl_crefs); - uip_unlock(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) - { - /* Close each open socket in the list - * REVISIT: psock_close() will attempt to use semaphores. - * If we actually are in the IDLE thread, then could this cause - * problems? Probably not, if the task has exited and crefs is - * zero, then there probably could not be a contender for the - * semaphore. - */ - - for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++) - { - FAR struct socket *psock = &list->sl_sockets[ndx]; - if (psock->s_crefs > 0) - { - (void)psock_close(psock); - } - } - - /* Destroy the semaphore and release the filelist */ - - (void)sem_destroy(&list->sl_sem); - sched_free(list); - } + FAR struct socket *psock = &list->sl_sockets[ndx]; + if (psock->s_crefs > 0) + { + (void)psock_close(psock); + } } - return OK; + + /* Destroy the semaphore */ + + (void)sem_destroy(&list->sl_sem); } int sockfd_allocate(int minsd) diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index c8fe7cf69..7710ae058 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -39,9 +39,7 @@ ASRCS = AOBJS = $(ASRCS:.S=$(OBJEXT)) MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c -MISC_SRCS += sched_garbage.c sched_setupstreams.c sched_getfiles.c sched_getsockets.c -MISC_SRCS += sched_getstreams.c sched_setupidlefiles.c sched_setuptaskfiles.c -MISC_SRCS += sched_setuppthreadfiles.c +MISC_SRCS += sched_garbage.c sched_getfiles.c sched_getsockets.c sched_getstreams.c TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c TSK_SRCS += task_start.c task_delete.c task_deletecurrent.c task_exithook.c @@ -81,7 +79,7 @@ endif endif GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c -GRP_SRCS += group_releasefiles.c +GRP_SRCS += group_setupstreams.c group_setupidlefiles.c group_setuptaskfiles.c ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) GRP_SRCS += task_reparent.c diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c index a9e9f5efd..062fd60ed 100644 --- a/nuttx/sched/env_clearenv.c +++ b/nuttx/sched/env_clearenv.c @@ -74,7 +74,10 @@ int clearenv(void) { - env_release((FAR _TCB*)g_readytorun.head); + FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head; + DEBUGASSERT(tcb->group); + + env_release(tcb->group); return OK; } diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c index 479f7cae7..3b653b010 100644 --- a/nuttx/sched/env_dup.c +++ b/nuttx/sched/env_dup.c @@ -68,8 +68,8 @@ * exact duplicate of the parent task's environment. * * Parameters: - * ctcb The child tcb to receive the newly allocated copy of the parent - * TCB's environment structure with reference count equal to one + * group The child task group to receive the newly allocated copy of the + * parent task groups environment structure. * * Return Value: * zero on success @@ -79,14 +79,14 @@ * ****************************************************************************/ -int env_dup(FAR _TCB *ctcb) +int env_dup(FAR struct task_group_s *group) { FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head; FAR char *envp = NULL; size_t envlen; int ret = OK; - DEBUGASSERT(ctcb && ptcb && ctcb->group && ptcb->group); + DEBUGASSERT(group && ptcb && ptcb->group); /* Pre-emption must be disabled throughout the following because the * environment may be shared. @@ -108,8 +108,8 @@ int env_dup(FAR _TCB *ctcb) } else { - ctcb->group->tg_envsize = envlen; - ctcb->group->tg_envp = envp; + group->tg_envsize = envlen; + group->tg_envp = envp; memcpy(envp, ptcb->group->tg_envp, envlen); } } diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h index 6f1097c0b..e02bf289d 100644 --- a/nuttx/sched/env_internal.h +++ b/nuttx/sched/env_internal.h @@ -49,8 +49,8 @@ ****************************************************************************/ #ifdef CONFIG_DISABLE_ENVIRON -# define env_dup(ptcb) (0) -# define env_release(ptcb) (0) +# define env_dup(group) (0) +# define env_release(group) (0) #else /**************************************************************************** @@ -75,8 +75,8 @@ extern "C" /* Functions used by the task/pthread creation and destruction logic */ -int env_dup(FAR _TCB *ctcb); -void env_release(FAR _TCB *tcb); +int env_dup(FAR struct task_group_s *group); +void env_release(FAR struct task_group_s *group); /* Functions used internally by the environment handling logic */ diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c index 4de55c388..aebb1f7e8 100644 --- a/nuttx/sched/env_release.c +++ b/nuttx/sched/env_release.c @@ -64,8 +64,8 @@ * environ to NULL. * * Parameters: - * tcb Identifies the TCB containing the environment structure to be - * released. + * group Identifies the task group containing the environment structure + * to be released. * * Return Value: * None @@ -75,12 +75,9 @@ * ****************************************************************************/ -void env_release(FAR _TCB *tcb) +void env_release(FAR struct task_group_s *group) { - FAR struct task_group_s *group; - - DEBUGASSERT(tcb && tcb->group); - group = tcb->group; + DEBUGASSERT(group); /* Free any allocate environment strings */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index 768641be1..24f6923aa 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -198,7 +198,7 @@ int group_allocate(FAR _TCB *tcb) /* Duplicate the parent tasks envionment */ - ret = env_dup(tcb); + ret = env_dup(tcb->group); if (ret < 0) { kfree(tcb->group); diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index e6e0dfd16..ca6aacff7 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -113,10 +113,14 @@ void group_removechildren(FAR struct task_group_s *group); #endif /* CONFIG_SCHED_CHILD_STATUS */ #endif /* CONFIG_SCHED_HAVE_PARENT */ -/* File/network resources */ +/* Group data resource configuration */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int group_releasefiles(FAR _TCB *tcb); +int group_setupidlefiles(FAR _TCB *tcb); +int group_setuptaskfiles(FAR _TCB *tcb); +#if CONFIG_NFILE_STREAMS > 0 +int group_setupstreams(FAR _TCB *tcb); +#endif #endif #endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 70ef93666..4dec30633 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -44,6 +44,10 @@ #include #include +#include +#include +#include + #include "group_internal.h" #include "env_internal.h" @@ -142,8 +146,7 @@ void group_remove(FAR struct task_group_s *group) * *****************************************************************************/ -static inline void group_release(FAR _TCB *tcb, - FAR struct task_group_s *group) +static inline void group_release(FAR struct task_group_s *group) { /* Free all un-reaped child exit status */ @@ -155,14 +158,29 @@ static inline void group_release(FAR _TCB *tcb, * soon as possible while we still have a functioning task. */ -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - (void)group_releasefiles(tcb); -#endif +#if CONFIG_NFILE_DESCRIPTORS > 0 + /* Free resources held by the file descriptor list */ + + files_releaselist(&group->tg_filelist); + +#if CONFIG_NFILE_STREAMS > 0 + /* Free resource held by the stream list */ + + lib_releaselist(&group->tg_streamlist); + +#endif /* CONFIG_NFILE_STREAMS */ +#endif /* CONFIG_NFILE_DESCRIPTORS */ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Free resource held by the socket list */ + + net_releaselist(&group->tg_socketlist); +#endif /* CONFIG_NSOCKET_DESCRIPTORS */ /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); + env_release(group); #endif #ifdef HAVE_GROUP_MEMBERS @@ -232,7 +250,7 @@ void group_leave(FAR _TCB *tcb) { /* Release all of the resource held by the task group */ - group_release(tcb, group); + group_release(group); } /* In any event, we can detach the group from the TCB so that we won't @@ -271,7 +289,7 @@ void group_leave(FAR _TCB *tcb) { /* Release all of the resource held by the task group */ - group_release(tcb, group); + group_release(group); } /* In any event, we can detach the group from the TCB so we won't do diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c deleted file mode 100644 index b33415c76..000000000 --- a/nuttx/sched/group_releasefiles.c +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * sched/group_releasefiles.c - * - * 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 - * 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 - -#include -#include -#include -#include - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: group_releasefiles - * - * Description: - * Release file resources attached to a TCB. This file may be called - * multiple times as a task exists. It will be called as early as possible - * to support proper closing of complex drivers that may need to wait - * on external events. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int group_releasefiles(_TCB *tcb) -{ - if (tcb) - { -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = tcb->group; - DEBUGASSERT(group); -#endif - -#if CONFIG_NFILE_DESCRIPTORS > 0 - /* Free resources used by the file descriptor list */ - - files_releaselist(&group->tg_filelist); - -#if CONFIG_NFILE_STREAMS > 0 - /* Free the stream list */ - - lib_releaselist(&group->tg_streamlist); - -#endif /* CONFIG_NFILE_STREAMS */ -#endif /* CONFIG_NFILE_DESCRIPTORS */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - /* Free the file descriptor list */ - - if (tcb->sockets) - { - net_releaselist(tcb->sockets); - tcb->sockets = NULL; - } -#endif /* CONFIG_NSOCKET_DESCRIPTORS */ - } - - return OK; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/group_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c new file mode 100644 index 000000000..98cc7885e --- /dev/null +++ b/nuttx/sched/group_setupidlefiles.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * sched/group_setupidlefiles.c + * + * Copyright (C) 2007-2010, 2012-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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "os_internal.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_setupidlefiles + * + * Description: + * Configure the idle thread's TCB. + * + * Parameters: + * tcb - tcb of the idle task. + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int group_setupidlefiles(FAR _TCB *tcb) +{ +#if CONFIG_NFILE_DESCRIPTORS > 0 || 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 + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 + DEBUGASSERT(group); +#endif + +#if CONFIG_NFILE_DESCRIPTORS > 0 + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); +#endif + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Allocate socket descriptors for the TCB */ + + net_initlist(&group->tg_socketlist); +#endif + + /* Open stdin, dup to get stdout and stderr. This should always + * be the first file opened and, hence, should always get file + * descriptor 0. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) + fd = open("/dev/console", O_RDWR); + if (fd == 0) + { + /* Successfully opened /dev/console as stdin (fd == 0) */ + + (void)file_dup2(0, 1); + (void)file_dup2(0, 2); + } + else + { + /* We failed to open /dev/console OR for some reason, we opened + * it and got some file descriptor other than 0. + */ + + if (fd > 0) + { + slldbg("Open /dev/console fd: %d\n", fd); + (void)close(fd); + } + else + { + slldbg("Failed to open /dev/console: %d\n", errno); + } + return -ENFILE; + } +#endif + + /* Allocate file/socket streams for the TCB */ + +#if CONFIG_NFILE_STREAMS > 0 + return group_setupstreams(tcb); +#else + return OK; +#endif +} + +#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/group_setupstreams.c b/nuttx/sched/group_setupstreams.c new file mode 100644 index 000000000..88e266280 --- /dev/null +++ b/nuttx/sched/group_setupstreams.c @@ -0,0 +1,97 @@ +/**************************************************************************** + * group_setupstreams.c + * + * Copyright (C) 2007-2008, 2010-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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +/* Make sure that there are file or socket descriptors in the system and + * that some number of streams have been configured. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_setupstreams + * + * Description: + * Setup streams data structures that may be used for standard C buffered + * I/O with underlying socket or file desciptors + * + ****************************************************************************/ + +int group_setupstreams(FAR _TCB *tcb) +{ + DEBUGASSERT(tcb && tcb->group); + + /* Initialize file streams for the task group */ + + lib_streaminit(&tcb->group->tg_streamlist); + + /* fdopen to get the stdin, stdout and stderr streams. The following logic + * depends on the fact that the library layer will allocate FILEs in order. + * + * fd = 0 is stdin (read-only) + * fd = 1 is stdout (write-only, append) + * fd = 2 is stderr (write-only, append) + */ + + (void)fs_fdopen(0, O_RDONLY, tcb); + (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); + (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); + + return OK; +} + +#endif /* CONFIG_NFILE_STREAMS > 0 */ +#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/group_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c new file mode 100644 index 000000000..d52adcfee --- /dev/null +++ b/nuttx/sched/group_setuptaskfiles.c @@ -0,0 +1,245 @@ +/**************************************************************************** + * sched/group_setuptaskfiles.c + * + * 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 + * 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 + +#include +#include + +#include +#include + +#include "os_internal.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Determine how many file descriptors to clone. If CONFIG_FDCLONE_DISABLE + * is set, no file descriptors will be cloned. If CONFIG_FDCLONE_STDIO is + * set, only the first three descriptors (stdin, stdout, and stderr) will + * be cloned. Otherwise all file descriptors will be cloned. + */ + +#if defined(CONFIG_FDCLONE_STDIO) && CONFIG_NFILE_DESCRIPTORS > 3 +# define NFDS_TOCLONE 3 +#else +# define NFDS_TOCLONE CONFIG_NFILE_DESCRIPTORS +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sched_dupfiles + * + * Description: + * Duplicate parent task's file descriptors. + * + * Input Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * None + * + ****************************************************************************/ + +#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_FDCLONE_DISABLE) +static inline void sched_dupfiles(FAR _TCB *tcb) +{ + /* The parent task is the one at the head of the ready-to-run list */ + + FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + FAR struct file *parent; + 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. + */ + + /* Get pointers to the parent and child task file lists */ + + parent = rtcb->group->tg_filelist.fl_files; + child = tcb->group->tg_filelist.fl_files; + + /* 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. + */ + + if (parent[i].f_inode) + { + /* Yes... duplicate it for the child */ + + (void)files_dup(&parent[i], &child[i]); + } + } +} +#else /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ +# define sched_dupfiles(tcb) +#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ + +/**************************************************************************** + * Name: sched_dupsockets + * + * Description: + * Duplicate the parent task's socket descriptors. + * + * Input Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * None + * + ****************************************************************************/ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 && !defined(CONFIG_SDCLONE_DISABLE) +static inline void sched_dupsockets(FAR _TCB *tcb) +{ + /* The parent task is the one at the head of the ready-to-run list */ + + FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + FAR struct socket *parent; + FAR struct socket *child; + int i; + + /* Duplicate the socket descriptors of all sockets opened by the parent + * task. + */ + + DEBUGASSERT(tcb && tcb->group && rtcb->group); + + /* Get pointers to the parent and child task socket lists */ + + parent = rtcb->group->tg_sockets->sl_sockets; + child = tcb->group->tg_sockets->sl_sockets; + + /* Check each socket in the parent socket list */ + + for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++) + { + /* Check if this parent socket is allocated. We can tell if the + * socket is allocated because it will have a positive, non-zero + * reference count. + */ + + if (parent[i].s_crefs > 0) + { + /* Yes... duplicate it for the child */ + + (void)net_clone(&parent[i], &child[i]); + } + } +} +#else /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ +# define sched_dupsockets(tcb) +#endif /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_setuptaskfiles + * + * Description: + * Configure a newly allocated TCB so that it will inherit + * file descriptors and streams from the parent task. + * + * Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * Zero (OK) is returned on success; A negated errno value is returned on + * failure. + * + * Assumptions: + * + ****************************************************************************/ + +int group_setuptaskfiles(FAR _TCB *tcb) +{ +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; + + DEBUGASSERT(group); +#endif + +#if CONFIG_NFILE_DESCRIPTORS > 0 + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); +#endif + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Allocate socket descriptors for the TCB */ + + net_initlist(&group->tg_socketlist); +#endif + + /* Duplicate the parent task's file descriptors */ + + sched_dupfiles(tcb); + + /* Duplicate the parent task's socket descriptors */ + + sched_dupsockets(tcb); + + /* Allocate file/socket streams for the new TCB */ + +#if CONFIG_NFILE_STREAMS > 0 + return group_setupstreams(tcb); +#else + return OK; +#endif +} + +#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 5aa6487d0..262a40ccc 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -99,14 +99,6 @@ enum os_crash_codes_e #define MAX_TASKS_MASK (CONFIG_MAX_TASKS-1) #define PIDHASH(pid) ((pid) & MAX_TASKS_MASK) -/* Stubs used when there are no file descriptors */ - -#if CONFIG_NFILE_DESCRIPTORS <= 0 && CONFIG_NSOCKET_DESCRIPTORS <= 0 -# define sched_setupidlefiles(t) (OK) -# define sched_setuptaskfiles(t) (OK) -# define sched_setuppthreadfiles(t) (OK) -#endif - /* One processor family supported by NuttX has a single, fixed hardware stack. * That is the 8051 family. So for that family only, there is a variant form * of kernel_thread() that does not take a stack size parameter. The following @@ -293,15 +285,6 @@ int sched_reprioritize(FAR _TCB *tcb, int sched_priority); FAR _TCB *sched_gettcb(pid_t pid); bool sched_verifytcb(FAR _TCB *tcb); -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int sched_setupidlefiles(FAR _TCB *tcb); -int sched_setuptaskfiles(FAR _TCB *tcb); -int sched_setuppthreadfiles(FAR _TCB *tcb); -#if CONFIG_NFILE_STREAMS > 0 -int sched_setupstreams(FAR _TCB *tcb); -#endif -#endif - int sched_releasetcb(FAR _TCB *tcb); void sched_garbagecollection(void); diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index b2551d2a3..5e6eaa858 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -451,7 +451,7 @@ void os_start(void) * inherited by all of the threads created by the IDLE task. */ - (void)sched_setupidlefiles(&g_idletcb); + (void)group_setupidlefiles(&g_idletcb); /* Create initial tasks and bring-up the system */ diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c index 9fd6a4a61..48a0788a6 100644 --- a/nuttx/sched/pthread_create.c +++ b/nuttx/sched/pthread_create.c @@ -296,15 +296,6 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, } #endif - /* Associate file descriptors with the new task */ - - ret = sched_setuppthreadfiles(ptcb); - if (ret != OK) - { - errcode = ret; - goto errout_with_tcb; - } - /* Allocate a detachable structure to support pthread_join logic */ pjoin = (FAR join_t*)kzalloc(sizeof(join_t)); diff --git a/nuttx/sched/sched_getsockets.c b/nuttx/sched/sched_getsockets.c index cd499420f..ea988d6ff 100644 --- a/nuttx/sched/sched_getsockets.c +++ b/nuttx/sched/sched_getsockets.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_getsockets.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 @@ -71,7 +71,10 @@ FAR struct socketlist *sched_getsockets(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->sockets; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_socketlist; } #endif /* CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c deleted file mode 100644 index 4bbd4d3b7..000000000 --- a/nuttx/sched/sched_setupidlefiles.c +++ /dev/null @@ -1,151 +0,0 @@ -/**************************************************************************** - * sched/sched_setupidlefiles.c - * - * Copyright (C) 2007-2010, 2012 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 - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "os_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setupidlefiles - * - * Description: - * Configure the idle thread's TCB. - * - * Parameters: - * tcb - tcb of the idle task. - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -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 - -#if CONFIG_NFILE_DESCRIPTORS > 0 - DEBUGASSERT(group); -#endif - - /* Initialize file descriptors for the TCB */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 - files_initlist(&group->tg_filelist); -#endif - - /* Allocate socket descriptors for the TCB */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - tcb->sockets = net_alloclist(); - if (!tcb->sockets) - { - return -ENOMEM; - } -#endif - - /* Open stdin, dup to get stdout and stderr. This should always - * be the first file opened and, hence, should always get file - * descriptor 0. - */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) - fd = open("/dev/console", O_RDWR); - if (fd == 0) - { - /* Successfully opened /dev/console as stdin (fd == 0) */ - - (void)file_dup2(0, 1); - (void)file_dup2(0, 2); - } - else - { - /* We failed to open /dev/console OR for some reason, we opened - * it and got some file descriptor other than 0. - */ - - if (fd > 0) - { - slldbg("Open /dev/console fd: %d\n", fd); - (void)close(fd); - } - else - { - slldbg("Failed to open /dev/console: %d\n", errno); - } - return -ENFILE; - } -#endif - - /* Allocate file/socket streams for the TCB */ - -#if CONFIG_NFILE_STREAMS > 0 - return sched_setupstreams(tcb); -#else - return OK; -#endif -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c deleted file mode 100644 index 91d72fa7f..000000000 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ /dev/null @@ -1,91 +0,0 @@ -/**************************************************************************** - * sched_setuppthreadfiles.c - * - * Copyright (C) 2007, 2009, 2012 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 - -#include - -#include -#include -#include - -#include "os_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setuppthreadfiles - * - * Description: - * Configure a newly allocated TCB so that it will inherit file - * descriptors and streams from the parent pthread. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * OK (if an error were returned, it would need to be a non-negated - * errno value). - * - * Assumptions: - * - ****************************************************************************/ - -int sched_setuppthreadfiles(FAR _TCB *tcb) -{ -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - /* The child thread inherits the parent socket descriptors */ - - tcb->sockets = rtcb->sockets; - net_addreflist(tcb->sockets); - -#endif /* CONFIG_NSOCKET_DESCRIPTORS */ - - return OK; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c deleted file mode 100644 index fb2e4d0be..000000000 --- a/nuttx/sched/sched_setupstreams.c +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * sched_setupstreams.c - * - * Copyright (C) 2007-2008, 2010-2012 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 - -#include -#include - -#include -#include -#include - -/* Make sure that there are file or socket descriptors in the system and - * that some number of streams have been configured. - */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -#if CONFIG_NFILE_STREAMS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setupstreams - * - * Description: - * Setup streams data structures that may be used for standard C buffered - * I/O with underlying socket or file desciptors - * - ****************************************************************************/ - -int sched_setupstreams(FAR _TCB *tcb) -{ - DEBUGASSERT(tcb && tcb->group); - - /* Initialize file streams for the task group */ - - lib_streaminit(&tcb->group->tg_streamlist); - - /* fdopen to get the stdin, stdout and stderr streams. The following logic - * depends on the fact that the library layer will allocate FILEs in order. - * - * fd = 0 is stdin (read-only) - * fd = 1 is stdout (write-only, append) - * fd = 2 is stderr (write-only, append) - */ - - (void)fs_fdopen(0, O_RDONLY, tcb); - (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); - (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); - - return OK; -} - -#endif /* CONFIG_NFILE_STREAMS > 0 */ -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c deleted file mode 100644 index 9e44147e9..000000000 --- a/nuttx/sched/sched_setuptaskfiles.c +++ /dev/null @@ -1,248 +0,0 @@ -/**************************************************************************** - * sched/sched_setuptaskfiles.c - * - * 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 - * 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 - -#include -#include - -#include -#include - -#include "os_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Determine how many file descriptors to clone. If CONFIG_FDCLONE_DISABLE - * is set, no file descriptors will be cloned. If CONFIG_FDCLONE_STDIO is - * set, only the first three descriptors (stdin, stdout, and stderr) will - * be cloned. Otherwise all file descriptors will be cloned. - */ - -#if defined(CONFIG_FDCLONE_STDIO) && CONFIG_NFILE_DESCRIPTORS > 3 -# define NFDS_TOCLONE 3 -#else -# define NFDS_TOCLONE CONFIG_NFILE_DESCRIPTORS -#endif - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_dupfiles - * - * Description: - * Duplicate parent task's file descriptors. - * - * Input Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - ****************************************************************************/ - -#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_FDCLONE_DISABLE) -static inline void sched_dupfiles(FAR _TCB *tcb) -{ - /* The parent task is the one at the head of the ready-to-run list */ - - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - FAR struct file *parent; - 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. - */ - - /* Get pointers to the parent and child task file lists */ - - parent = rtcb->group->tg_filelist.fl_files; - child = tcb->group->tg_filelist.fl_files; - - /* 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. - */ - - if (parent[i].f_inode) - { - /* Yes... duplicate it for the child */ - - (void)files_dup(&parent[i], &child[i]); - } - } -} -#else /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ -# define sched_dupfiles(tcb) -#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ - -/**************************************************************************** - * Name: sched_dupsockets - * - * Description: - * Duplicate the parent task's socket descriptors. - * - * Input Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - ****************************************************************************/ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 && !defined(CONFIG_SDCLONE_DISABLE) -static inline void sched_dupsockets(FAR _TCB *tcb) -{ - /* The parent task is the one at the head of the ready-to-run list */ - - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - FAR struct socket *parent; - FAR struct socket *child; - int i; - - /* Duplicate the socket descriptors of all sockets opened by the parent - * task. - */ - - if (rtcb->sockets) - { - /* Get pointers to the parent and child task socket lists */ - - parent = rtcb->sockets->sl_sockets; - child = tcb->sockets->sl_sockets; - - /* Check each socket in the parent socket list */ - - for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++) - { - /* Check if this parent socket is allocated. We can tell if the - * socket is allocated because it will have a positive, non-zero - * reference count. - */ - - if (parent[i].s_crefs > 0) - { - /* Yes... duplicate it for the child */ - - (void)net_clone(&parent[i], &child[i]); - } - } - } -} -#else /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ -# define sched_dupsockets(tcb) -#endif /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setuptaskfiles - * - * Description: - * Configure a newly allocated TCB so that it will inherit - * file descriptors and streams from the parent task. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * Zero (OK) is returned on success; A negated errno value is returned on - * failure. - * - * Assumptions: - * - ****************************************************************************/ - -int sched_setuptaskfiles(FAR _TCB *tcb) -{ -#if CONFIG_NFILE_DESCRIPTORS > 0 - 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 */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - tcb->sockets = net_alloclist(); - if (!tcb->sockets) - { - return -ENOMEM; - } -#endif - - /* Duplicate the parent task's file descriptors */ - - sched_dupfiles(tcb); - - /* Duplicate the parent task's socket descriptors */ - - sched_dupsockets(tcb); - - /* Allocate file/socket streams for the new TCB */ - -#if CONFIG_NFILE_STREAMS > 0 - return sched_setupstreams(tcb); -#else - return OK; -#endif -} - -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c index 85c0f5e92..944743200 100644 --- a/nuttx/sched/task_create.c +++ b/nuttx/sched/task_create.c @@ -134,7 +134,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority, /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - ret = sched_setuptaskfiles(tcb); + ret = group_setuptaskfiles(tcb); if (ret != OK) { errcode = -ret; diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c index 8dfd8b7f6..78f35bc2a 100644 --- a/nuttx/sched/task_init.c +++ b/nuttx/sched/task_init.c @@ -137,7 +137,7 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - ret = sched_setuptaskfiles(tcb); + ret = group_setuptaskfiles(tcb); if (ret < 0) { errcode = -ret; diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c index 3f058bdec..5b42a1e55 100644 --- a/nuttx/sched/task_vfork.c +++ b/nuttx/sched/task_vfork.c @@ -125,7 +125,7 @@ FAR _TCB *task_vforksetup(start_t retaddr) /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - ret = sched_setuptaskfiles(child); + ret = group_setuptaskfiles(child); if (ret != OK) { goto errout_with_tcb; -- cgit v1.2.3