forked from Archive/PX4-Autopilot
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
This commit is contained in:
parent
b82c36961a
commit
47b94bafa5
|
@ -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.
|
||||
|
|
|
@ -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 <gnutt@nuttx.org>
|
||||
*
|
||||
* 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.
|
||||
|
|
|
@ -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. */
|
||||
|
||||
|
|
|
@ -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 */
|
||||
/* Initialize the list access mutex */
|
||||
|
||||
list->sl_crefs = 1;
|
||||
|
||||
/* 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;
|
||||
}
|
||||
|
||||
/* Release a reference to the file list */
|
||||
|
||||
int net_releaselist(FAR struct socketlist *list)
|
||||
{
|
||||
int crefs;
|
||||
int ndx;
|
||||
|
||||
if (list)
|
||||
DEBUGASSERT(list);
|
||||
|
||||
/* Close each open socket in the 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)
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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 */
|
||||
|
||||
|
|
|
@ -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 */
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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 */
|
||||
|
|
|
@ -44,6 +44,10 @@
|
|||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/net/net.h>
|
||||
#include <nuttx/lib.h>
|
||||
|
||||
#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
|
||||
|
|
|
@ -1,112 +0,0 @@
|
|||
/****************************************************************************
|
||||
* sched/group_releasefiles.c
|
||||
*
|
||||
* Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sched.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/net/net.h>
|
||||
#include <nuttx/lib.h>
|
||||
|
||||
#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 */
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched/sched_setupidlefiles.c
|
||||
* sched/group_setupidlefiles.c
|
||||
*
|
||||
* Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -62,7 +62,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: sched_setupidlefiles
|
||||
* Name: group_setupidlefiles
|
||||
*
|
||||
* Description:
|
||||
* Configure the idle thread's TCB.
|
||||
|
@ -77,33 +77,29 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
int sched_setupidlefiles(FAR _TCB *tcb)
|
||||
int group_setupidlefiles(FAR _TCB *tcb)
|
||||
{
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
#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
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
|
||||
DEBUGASSERT(group);
|
||||
#endif
|
||||
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
/* Initialize file descriptors for the TCB */
|
||||
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
files_initlist(&group->tg_filelist);
|
||||
#endif
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
/* Allocate socket descriptors for the TCB */
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
tcb->sockets = net_alloclist();
|
||||
if (!tcb->sockets)
|
||||
{
|
||||
return -ENOMEM;
|
||||
}
|
||||
net_initlist(&group->tg_socketlist);
|
||||
#endif
|
||||
|
||||
/* Open stdin, dup to get stdout and stderr. This should always
|
||||
|
@ -142,7 +138,7 @@ int sched_setupidlefiles(FAR _TCB *tcb)
|
|||
/* Allocate file/socket streams for the TCB */
|
||||
|
||||
#if CONFIG_NFILE_STREAMS > 0
|
||||
return sched_setupstreams(tcb);
|
||||
return group_setupstreams(tcb);
|
||||
#else
|
||||
return OK;
|
||||
#endif
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched_setupstreams.c
|
||||
* group_setupstreams.c
|
||||
*
|
||||
* Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2007-2008, 2010-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -62,7 +62,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: sched_setupstreams
|
||||
* Name: group_setupstreams
|
||||
*
|
||||
* Description:
|
||||
* Setup streams data structures that may be used for standard C buffered
|
||||
|
@ -70,7 +70,7 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
int sched_setupstreams(FAR _TCB *tcb)
|
||||
int group_setupstreams(FAR _TCB *tcb)
|
||||
{
|
||||
DEBUGASSERT(tcb && tcb->group);
|
||||
|
|
@ -1,5 +1,5 @@
|
|||
/****************************************************************************
|
||||
* sched/sched_setuptaskfiles.c
|
||||
* sched/group_setuptaskfiles.c
|
||||
*
|
||||
* Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
|
@ -151,32 +151,31 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
|
|||
FAR struct socket *child;
|
||||
int i;
|
||||
|
||||
/* Duplicate the socket descriptors of all sockets opened by the parent
|
||||
* task.
|
||||
*/
|
||||
/* Duplicate the socket descriptors of all sockets opened by the parent
|
||||
* task.
|
||||
*/
|
||||
|
||||
if (rtcb->sockets)
|
||||
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++)
|
||||
{
|
||||
/* Get pointers to the parent and child task socket lists */
|
||||
/* 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.
|
||||
*/
|
||||
|
||||
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++)
|
||||
if (parent[i].s_crefs > 0)
|
||||
{
|
||||
/* 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.
|
||||
*/
|
||||
/* Yes... duplicate it for the child */
|
||||
|
||||
if (parent[i].s_crefs > 0)
|
||||
{
|
||||
/* Yes... duplicate it for the child */
|
||||
|
||||
(void)net_clone(&parent[i], &child[i]);
|
||||
}
|
||||
(void)net_clone(&parent[i], &child[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -189,7 +188,7 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: sched_setuptaskfiles
|
||||
* Name: group_setuptaskfiles
|
||||
*
|
||||
* Description:
|
||||
* Configure a newly allocated TCB so that it will inherit
|
||||
|
@ -206,26 +205,24 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
int sched_setuptaskfiles(FAR _TCB *tcb)
|
||||
int group_setuptaskfiles(FAR _TCB *tcb)
|
||||
{
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
#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 */
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
tcb->sockets = net_alloclist();
|
||||
if (!tcb->sockets)
|
||||
{
|
||||
return -ENOMEM;
|
||||
}
|
||||
net_initlist(&group->tg_socketlist);
|
||||
#endif
|
||||
|
||||
/* Duplicate the parent task's file descriptors */
|
||||
|
@ -239,7 +236,7 @@ int sched_setuptaskfiles(FAR _TCB *tcb)
|
|||
/* Allocate file/socket streams for the new TCB */
|
||||
|
||||
#if CONFIG_NFILE_STREAMS > 0
|
||||
return sched_setupstreams(tcb);
|
||||
return group_setupstreams(tcb);
|
||||
#else
|
||||
return OK;
|
||||
#endif
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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 */
|
||||
|
||||
|
|
|
@ -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));
|
||||
|
|
|
@ -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 <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 */
|
||||
|
|
|
@ -1,91 +0,0 @@
|
|||
/****************************************************************************
|
||||
* sched_setuppthreadfiles.c
|
||||
*
|
||||
* Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sched.h>
|
||||
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/net/net.h>
|
||||
#include <nuttx/lib.h>
|
||||
|
||||
#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 */
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue