summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-23 23:22:22 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-23 23:22:22 +0000
commit1113121fa268695f1816574c47bb88d737d12a3e (patch)
tree776672757efb51d171d9bd17355fa8cd5053f9ef /nuttx/sched
parentfb18a14fa419ea6627fa1f148bd1a479cd53639b (diff)
downloadpx4-nuttx-1113121fa268695f1816574c47bb88d737d12a3e.tar.gz
px4-nuttx-1113121fa268695f1816574c47bb88d737d12a3e.tar.bz2
px4-nuttx-1113121fa268695f1816574c47bb88d737d12a3e.zip
Add new pthread_* APIs
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@134 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile7
-rw-r--r--nuttx/sched/clock_abstime2ticks.c1
-rw-r--r--nuttx/sched/os_internal.h2
-rw-r--r--nuttx/sched/os_start.c4
-rw-r--r--nuttx/sched/pthread_barrierattrdestroy.c101
-rw-r--r--nuttx/sched/pthread_barrierattrgetpshared.c100
-rw-r--r--nuttx/sched/pthread_barrierattrinit.c100
-rw-r--r--nuttx/sched/pthread_barrierattrsetpshared.c110
-rw-r--r--nuttx/sched/pthread_barrierdestroy.c109
-rw-r--r--nuttx/sched/pthread_barrierinit.c120
-rw-r--r--nuttx/sched/pthread_barrierwait.c181
-rw-r--r--nuttx/sched/pthread_kill.c93
-rw-r--r--nuttx/sched/pthread_once.c125
-rw-r--r--nuttx/sched/pthread_sigmask.c106
-rw-r--r--nuttx/sched/sig_kill.c6
-rw-r--r--nuttx/sched/task_setup.c2
-rw-r--r--nuttx/sched/timer_initialize.c4
17 files changed, 1160 insertions, 11 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 727c4d9c4..b6a1dbdbd 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -89,12 +89,15 @@ PTHREAD_SRCS = pthread_attrinit.c pthread_attrdestroy.c \
pthread_condinit.c pthread_conddestroy.c \
pthread_condattrinit.c pthread_condattrdestroy.c \
pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c \
+ pthread_barrierattrinit.c pthread_barrierattrdestroy.c \
+ pthread_barrierattrgetpshared.c pthread_barrierattrsetpshared.c \
+ pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c \
pthread_cancel.c pthread_setcancelstate.c \
pthread_keycreate.c pthread_setspecific.c pthread_getspecific.c pthread_keydelete.c \
pthread_initialize.c pthread_completejoin.c pthread_findjoininfo.c \
- pthread_removejoininfo.c
+ pthread_removejoininfo.c pthread_once.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
-PTHREAD_SRCS += pthread_condtimedwait.c
+PTHREAD_SRCS += pthread_condtimedwait.c pthread_kill.c pthread_sigmask.c
endif
SEM_SRCS = sem_initialize.c sem_init.c sem_destroy.c\
sem_open.c sem_close.c sem_unlink.c \
diff --git a/nuttx/sched/clock_abstime2ticks.c b/nuttx/sched/clock_abstime2ticks.c
index 359bd2165..7cd3eb495 100644
--- a/nuttx/sched/clock_abstime2ticks.c
+++ b/nuttx/sched/clock_abstime2ticks.c
@@ -93,7 +93,6 @@ extern int clock_abstime2ticks(clockid_t clockid, const struct timespec *abstime
{
struct timespec currtime;
struct timespec reltime;
- sint32 relusec;
int ret;
/* Convert the timespec to clock ticks. NOTE: Here we use
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 85dda8c96..da6974066 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -243,7 +243,7 @@ extern void task_start(void);
extern STATUS task_schedsetup(FAR _TCB *tcb, int priority,
start_t start, main_t main);
extern STATUS task_argsetup(FAR _TCB *tcb, const char *name,
- char *argv[]);
+ const char *argv[]);
extern boolean sched_addreadytorun(FAR _TCB *rtrtcb);
extern boolean sched_removereadytorun(FAR _TCB *rtrtcb);
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 4cb128d3c..c01778295 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -418,10 +418,10 @@ void os_start(void)
#ifndef CONFIG_CUSTOM_STACK
init_taskid = task_create("init", SCHED_PRIORITY_DEFAULT,
CONFIG_PROC_STACK_SIZE,
- (main_t)user_start, (char **)NULL);
+ (main_t)user_start, (const char **)NULL);
#else
init_taskid = task_create("init", SCHED_PRIORITY_DEFAULT,
- (main_t)user_start, (char **)NULL);
+ (main_t)user_start, (const char **)NULL);
#endif
ASSERT(init_taskid != ERROR);
diff --git a/nuttx/sched/pthread_barrierattrdestroy.c b/nuttx/sched/pthread_barrierattrdestroy.c
new file mode 100644
index 000000000..de20d16f6
--- /dev/null
+++ b/nuttx/sched/pthread_barrierattrdestroy.c
@@ -0,0 +1,101 @@
+/********************************************************************************
+ * pthread_barrierattrdestroy.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 <sys/types.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrierattr_destroy
+ *
+ * Description:
+ * The pthread_barrierattr_destroy() function will destroy a barrier attributes
+ * object. A destroyed attr attributes object can be reinitialized using
+ * pthread_barrierattr_init(); the results of otherwise referencing the object
+ * after it has been destroyed are undefined.
+ *
+ * Parameters:
+ * attr - barrier attributes to be destroyed.
+ *
+ * Return Value:
+ * 0 (OK) on success or EINVAL if attr is invalid.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrierattr_destroy(FAR pthread_barrierattr_t *attr)
+{
+ int ret = OK;
+
+ if (!attr)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ attr->pshared = PTHREAD_PROCESS_PRIVATE;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread_barrierattrgetpshared.c b/nuttx/sched/pthread_barrierattrgetpshared.c
new file mode 100644
index 000000000..23cf43872
--- /dev/null
+++ b/nuttx/sched/pthread_barrierattrgetpshared.c
@@ -0,0 +1,100 @@
+/********************************************************************************
+ * pthread_barrierattrgetpshared.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 <sys/types.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrierattr_getpshared
+ *
+ * Description:
+ * The pthread_barrierattr_getpshared() function will obtain the value of the
+ * process-shared attribute from the attributes object referenced by attr.
+ *
+ * Parameters:
+ * attr - barrier attributes to be queried.
+ * pshared - the location to stored the current value of the pshared attribute.
+ *
+ * Return Value:
+ * 0 (OK) on success or EINVAL if either attr or pshared is invalid.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrierattr_getpshared(FAR const pthread_barrierattr_t *attr, FAR int *pshared)
+{
+ int ret = OK;
+
+ if (!attr || !pshared)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ *pshared = attr->pshared;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread_barrierattrinit.c b/nuttx/sched/pthread_barrierattrinit.c
new file mode 100644
index 000000000..b2787bd31
--- /dev/null
+++ b/nuttx/sched/pthread_barrierattrinit.c
@@ -0,0 +1,100 @@
+/********************************************************************************
+ * pthread_barrierattrinit.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 <sys/types.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrierattr_init
+ *
+ * Description:
+ * The pthread_barrierattr_init() function will initialize a barrier attribute
+ * object attr with the default value for all of the attributes defined by the
+ * implementation.
+ *
+ * Parameters:
+ * attr - barrier attributes to be initialized.
+ *
+ * Return Value:
+ * 0 (OK) on success or EINVAL if attr is invalid.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrierattr_init(FAR pthread_barrierattr_t *attr)
+{
+ int ret = OK;
+
+ if (!attr)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ attr->pshared = PTHREAD_PROCESS_PRIVATE;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread_barrierattrsetpshared.c b/nuttx/sched/pthread_barrierattrsetpshared.c
new file mode 100644
index 000000000..2f1aee4f1
--- /dev/null
+++ b/nuttx/sched/pthread_barrierattrsetpshared.c
@@ -0,0 +1,110 @@
+/********************************************************************************
+ * pthread_barrierattrsetpshared.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 <sys/types.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrierattr_setpshared
+ *
+ * Description:
+ * The process-shared attribute is set to PTHREAD_PROCESS_SHARED to permit a
+ * barrier to be operated upon by any thread that has access to the memory where
+ * the barrier is allocated. If the process-shared attribute is
+ * PTHREAD_PROCESS_PRIVATE, the barrier can only be operated upon by threads
+ * created within the same process as the thread that initialized the barrier.
+ * If threads of different processes attempt to operate on such a barrier, the
+ * behavior is undefined. The default value of the attribute is
+ * PTHREAD_PROCESS_PRIVATE.
+ *
+ * Both constants PTHREAD_PROCESS_SHARED and PTHREAD_PROCESS_PRIVATE are defined
+ * in pthread.h.
+ *
+ * Parameters:
+ * attr - barrier attributes to be modified.
+ * pshared - the new value of the pshared attribute.
+ *
+ * Return Value:
+ * 0 (OK) on success or EINVAL if either attr is invalid or pshared is not one
+ * of PTHREAD_PROCESS_SHARED or PTHREAD_PROCESS_PRIVATE.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrierattr_setpshared(FAR pthread_barrierattr_t *attr, int pshared)
+{
+ int ret = OK;
+
+ if (!attr || (pshared != PTHREAD_PROCESS_SHARED && pshared != PTHREAD_PROCESS_PRIVATE))
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ attr->pshared = pshared;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread_barrierdestroy.c b/nuttx/sched/pthread_barrierdestroy.c
new file mode 100644
index 000000000..d4a33cc20
--- /dev/null
+++ b/nuttx/sched/pthread_barrierdestroy.c
@@ -0,0 +1,109 @@
+/********************************************************************************
+ * pthread_barriedestroy.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 <sys/types.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrier_destroy
+ *
+ * Description:
+ * The pthread_barrier_destroy() function destroys the barrier referenced by
+ * 'barrier' and releases any resources used by the barrier. The effect of
+ * subsequent use of the barrier is undefined until the barrier is
+ * reinitialized by another call to pthread_barrier_init(). The results are
+ * undefined if pthread_barrier_destroy() is called when any thread is blocked
+ * on the barrier, or if this function is called with an uninitialized barrier.
+ *
+ * Parameters:
+ * barrier - barrier to be destroyed.
+ *
+ * Return Value:
+ * 0 (OK) on success or on of the following error numbers:
+ *
+ * EBUSY The implementation has detected an attempt to destroy a barrier while
+ * it is in use.
+ * EINVAL The value specified by barrier is invalid.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrier_destroy(FAR pthread_barrier_t *barrier)
+{
+ int ret = OK;
+
+ if (!barrier)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ sem_destroy(&barrier->sem);
+ barrier->count = 0;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread_barrierinit.c b/nuttx/sched/pthread_barrierinit.c
new file mode 100644
index 000000000..bafb0794a
--- /dev/null
+++ b/nuttx/sched/pthread_barrierinit.c
@@ -0,0 +1,120 @@
+/********************************************************************************
+ * pthread_barrieinit.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 <sys/types.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrier_init
+ *
+ * Description:
+ * The pthread_barrier_init() function allocates any resources required to use
+ * the barrier referenced by 'barrier' and initialized the barrier with the
+ * attributes referenced by attr. If attr is NULL, the default barrier
+ * attributes will be used. The results are undefined if pthread_barrier_init()
+ * is called when any thread is blocked on the barrier. The results are
+ * undefined if a barrier is used without first being initialized. The results
+ * are undefined if pthread_barrier_init() is called specifying an already
+ * initialized barrier.
+ *
+ * Parameters:
+ * barrier - the barrier to be initialized
+ * attr - barrier attributes to be used in the initialization.
+ * count - the count to be associated with the barrier. The count argument
+ * specifies the number of threads that must call pthread_barrier_wait() before
+ * any of them successfully return from the call. The value specified by
+ * count must be greater than zero.
+ *
+ * Return Value:
+ * 0 (OK) on success or on of the following error numbers:
+ *
+ * EAGAIN The system lacks the necessary resources to initialize another barrier.
+ * EINVAL The barrier reference is invalid, or the values specified by attr are
+ * invalid, or the value specified by count is equal to zero.
+ * ENOMEM Insufficient memory exists to initialize the barrier.
+ * EBUSY The implementation has detected an attempt to reinitialize a barrier
+ * while it is in use.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrier_init(FAR pthread_barrier_t *barrier,
+ FAR const pthread_barrierattr_t *attr, unsigned int count)
+{
+ int ret = OK;
+
+ if (!barrier || count == 0)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ sem_init(&barrier->sem, 0, 0);
+ barrier->count = count;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread_barrierwait.c b/nuttx/sched/pthread_barrierwait.c
new file mode 100644
index 000000000..14cfa2eb3
--- /dev/null
+++ b/nuttx/sched/pthread_barrierwait.c
@@ -0,0 +1,181 @@
+/********************************************************************************
+ * pthread_barrierwait.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 <sys/types.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_barrier_wait
+ *
+ * Description:
+ * The pthread_barrier_wait() function synchronizse participating threads at
+ * the barrier referenced by 'barrier'. The calling thread is blocked until
+ * the required number of threads have called pthread_barrier_wait() specifying
+ * the same 'barrier'. When the required number of threads have called
+ * pthread_barrier_wait() specifying the 'barrier', the constant
+ * PTHREAD_BARRIER_SERIAL_THREAD will be returned to one unspecified thread
+ * and zero will be returned to each of the remaining threads. At this point,
+ * the barrier will be reset to the state it had as a result of the most recent
+ * pthread_barrier_init() function that referenced it.
+ *
+ * The constant PTHREAD_BARRIER_SERIAL_THREAD is defined in pthread.h and its
+ * value must be distinct from any other value returned by pthread_barrier_wait().
+ *
+ * The results are undefined if this function is called with an uninitialized
+ * barrier.
+ *
+ * If a signal is delivered to a thread blocked on a barrier, upon return from
+ * the signal handler the thread will resume waiting at the barrier if the barrier
+ * wait has not completed; otherwise, the thread will continue as normal from
+ * the completed barrier wait. Until the thread in the signal handler returns
+ * from it, it is unspecified whether other threads may proceed past the barrier
+ * once they have all reached it.
+ *
+ * A thread that has blocked on a barrier will not prevent any unblocked thread
+ * that is eligible to use the same processing resources from eventually making
+ * forward progress in its execution. Eligibility for processing resources will
+ * be determined by the scheduling policy.
+ *
+ * Parameters:
+ * barrier - the barrier to wait on
+ *
+ * Return Value:
+ * 0 (OK) on success or EINVAL if the barrier is not valid.
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_barrier_wait(FAR pthread_barrier_t *barrier)
+{
+ int semcount;
+ int ret = OK;
+
+ if (!barrier)
+ {
+ return EINVAL;
+ }
+
+ /* Disable pre-emption throughout the following */
+
+ sched_lock();
+
+ /* Find out how many threads are already waiting at the barrier */
+
+ ret = sem_getvalue(&barrier->sem, &semcount);
+ if (ret != OK)
+ {
+ sched_unlock();
+ return EINVAL;
+ }
+
+ /* If the number of waiters would be equal to the count, then we are done */
+
+ if (1 - semcount >= barrier->count)
+ {
+ /* Free all of the waiting threads */
+
+ while (semcount < 0)
+ {
+ (void)sem_post(&barrier->sem);
+ (void)sem_getvalue(&barrier->sem, &semcount);
+ }
+
+ /* Then return PTHREAD_BARRIER_SERIAL_THREAD to the final thread */
+
+ sched_unlock();
+ return PTHREAD_BARRIER_SERIAL_THREAD;
+ }
+ else
+ {
+ /* Otherwise, this thread must wait as well */
+
+ while (sem_wait(&barrier->sem) != OK)
+ {
+ /* If the thread is awakened by a signal, just continue to wait */
+
+ int errornumber = *get_errno_ptr();
+ if (errornumber != EINTR)
+ {
+ /* If it is awakened by some other error, then there is a
+ * problem
+ */
+
+ sched_unlock();
+ return errornumber;
+ }
+ }
+
+ /* We will only get here when we are one of the N-1 threads that were
+ * waiting for the final thread at the barrier. We just need to return
+ * zero.
+ */
+
+ sched_unlock();
+ return 0;
+ }
+}
diff --git a/nuttx/sched/pthread_kill.c b/nuttx/sched/pthread_kill.c
new file mode 100644
index 000000000..bf6c42d33
--- /dev/null
+++ b/nuttx/sched/pthread_kill.c
@@ -0,0 +1,93 @@
+/************************************************************
+ * pthread_kill.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>
+#include <signal.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/************************************************************
+ * Global Functions
+ ************************************************************/
+
+/************************************************************
+ * Function: pthread_kill
+ *
+ * Description:
+ * The pthread_kill() system call can be used to send any
+ * signal to a thread. See kill() for further information
+ * as this is just a simple wrapper around the kill()
+ * function.
+ *
+ * Parameters:
+ * thread - The id of the thread to receive the signal. Only
+ * positive, non-zero values of 'thread' are supported.
+ * signo - The signal number to send. If 'signo' is zero,
+ * no signal is sent, but all error checking is performed.
+ *
+ * Return Value:
+ * On success the signal was send and zero is returned.
+ * On error one of the following error numbers is returned.
+ *
+ * EINVAL An invalid signal was specified.
+ * EPERM The thread does not have permission to send the
+ * signal to the target thread.
+ * ESRCH No thread could be found corresponding to that
+ * specified by the given thread ID
+ * ENOSYS Do not support sending signals to process groups.
+ *
+ * Assumptions:
+ *
+ ************************************************************/
+
+int pthread_kill(pthread_t thread, int signo)
+{
+ int ret;
+
+ *get_errno_ptr() = EINVAL;
+ ret = kill((pid_t)thread, signo);
+ if (ret != OK)
+ {
+ ret = *get_errno_ptr();
+ }
+ return ret;
+}
+
+
diff --git a/nuttx/sched/pthread_once.c b/nuttx/sched/pthread_once.c
new file mode 100644
index 000000000..011c186f0
--- /dev/null
+++ b/nuttx/sched/pthread_once.c
@@ -0,0 +1,125 @@
+/********************************************************************************
+ * pthread_once.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>
+#include <sys/types.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Function: pthread_once
+ *
+ * Description:
+ * The first call to pthread_once() by any thread with a given once_control,
+ * will call the init_routine with no arguments. Subsequent calls to
+ * pthread_once() with the same once_control will have no effect. On return
+ * from pthread_once(), init_routine will have completed.
+ *
+ * Parameters:
+ * once_control - Determines if init_routine should be called. once_control
+ * should be declared and intialized as follows:
+ *
+ * pthread_once_t once_control = PTHREAD_ONCE_INIT;
+ *
+ * PTHREAD_ONCE_INIT is defined in pthread.h
+ * init_routine - The initialization routine that will be called once.
+ *
+ * Return Value:
+ * 0 (OK) on success or EINVAL if either once_control or init_routine are invalid
+ *
+ * Assumptions:
+ *
+ ********************************************************************************/
+
+int pthread_once(FAR pthread_once_t *once_control, CODE void (*init_routine)(void))
+{
+ /* Sanity checks */
+
+ if (once_control && init_routine)
+ {
+ /* Prohibit pre-emption while we test and set the once_control */
+
+ sched_lock();
+ if (!*once_control)
+ {
+ *once_control = TRUE;
+
+ /* Call the init_routine with pre-emption enabled. */
+
+ sched_unlock();
+ init_routine();
+ return OK;
+ }
+
+ /* The init_routine has already been called. Restore pre-emption and return */
+
+ sched_unlock();
+ return OK;
+ }
+
+ /* One of the two arguments is NULL */
+
+ return EINVAL;
+}
diff --git a/nuttx/sched/pthread_sigmask.c b/nuttx/sched/pthread_sigmask.c
new file mode 100644
index 000000000..02f318cea
--- /dev/null
+++ b/nuttx/sched/pthread_sigmask.c
@@ -0,0 +1,106 @@
+/************************************************************
+ * pthread_sigmask.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 <sys/types.h>
+#include <signal.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Type Declarations
+ ************************************************************/
+
+/************************************************************
+ * Global Variables
+ ************************************************************/
+
+/************************************************************
+ * Private Variables
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Function: pthread_sigmask
+ *
+ * Description:
+ * This function is a simple wrapper around sigprocmask().
+ * See the sigprocmask() function description for further
+ * information.
+ *
+ * Parameters:
+ * how - How the signal mast will be changed:
+ * SIG_BLOCK - The resulting set is the union of
+ * the current set and the signal set
+ * pointed to by 'set'.
+ * SIG_UNBLOCK - The resulting set is the intersection
+ * of the current set and the complement
+ * of the signal set pointed to by 'set'.
+ * SIG_SETMASK - The resulting set is the signal set
+ * pointed to by 'set'.
+ * set - Location of the new signal mask
+ * oset - Location to store the old signal mask
+ *
+ * Return Value:
+ * 0 (OK) or EINVAL if how is invalid.
+ *
+ * Assumptions:
+ *
+ ************************************************************/
+
+int pthread_sigmask(int how, FAR const sigset_t *set, FAR sigset_t *oset)
+{
+ int ret = sigprocmask(how, set, oset);
+ if (ret != OK)
+ {
+ ret = EINVAL;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/sig_kill.c b/nuttx/sched/sig_kill.c
index db9a73ba2..9e39a00e5 100644
--- a/nuttx/sched/sig_kill.c
+++ b/nuttx/sched/sig_kill.c
@@ -64,10 +64,12 @@
* information as zero and negative pid values. Only
* positive, non-zero values of pid are supported by this
* implementation.
- * signo - The signal number to send.
+ * signo - The signal number to send. If signo is zero,
+ * no signal is sent, but all error checking is performed.
+ *
*
* Return Value:
- * On success (at least one signal was sent), zero is
+ * On success (at least one signal was sent), zero is
* returned. On error, -1 is returned, and errno is set
* appropriately.
*
diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c
index 6b2a5c2ff..fb1c0b932 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -235,7 +235,7 @@ STATUS task_schedsetup(FAR _TCB *tcb, int priority,
*
************************************************************/
-STATUS task_argsetup(FAR _TCB *tcb, const char *name, char *argv[])
+STATUS task_argsetup(FAR _TCB *tcb, const char *name, const char *argv[])
{
int i;
diff --git a/nuttx/sched/timer_initialize.c b/nuttx/sched/timer_initialize.c
index a32189e89..a7acef5bf 100644
--- a/nuttx/sched/timer_initialize.c
+++ b/nuttx/sched/timer_initialize.c
@@ -150,10 +150,10 @@ void weak_function timer_deleteall(pid_t pid)
irqstate_t flags;
flags = irqsave();
- for (timer = g_alloctimers.head; timer; timer = next)
+ for (timer = (FAR struct posix_timer_s*)g_alloctimers.head; timer; timer = next)
{
next = timer->flink;
- if (timer->pt_owner = pid)
+ if (timer->pt_owner == pid)
{
timer_delete((timer_t)timer);
}