summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-02 15:25:22 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-02 15:25:22 +0000
commit68551d0cf274eacbf5c6de959e7bf812a6ee7eba (patch)
treea26751e5f0991b18a587dbc2d37c6ee7c3ce847d /nuttx/sched
parent158978359318cb94de9e08900af4300bdfa5f651 (diff)
downloadpx4-nuttx-68551d0cf274eacbf5c6de959e7bf812a6ee7eba.tar.gz
px4-nuttx-68551d0cf274eacbf5c6de959e7bf812a6ee7eba.tar.bz2
px4-nuttx-68551d0cf274eacbf5c6de959e7bf812a6ee7eba.zip
Kernel build mostly successful
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3454 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile18
-rw-r--r--nuttx/sched/errno_get.c (renamed from nuttx/sched/sig_emptyset.c)43
-rw-r--r--nuttx/sched/errno_getptr.c (renamed from nuttx/sched/get_errno_ptr.c)8
-rw-r--r--nuttx/sched/errno_set.c (renamed from nuttx/sched/sig_fillset.c)44
-rw-r--r--nuttx/sched/sched_lockcount.c16
-rw-r--r--nuttx/sched/sig_addset.c99
-rw-r--r--nuttx/sched/sig_delset.c99
-rw-r--r--nuttx/sched/sig_ismember.c100
8 files changed, 63 insertions, 364 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 8b8b33a58..86e7c0b76 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -38,10 +38,10 @@
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-MISC_SRCS = os_start.c os_bringup.c get_errno_ptr.c sched_garbage.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
+MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c \
+ sched_garbage.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 \
task_start.c task_delete.c task_deletecurrent.c task_restart.c \
@@ -80,12 +80,10 @@ CLOCK_SRCS = clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c \
SIGNAL_SRCS = sig_initialize.c \
sig_action.c sig_procmask.c sig_pending.c sig_suspend.c \
sig_kill.c sig_queue.c sig_waitinfo.c sig_timedwait.c \
- sig_emptyset.c sig_fillset.c sig_addset.c sig_delset.c \
- sig_ismember.c sig_findaction.c \
- sig_allocatependingsigaction.c sig_releasependingsigaction.c \
- sig_unmaskpendingsignal.c sig_removependingsignal.c \
- sig_releasependingsignal.c sig_lowest.c sig_mqnotempty.c \
- sig_cleanup.c sig_received.c sig_deliver.c
+ sig_findaction.c sig_allocatependingsigaction.c \
+ sig_releasependingsigaction.c sig_unmaskpendingsignal.c \
+ sig_removependingsignal.c sig_releasependingsignal.c sig_lowest.c \
+ sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c
MQUEUE_SRCS = mq_open.c mq_close.c mq_unlink.c mq_send.c mq_timedsend.c\
mq_sndinternal.c mq_receive.c mq_timedreceive.c mq_rcvinternal.c \
diff --git a/nuttx/sched/sig_emptyset.c b/nuttx/sched/errno_get.c
index c8fc4ef40..7461a42c7 100644
--- a/nuttx/sched/sig_emptyset.c
+++ b/nuttx/sched/errno_get.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sig_emptyset.c
+ * sched/errno_get.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -37,26 +37,20 @@
* Included Files
****************************************************************************/
-#include <signal.h>
+#include <nuttx/config.h>
-/****************************************************************************
- * Definitions
- ****************************************************************************/
+#include <errno.h>
/****************************************************************************
- * Private Type Declarations
+ * Pre-processor Definitions
****************************************************************************/
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
+#undef get_errno_ptr
+#undef get_errno
+#undef errno
/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
+ * Private Data
****************************************************************************/
/****************************************************************************
@@ -64,24 +58,27 @@
****************************************************************************/
/****************************************************************************
- * Function: sigemptyset
+ * Function: get_errno
*
* Description:
- * This function initializes the signal set specified by set such that all
- * signals are excluded.
+ * Return the value of the thread specific errno. This function is only
+ * intended to provide a mechanism for user-mode programs to get the
+ * thread-specific errno value. It is #define'd to the symbol errno in
+ * include/errno.h.
*
* Parameters:
- * set - Signal set to initalize
+ * None
*
* Return Value:
- * 0 (OK), or -1 (ERROR) if the signal set cannot be initialized.
+ * The current value of the thread specific errno.
*
* Assumptions:
*
****************************************************************************/
-int sigemptyset(FAR sigset_t *set)
+int get_errno(void)
{
- *set = NULL_SIGNAL_SET;
- return OK;
+ return *get_errno_ptr();
}
+
+
diff --git a/nuttx/sched/get_errno_ptr.c b/nuttx/sched/errno_getptr.c
index ebf2e105c..8daf5b2cc 100644
--- a/nuttx/sched/get_errno_ptr.c
+++ b/nuttx/sched/errno_getptr.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/get_errno_ptr.c
+ * sched/errno_getptr.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,6 +43,10 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
#undef get_errno_ptr
#undef errno
diff --git a/nuttx/sched/sig_fillset.c b/nuttx/sched/errno_set.c
index d315c0d63..2bf01d9b1 100644
--- a/nuttx/sched/sig_fillset.c
+++ b/nuttx/sched/errno_set.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sig_fillset.c
+ * sched/errno_set.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -37,51 +37,47 @@
* Included Files
****************************************************************************/
-#include <signal.h>
+#include <nuttx/config.h>
-/****************************************************************************
- * Definitions
- ****************************************************************************/
+#include <errno.h>
/****************************************************************************
- * Private Type Declarations
+ * Pre-processor Definitions
****************************************************************************/
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
+#undef get_errno_ptr
+#undef set_errno
+#undef errno
/****************************************************************************
- * Private Variables
+ * Private Data
****************************************************************************/
/****************************************************************************
- * Private Function Prototypes
+ * Public Functions
****************************************************************************/
/****************************************************************************
- * Publics Functioins
- ****************************************************************************/
-
-/****************************************************************************
- * Function: sigfillset
+ * Function: set_errno
*
* Description:
- * This function initializes the signal set specified by set such that all
- * signals are included.
+ * Set the value of the thread specific errno. This function is only
+ * intended to provide a mechanism for user-mode programs to set the
+ * thread-specific errno value.
*
* Parameters:
- * set - Signal set to initalize
+ * errcode - The thread specific errno will be set to this error code value.
*
* Return Value:
- * 0 (OK), or -1 (ERROR) if the signal set cannot be initialized.
+ * None
*
* Assumptions:
*
****************************************************************************/
-int sigfillset(FAR sigset_t *set)
+void set_errno(int errcode)
{
- *set = ALL_SIGNAL_SET;
- return OK;
+ *get_errno_ptr() = errcode;
}
+
+
diff --git a/nuttx/sched/sched_lockcount.c b/nuttx/sched/sched_lockcount.c
index 21998f6b3..6ac3a9dee 100644
--- a/nuttx/sched/sched_lockcount.c
+++ b/nuttx/sched/sched_lockcount.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_lockcount.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -75,10 +75,11 @@
* Name: sched_lockcount
*
* Description:
- * This function returns the current value of the lockcount.
- * If zero, preemption is enabled; if non-zero, this value
- * indicates the number of times that osTask() has been
- * called on this thread of execution.
+ * This function returns the current value of the lockcount. If zero,
+ * pre-emption is enabled; if non-zero, this value indicates the number
+ * of times that sched_lock() has been called on this thread of
+ * execution. sched_unlock() will have to called that many times from
+ * this thread in order to re-enable pre-emption.
*
* Inputs:
* None
@@ -88,8 +89,9 @@
*
************************************************************************/
-int32_t sched_lockcount(void)
+int sched_lockcount(void)
{
_TCB *rtcb = (_TCB*)g_readytorun.head;
- return (int32_t)rtcb->lockcount;
+ return (int)rtcb->lockcount;
}
+
diff --git a/nuttx/sched/sig_addset.c b/nuttx/sched/sig_addset.c
deleted file mode 100644
index 678a7fcaf..000000000
--- a/nuttx/sched/sig_addset.c
+++ /dev/null
@@ -1,99 +0,0 @@
-/****************************************************************************
- * sched/sig_addset.c
- *
- * Copyright (C) 2007, 2008 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 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 <signal.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Type Declarations
- ****************************************************************************/
-
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: sigaddset
- *
- * Description:
- * This function adds the signal specified by signo to the signal set
- * specified by set.
- *
- * Parameters:
- * set - Signal set to add signal to
- * signo - Signal to add
- *
- * Return Value:
- * 0 (OK), or -1 (ERROR) if the signal number is invalid.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-int sigaddset(FAR sigset_t *set, int signo)
-{
- int ret = ERROR;
-
- /* Verify the signal */
-
- if (GOOD_SIGNO(signo))
- {
- /* Add the signal to the set */
-
- *set |= SIGNO2SET(signo);
- ret = OK;
- }
-
- return ret;
-}
diff --git a/nuttx/sched/sig_delset.c b/nuttx/sched/sig_delset.c
deleted file mode 100644
index 78f8dc177..000000000
--- a/nuttx/sched/sig_delset.c
+++ /dev/null
@@ -1,99 +0,0 @@
-/****************************************************************************
- * sched/sig_delset.c
- *
- * Copyright (C) 2007, 2008 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 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 <signal.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Type Declarations
- ****************************************************************************/
-
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: sigdelset
- *
- * Description:
- * This function deletes the signal specified by signo from the signal
- * set specified by the 'set' argument.
- *
- * Parameters:
- * set - Signal set to delete the signal from
- * signo - Signal to delete
- *
- * Return Value:
- * 0 (OK), or -1 (ERROR) if the signal number is invalid.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-int sigdelset(FAR sigset_t *set, int signo)
-{
- int ret = ERROR;
-
- /* Verify the signal */
-
- if (GOOD_SIGNO(signo))
- {
- /* Delete the signal to the set */
-
- *set &= ~SIGNO2SET(signo);
- ret = OK;
- }
-
- return ret;
-}
diff --git a/nuttx/sched/sig_ismember.c b/nuttx/sched/sig_ismember.c
deleted file mode 100644
index 670ef7bd2..000000000
--- a/nuttx/sched/sig_ismember.c
+++ /dev/null
@@ -1,100 +0,0 @@
-/****************************************************************************
- * sched/sig_ismember.c
- *
- * Copyright (C) 2007, 2008 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 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 <signal.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Type Declarations
- ****************************************************************************/
-
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: sigismember
- *
- * Description:
- * This function tests whether the signal specified by signo is a member
- * of the set specified by set.
- *
- * Parameters:
- * set - Signal set to test
- * signo - Signal to test for
- *
- * Return Value:
- * 1 (true), if the specified signal is a member of the set,
- * 0 (OK or FALSE), if it is not, or
- * -1 (ERROR) if the signal number is invalid.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-int sigismember(FAR const sigset_t *set, int signo)
-{
- int ret = ERROR;
-
- /* Verify the signal */
-
- if (GOOD_SIGNO(signo))
- {
- /* Check if the signal is in the set */
-
- ret = ((*set & SIGNO2SET(signo)) != 0);
- }
-
- return ret;
-}