summaryrefslogtreecommitdiff
path: root/nuttx/sched/pthread
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-08-08 12:55:02 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-08-08 12:55:02 -0600
commit6516afc61128cf7f407e63d9761d64061de0ce41 (patch)
tree45c1ee2ee1f0085dd60e145a8a9acf1af68fda65 /nuttx/sched/pthread
parent6b08270554c627bd8034cfd772e4e40cde579648 (diff)
downloadpx4-nuttx-6516afc61128cf7f407e63d9761d64061de0ce41.tar.gz
px4-nuttx-6516afc61128cf7f407e63d9761d64061de0ce41.tar.bz2
px4-nuttx-6516afc61128cf7f407e63d9761d64061de0ce41.zip
Move all pthread files from sched/ to sched/pthread
Diffstat (limited to 'nuttx/sched/pthread')
-rw-r--r--nuttx/sched/pthread/pthread.h122
-rw-r--r--nuttx/sched/pthread/pthread_barrierdestroy.c110
-rw-r--r--nuttx/sched/pthread/pthread_barrierinit.c122
-rw-r--r--nuttx/sched/pthread/pthread_barrierwait.c182
-rw-r--r--nuttx/sched/pthread/pthread_cancel.c149
-rw-r--r--nuttx/sched/pthread/pthread_completejoin.c305
-rw-r--r--nuttx/sched/pthread/pthread_condbroadcast.c145
-rw-r--r--nuttx/sched/pthread/pthread_conddestroy.c88
-rw-r--r--nuttx/sched/pthread/pthread_condinit.c93
-rw-r--r--nuttx/sched/pthread/pthread_condsignal.c137
-rw-r--r--nuttx/sched/pthread/pthread_condtimedwait.c357
-rw-r--r--nuttx/sched/pthread/pthread_condwait.c137
-rw-r--r--nuttx/sched/pthread/pthread_create.c455
-rw-r--r--nuttx/sched/pthread/pthread_detach.c146
-rw-r--r--nuttx/sched/pthread/pthread_exit.c140
-rw-r--r--nuttx/sched/pthread/pthread_findjoininfo.c106
-rw-r--r--nuttx/sched/pthread/pthread_getschedparam.c139
-rw-r--r--nuttx/sched/pthread/pthread_getspecific.c128
-rw-r--r--nuttx/sched/pthread/pthread_initialize.c170
-rw-r--r--nuttx/sched/pthread/pthread_join.c255
-rw-r--r--nuttx/sched/pthread/pthread_keycreate.c141
-rw-r--r--nuttx/sched/pthread/pthread_keydelete.c96
-rw-r--r--nuttx/sched/pthread/pthread_kill.c95
-rw-r--r--nuttx/sched/pthread/pthread_mutexdestroy.c131
-rw-r--r--nuttx/sched/pthread/pthread_mutexinit.c138
-rw-r--r--nuttx/sched/pthread/pthread_mutexlock.c187
-rw-r--r--nuttx/sched/pthread/pthread_mutextrylock.c147
-rw-r--r--nuttx/sched/pthread/pthread_mutexunlock.c164
-rw-r--r--nuttx/sched/pthread/pthread_once.c128
-rw-r--r--nuttx/sched/pthread/pthread_release.c123
-rw-r--r--nuttx/sched/pthread/pthread_setcancelstate.c131
-rw-r--r--nuttx/sched/pthread/pthread_setschedparam.c142
-rw-r--r--nuttx/sched/pthread/pthread_setschedprio.c120
-rw-r--r--nuttx/sched/pthread/pthread_setspecific.c143
-rw-r--r--nuttx/sched/pthread/pthread_sigmask.c107
-rw-r--r--nuttx/sched/pthread/pthread_yield.c87
36 files changed, 5566 insertions, 0 deletions
diff --git a/nuttx/sched/pthread/pthread.h b/nuttx/sched/pthread/pthread.h
new file mode 100644
index 000000000..a436bd090
--- /dev/null
+++ b/nuttx/sched/pthread/pthread.h
@@ -0,0 +1,122 @@
+/****************************************************************************
+ * sched/pthread/pthread.h
+ *
+ * Copyright (C) 2007-2009, 2011, 2013-2014 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.
+ *
+ ****************************************************************************/
+
+#ifndef __SCHED_PTHREAD_PTHREAD_H
+#define __SCHED_PTHREAD_PTHREAD_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <pthread.h>
+#include <sched.h>
+
+#include <nuttx/compiler.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Type Declarations
+ ****************************************************************************/
+
+/* The following defines an entry in the pthread logic's local data set.
+ * Note that this structure is used to implemented a singly linked list.
+ * This structure is used (instead of, say, a binary search tree) because
+ * the data set will be searched using the pid as a key -- a process IDs will
+ * always be created in a montonically increasing fashion.
+ */
+
+struct join_s
+{
+ FAR struct join_s *next; /* Implements link list */
+ uint8_t crefs; /* Reference count */
+ bool started; /* true: pthread started. */
+ bool detached; /* true: pthread_detached'ed */
+ bool terminated; /* true: detach'ed+exit'ed */
+ pthread_t thread; /* Includes pid */
+ sem_t exit_sem; /* Implements join */
+ sem_t data_sem; /* Implements join */
+ pthread_addr_t exit_value; /* Returned data */
+};
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+struct pthread_tcb_s; /* Forward reference */
+struct task_group_s; /* Forward reference */
+
+void weak_function pthread_initialize(void);
+int pthread_schedsetup(FAR struct pthread_tcb_s *tcb, int priority, start_t start,
+ pthread_startroutine_t entry);
+int pthread_completejoin(pid_t pid, FAR void *exit_value);
+void pthread_destroyjoin(FAR struct task_group_s *group,
+ FAR struct join_s *pjoin);
+FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group,
+ pid_t pid);
+void pthread_release(FAR struct task_group_s *group);
+int pthread_givesemaphore(sem_t *sem);
+int pthread_takesemaphore(sem_t *sem);
+
+#ifdef CONFIG_MUTEX_TYPES
+int pthread_mutexattr_verifytype(int type);
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __SCHED_PTHREAD_PTHREAD_H */
+
diff --git a/nuttx/sched/pthread/pthread_barrierdestroy.c b/nuttx/sched/pthread/pthread_barrierdestroy.c
new file mode 100644
index 000000000..40e8e875c
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_barrierdestroy.c
@@ -0,0 +1,110 @@
+/********************************************************************************
+ * sched/pthread_barriedestroy.c
+ *
+ * Copyright (C) 2007, 2009 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 <pthread.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Name: 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/pthread_barrierinit.c b/nuttx/sched/pthread/pthread_barrierinit.c
new file mode 100644
index 000000000..73b974b18
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_barrierinit.c
@@ -0,0 +1,122 @@
+/********************************************************************************
+ * sched/pthread_barrieinit.c
+ *
+ * Copyright (C) 2007, 2009 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 <pthread.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Name: 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/pthread_barrierwait.c b/nuttx/sched/pthread/pthread_barrierwait.c
new file mode 100644
index 000000000..397c7bad2
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_barrierwait.c
@@ -0,0 +1,182 @@
+/********************************************************************************
+ * sched/pthread_barrierwait.c
+ *
+ * Copyright (C) 2007, 2009, 2014 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 <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
+ ********************************************************************************/
+
+/********************************************************************************
+ * Name: 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) >= (int)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();
+ 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/pthread_cancel.c b/nuttx/sched/pthread/pthread_cancel.c
new file mode 100644
index 000000000..1b9e1e572
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_cancel.c
@@ -0,0 +1,149 @@
+/**************************************************************************
+ * sched/pthread_cancel.c
+ *
+ * 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
+ * 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 <sys/types.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <errno.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+int pthread_cancel(pthread_t thread)
+{
+ struct tcb_s *tcb;
+
+ /* First, make sure that the handle references a valid thread */
+
+ if (!thread)
+ {
+ /* pid == 0 is the IDLE task. Callers cannot cancel the
+ * IDLE task.
+ */
+
+ return ESRCH;
+ }
+
+ tcb = sched_gettcb((pid_t)thread);
+ if (!tcb)
+ {
+ /* The pid does not correspond to any known thread. The thread
+ * has probably already exited.
+ */
+
+ return ESRCH;
+ }
+
+ /* Check to see if this thread has the non-cancelable bit set in its
+ * flags. Suppress context changes for a bit so that the flags are stable.
+ * (the flags should not change in interrupt handling.
+ */
+
+ sched_lock();
+ if ((tcb->flags & TCB_FLAG_NONCANCELABLE) != 0)
+ {
+ /* Then we cannot cancel the thread now. Here is how this is
+ * supposed to work:
+ *
+ * "When cancelability is disabled, all cancels are held pending
+ * in the target thread until the thread changes the cancelability.
+ * When cancelability is deferred, all cancels are held pending in
+ * the target thread until the thread changes the cancelability, calls
+ * a function which is a cancellation point or calls pthread_testcancel(),
+ * thus creating a cancellation point. When cancelability is asynchronous,
+ * all cancels are acted upon immediately, interrupting the thread with its
+ * processing."
+ */
+
+ tcb->flags |= TCB_FLAG_CANCEL_PENDING;
+ sched_unlock();
+ return OK;
+ }
+
+ sched_unlock();
+
+ /* Check to see if the ID refers to ourselves.. this would be the
+ * same as pthread_exit(PTHREAD_CANCELED).
+ */
+
+ if (tcb == (struct tcb_s*)g_readytorun.head)
+ {
+ pthread_exit(PTHREAD_CANCELED);
+ }
+
+ /* Complete pending join operations */
+
+ (void)pthread_completejoin((pid_t)thread, PTHREAD_CANCELED);
+
+ /* Then let pthread_delete do the real work */
+
+ task_delete((pid_t)thread);
+ return OK;
+}
+
diff --git a/nuttx/sched/pthread/pthread_completejoin.c b/nuttx/sched/pthread/pthread_completejoin.c
new file mode 100644
index 000000000..cfe65176f
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_completejoin.c
@@ -0,0 +1,305 @@
+/************************************************************************
+ * sched/pthread_completejoin.c
+ *
+ * Copyright (C) 2007, 2009, 2011, 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 <sys/types.h>
+#include <stdbool.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_notifywaiters
+ *
+ * Description:
+ * Notify all other threads waiting in phread join for this thread's
+ * exit data. This must be done by the child at child thread
+ * destruction time.
+ *
+ ************************************************************************/
+
+static bool pthread_notifywaiters(FAR struct join_s *pjoin)
+{
+ int ntasks_waiting;
+ int status;
+
+ svdbg("pjoin=0x%p\n", pjoin);
+
+ /* Are any tasks waiting for our exit value? */
+
+ status = sem_getvalue(&pjoin->exit_sem, &ntasks_waiting);
+ if (status == OK && ntasks_waiting < 0)
+ {
+ /* Set the data semaphore so that this thread will be
+ * awakened when all waiting tasks receive the data
+ */
+
+ (void)sem_init(&pjoin->data_sem, 0, (ntasks_waiting+1));
+
+ /* Post the semaphore to restart each thread that is waiting
+ * on the semaphore
+ */
+
+ do
+ {
+ status = pthread_givesemaphore(&pjoin->exit_sem);
+ if (status == OK)
+ {
+ status = sem_getvalue(&pjoin->exit_sem, &ntasks_waiting);
+ }
+ }
+ while (ntasks_waiting < 0 && status == OK);
+
+ /* Now wait for all these restarted tasks to obtain the return
+ * value.
+ */
+
+ (void)pthread_takesemaphore(&pjoin->data_sem);
+ return true;
+ }
+
+ return false;
+}
+
+/************************************************************************
+ * Name: pthread_removejoininfo
+ *
+ * Description:
+ * Remove a join structure from the local data set.
+ *
+ * Parameters:
+ * pid
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * The caller has provided protection from re-entrancy.
+ *
+ ************************************************************************/
+
+static void pthread_removejoininfo(FAR struct task_group_s *group,
+ pid_t pid)
+{
+ FAR struct join_s *prev;
+ FAR struct join_s *join;
+
+ /* Find the entry with the matching pid */
+
+ for (prev = NULL, join = group->tg_joinhead;
+ (join && (pid_t)join->thread != pid);
+ prev = join, join = join->next);
+
+ /* Remove it from the data set. */
+
+ /* First check if this is the entry at the head of the list. */
+
+ if (join)
+ {
+ if (!prev)
+ {
+ /* Check if this is the only entry in the list */
+
+ if (!join->next)
+ {
+ group->tg_joinhead = NULL;
+ group->tg_jointail = NULL;
+ }
+
+ /* Otherwise, remove it from the head of the list */
+
+ else
+ {
+ group->tg_joinhead = join->next;
+ }
+ }
+
+ /* It is not at the head of the list, check if it is at the tail. */
+
+ else if (!join->next)
+ {
+ group->tg_jointail = prev;
+ prev->next = NULL;
+ }
+
+ /* No, remove it from the middle of the list. */
+
+ else
+ {
+ prev->next = join->next;
+ }
+ }
+}
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_completejoin
+ *
+ * Description:
+ * A thread has been terminated -- either by returning, calling
+ * pthread_exit(), or through pthread_cancel(). In any event, we must
+ * complete any pending join events.
+ *
+ * Parameters:
+ * exit_value
+ *
+ * Returned Value:
+ * OK unless there is no join information associated with the pid.
+ * This could happen, for example, if a task started with task_create()
+ * calls pthread_exit().
+ *
+ * Assumptions:
+ *
+ ************************************************************************/
+
+int pthread_completejoin(pid_t pid, FAR void *exit_value)
+{
+ FAR struct task_group_s *group = task_getgroup(pid);
+ FAR struct join_s *pjoin;
+
+ svdbg("pid=%d exit_value=%p group=%p\n", pid, exit_value, group);
+ DEBUGASSERT(group);
+
+ /* First, find thread's structure in the private data set. */
+
+ (void)pthread_takesemaphore(&group->tg_joinsem);
+ pjoin = pthread_findjoininfo(group, pid);
+ if (!pjoin)
+ {
+ sdbg("Could not find join info, pid=%d\n", pid);
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+ return ERROR;
+ }
+ else
+ {
+ bool waiters;
+
+ /* Save the return exit value in the thread structure. */
+
+ pjoin->terminated = true;
+ pjoin->exit_value = exit_value;
+
+ /* Notify waiters of the availability of the exit value */
+
+ waiters = pthread_notifywaiters(pjoin);
+
+ /* If there are no waiters and if the thread is marked as detached.
+ * then discard the join information now. Otherwise, the pthread
+ * join logic will call pthread_destroyjoin() when all of the threads
+ * have sampled the exit value.
+ */
+
+ if (!waiters && pjoin->detached)
+ {
+ pthread_destroyjoin(group, pjoin);
+ }
+
+ /* Giving the following semaphore will allow the waiters
+ * to call pthread_destroyjoin.
+ */
+
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+ }
+
+ return OK;
+}
+
+/************************************************************************
+ * Name: pthread_destroyjoin
+ *
+ * Description:
+ * This is called from pthread_completejoin if the join info was
+ * detached or from pthread_join when the last waiting thread has
+ * received the thread exit info.
+ *
+ * Or it may never be called if the join info was never detached or if
+ * no thread ever calls pthread_join. In case, there is a memory leak!
+ *
+ * Assumptions:
+ * The caller holds tg_joinsem
+ *
+ ************************************************************************/
+
+void pthread_destroyjoin(FAR struct task_group_s *group,
+ FAR struct join_s *pjoin)
+{
+ sdbg("pjoin=0x%p\n", pjoin);
+
+ /* Remove the join info from the set of joins */
+
+ pthread_removejoininfo(group, (pid_t)pjoin->thread);
+
+ /* Destroy its semaphores */
+
+ (void)sem_destroy(&pjoin->data_sem);
+ (void)sem_destroy(&pjoin->exit_sem);
+
+ /* And deallocate the pjoin structure */
+
+ sched_kfree(pjoin);
+}
+
diff --git a/nuttx/sched/pthread/pthread_condbroadcast.c b/nuttx/sched/pthread/pthread_condbroadcast.c
new file mode 100644
index 000000000..1a7adae66
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_condbroadcast.c
@@ -0,0 +1,145 @@
+/****************************************************************************
+ * sched/pthread_condbroadcast.c
+ *
+ * Copyright (C) 2007-2009 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 <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_cond_broadcast
+ *
+ * Description:
+ * A thread broadcast on a condition variable.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_cond_broadcast(FAR pthread_cond_t *cond)
+{
+ int ret = OK;
+ int sval;
+
+ sdbg("cond=0x%p\n", cond);
+
+ if (!cond)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Disable pre-emption until all of the waiting threads have been
+ * restarted. This is necessary to assure that the sval behaves as
+ * expected in the following while loop
+ */
+
+ sched_lock();
+
+ /* Get the current value of the semaphore */
+
+ if (sem_getvalue((sem_t*)&cond->sem, &sval) != OK)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Loop until all of the waiting threads have been restarted. */
+
+ while (sval < 0)
+ {
+ /* If the value is less than zero (meaning that one or more
+ * thread is waiting), then post the condition semaphore.
+ * Only the highest priority waiting thread will get to execute
+ */
+
+ ret = pthread_givesemaphore((sem_t*)&cond->sem);
+
+ /* Increment the semaphore count (as was done by the
+ * above post).
+ */
+
+ sval++;
+ }
+ }
+
+ /* Now we can let the restarted threads run */
+
+ sched_unlock();
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
+
diff --git a/nuttx/sched/pthread/pthread_conddestroy.c b/nuttx/sched/pthread/pthread_conddestroy.c
new file mode 100644
index 000000000..0788aaf93
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_conddestroy.c
@@ -0,0 +1,88 @@
+/****************************************************************************
+ * sched/pthread_conddestroy.c
+ *
+ * Copyright (C) 2007-2009 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 <pthread.h>
+#include <debug.h>
+#include <errno.h>
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_cond_destroy
+ *
+ * Description:
+ * A thread can delete condition variables.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_cond_destroy(FAR pthread_cond_t *cond)
+{
+ int ret = OK;
+
+ sdbg("cond=0x%p\n", cond);
+
+ if (!cond)
+ {
+ ret = EINVAL;
+ }
+
+ /* Destroy the semaphore contained in the structure */
+
+ else if (sem_destroy((sem_t*)&cond->sem) != OK)
+ {
+ ret = EINVAL;
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
diff --git a/nuttx/sched/pthread/pthread_condinit.c b/nuttx/sched/pthread/pthread_condinit.c
new file mode 100644
index 000000000..84f7d0405
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_condinit.c
@@ -0,0 +1,93 @@
+/****************************************************************************
+ * sched/pthread_condinit.c
+ *
+ * Copyright (C) 2007-2009 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 <pthread.h>
+#include <debug.h>
+#include <errno.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_cond_init
+ *
+ * Description:
+ * A thread can create condition variables.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_cond_init(FAR pthread_cond_t *cond, FAR pthread_condattr_t *attr)
+{
+ int ret = OK;
+
+ sdbg("cond=0x%p attr=0x%p\n", cond, attr);
+
+ if (!cond)
+ {
+ ret = EINVAL;
+ }
+
+ /* Initialize the semaphore contained in the condition structure
+ * with initial count = 0
+ */
+
+ else if (sem_init((sem_t*)&cond->sem, 0, 0) != OK)
+ {
+ ret = EINVAL;
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
+
+
diff --git a/nuttx/sched/pthread/pthread_condsignal.c b/nuttx/sched/pthread/pthread_condsignal.c
new file mode 100644
index 000000000..5a6995b37
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_condsignal.c
@@ -0,0 +1,137 @@
+/****************************************************************************
+ * sched/pthread_condsignal.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 <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_cond_signal
+ *
+ * Description:
+ * A thread can signal on a condition variable.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_cond_signal(FAR pthread_cond_t *cond)
+{
+ int ret = OK;
+ int sval;
+
+ sdbg("cond=0x%p\n", cond);
+
+ if (!cond)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Get the current value of the semaphore */
+
+ if (sem_getvalue((sem_t*)&cond->sem, &sval) != OK)
+ {
+ ret = EINVAL;
+ }
+
+ /* If the value is less than zero (meaning that one or more
+ * thread is waiting), then post the condition semaphore.
+ * Only the highest priority waiting thread will get to execute
+ */
+
+ else
+ {
+ /* One of my objectives in this design was to make pthread_cond_signal
+ * usable from interrupt handlers. However, from interrupt handlers,
+ * you cannot take the associated mutex before signaling the condition.
+ * As a result, I think that there could be a race condition with
+ * the following logic which assumes that the if sval < 0 then the
+ * thread is waiting. Without the mutex, there is no atomic, protected
+ * operation that will guarantee this to be so.
+ */
+
+ sdbg("sval=%d\n", sval);
+ if (sval < 0)
+ {
+ sdbg("Signalling...\n");
+ ret = pthread_givesemaphore((sem_t*)&cond->sem);
+ }
+ }
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
+
diff --git a/nuttx/sched/pthread/pthread_condtimedwait.c b/nuttx/sched/pthread/pthread_condtimedwait.c
new file mode 100644
index 000000000..3cc4dc4ee
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_condtimedwait.c
@@ -0,0 +1,357 @@
+/****************************************************************************
+ * sched/pthread_condtimedwait.c
+ *
+ * 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
+ * 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 <nuttx/compiler.h>
+
+#include <stdint.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <signal.h>
+#include <time.h>
+#include <errno.h>
+#include <assert.h>
+#include <wdog.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+#include "clock_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_condtimedout
+ *
+ * Description:
+ * This function is called if the timeout elapses before
+ * the condition is signaled.
+ *
+ * Parameters:
+ * argc - the number of arguments (should be 2)
+ * pid - the task ID of the task to wakeup
+ * signo - The signal to use to wake up the task
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void pthread_condtimedout(int argc, uint32_t pid, uint32_t signo)
+{
+#ifdef HAVE_GROUP_MEMBERS
+
+ FAR struct tcb_s *tcb;
+ siginfo_t info;
+
+ /* The logic below if equivalent to sigqueue(), but uses sig_tcbdispatch()
+ * instead of sig_dispatch(). This avoids the group signal deliver logic
+ * and assures, instead, that the signal is delivered specifically to this
+ * thread that is known to be waiting on the signal.
+ */
+
+ /* Get the waiting TCB. sched_gettcb() might return NULL if the task has
+ * exited for some reason.
+ */
+
+ tcb = sched_gettcb((pid_t)pid);
+ if (tcb)
+ {
+ /* Create the siginfo structure */
+
+ info.si_signo = signo;
+ info.si_code = SI_QUEUE;
+ info.si_value.sival_ptr = NULL;
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = (pid_t)pid;
+ info.si_status = OK;
+#endif
+
+ /* Process the receipt of the signal. The scheduler is not locked as
+ * is normally the case when this function is called because we are in
+ * a watchdog timer interrupt handler.
+ */
+
+ (void)sig_tcbdispatch(tcb, &info);
+ }
+
+#else /* HAVE_GROUP_MEMBERS */
+
+ /* Things are a little easier if there are not group members. We can just
+ * use sigqueue().
+ */
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ union sigval value;
+
+ /* Send the specified signal to the specified task. */
+
+ value.sival_ptr = NULL;
+ (void)sigqueue((int)pid, (int)signo, value);
+#else
+ (void)sigqueue((int)pid, (int)signo, NULL);
+#endif
+
+#endif /* HAVE_GROUP_MEMBERS */
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_cond_timedwait
+ *
+ * Description:
+ * A thread can perform a timed wait on a condition variable.
+ *
+ * Parameters:
+ * cond - the condition variable to wait on
+ * mutex - the mutex that protects the condition variable
+ * abstime - wait until this absolute time
+ *
+ * Return Value:
+ * OK (0) on success; ERROR (-1) on failure with errno
+ * set appropriately.
+ *
+ * Assumptions:
+ * Timing is of resolution 1 msec, with +/-1 millisecond
+ * accuracy.
+ *
+ ****************************************************************************/
+
+int pthread_cond_timedwait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex,
+ FAR const struct timespec *abstime)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s *)g_readytorun.head;
+ int ticks;
+ int mypid = (int)getpid();
+ irqstate_t int_state;
+ int ret = OK;
+ int status;
+
+ sdbg("cond=0x%p mutex=0x%p abstime=0x%p\n", cond, mutex, abstime);
+
+ DEBUGASSERT(rtcb->waitdog == NULL);
+
+ /* Make sure that non-NULL references were provided. */
+
+ if (!cond || !mutex)
+ {
+ ret = EINVAL;
+ }
+
+ /* Make sure that the caller holds the mutex */
+
+ else if (mutex->pid != mypid)
+ {
+ ret = EPERM;
+ }
+
+ /* If no wait time is provided, this function degenerates to
+ * the same behavior as pthread_cond_wait().
+ */
+
+ else if (!abstime)
+ {
+ ret = pthread_cond_wait(cond, mutex);
+ }
+
+ else
+ {
+ /* Create a watchdog */
+
+ rtcb->waitdog = wd_create();
+ if (!rtcb->waitdog)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ sdbg("Give up mutex...\n");
+
+ /* We must disable pre-emption and interrupts here so that
+ * the time stays valid until the wait begins. This adds
+ * complexity because we assure that interrupts and
+ * pre-emption are re-enabled correctly.
+ */
+
+ sched_lock();
+ int_state = irqsave();
+
+ /* Convert the timespec to clock ticks. We must disable pre-emption
+ * here so that this time stays valid until the wait begins.
+ */
+
+ ret = clock_abstime2ticks(CLOCK_REALTIME, abstime, &ticks);
+ if (ret)
+ {
+ /* Restore interrupts (pre-emption will be enabled when
+ * we fall through the if/then/else
+ */
+
+ irqrestore(int_state);
+ }
+ else
+ {
+ /* Check the absolute time to wait. If it is now or in the past, then
+ * just return with the timedout condition.
+ */
+
+ if (ticks <= 0)
+ {
+ /* Restore interrupts and indicate that we have already timed out.
+ * (pre-emption will be enabled when we fall through the
+ * if/then/else
+ */
+
+ irqrestore(int_state);
+ ret = ETIMEDOUT;
+ }
+ else
+ {
+ /* Give up the mutex */
+
+ mutex->pid = 0;
+ ret = pthread_givesemaphore((sem_t*)&mutex->sem);
+ if (ret)
+ {
+ /* Restore interrupts (pre-emption will be enabled when
+ * we fall through the if/then/else)
+ */
+
+ irqrestore(int_state);
+ }
+ else
+ {
+ /* Start the watchdog */
+
+ wd_start(rtcb->waitdog, ticks, (wdentry_t)pthread_condtimedout,
+ 2, (uint32_t)mypid, (uint32_t)SIGCONDTIMEDOUT);
+
+ /* Take the condition semaphore. Do not restore interrupts
+ * until we return from the wait. This is necessary to
+ * make sure that the watchdog timer and the condition wait
+ * are started atomically.
+ */
+
+ status = sem_wait((sem_t*)&cond->sem);
+
+ /* Did we get the condition semaphore. */
+
+ if (status != OK)
+ {
+ /* NO.. Handle the special case where the semaphore wait was
+ * awakened by the receipt of a signal -- presumably the
+ * signal posted by pthread_condtimedout().
+ */
+
+ if (get_errno() == EINTR)
+ {
+ sdbg("Timedout!\n");
+ ret = ETIMEDOUT;
+ }
+ else
+ {
+ ret = EINVAL;
+ }
+ }
+
+ /* The interrupts stay disabled until after we sample the errno.
+ * This is because when debug is enabled and the console is used
+ * for debug output, then the errno can be altered by interrupt
+ * handling! (bad)
+ */
+
+ irqrestore(int_state);
+ }
+
+ /* Reacquire the mutex (retaining the ret). */
+
+ sdbg("Re-locking...\n");
+ status = pthread_takesemaphore((sem_t*)&mutex->sem);
+ if (!status)
+ {
+ mutex->pid = mypid;
+ }
+ else if (!ret)
+ {
+ ret = status;
+ }
+ }
+
+ /* Re-enable pre-emption (It is expected that interrupts
+ * have already been re-enabled in the above logic)
+ */
+
+ sched_unlock();
+ }
+
+ /* We no longer need the watchdog */
+
+ wd_delete(rtcb->waitdog);
+ rtcb->waitdog = NULL;
+ }
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
diff --git a/nuttx/sched/pthread/pthread_condwait.c b/nuttx/sched/pthread/pthread_condwait.c
new file mode 100644
index 000000000..9665193f5
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_condwait.c
@@ -0,0 +1,137 @@
+/****************************************************************************
+ * sched/pthread_condwait.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 <unistd.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: int pthread_cond_wait
+ *
+ * Description:
+ * A thread can wait for a condition variable to be signalled or broadcast.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_cond_wait(FAR pthread_cond_t *cond, FAR pthread_mutex_t *mutex)
+{
+ int ret;
+
+ sdbg("cond=0x%p mutex=0x%p\n", cond, mutex);
+
+ /* Make sure that non-NULL references were provided. */
+
+ if (!cond || !mutex)
+ {
+ ret = EINVAL;
+ }
+
+ /* Make sure that the caller holds the mutex */
+
+ else if (mutex->pid != (int)getpid())
+ {
+ ret = EPERM;
+ }
+ else
+ {
+ /* Give up the mutex */
+
+ sdbg("Give up mutex / take cond\n");
+
+ sched_lock();
+ mutex->pid = 0;
+ ret = pthread_givesemaphore((sem_t*)&mutex->sem);
+
+ /* Take the semaphore */
+
+ ret |= pthread_takesemaphore((sem_t*)&cond->sem);
+ sched_unlock();
+
+ /* Reacquire the mutex */
+
+ sdbg("Reacquire mutex...\n");
+ ret |= pthread_takesemaphore((sem_t*)&mutex->sem);
+ if (!ret)
+ {
+ mutex->pid = getpid();;
+ }
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
diff --git a/nuttx/sched/pthread/pthread_create.c b/nuttx/sched/pthread/pthread_create.c
new file mode 100644
index 000000000..1484ef634
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_create.c
@@ -0,0 +1,455 @@
+/****************************************************************************
+ * sched/pthread_create.c
+ *
+ * Copyright (C) 2007-2009, 2011, 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 <sys/types.h>
+#include <stdbool.h>
+#include <string.h>
+#include <pthread.h>
+#include <sched.h>
+#include <debug.h>
+#include <errno.h>
+#include <queue.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/pthread.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "clock_internal.h"
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/* Default pthread attributes */
+
+pthread_attr_t g_default_pthread_attr = PTHREAD_ATTR_INITIALIZER;
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/* This is the name for name-less pthreads */
+
+static const char g_pthreadname[] = "<pthread>";
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_argsetup
+ *
+ * Description:
+ * This functions sets up parameters in the Task Control Block (TCB) in
+ * preparation for starting a new thread.
+ *
+ * pthread_argsetup() is called from task_init() and task_start() to create
+ * a new task (with arguments cloned via strdup) or pthread_create() which
+ * has one argument passed by value (distinguished by the pthread boolean
+ * argument).
+ *
+ * Input Parameters:
+ * tcb - Address of the new task's TCB
+ * arg - The argument to provide to the pthread on startup.
+ *
+ * Return Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void pthread_argsetup(FAR struct pthread_tcb_s *tcb, pthread_addr_t arg)
+{
+#if CONFIG_TASK_NAME_SIZE > 0
+ /* Copy the pthread name into the TCB */
+
+ strncpy(tcb->cmn.name, g_pthreadname, CONFIG_TASK_NAME_SIZE);
+#endif /* CONFIG_TASK_NAME_SIZE */
+
+ /* For pthreads, args are strictly pass-by-value; that actual
+ * type wrapped by pthread_addr_t is unknown.
+ */
+
+ tcb->arg = arg;
+}
+
+/****************************************************************************
+ * Name: pthread_addjoininfo
+ *
+ * Description:
+ * Add a join structure to the local data set.
+ *
+ * Parameters:
+ * pjoin
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * The caller has provided protection from re-entrancy.
+ *
+ ****************************************************************************/
+
+static inline void pthread_addjoininfo(FAR struct task_group_s *group,
+ FAR struct join_s *pjoin)
+{
+ pjoin->next = NULL;
+ if (!group->tg_jointail)
+ {
+ group->tg_joinhead = pjoin;
+ }
+ else
+ {
+ group->tg_jointail->next = pjoin;
+ }
+
+ group->tg_jointail = pjoin;
+}
+
+/****************************************************************************
+ * Name: pthread_start
+ *
+ * Description:
+ * This function is the low level entry point into the pthread
+ *
+ * Parameters:
+ * None
+ *
+ ****************************************************************************/
+
+static void pthread_start(void)
+{
+ FAR struct pthread_tcb_s *ptcb = (FAR struct pthread_tcb_s*)g_readytorun.head;
+ FAR struct task_group_s *group = ptcb->cmn.group;
+ FAR struct join_s *pjoin = (FAR struct join_s*)ptcb->joininfo;
+ pthread_addr_t exit_status;
+
+ DEBUGASSERT(group && pjoin);
+
+ /* Sucessfully spawned, add the pjoin to our data set. */
+
+ (void)pthread_takesemaphore(&group->tg_joinsem);
+ pthread_addjoininfo(group, pjoin);
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+
+ /* Report to the spawner that we successfully started. */
+
+ pjoin->started = true;
+ (void)pthread_givesemaphore(&pjoin->data_sem);
+
+ /* Pass control to the thread entry point. In the kernel build this has to
+ * be handled differently if we are starting a user-space pthread; we have
+ * to switch to user-mode before calling into the pthread.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ up_pthread_start(ptcb->cmn.entry.pthread, ptcb->arg);
+ exit_status = NULL;
+#else
+ exit_status = (*ptcb->cmn.entry.pthread)(ptcb->arg);
+#endif
+
+ /* The thread has returned (should never happen in the kernel mode case) */
+
+ pthread_exit(exit_status);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_create
+ *
+ * Description:
+ * This function creates and activates a new thread with a specified
+ * attributes.
+ *
+ * Input Parameters:
+ * thread
+ * attr
+ * start_routine
+ * arg
+ *
+ * Returned value:
+ * OK (0) on success; a (non-negated) errno value on failure. The errno
+ * variable is not set.
+ *
+ ****************************************************************************/
+
+int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
+ pthread_startroutine_t start_routine, pthread_addr_t arg)
+{
+ FAR struct pthread_tcb_s *ptcb;
+ FAR struct join_s *pjoin;
+ int priority;
+#if CONFIG_RR_INTERVAL > 0
+ int policy;
+#endif
+ int errcode;
+ pid_t pid;
+ int ret;
+
+ /* If attributes were not supplied, use the default attributes */
+
+ if (!attr)
+ {
+ attr = &g_default_pthread_attr;
+ }
+
+ /* Allocate a TCB for the new task. */
+
+ ptcb = (FAR struct pthread_tcb_s *)kzalloc(sizeof(struct pthread_tcb_s));
+ if (!ptcb)
+ {
+ sdbg("ERROR: Failed to allocate TCB\n");
+ return ENOMEM;
+ }
+
+ /* Bind the parent's group to the new TCB (we have not yet joined the
+ * group).
+ */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_bind(ptcb);
+ if (ret < 0)
+ {
+ errcode = ENOMEM;
+ goto errout_with_tcb;
+ }
+#endif
+
+ /* Share the address environment of the parent task. NOTE: Only tasks
+ * created throught the nuttx/binfmt loaders may have an address
+ * environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_share((FAR const struct tcb_s *)g_readytorun.head,
+ (FAR struct tcb_s *)ptcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_tcb;
+ }
+#endif
+
+ /* Allocate a detachable structure to support pthread_join logic */
+
+ pjoin = (FAR struct join_s*)kzalloc(sizeof(struct join_s));
+ if (!pjoin)
+ {
+ sdbg("ERROR: Failed to allocate join\n");
+ errcode = ENOMEM;
+ goto errout_with_tcb;
+ }
+
+ /* Allocate the stack for the TCB */
+
+ ret = up_create_stack((FAR struct tcb_s *)ptcb, attr->stacksize,
+ TCB_FLAG_TTYPE_PTHREAD);
+ if (ret != OK)
+ {
+ errcode = ENOMEM;
+ goto errout_with_join;
+ }
+
+ /* Should we use the priority and scheduler specified in the
+ * pthread attributes? Or should we use the current thread's
+ * priority and scheduler?
+ */
+
+ if (attr->inheritsched == PTHREAD_INHERIT_SCHED)
+ {
+ struct sched_param param;
+
+ /* Get the priority for this thread. */
+
+ ret = sched_getparam(0, &param);
+ if (ret == OK)
+ {
+ priority = param.sched_priority;
+ }
+ else
+ {
+ priority = SCHED_FIFO;
+ }
+
+ /* Get the scheduler policy for this thread */
+
+#if CONFIG_RR_INTERVAL > 0
+ policy = sched_getscheduler(0);
+ if (policy == ERROR)
+ {
+ policy = SCHED_FIFO;
+ }
+#endif
+ }
+ else
+ {
+ /* Use the priority and scheduler from the attributes */
+
+ priority = attr->priority;
+#if CONFIG_RR_INTERVAL > 0
+ policy = attr->policy;
+#endif
+ }
+
+ /* Initialize the task control block */
+
+ ret = pthread_schedsetup(ptcb, priority, pthread_start, start_routine);
+ if (ret != OK)
+ {
+ errcode = EBUSY;
+ goto errout_with_join;
+ }
+
+ /* Configure the TCB for a pthread receiving on parameter
+ * passed by value
+ */
+
+ pthread_argsetup(ptcb, arg);
+
+ /* Join the parent's task group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_join(ptcb);
+ if (ret < 0)
+ {
+ errcode = ENOMEM;
+ goto errout_with_join;
+ }
+#endif
+
+ /* Attach the join info to the TCB. */
+
+ ptcb->joininfo = (FAR void *)pjoin;
+
+ /* If round robin scheduling is selected, set the appropriate flag
+ * in the TCB.
+ */
+
+#if CONFIG_RR_INTERVAL > 0
+ if (policy == SCHED_RR)
+ {
+ ptcb->cmn.flags |= TCB_FLAG_ROUND_ROBIN;
+ ptcb->cmn.timeslice = MSEC2TICK(CONFIG_RR_INTERVAL);
+ }
+#endif
+
+ /* Get the assigned pid before we start the task (who knows what
+ * could happen to ptcb after this!). Copy this ID into the join structure
+ * as well.
+ */
+
+ pid = (int)ptcb->cmn.pid;
+ pjoin->thread = (pthread_t)pid;
+
+ /* Initialize the semaphores in the join structure to zero. */
+
+ ret = sem_init(&pjoin->data_sem, 0, 0);
+ if (ret == OK)
+ {
+ ret = sem_init(&pjoin->exit_sem, 0, 0);
+ }
+
+ /* Activate the task */
+
+ sched_lock();
+ if (ret == OK)
+ {
+ ret = task_activate((FAR struct tcb_s *)ptcb);
+ }
+
+ if (ret == OK)
+ {
+ /* Wait for the task to actually get running and to register
+ * its join structure.
+ */
+
+ (void)pthread_takesemaphore(&pjoin->data_sem);
+
+ /* Return the thread information to the caller */
+
+ if (thread)
+ {
+ *thread = (pthread_t)pid;
+ }
+
+ if (!pjoin->started)
+ {
+ ret = EINVAL;
+ }
+
+ sched_unlock();
+ (void)sem_destroy(&pjoin->data_sem);
+ }
+ else
+ {
+ sched_unlock();
+ dq_rem((FAR dq_entry_t*)ptcb, (dq_queue_t*)&g_inactivetasks);
+ (void)sem_destroy(&pjoin->data_sem);
+ (void)sem_destroy(&pjoin->exit_sem);
+
+ errcode = EIO;
+ goto errout_with_join;
+ }
+
+ return ret;
+
+errout_with_join:
+ sched_kfree(pjoin);
+ ptcb->joininfo = NULL;
+
+errout_with_tcb:
+ sched_releasetcb((FAR struct tcb_s *)ptcb, TCB_FLAG_TTYPE_PTHREAD);
+ return errcode;
+}
diff --git a/nuttx/sched/pthread/pthread_detach.c b/nuttx/sched/pthread/pthread_detach.c
new file mode 100644
index 000000000..5b7f4a611
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_detach.c
@@ -0,0 +1,146 @@
+/************************************************************************
+ * sched/pthread_detach.c
+ *
+ * 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
+ * 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 <sys/types.h>
+#include <stdbool.h>
+#include <pthread.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_detach
+ *
+ * Description:
+ * A thread object may be "detached" to specify that the return value
+ * and completion status will not be requested.
+ *
+ * The caller's task/thread must belong to the same "task group" as the
+ * pthread is (or was) a member of. The thread may or may not still
+ * be running.
+ *
+ * Parameters:
+ * thread
+ *
+ * Return Value:
+ * 0 if successful. Otherwise, an error code.
+ *
+ * Assumptions:
+ *
+ ************************************************************************/
+
+int pthread_detach(pthread_t thread)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s *)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->group;
+ FAR struct join_s *pjoin;
+ int ret;
+
+ sdbg("Thread=%d group=%p\n", thread, group);
+ DEBUGASSERT(group);
+
+ /* Find the entry associated with this pthread. */
+
+ (void)pthread_takesemaphore(&group->tg_joinsem);
+ pjoin = pthread_findjoininfo(group, (pid_t)thread);
+ if (!pjoin)
+ {
+ sdbg("Could not find thread entry\n");
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Has the thread already terminated? */
+
+ if (pjoin->terminated)
+ {
+ /* YES.. just remove the thread entry. */
+
+ pthread_destroyjoin(group, pjoin);
+ }
+ else
+ {
+ /* NO.. Just mark the thread as detached. It
+ * will be removed and deallocated when the
+ * thread exits
+ */
+
+ pjoin->detached = true;
+ }
+
+ /* Either case is successful */
+
+ ret = OK;
+ }
+
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_exit.c b/nuttx/sched/pthread/pthread_exit.c
new file mode 100644
index 000000000..8e5c39670
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_exit.c
@@ -0,0 +1,140 @@
+/************************************************************************
+ * sched/pthread_exit.c
+ *
+ * Copyright (C) 2007, 2009, 2011-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 <stdint.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <signal.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_exit
+ *
+ * Description:
+ * Terminate execution of a thread started with pthread_create.
+ *
+ * Parameters:
+ * exit_valie
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ************************************************************************/
+
+void pthread_exit(FAR void *exit_value)
+{
+ struct tcb_s *tcb = (struct tcb_s*)g_readytorun.head;
+ int status;
+
+ sdbg("exit_value=%p\n", exit_value);
+
+ /* Block any signal actions that would awaken us while were
+ * are performing the JOIN handshake.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ {
+ sigset_t set = ALL_SIGNAL_SET;
+ (void)sigprocmask(SIG_SETMASK, &set, NULL);
+ }
+#endif
+
+ /* Complete pending join operations */
+
+ status = pthread_completejoin(getpid(), exit_value);
+ if (status != OK)
+ {
+ /* Assume that the join completion failured because this
+ * not really a pthread. Exit by calling exit().
+ */
+
+ exit(EXIT_FAILURE);
+ }
+
+ /* Perform common task termination logic. This will get called again later
+ * through logic kicked off by _exit(). However, we need to call it before
+ * calling _exit() in order certain operations if this is the last thread
+ * of a task group: (2) To handle atexit() and on_exit() callbacks and
+ * (2) so that we can flush buffered I/O (which may required suspending).
+ */
+
+ task_exithook(tcb, EXIT_SUCCESS, false);
+
+ /* Then just exit, retaining all file descriptors and without
+ * calling atexit() functions.
+ */
+
+ _exit(EXIT_SUCCESS);
+}
+
diff --git a/nuttx/sched/pthread/pthread_findjoininfo.c b/nuttx/sched/pthread/pthread_findjoininfo.c
new file mode 100644
index 000000000..0f49becfe
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_findjoininfo.c
@@ -0,0 +1,106 @@
+/************************************************************************
+ * pthread_findjoininfo.c
+ *
+ * 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
+ * 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 <sys/types.h>
+
+#include "group_internal.h"
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: thread_findjoininfo
+ *
+ * Description:
+ * Find a join structure in a local data set.
+ *
+ * Parameters:
+ * group - The that the pid is (or was) a member of of
+ * pid - The ID of the pthread
+ *
+ * Return Value:
+ * None or pointer to the found entry.
+ *
+ * Assumptions:
+ * The caller has provided protection from re-entrancy.
+ *
+ ************************************************************************/
+
+FAR struct join_s *pthread_findjoininfo(FAR struct task_group_s *group,
+ pid_t pid)
+{
+ FAR struct join_s *pjoin;
+
+ DEBUGASSERT(group);
+
+ /* Find the entry with the matching pid */
+
+ for (pjoin = group->tg_joinhead;
+ (pjoin && (pid_t)pjoin->thread != pid);
+ pjoin = pjoin->next);
+
+ /* and return it */
+
+ return pjoin;
+}
+
diff --git a/nuttx/sched/pthread/pthread_getschedparam.c b/nuttx/sched/pthread/pthread_getschedparam.c
new file mode 100644
index 000000000..9c0743020
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_getschedparam.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * pthread_getschedparam.c
+ *
+ * Copyright (C) 2007, 2008 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 <sys/types.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_getschedparam
+ *
+ * Description:
+ * The pthread_getschedparam() functions will get the scheduling policy and
+ * parameters of threads. For SCHED_FIFO and SCHED_RR, the only required
+ * member of the sched_param structure is the priority sched_priority.
+ *
+ * The pthread_getschedparam() function will retrieve the scheduling
+ * policy and scheduling parameters for the thread whose thread ID is
+ * given by 'thread' and will store those values in 'policy' and 'param',
+ * respectively. The priority value returned from pthread_getschedparam()
+ * will be the value specified by the most recent pthread_setschedparam(),
+ * pthread_setschedprio(), or pthread_create() call affecting the target
+ * thread. It will not reflect any temporary adjustments to its priority
+ * (such as might result of any priority inheritance, for example).
+ *
+ * The policy parameter may have the value SCHED_FIFO, or SCHED_RR
+ * (SCHED_OTHER and SCHED_SPORADIC, in particular, are not supported).
+ * The SCHED_FIFO and SCHED_RR policies will have a single scheduling
+ * parameter, sched_priority.
+*
+ * Parameters:
+ * thread - The ID of thread whose scheduling parameters will be queried.
+ * policy - The location to store the thread's scheduling policy.
+ * param - The location to store the thread's priority.
+ *
+ * Return Value:
+ * 0 if successful. Otherwise, the error code ESRCH if the value specified
+ * by thread does not refer to an existing thread.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_getschedparam(pthread_t thread, FAR int *policy,
+ FAR struct sched_param *param)
+{
+ int ret;
+
+ sdbg("Thread ID=%d policy=0x%p param=0x%p\n", thread, policy, param);
+
+ if (!policy || !param)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Get the schedparams of the thread. */
+
+ ret = sched_getparam((pid_t)thread, param);
+ if (ret != OK)
+ {
+ ret = EINVAL;
+ }
+
+ /* Return the policy. */
+
+ *policy = sched_getscheduler((pid_t)thread);
+ if (*policy == ERROR)
+ {
+ ret = get_errno();
+ }
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
diff --git a/nuttx/sched/pthread/pthread_getspecific.c b/nuttx/sched/pthread/pthread_getspecific.c
new file mode 100644
index 000000000..dbed372d5
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_getspecific.c
@@ -0,0 +1,128 @@
+/************************************************************************
+ * sched/pthread_getspecific.c
+ *
+ * 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
+ * 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 <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_getspecific
+ *
+ * Description:
+ * The pthread_getspecific() function returns the value currently
+ * bound to the specified key on behalf of the calling thread.
+ *
+ * The effect of calling pthread_getspecific() with with a key value
+ * not obtained from pthread_create() or after a key has been deleted
+ * with pthread_key_delete() is undefined.
+ *
+ * Parameters:
+ * key = The data key to get or set
+ *
+ * Return Value:
+ * The function pthread_getspecific() returns the thread-specific data
+ * associated with the given key. If no thread specific data is
+ * associated with the key, then the value NULL is returned.
+ *
+ * EINVAL - The key value is invalid.
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ * - Both calling pthread_setspecific() and pthread_getspecific()
+ * may be called from a thread-specific data destructor
+ * function.
+ *
+ ************************************************************************/
+
+FAR void *pthread_getspecific(pthread_key_t key)
+{
+#if CONFIG_NPTHREAD_KEYS > 0
+ FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s*)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->cmn.group;
+ FAR void *ret = NULL;
+
+ DEBUGASSERT(group &&
+ (rtcb->cmn.flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_PTHREAD);
+
+ /* Check if the key is valid. */
+
+ if (key < group->tg_nkeys)
+ {
+ /* Return the stored value. */
+
+ ret = rtcb->pthread_data[key];
+ }
+
+ return ret;
+#else
+ return NULL;
+#endif
+}
+
diff --git a/nuttx/sched/pthread/pthread_initialize.c b/nuttx/sched/pthread/pthread_initialize.c
new file mode 100644
index 000000000..cde71429e
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_initialize.c
@@ -0,0 +1,170 @@
+/****************************************************************************
+ * sched/pthread_initialize.c
+ *
+ * Copyright (C) 2007-2010, 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 <stdint.h>
+#include <semaphore.h>
+#include <errno.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_initialize
+ *
+ * Description:
+ * This is an internal OS function called only at power-up boot time. It
+ * no longer does anything since all of the pthread data structures have
+ * been moved into the "task group"
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void pthread_initialize(void)
+{
+}
+
+/****************************************************************************
+ * Name: pthread_takesemaphore and pthread_givesemaphore
+ *
+ * Description:
+ * Support managed access to the private data sets.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * 0 on success or an ERROR on failure with errno value set to EINVAL.
+ * Note that the errno EINTR is never returned by this function.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_takesemaphore(sem_t *sem)
+{
+ /* Verify input parameters */
+
+ if (sem)
+ {
+ /* Take the semaphore */
+
+ while (sem_wait(sem) != OK)
+ {
+ /* Handle the special case where the semaphore wait was
+ * awakened by the receipt of a signal.
+ */
+
+ if (get_errno() != EINTR)
+ {
+ set_errno(EINVAL);
+ return ERROR;
+ }
+ }
+ return OK;
+ }
+ else
+ {
+ /* NULL semaphore pointer! */
+
+ set_errno(EINVAL);
+ return ERROR;
+ }
+}
+
+int pthread_givesemaphore(sem_t *sem)
+{
+ /* Verify input parameters */
+
+ if (sem)
+ {
+ /* Give the semaphore */
+
+ if (sem_post(sem) == OK)
+ {
+ return OK;
+ }
+ else
+ {
+ /* sem_post() reported an error */
+
+ set_errno(EINVAL);
+ return ERROR;
+ }
+ }
+ else
+ {
+ /* NULL semaphore pointer! */
+
+ set_errno(EINVAL);
+ return ERROR;
+ }
+}
+
diff --git a/nuttx/sched/pthread/pthread_join.c b/nuttx/sched/pthread/pthread_join.c
new file mode 100644
index 000000000..3aeb133f3
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_join.c
@@ -0,0 +1,255 @@
+/****************************************************************************
+ * pthread_join.c
+ *
+ * Copyright (C) 2007, 2008, 2011, 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 <sys/types.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_join
+ *
+ * Description:
+ * A thread can await termination of another thread and retrieve the
+ * return value of the thread.
+ *
+ * The caller's task/thread must belong to the same "task group" as the
+ * pthread is (or was) a member of. The thread may or may not still
+ * be running.
+ *
+ * Parameters:
+ * thread
+ * pexit_value
+ *
+ * Return Value:
+ * 0 if successful. Otherwise, one of the following error codes:
+ *
+ * EINVAL The value specified by thread does not refer to joinable
+ * thread.
+ * ESRCH No thread could be found corresponding to that specified by the
+ * given thread ID.
+ * EDEADLK A deadlock was detected or the value of thread specifies the
+ * calling thread.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s *)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->group;
+ FAR struct join_s *pjoin;
+ int ret;
+
+ sdbg("thread=%d group=%p\n", thread, group);
+ DEBUGASSERT(group);
+
+ /* First make sure that this is not an attempt to join to
+ * ourself.
+ */
+
+ if ((pid_t)thread == getpid())
+ {
+ return EDEADLK;
+ }
+
+ /* Make sure no other task is mucking with the data structures
+ * while we are performing the following operations. NOTE:
+ * we can be also sure that pthread_exit() will not execute
+ * because it will also attempt to get this semaphore.
+ */
+
+ (void)pthread_takesemaphore(&group->tg_joinsem);
+
+ /* Find the join information associated with this thread.
+ * This can fail for one of three reasons: (1) There is no
+ * thread associated with 'thread,' (2) the thread is a task
+ * and does not have join information, or (3) the thread
+ * was detached and has exited.
+ */
+
+ pjoin = pthread_findjoininfo(group, (pid_t)thread);
+ if (!pjoin)
+ {
+ /* Determine what kind of error to return */
+
+ FAR struct tcb_s *tcb = sched_gettcb((pthread_t)thread);
+
+ sdbg("Could not find thread data\n");
+
+ /* Case (1) or (3) -- we can't tell which. Assume (3) */
+
+ if (!tcb)
+ {
+ ret = ESRCH;
+ }
+
+ /* The thread is still active but has no join info. In that
+ * case, it must be a task and not a pthread.
+ */
+
+ else
+ {
+ ret = EINVAL;
+ }
+
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+ }
+ else
+ {
+ /* We found the join info structure. Increment for the reference
+ * to the join structure that we have. This will keep things
+ * stable for we have to do
+ */
+
+ sched_lock();
+ pjoin->crefs++;
+
+ /* Check if the thread is still running. If not, then things are
+ * simpler. There are still race conditions to be concerned with.
+ * For example, there could be multiple threads executing in the
+ * 'else' block below when we enter!
+ */
+
+ if (pjoin->terminated)
+ {
+ sdbg("Thread has terminated\n");
+
+ /* Get the thread exit value from the terminated thread. */
+
+ if (pexit_value)
+ {
+ sdbg("exit_value=0x%p\n", pjoin->exit_value);
+ *pexit_value = pjoin->exit_value;
+ }
+ }
+ else
+ {
+ sdbg("Thread is still running\n");
+
+ /* Relinquish the data set semaphore. Since pre-emption is
+ * disabled, we can be certain that no task has the
+ * opportunity to run between the time we relinquish the
+ * join semaphore and the time that we wait on the thread exit
+ * semaphore.
+ */
+
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+
+ /* Take the thread's thread exit semaphore. We will sleep here
+ * until the thread exits. We need to exercise caution because
+ * there could be multiple threads waiting here for the same
+ * pthread to exit.
+ */
+
+ (void)pthread_takesemaphore(&pjoin->exit_sem);
+
+ /* The thread has exited! Get the thread exit value */
+
+ if (pexit_value)
+ {
+ *pexit_value = pjoin->exit_value;
+ sdbg("exit_value=0x%p\n", pjoin->exit_value);
+ }
+
+ /* Post the thread's data semaphore so that the exiting thread
+ * will know that we have received the data.
+ */
+
+ (void)pthread_givesemaphore(&pjoin->data_sem);
+
+ /* Retake the join semaphore, we need to hold this when
+ * pthread_destroyjoin is called.
+ */
+
+ (void)pthread_takesemaphore(&group->tg_joinsem);
+ }
+
+ /* Pre-emption is okay now. The logic still cannot be re-entered
+ * because we hold the join semaphore
+ */
+
+ sched_unlock();
+
+ /* Release our reference to the join structure and, if the reference
+ * count decrements to zero, deallocate the join structure.
+ */
+
+ if (--pjoin->crefs <= 0)
+ {
+ (void)pthread_destroyjoin(group, pjoin);
+ }
+
+ (void)pthread_givesemaphore(&group->tg_joinsem);
+ ret = OK;
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_keycreate.c b/nuttx/sched/pthread/pthread_keycreate.c
new file mode 100644
index 000000000..9d0e8f4e7
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_keycreate.c
@@ -0,0 +1,141 @@
+/****************************************************************************
+ * sched/pthread_keycreate.c
+ *
+ * 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
+ * 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 <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_key_create
+ *
+ * Description:
+ * This function creates a thread-specific data key visible to all threads
+ * in the system. Although the same key value may be used by different
+ * threads, the values bound to the key by pthread_setspecific() are
+ * maintained on a per-thread basis and persist for the life of the calling
+ * thread.
+ *
+ * Upon key creation, the value NULL will be associated with the new key
+ * in all active threads. Upon thread creation, the value NULL will be
+ * associated with all defined keys in the new thread.
+ *
+ * Parameters:
+ * key = A pointer to the key to create.
+ * destructor = An optional destructor() function that may be associated
+ * with each key that is invoked when a thread exits. However, this
+ * argument is ignored in the current implementation.
+ *
+ * Return Value:
+ * If successful, the pthread_key_create() function will store the newly
+ * created key value at *key and return zero (OK). Otherwise, an error
+ * number will bereturned to indicate the error:
+ *
+ * EAGAIN - The system lacked sufficient resources to create another
+ * thread-specific data key, or the system-imposed limit on the total
+ * number of keys pers process {PTHREAD_KEYS_MAX} has been exceeded
+ * ENONMEM - Insufficient memory exists to create the key.
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ * - The present implementation ignores the destructor argument.
+ *
+ ****************************************************************************/
+
+int pthread_key_create(FAR pthread_key_t *key, CODE void (*destructor)(void*))
+{
+#if CONFIG_NPTHREAD_KEYS > 0
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->group;
+ int ret = EAGAIN;
+
+ DEBUGASSERT(group);
+
+ /* Check if we have exceeded the system-defined number of keys. */
+
+ if (group->tg_nkeys < PTHREAD_KEYS_MAX)
+ {
+ /* Return the key value */
+
+ *key = group->tg_nkeys;
+
+ /* Increment the count of global keys. */
+
+ group->tg_nkeys++;
+
+ /* Return success. */
+
+ ret = OK;
+ }
+
+ return ret;
+#else
+ return ENOSYS;
+#endif
+}
diff --git a/nuttx/sched/pthread/pthread_keydelete.c b/nuttx/sched/pthread/pthread_keydelete.c
new file mode 100644
index 000000000..f70a15cbb
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_keydelete.c
@@ -0,0 +1,96 @@
+/************************************************************************
+ * sched/pthread_keydelete.c
+ *
+ * Copyright (C) 2007, 2009 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 <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_key_delete
+ *
+ * Description:
+ * This POSIX function should delete a thread-specific data key
+ * previously returned by pthread_key_create(). However, this function
+ * does nothing in the present implementation.
+ *
+ * Parameters:
+ * key = the key to delete
+ *
+ * Return Value:
+ * Always returns ENOSYS.
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ *
+ ************************************************************************/
+
+int pthread_key_delete(pthread_key_t key)
+{
+ return ENOSYS;
+}
+
diff --git a/nuttx/sched/pthread/pthread_kill.c b/nuttx/sched/pthread/pthread_kill.c
new file mode 100644
index 000000000..5a1506c0c
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_kill.c
@@ -0,0 +1,95 @@
+/************************************************************************
+ * sched/pthread_kill.c
+ *
+ * Copyright (C) 2007, 2009, 2011 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 <sys/types.h>
+#include <signal.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/************************************************************************
+ * Global Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: 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;
+
+ set_errno(EINVAL);
+ ret = kill((pid_t)thread, signo);
+ if (ret != OK)
+ {
+ ret = get_errno();
+ }
+
+ return ret;
+}
+
+
diff --git a/nuttx/sched/pthread/pthread_mutexdestroy.c b/nuttx/sched/pthread/pthread_mutexdestroy.c
new file mode 100644
index 000000000..ddbd66296
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_mutexdestroy.c
@@ -0,0 +1,131 @@
+/****************************************************************************
+ * sched/pthread_mutexdestroy.c
+ *
+ * Copyright (C) 2007-2009 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 <pthread.h>
+#include <semaphore.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_mutex_destroy
+ *
+ * Description:
+ * Destroy a mutex.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_mutex_destroy(FAR pthread_mutex_t *mutex)
+{
+ int ret = OK;
+ int status;
+
+ sdbg("mutex=0x%p\n", mutex);
+
+ if (!mutex)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Make sure the semaphore is stable while we make the following
+ * checks
+ */
+
+ sched_lock();
+
+ /* Is the semaphore available? */
+
+ if (mutex->pid != 0)
+ {
+ ret = EBUSY;
+ }
+ else
+ {
+ /* Destroy the semaphore */
+
+ status = sem_destroy((sem_t*)&mutex->sem);
+ if (status != OK)
+ {
+ ret = EINVAL;
+ }
+ }
+
+ sched_unlock();
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_mutexinit.c b/nuttx/sched/pthread/pthread_mutexinit.c
new file mode 100644
index 000000000..08715d4b0
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_mutexinit.c
@@ -0,0 +1,138 @@
+/****************************************************************************
+ * sched/pthread_mutexinit.c
+ *
+ * Copyright (C) 2007-2009, 2011 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 <stdint.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_mutex_init
+ *
+ * Description:
+ * Create a mutex
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_mutex_init(FAR pthread_mutex_t *mutex, FAR pthread_mutexattr_t *attr)
+{
+ int pshared = 0;
+#ifdef CONFIG_MUTEX_TYPES
+ uint8_t type = PTHREAD_MUTEX_DEFAULT;
+#endif
+ int ret = OK;
+ int status;
+
+ sdbg("mutex=0x%p attr=0x%p\n", mutex, attr);
+
+ if (!mutex)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Were attributes specified? If so, use them */
+
+ if (attr)
+ {
+ pshared = attr->pshared;
+#ifdef CONFIG_MUTEX_TYPES
+ type = attr->type;
+#endif
+ }
+
+ /* Indicate that the semaphore is not held by any thread. */
+
+ mutex->pid = 0;
+
+ /* Initialize the mutex like a semaphore with initial count = 1 */
+
+ status = sem_init((sem_t*)&mutex->sem, pshared, 1);
+ if (status != OK)
+ {
+ ret = EINVAL;
+ }
+
+ /* Set up attributes unique to the mutex type */
+
+#ifdef CONFIG_MUTEX_TYPES
+ mutex->type = type;
+ mutex->nlocks = 0;
+#endif
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_mutexlock.c b/nuttx/sched/pthread/pthread_mutexlock.c
new file mode 100644
index 000000000..2e786ad7d
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_mutexlock.c
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * sched/pthread_mutexlock.c
+ *
+ * Copyright (C) 2007-2009 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 <unistd.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_mutex_lock
+ *
+ * Description:
+ * The mutex object referenced by mutex is locked by calling
+ * pthread_mutex_lock(). If the mutex is already locked, the calling thread
+ * blocks until the mutex becomes available. This operation returns with the
+ * mutex object referenced by mutex in the locked state with the calling
+ * thread as its owner.
+ *
+ * If the mutex type is PTHREAD_MUTEX_NORMAL, deadlock detection is not
+ * provided. Attempting to relock the mutex causes deadlock. If a thread
+ * attempts to unlock a mutex that it has not locked or a mutex which is
+ * unlocked, undefined behavior results.
+ *
+ * If the mutex type is PTHREAD_MUTEX_ERRORCHECK, then error checking is
+ * provided. If a thread attempts to relock a mutex that it has already
+ * locked, an error will be returned. If a thread attempts to unlock a
+ * mutex that it has not locked or a mutex which is unlocked, an error will
+ * be returned.
+ *
+ * If the mutex type is PTHREAD_MUTEX_RECURSIVE, then the mutex maintains
+ * the concept of a lock count. When a thread successfully acquires a mutex
+ * for the first time, the lock count is set to one. Every time a thread
+ * relocks this mutex, the lock count is incremented by one. Each time the
+ * thread unlocks the mutex, the lock count is decremented by one. When the
+ * lock count reaches zero, the mutex becomes available for other threads to
+ * acquire. If a thread attempts to unlock a mutex that it has not locked or
+ * a mutex which is unlocked, an error will be returned.
+ *
+ * If a signal is delivered to a thread waiting for a mutex, upon return
+ * from the signal handler the thread resumes waiting for the mutex as if
+ * it was not interrupted.
+ *
+ * Parameters:
+ * mutex - A reference to the mutex to be locked.
+ *
+ * Return Value:
+ * 0 on success or an errno value on failure. Note that the errno EINTR
+ * is never returned by pthread_mutex_lock().
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_mutex_lock(FAR pthread_mutex_t *mutex)
+{
+ int mypid = (int)getpid();
+ int ret = OK;
+
+ sdbg("mutex=0x%p\n", mutex);
+
+ if (!mutex)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Make sure the semaphore is stable while we make the following
+ * checks. This all needs to be one atomic action.
+ */
+
+ sched_lock();
+
+ /* Does this task already hold the semaphore? */
+
+ if (mutex->pid == mypid)
+ {
+ /* Yes.. Is this a recursive mutex? */
+
+#ifdef CONFIG_MUTEX_TYPES
+ if (mutex->type == PTHREAD_MUTEX_RECURSIVE)
+ {
+ /* Yes... just increment the number of locks held and return success */
+
+ mutex->nlocks++;
+ }
+ else
+#endif
+ {
+ /* No, then we would deadlock... return an error (default behavior
+ * is like PTHREAD_MUTEX_ERRORCHECK)
+ */
+
+ sdbg("Returning EDEADLK\n");
+ ret = EDEADLK;
+ }
+ }
+ else
+ {
+ /* Take the semaphore */
+
+ ret = pthread_takesemaphore((sem_t*)&mutex->sem);
+
+ /* If we succussfully obtained the semaphore, then indicate
+ * that we own it.
+ */
+
+ if (!ret)
+ {
+ mutex->pid = mypid;
+#ifdef CONFIG_MUTEX_TYPES
+ mutex->nlocks = 1;
+#endif
+ }
+ }
+
+ sched_unlock();
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
diff --git a/nuttx/sched/pthread/pthread_mutextrylock.c b/nuttx/sched/pthread/pthread_mutextrylock.c
new file mode 100644
index 000000000..a289bf8c3
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_mutextrylock.c
@@ -0,0 +1,147 @@
+/****************************************************************************
+ * sched/pthread_mutextrylock.c
+ *
+ * Copyright (C) 2007-2009 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 <unistd.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_mutex_trylock
+ *
+ * Description:
+ * The function pthread_mutex_trylock() is identical to pthread_mutex_lock()
+ * except that if the mutex object referenced by mutex is currently locked
+ * (by any thread, including the current thread), the call returns immediately
+ * with the errno EBUSY.
+ *
+ * If a signal is delivered to a thread waiting for a mutex, upon return from
+ * the signal handler the thread resumes waiting for the mutex as if it was
+ * not interrupted.
+ *
+ * Parameters:
+ * mutex - A reference to the mutex to be locked.
+ *
+ * Return Value:
+ * 0 on success or an errno value on failure. Note that the errno EINTR
+ * is never returned by pthread_mutex_lock().
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_mutex_trylock(FAR pthread_mutex_t *mutex)
+{
+ int ret = OK;
+
+ sdbg("mutex=0x%p\n", mutex);
+
+ if (!mutex)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Make sure the semaphore is stable while we make the following
+ * checks. This all needs to be one atomic action.
+ */
+
+ sched_lock();
+
+ /* Try to get the semaphore. */
+
+ if (sem_trywait((sem_t*)&mutex->sem) == OK)
+ {
+ /* If we succussfully obtained the semaphore, then indicate
+ * that we own it.
+ */
+
+ mutex->pid = (int)getpid();
+ }
+
+ /* Was it not available? */
+
+ else if (get_errno() == EAGAIN)
+ {
+ ret = EBUSY;
+ }
+ else
+ {
+ ret = EINVAL;
+ }
+
+ sched_unlock();
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
+
+
diff --git a/nuttx/sched/pthread/pthread_mutexunlock.c b/nuttx/sched/pthread/pthread_mutexunlock.c
new file mode 100644
index 000000000..04a02af9c
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_mutexunlock.c
@@ -0,0 +1,164 @@
+/****************************************************************************
+ * sched/pthread_mutexunlock.c
+ *
+ * Copyright (C) 2007-2009 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 <unistd.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_mutex_unlock
+ *
+ * Description:
+ * The pthread_mutex_unlock() function releases the mutex object referenced
+ * by mutex. The manner in which a mutex is released is dependent upon the
+ * mutex's type attribute. If there are threads blocked on the mutex object
+ * referenced by mutex when pthread_mutex_unlock() is called, resulting in
+ * the mutex becoming available, the scheduling policy is used to determine
+ * which thread shall acquire the mutex. (In the case of PTHREAD_MUTEX_RECURSIVE
+ * mutexes, the mutex becomes available when the count reaches zero and the
+ * calling thread no longer has any locks on this mutex).
+ *
+ * If a signal is delivered to a thread waiting for a mutex, upon return from
+ * the signal handler the thread resumes waiting for the mutex as if it was
+ * not interrupted.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_mutex_unlock(FAR pthread_mutex_t *mutex)
+{
+ int ret = OK;
+
+ sdbg("mutex=0x%p\n", mutex);
+
+ if (!mutex)
+ {
+ ret = EINVAL;
+ }
+ else
+ {
+ /* Make sure the semaphore is stable while we make the following
+ * checks. This all needs to be one atomic action.
+ */
+
+ sched_lock();
+
+ /* Does the calling thread own the semaphore? */
+
+ if (mutex->pid != (int)getpid())
+ {
+ /* No... return an error (default behavior is like PTHREAD_MUTEX_ERRORCHECK) */
+
+ sdbg("Holder=%d returning EPERM\n", mutex->pid);
+ ret = EPERM;
+ }
+
+
+ /* Yes, the caller owns the semaphore.. Is this a recursive mutex? */
+
+#ifdef CONFIG_MUTEX_TYPES
+ else if (mutex->type == PTHREAD_MUTEX_RECURSIVE && mutex->nlocks > 1)
+ {
+ /* This is a recursive mutex and we there are multiple locks held. Retain
+ * the mutex lock, just decrement the count of locks held, and return
+ * success.
+ */
+ mutex->nlocks--;
+ }
+#endif
+
+ /* This is either a non-recursive mutex or is the outermost unlock of
+ * a recursive mutex.
+ */
+
+ else
+ {
+ /* Nullify the pid and lock count then post the semaphore */
+
+ mutex->pid = 0;
+#ifdef CONFIG_MUTEX_TYPES
+ mutex->nlocks = 0;
+#endif
+ ret = pthread_givesemaphore((sem_t*)&mutex->sem);
+ }
+ sched_unlock();
+ }
+
+ sdbg("Returning %d\n", ret);
+ return ret;
+}
+
+
diff --git a/nuttx/sched/pthread/pthread_once.c b/nuttx/sched/pthread/pthread_once.c
new file mode 100644
index 000000000..46b37c5a5
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_once.c
@@ -0,0 +1,128 @@
+/********************************************************************************
+ * sched/pthread_once.c
+ *
+ * Copyright (C) 2007, 2009 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 <stdbool.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+/********************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Type Declarations
+ ********************************************************************************/
+
+/********************************************************************************
+ * Global Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Variables
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Function Prototypes
+ ********************************************************************************/
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Name: 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 initializeed 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/pthread_release.c b/nuttx/sched/pthread/pthread_release.c
new file mode 100644
index 000000000..b6afb5a2e
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_release.c
@@ -0,0 +1,123 @@
+/************************************************************************
+ * sched/pthread_release.c
+ *
+ * Copyright (C) 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 <debug.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_release
+ *
+ * Description:
+ * Release pthread resources from the task group with the group
+ * terminated.
+ *
+ * Parameters:
+ * group = The task group containing the pthread resources to be
+ * released.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ *
+ ************************************************************************/
+
+void pthread_release(FAR struct task_group_s *group)
+{
+ FAR struct join_s *join;
+
+ sdbg("group=0x%p\n", group);
+
+ /* Visit and delete each join structure still in the list. Since we
+ * are last exiting thread of the group, no special protection should
+ * be required.
+ */
+
+ while (group->tg_joinhead)
+ {
+ /* Remove the join from the head of the list. */
+
+ join = group->tg_joinhead;
+ group->tg_joinhead = join->next;
+
+ /* Destroy the join semaphores */
+
+ (void)sem_destroy(&join->data_sem);
+ (void)sem_destroy(&join->exit_sem);
+
+ /* And deallocate the join structure */
+
+ sched_kfree(join);
+ }
+
+ /* Destroy the join list semaphore */
+
+ (void)sem_destroy(&group->tg_joinsem);
+}
diff --git a/nuttx/sched/pthread/pthread_setcancelstate.c b/nuttx/sched/pthread/pthread_setcancelstate.c
new file mode 100644
index 000000000..834dc4a59
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_setcancelstate.c
@@ -0,0 +1,131 @@
+/******************************************************************************************
+ * pthread_setcancelstate.c
+ *
+ * Copyright (C) 2007, 2008 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 <pthread.h>
+#include <errno.h>
+#include "os_internal.h"
+
+/******************************************************************************************
+ * Private Definitions
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Private Types
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Private Function Prototypes
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Global Variables
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Private Variables
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Private Functions
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Public Functions
+ ******************************************************************************************/
+
+/******************************************************************************************
+ * Name: pthread_setcancelstate
+ ******************************************************************************************/
+
+int pthread_setcancelstate(int state, FAR int *oldstate)
+{
+ struct tcb_s *tcb = (struct tcb_s*)g_readytorun.head;
+ int ret = OK;
+
+ /* Suppress context changes for a bit so that the flags are stable. (the
+ * flags should not change in interrupt handling).
+ */
+
+ sched_lock();
+
+ /* Return the current state if so requrested */
+
+ if (oldstate)
+ {
+ if ((tcb->flags & TCB_FLAG_NONCANCELABLE) != 0)
+ {
+ *oldstate = PTHREAD_CANCEL_DISABLE;
+ }
+ else
+ {
+ *oldstate = PTHREAD_CANCEL_ENABLE;
+ }
+ }
+
+ /* Set the new cancellation state */
+
+ if (state == PTHREAD_CANCEL_ENABLE)
+ {
+ unsigned flags = tcb->flags;
+
+ /* Clear the non-cancelable and cancel pending flags */
+
+ tcb->flags &= ~(TCB_FLAG_NONCANCELABLE|TCB_FLAG_CANCEL_PENDING);
+
+ /* If the cancel was pending, then just exit as requested */
+
+ if (flags & TCB_FLAG_CANCEL_PENDING)
+ {
+ pthread_exit(PTHREAD_CANCELED);
+ }
+ }
+ else if (state == PTHREAD_CANCEL_DISABLE)
+ {
+ /* Set the non-cancelable state */
+
+ tcb->flags |= TCB_FLAG_NONCANCELABLE;
+ }
+ else
+ {
+ ret = EINVAL;
+ }
+
+ sched_unlock();
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_setschedparam.c b/nuttx/sched/pthread/pthread_setschedparam.c
new file mode 100644
index 000000000..3b24eb7f8
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_setschedparam.c
@@ -0,0 +1,142 @@
+/****************************************************************************
+ * pthread_setschedparam.c
+ *
+ * Copyright (C) 2007, 2008, 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 <sys/types.h>
+#include <pthread.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_setschedparam
+ *
+ * Description:
+ * The pthread_setschedparam() functions will set the scheduling policy
+ * and parameters of threads. For SCHED_FIFO and SCHED_RR, the only
+ * required member of the sched_param structure is the priority
+ * sched_priority.
+ *
+ * The pthread_setschedparam() function will set the scheduling policy
+ * and associated scheduling parameters for the thread whose thread ID
+ * is given by 'thread' to the policy and associated parameters provided
+ * in 'policy' and 'param', respectively.
+ *
+ * The policy parameter may have the value SCHED_FIFO, or SCHED_RR
+ * (SCHED_OTHER and SCHED_SPORADIC, in particular, are not supported).
+ * The SCHED_FIFO and SCHED_RR policies will have a single scheduling
+ * parameter, sched_priority.
+ *
+ * If the pthread_setschedparam() function fails, the scheduling parameters
+ * will not be changed for the target thread.
+ *
+ * Parameters:
+ * thread - The ID of thread whose scheduling parameters will be modified.
+ * policy - The new scheduling policy of the thread. Either SCHED_FIFO or
+ * SCHED_RR. SCHED_OTHER and SCHED_SPORADIC are not supported.
+ * param - Provides the new priority of the thread.
+ *
+ * Return Value:
+ * 0 if successful. Otherwise, an error code identifying the cause of the
+ * failure:
+ *
+ * EINVAL The value specified by 'policy' or one of the scheduling
+ * parameters associated with the scheduling policy 'policy' is
+ * invalid.
+ * ENOTSUP An attempt was made to set the policy or scheduling parameters
+ * to an unsupported value (SCHED_OTHER and SCHED_SPORADIC in
+ * particular are not supported)
+ * EPERM The caller does not have the appropriate permission to set either
+ * the scheduling parameters or the scheduling policy of the
+ * specified thread. Or, the implementation does not allow the
+ * application to modify one of the parameters to the value
+ * specified.
+ * ESRCH The value specified by thread does not refer to a existing thread.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_setschedparam(pthread_t thread, int policy, FAR const struct sched_param *param)
+{
+ int ret;
+
+ sdbg("thread ID=%d policy=%d param=0x%p\n", thread, policy, param);
+
+ /* Set the errno to some non-zero value (failsafe) */
+
+ set_errno(EINVAL);
+
+ /* Let sched_setscheduler do all of the work */
+
+ ret = sched_setscheduler((pid_t)thread, policy, param);
+ if (ret != OK)
+ {
+ /* If sched_setscheduler() fails, return the errno */
+
+ ret = get_errno();
+ }
+
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_setschedprio.c b/nuttx/sched/pthread/pthread_setschedprio.c
new file mode 100644
index 000000000..a523b20ea
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_setschedprio.c
@@ -0,0 +1,120 @@
+/****************************************************************************
+ * pthread_schedsetprio.c
+ *
+ * Copyright (C) 2007, 2009 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 <sys/types.h>
+#include <sched.h>
+#include <errno.h>
+#include <nuttx/arch.h>
+#include "os_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_setsetprio
+ *
+ * Description:
+ * The pthread_setschedprio() function sets the scheduling priority for the
+ * thread whose thread ID is given by 'thread' to the value given by 'prio'.
+ * If the thread_setschedprio() function fails, the scheduling priority
+ * of the target thread will not be changed.
+ *
+ * Inputs:
+ * thread - the thread ID of the task to reprioritize.
+ * prio - The new thread priority. The range of valid priority numbers is
+ * from SCHED_PRIORITY_MIN through SCHED_PRIORITY_MAX.
+ *
+ * Return Value:
+ * OK if successful, otherwise an error number. This function can
+ * fail for the following reasons:
+ *
+ * EINVAL - prio is out of range.
+ * ESRCH - thread ID does not correspond to any thread.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int pthread_setschedprio(pthread_t thread, int prio)
+{
+ struct sched_param param;
+ int ret;
+
+ /* Set the errno to some non-zero value (failsafe) */
+
+ errno = EINVAL;
+
+ /* Call sched_setparam() to change the priority */
+
+ param.sched_priority = prio;
+ ret = sched_setparam((pid_t)thread, &param);
+ if (ret != OK)
+ {
+ /* If sched_setparam() fails, return the errno */
+
+ ret = errno;
+ }
+ return ret;
+}
diff --git a/nuttx/sched/pthread/pthread_setspecific.c b/nuttx/sched/pthread/pthread_setspecific.c
new file mode 100644
index 000000000..32a26224f
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_setspecific.c
@@ -0,0 +1,143 @@
+/****************************************************************************
+ * sched/pthread_setspecific.c
+ *
+ * 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
+ * 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 <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "pthread/pthread.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pthread_setspecific
+ *
+ * Description:
+ * The pthread_setspecific() function associates a thread-
+ * specific value with a key obtained via a previous call
+ * to pthread_key_create(). Different threads may bind
+ * different values to the same key. These values are
+ * typically pointers to blocks of dynamically allocated
+ * memory that have been reserved for use by the calling
+ * thread.
+ *
+ * The effect of calling pthread_setspecific() with
+ * with a key value not obtained from pthread_create() or
+ * after a key has been deleted with pthread_key_delete()
+ * is undefined.
+ *
+ * Parameters:
+ * key = The data key to get or set
+ * value = The value to bind to the key.
+ *
+ * Return Value:
+ * If successful, pthread_setspecific() will return zero (OK).
+ * Otherwise, an error number will be returned:
+ *
+ * ENOMEM - Insufficient memory exists to associate
+ * the value with the key.
+ * EINVAL - The key value is invalid.
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ * int pthread_setspecific(pthread_key_t key, void *value)
+ * void *pthread_getspecific(pthread_key_t key)
+ *
+ * - Both calling pthread_setspecific() and pthread_getspecific()
+ * may be called from a thread-specific data destructor
+ * function.
+ *
+ ****************************************************************************/
+
+int pthread_setspecific(pthread_key_t key, FAR void *value)
+{
+#if CONFIG_NPTHREAD_KEYS > 0
+ FAR struct pthread_tcb_s *rtcb = (FAR struct pthread_tcb_s*)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->cmn.group;
+ int ret = EINVAL;
+
+ DEBUGASSERT(group &&
+ (rtcb->cmn.flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_PTHREAD);
+
+ /* Check if the key is valid. */
+
+ if (key < group->tg_nkeys)
+ {
+ /* Store the data in the TCB. */
+
+ rtcb->pthread_data[key] = value;
+
+ /* Return success. */
+
+ ret = OK;
+ }
+
+ return ret;
+#else
+ return ENOSYS;
+#endif
+}
+
diff --git a/nuttx/sched/pthread/pthread_sigmask.c b/nuttx/sched/pthread/pthread_sigmask.c
new file mode 100644
index 000000000..c66b8591c
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_sigmask.c
@@ -0,0 +1,107 @@
+/************************************************************************
+ * sched/pthread_sigmask.c
+ *
+ * Copyright (C) 2007, 2009 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 <signal.h>
+#include <pthread.h>
+#include <errno.h>
+#include <debug.h>
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Function Prototypes
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: 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/pthread/pthread_yield.c b/nuttx/sched/pthread/pthread_yield.c
new file mode 100644
index 000000000..c4535b9db
--- /dev/null
+++ b/nuttx/sched/pthread/pthread_yield.c
@@ -0,0 +1,87 @@
+/************************************************************************
+ * sched/pthread_yield.c
+ *
+ * Copyright (C) 2007, 2009 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 <pthread.h>
+#include <sched.h>
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: pthread_yield
+ *
+ * Description:
+ * A thread may tell the scheduler that its processor can be
+ * made available.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ************************************************************************/
+
+void pthread_yield(void)
+{
+ (void)sched_yield();
+}