summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile6
-rw-r--r--nuttx/sched/os_internal.h6
-rw-r--r--nuttx/sched/sched_getsockets.c76
-rw-r--r--nuttx/sched/sched_releasefiles.c18
-rw-r--r--nuttx/sched/sched_setupidlefiles.c27
-rw-r--r--nuttx/sched/sched_setuppthreadfiles.c19
-rw-r--r--nuttx/sched/sched_setupstreams.c5
-rw-r--r--nuttx/sched/sched_setuptaskfiles.c28
8 files changed, 160 insertions, 25 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 56bcb3a90..eb0473f66 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -1,4 +1,4 @@
-############################################################
+############################################################################
# Makefile
#
# Copyright (C) 2007 Gregory Nutt. All rights reserved.
@@ -31,7 +31,7 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
-############################################################
+############################################################################
-include $(TOPDIR)/Make.defs
@@ -41,7 +41,7 @@ ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
MISC_SRCS = os_start.c get_errno_ptr.c \
- sched_setupstreams.c sched_getfiles.c sched_getstreams.c \
+ sched_setupstreams.c sched_getfiles.c sched_getsockets.c sched_getstreams.c \
sched_setupidlefiles.c sched_setuptaskfiles.c sched_setuppthreadfiles.c \
sched_releasefiles.c
TSK_SRCS = task_create.c task_init.c task_setup.c task_activate.c \
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index da6974066..94da9bbbc 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -96,7 +96,7 @@ enum os_crash_codes_e
/* Stubs used when there are no file descriptors */
-#if CONFIG_NFILE_DESCRIPTORS <= 0
+#if CONFIG_NFILE_DESCRIPTORS <= 0 && CONFIG_NSOCKET_DESCRIPTORS <= 0
# define sched_setupidlefiles(t) (OK)
# define sched_setuptaskfiles(t) (OK)
# define sched_setuppthreadfiles(t) (OK)
@@ -254,11 +254,11 @@ extern void sched_addblocked(FAR _TCB *btcb, tstate_t task_state);
extern void sched_removeblocked(FAR _TCB *btcb);
extern FAR _TCB *sched_gettcb(pid_t pid);
-#if CONFIG_NFILE_DESCRIPTORS > 0
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
extern int sched_setupidlefiles(FAR _TCB *tcb);
extern int sched_setuptaskfiles(FAR _TCB *tcb);
extern int sched_setuppthreadfiles(FAR _TCB *tcb);
-#if CONFIG_NFILE_STREAMS > 0
+#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0
extern int sched_setupstreams(FAR _TCB *tcb);
extern int sched_flushfiles(FAR _TCB *tcb);
#endif
diff --git a/nuttx/sched/sched_getsockets.c b/nuttx/sched/sched_getsockets.c
new file mode 100644
index 000000000..c54c5f236
--- /dev/null
+++ b/nuttx/sched/sched_getsockets.c
@@ -0,0 +1,76 @@
+/************************************************************
+ * sched_getsockets.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+
+#include <sched.h>
+#include "os_internal.h"
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Function: sched_getsockets
+ *
+ * Description:
+ * Return a pointer to the socket list for this thread
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * A pointer to the errno.
+ *
+ * Assumptions:
+ *
+ ************************************************************/
+
+FAR struct socketlist *sched_getsockets(void)
+{
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ return rtcb->sockets;
+}
+
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/sched_releasefiles.c
index c511bdb54..707e8636a 100644
--- a/nuttx/sched/sched_releasefiles.c
+++ b/nuttx/sched/sched_releasefiles.c
@@ -38,8 +38,11 @@
************************************************************/
#include <nuttx/config.h>
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+
#include <sched.h>
#include <nuttx/fs.h>
+#include <nuttx/net.h>
#include <nuttx/lib.h>
/************************************************************
@@ -66,12 +69,11 @@
*
************************************************************/
-#if CONFIG_NFILE_DESCRIPTORS > 0
-
int sched_releasefiles(_TCB *tcb)
{
if (tcb)
{
+#if CONFIG_NFILE_DESCRIPTORS > 0
/* Free the file descriptor list */
files_releaselist(tcb->filelist);
@@ -83,7 +85,17 @@ int sched_releasefiles(_TCB *tcb)
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 */
+
+ net_releaselist(tcb->sockets);
+ tcb->sockets = NULL;
+
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
}
return OK;
}
-#endif /* CONFIG_NFILE_DESCRIPTORS */
+
+#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c
index 78d8d60ad..4949779af 100644
--- a/nuttx/sched/sched_setupidlefiles.c
+++ b/nuttx/sched/sched_setupidlefiles.c
@@ -38,11 +38,17 @@
************************************************************/
#include <nuttx/config.h>
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <sched.h>
#include <errno.h>
+
+#include <nuttx/fs.h>
+#include <nuttx/net.h>
+
#include "os_internal.h"
/************************************************************
@@ -69,12 +75,11 @@
*
************************************************************/
-#if CONFIG_NFILE_DESCRIPTORS > 0
-
int sched_setupidlefiles(FAR _TCB *tcb)
{
int fd;
+#if CONFIG_NFILE_DESCRIPTORS > 0
/* Allocate file descriptors for the TCB */
tcb->filelist = files_alloclist();
@@ -83,8 +88,20 @@ int sched_setupidlefiles(FAR _TCB *tcb)
*get_errno_ptr() = ENOMEM;
return ERROR;
}
+#endif /* CONFIG_NFILE_DESCRIPTORS */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ /* Allocate socket descriptors for the TCB */
+
+ tcb->sockets = net_alloclist();
+ if (!tcb->sockets)
+ {
+ *get_errno_ptr() = ENOMEM;
+ return ERROR;
+ }
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
-#ifdef CONFIG_DEV_CONSOLE
+#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE)
/* Open stdin, dup to get stdout and stderr. */
fd = open("/dev/console", O_RDWR);
@@ -107,7 +124,7 @@ int sched_setupidlefiles(FAR _TCB *tcb)
#else
return OK;
#endif /* CONFIG_NFILE_STREAMS */
-#endif /* CONFIG_DEV_CONSOLE */
+#endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_DEV_CONSOLE */
}
-#endif /* CONFIG_NFILE_DESCRIPTORS */
+#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c
index 91dfd850f..e5f035afa 100644
--- a/nuttx/sched/sched_setuppthreadfiles.c
+++ b/nuttx/sched/sched_setuppthreadfiles.c
@@ -38,9 +38,14 @@
************************************************************/
#include <nuttx/config.h>
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+
#include <sched.h>
+
#include <nuttx/fs.h>
+#include <nuttx/net.h>
#include <nuttx/lib.h>
+
#include "os_internal.h"
/************************************************************
@@ -68,12 +73,11 @@
*
************************************************************/
-#if CONFIG_NFILE_DESCRIPTORS > 0
-
int sched_setuppthreadfiles(FAR _TCB *tcb)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+#if CONFIG_NFILE_DESCRIPTORS > 0
/* The child thread inherits the parent file descriptors */
tcb->filelist = rtcb->filelist;
@@ -86,8 +90,17 @@ int sched_setuppthreadfiles(FAR _TCB *tcb)
lib_addreflist(tcb->streams);
#endif /* CONFIG_NFILE_STREAMS */
+#endif /* CONFIG_NFILE_DESCRIPTORS */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ /* The child thread inherits the parent file descriptors */
+
+ tcb->sockets = rtcb->sockets;
+ net_addreflist(tcb->sockets);
+
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
return OK;
}
-#endif /* CONFIG_NFILE_DESCRIPTORS */
+#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c
index a19dd0bf1..1429ece31 100644
--- a/nuttx/sched/sched_setupstreams.c
+++ b/nuttx/sched/sched_setupstreams.c
@@ -38,8 +38,11 @@
************************************************************/
#include <nuttx/config.h>
+#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0
+
#include <sched.h>
#include <nuttx/fs.h>
+#include <nuttx/net.h>
#include <nuttx/lib.h>
/************************************************************
@@ -50,8 +53,6 @@
* Public Functions
************************************************************/
-#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0
-
int sched_setupstreams(FAR _TCB *tcb)
{
/* Allocate file strems for the TCB */
diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c
index 9fef59278..203a06b44 100644
--- a/nuttx/sched/sched_setuptaskfiles.c
+++ b/nuttx/sched/sched_setuptaskfiles.c
@@ -38,9 +38,14 @@
************************************************************/
#include <nuttx/config.h>
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+
#include <sched.h>
#include <errno.h>
+
#include <nuttx/fs.h>
+#include <nuttx/net.h>
+
#include "os_internal.h"
/************************************************************
@@ -68,16 +73,15 @@
*
************************************************************/
-#if CONFIG_NFILE_DESCRIPTORS > 0
-
int sched_setuptaskfiles(FAR _TCB *tcb)
{
-#ifdef CONFIG_DEV_CONSOLE
+#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE)
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
int i;
#endif /* CONFIG_DEV_CONSOLE */
int ret = OK;
+#if CONFIG_NFILE_DESCRIPTORS > 0
/* Allocate file descriptors for the TCB */
tcb->filelist = files_alloclist();
@@ -86,8 +90,20 @@ int sched_setuptaskfiles(FAR _TCB *tcb)
*get_errno_ptr() = ENOMEM;
return ERROR;
}
+#endif /* CONFIG_NFILE_DESCRIPTORS */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ /* Allocate socket descriptors for the TCB */
+
+ tcb->sockets = net_alloclist();
+ if (!tcb->sockets)
+ {
+ *get_errno_ptr() = ENOMEM;
+ return ERROR;
+ }
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
-#ifdef CONFIG_DEV_CONSOLE
+#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE)
/* Duplicate the first three file descriptors */
if (rtcb->filelist)
@@ -104,8 +120,8 @@ int sched_setuptaskfiles(FAR _TCB *tcb)
ret = sched_setupstreams(tcb);
#endif /* CONFIG_NFILE_STREAMS */
-#endif /* CONFIG_DEV_CONSOLE */
+#endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_DEV_CONSOLE */
return ret;
}
-#endif /* CONFIG_NFILE_DESCRIPTORS */
+#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */