summaryrefslogtreecommitdiff
path: root/nuttx/examples/ostest
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-02-17 23:21:28 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-02-17 23:21:28 +0000
commite3940eb2080711edac189cca3f642ee89dc215f2 (patch)
tree1c390958fae49e34dce698b175487e6d4681e540 /nuttx/examples/ostest
parent2223612deb2cc6322992f8595b6d6f86fcb53ae1 (diff)
downloadpx4-nuttx-e3940eb2080711edac189cca3f642ee89dc215f2.tar.gz
px4-nuttx-e3940eb2080711edac189cca3f642ee89dc215f2.tar.bz2
px4-nuttx-e3940eb2080711edac189cca3f642ee89dc215f2.zip
NuttX RTOS
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/examples/ostest')
-rw-r--r--nuttx/examples/ostest/Makefile75
-rw-r--r--nuttx/examples/ostest/cancel.c308
-rw-r--r--nuttx/examples/ostest/cond.c284
-rw-r--r--nuttx/examples/ostest/dev_null.c91
-rw-r--r--nuttx/examples/ostest/main.c178
-rw-r--r--nuttx/examples/ostest/mqueue.c333
-rw-r--r--nuttx/examples/ostest/mutex.c120
-rw-r--r--nuttx/examples/ostest/ostest.h91
-rw-r--r--nuttx/examples/ostest/sem.c238
-rw-r--r--nuttx/examples/ostest/sighand.c254
-rw-r--r--nuttx/examples/ostest/timedwait.c161
11 files changed, 2133 insertions, 0 deletions
diff --git a/nuttx/examples/ostest/Makefile b/nuttx/examples/ostest/Makefile
new file mode 100644
index 000000000..85612a992
--- /dev/null
+++ b/nuttx/examples/ostest/Makefile
@@ -0,0 +1,75 @@
+############################################################
+# Makefile
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name Gregory Nutt nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################
+
+-include $(TOPDIR)/.config
+-include $(TOPDIR)/Make.defs
+
+MKDEP = $(TOPDIR)/tools/mkdeps.sh
+
+ASRCS =
+AOBJS = $(ASRCS:.S=.o)
+CSRCS = main.c dev_null.c mutex.c cancel.c sem.c cond.c \
+ timedwait.c mqueue.c sighand.c
+COBJS = $(CSRCS:.c=.o)
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+BIN = lib$(CONFIG_EXAMPLE).a
+
+all: $(BIN)
+
+$(AOBJS): %.o: %.S
+ $(CC) -c $(CFLAGS) $< -o $@
+
+$(COBJS): %.o: %.c
+ $(CC) -c $(CFLAGS) $< -o $@
+
+$(BIN): $(OBJS)
+ $(AR) rcs $@ $(OBJS)
+
+.depend: Makefile $(SRCS)
+ $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ touch $@
+
+depend: .depend
+
+clean:
+ rm -f $(BIN) *.o *~
+
+distclean: clean
+ rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/examples/ostest/cancel.c b/nuttx/examples/ostest/cancel.c
new file mode 100644
index 000000000..d52c596fc
--- /dev/null
+++ b/nuttx/examples/ostest/cancel.c
@@ -0,0 +1,308 @@
+/***********************************************************************
+ * cancel.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***********************************************************************/
+
+#include <stdio.h>
+#include <time.h>
+#include <pthread.h>
+#include <errno.h>
+#include "ostest.h"
+
+static pthread_mutex_t mutex;
+static pthread_cond_t cond;
+
+static void *thread_waiter(void *parameter)
+{
+ int status;
+
+ /* Take the mutex */
+
+ printf("%s: Taking mutex\n", __FUNCTION__);
+ status = pthread_mutex_lock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_lock failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Starting wait for condition\n", __FUNCTION__);
+
+ /* Are we a non-cancelable thread? Yes, set the non-cancelable state */
+
+ if (!parameter)
+ {
+ printf("%s: Setting non-cancelable\n", __FUNCTION__);
+ status = pthread_setcancelstate(PTHREAD_CANCEL_DISABLE, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_setcancelstate failed, status=%d\n", __FUNCTION__, status);
+ }
+ }
+
+ /* The wait -- we will never awaken from this. */
+
+ status = pthread_cond_wait(&cond, &mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_wait failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Release the mutex */
+
+ printf("%s: Releasing mutex\n", __FUNCTION__);
+ status = pthread_mutex_unlock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_unlock failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Set the cancelable state */
+
+ printf("%s: Setting cancelable\n", __FUNCTION__);
+ status = pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_setcancelstate failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Exit with status 0x12345678\n", __FUNCTION__);
+ pthread_exit((void*)0x12345678);
+ return NULL;
+}
+
+static void start_thread(pthread_t *waiter, int cancelable)
+{
+ pthread_attr_t attr;
+ int status;
+
+ /* Initialize the mutex */
+
+ printf("%s: Initializing mutex\n", __FUNCTION__);
+ status = pthread_mutex_init(&mutex, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Initialize the condition variable */
+
+ printf("%s: Initializing cond\n", __FUNCTION__);
+ status = pthread_cond_init(&cond, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Set up attributes */
+
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ status = pthread_attr_setstacksize(&attr, 16384);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_setstacksize failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Start the waiter thread */
+
+ printf("%s: Starting thread\n", __FUNCTION__);
+ status = pthread_create(waiter, NULL, thread_waiter, (void*)cancelable);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_create failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Make sure that the waiter thread gets a chance to run */
+
+ printf("%s: Yielding\n", __FUNCTION__);
+ pthread_yield();
+
+}
+
+static void restart_thread(pthread_t *waiter, int cancelable)
+{
+ int status;
+
+ /* Destroy the condition variable */
+
+ printf("%s: Destroying cond\n", __FUNCTION__);
+ status = pthread_cond_destroy(&cond);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_destroy failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Destroy the mutex */
+
+ printf("%s: Destroying mutex\n", __FUNCTION__);
+ status = pthread_cond_destroy(&cond);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_destroy failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Then restart the thread */
+
+ printf("%s: Re-starting thread\n", __FUNCTION__);
+ start_thread(waiter, cancelable);
+}
+
+void cancel_test(void)
+{
+ pthread_t waiter;
+ void *result;
+ int status;
+
+ /* Test 1: Normal Cancel *********************************************/
+ /* Start the waiter thread */
+
+ printf("%s: Test 1: Normal Cancelation\n", __FUNCTION__);
+ printf("%s: Starting thread\n", __FUNCTION__);
+ start_thread(&waiter, 1);
+
+ /* Then cancel it. It should be in the pthread_cond_wait now */
+
+ printf("%s: Canceling thread\n", __FUNCTION__);
+ status = pthread_cancel(waiter);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cancel failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Then join to the thread to pick up the result */
+
+ printf("%s: Joining\n", __FUNCTION__);
+ status = pthread_join(waiter, &result);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_join failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: waiter exited with result=%p\n", __FUNCTION__, result);
+ if (result != PTHREAD_CANCELED)
+ {
+ printf("%s: ERROR expected result=%p\n", __FUNCTION__, PTHREAD_CANCELED);
+ }
+ else
+ {
+ printf("%s: PASS thread terminated with PTHREAD_CANCELED\n", __FUNCTION__);
+ }
+ }
+
+ /* Test 2: Cancel Detached Thread ************************************/
+
+ printf("%s: Test 2: Cancelation of detached thread\n", __FUNCTION__);
+ printf("%s: Re-starting thread\n", __FUNCTION__);
+ restart_thread(&waiter, 1);
+
+ /* Detach the thread */
+
+ status = pthread_detach(waiter);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_detach, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Then cancel it. It should be in the pthread_cond_wait now */
+
+ printf("%s: Canceling thread\n", __FUNCTION__);
+ status = pthread_cancel(waiter);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cancel failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Join should now fail */
+
+ printf("%s: Joining\n", __FUNCTION__);
+ status = pthread_join(waiter, &result);
+ if (status == 0)
+ {
+ printf("%s: ERROR pthread_join succeeded\n", __FUNCTION__);
+ }
+ else if (status != ESRCH)
+ {
+ printf("%s: ERROR pthread_join failed but with wrong status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: PASS pthread_join failed with status=ESRCH\n", __FUNCTION__);
+ }
+
+ /* Test 3: Non-cancelable threads ************************************/
+
+ printf("%s: Test 3: Non-cancelable threads\n", __FUNCTION__);
+ printf("%s: Re-starting thread (non-cancelable)\n", __FUNCTION__);
+ restart_thread(&waiter, 0);
+
+ /* Then cancel it. It should be in the pthread_cond_wait now. The
+ * behavior here is non-standard: when the thread is at a cancelation
+ * point, it should be cancelable, even when cancelation is disable.
+ *
+ * The cancelation should succeed, because the cancelation is pending.
+ */
+
+ printf("%s: Canceling thread\n", __FUNCTION__);
+ status = pthread_cancel(waiter);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cancel failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Signal the thread. It should wake up an restore the cancelable state.
+ * When the cancelable state is re-enabled, the thread should be canceled.
+ */
+
+ status = pthread_mutex_lock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_lock failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ status = pthread_cond_signal(&cond);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_signal failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ status = pthread_mutex_unlock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_unlock failed, status=%d\n", __FUNCTION__, status);
+ }
+}
diff --git a/nuttx/examples/ostest/cond.c b/nuttx/examples/ostest/cond.c
new file mode 100644
index 000000000..be995fa08
--- /dev/null
+++ b/nuttx/examples/ostest/cond.c
@@ -0,0 +1,284 @@
+/***********************************************************************
+ * cond.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***********************************************************************/
+
+#include <stdio.h>
+#include <pthread.h>
+#include <unistd.h>
+#include "ostest.h"
+
+#ifndef NULL
+# define NULL (void*)0
+#endif
+
+static volatile enum { RUNNING, MUTEX_WAIT, COND_WAIT} waiter_state;
+
+static pthread_mutex_t mutex;
+static pthread_cond_t cond;
+static volatile int data_available = 0;
+static int waiter_nloops = 0;
+static int waiter_waits = 0;
+static int waiter_nerrors = 0;
+static int signaler_nloops = 0;
+static int signaler_already = 0;
+static int signaler_state = 0;
+static int signaler_nerrors = 0;
+
+static void *thread_waiter(void *parameter)
+{
+ int status;
+
+ printf("%s: Started\n", __FUNCTION__);
+
+ for(;;)
+ {
+ /* Take the mutex */
+
+ waiter_state = MUTEX_WAIT;
+ status = pthread_mutex_lock(&mutex);
+ waiter_state = RUNNING;
+
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_lock failed, status=%d\n", __FUNCTION__, status);
+ waiter_nerrors++;
+ }
+
+ /* Check if data is available -- if data is not available then
+ * wait for it
+ */
+
+ if (!data_available)
+ {
+ /* We are higher priority than the signaler thread so the
+ * only time that the signaler thread will have a chance to run is when
+ * we are waiting for the condition variable. In this case, pthread_cond_wait
+ * will automatically release the mutex for the signaler (then re-acquire
+ * the mutex before returning.
+ */
+
+ waiter_state = COND_WAIT;
+ status = pthread_cond_wait(&cond, &mutex);
+ waiter_state = RUNNING;
+
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_wait failed, status=%d\n", __FUNCTION__, status);
+ waiter_nerrors++;
+ }
+ waiter_waits++;
+ }
+
+ /* Now data should be available */
+
+ if (!data_available)
+ {
+ printf("%s: ERROR data not available after wait\n", __FUNCTION__);
+ waiter_nerrors++;
+ }
+
+ /* Clear data available */
+
+ data_available = 0;
+
+ /* Release the mutex */
+
+ status = pthread_mutex_unlock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR waiter: pthread_mutex_unlock failed, status=%d\n", __FUNCTION__, status);
+ waiter_nerrors++;
+ }
+
+ waiter_nloops++;
+ }
+}
+
+static void *thread_signaler(void *parameter)
+{
+ int status;
+ int i;
+
+ printf("%s: Started\n", __FUNCTION__);
+ for (i = 0; i < 32; i++)
+ {
+ /* Take the mutex. The waiter is higher priority and should
+ * run until it waits for the condition. So, at this point
+ * signaler should be waiting for the condition.
+ */
+
+ status = pthread_mutex_lock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_lock failed, status=%d\n", __FUNCTION__, status);
+ signaler_nerrors++;
+ }
+
+ /* Verify the state */
+
+ if (waiter_state != COND_WAIT)
+ {
+ printf("%s: ERROR waiter state = %d != COND_WAITING\n", __FUNCTION__, waiter_state);
+ signaler_state++;
+ }
+
+ if (data_available)
+ {
+ printf("%s: ERROR data already available, waiter_state=%d\n", __FUNCTION__, waiter_state);
+ signaler_already++;
+ }
+
+ /* Set data available and signal the waiter */
+
+ data_available = 1;
+ status = pthread_cond_signal(&cond);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_signal failed, status=%d\n", __FUNCTION__, status);
+ signaler_nerrors++;
+ }
+
+ /* Release the mutex */
+
+ status = pthread_mutex_unlock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_unlock failed, status=%d\n", __FUNCTION__, status);
+ signaler_nerrors++;
+ }
+
+ signaler_nloops++;
+ }
+
+ printf("%s: Terminating\n", __FUNCTION__);
+ pthread_exit(NULL);
+}
+
+void cond_test(void)
+{
+ pthread_t waiter;
+ pthread_t signaler;
+ pthread_attr_t attr;
+ struct sched_param sparam;
+ int prio_min;
+ int prio_max;
+ int prio_mid;
+ int status;
+
+ /* Initialize the mutex */
+
+ printf("%s: Initializing mutex\n", __FUNCTION__);
+ status = pthread_mutex_init(&mutex, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Initialize the condition variable */
+
+ printf("%s: Initializing cond\n", __FUNCTION__);
+ status = pthread_cond_init(&cond, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_condinit failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Start the waiter thread at higher priority */
+
+ printf("%s: Starting waiter\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ prio_min = sched_get_priority_min(SCHED_FIFO);
+ prio_max = sched_get_priority_max(SCHED_FIFO);
+ prio_mid = (prio_min + prio_max) / 2;
+
+ sparam.sched_priority = prio_mid;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set thread 1 priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&waiter, &attr, thread_waiter, NULL);
+ if (status != 0)
+ {
+ printf("%s: pthread_create failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Starting signaler\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ sparam.sched_priority = (prio_min + prio_mid) / 2;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set thread 2 priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&signaler, &attr, thread_signaler, NULL);
+ if (status != 0)
+ {
+ printf("%s: pthread_create failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Wait for the threads to stop */
+
+ pthread_join(signaler, NULL);
+ printf("%s: signaler terminated, now cancel the waiter\n", __FUNCTION__);
+ pthread_detach(waiter);
+ pthread_cancel(waiter);
+
+ printf("%s: \tWaiter\tSignaler\n", __FUNCTION__);
+ printf("%s: Loops\t%d\t%d\n", __FUNCTION__, waiter_nloops, signaler_nloops);
+ printf("%s: Errors\t%d\t%d\n", __FUNCTION__, waiter_nerrors, signaler_nerrors);
+ printf("%s: \n%d times, waiter did not have to wait for data\n", __FUNCTION__, waiter_nloops - waiter_waits);
+ printf("%s: %d times, data was already available when the signaler run\n", __FUNCTION__, signaler_already);
+ printf("%s: %d times, the waiter was in an unexpected state when the signaler ran\n", __FUNCTION__, signaler_state);
+}
diff --git a/nuttx/examples/ostest/dev_null.c b/nuttx/examples/ostest/dev_null.c
new file mode 100644
index 000000000..11d6056c8
--- /dev/null
+++ b/nuttx/examples/ostest/dev_null.c
@@ -0,0 +1,91 @@
+/************************************************************
+ * dev_null.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Compilation Switches
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <nuttx/os_external.h>
+#include "ostest.h"
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+static char buffer[1024];
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+int dev_null(void)
+{
+ int nbytes;
+ int fd;
+
+ fd = open("/dev/null", O_RDWR);
+ if (fd < 0)
+ {
+ fprintf(stderr, "%s: Failed to open /dev/null\n", __FUNCTION__);
+ return -1;
+ }
+
+ nbytes = read(fd, buffer, 1024);
+ if (nbytes < 0)
+ {
+ fprintf(stderr, "%s: Failed to read from /dev/null\n", __FUNCTION__);
+ close(fd);
+ return -1;
+ }
+ printf("%s: Read %d bytes from /dev/null\n", __FUNCTION__, nbytes);
+
+ nbytes = write(fd, buffer, 1024);
+ if (nbytes < 0)
+ {
+ fprintf(stderr, "%s: Failed to write to /dev/null\n", __FUNCTION__);
+ close(fd);
+ return -1;
+ }
+ printf("%s: Wrote %d bytes to /dev/null\n", __FUNCTION__, nbytes);
+
+ close(fd);
+ return 0;
+}
diff --git a/nuttx/examples/ostest/main.c b/nuttx/examples/ostest/main.c
new file mode 100644
index 000000000..f6c0c65ca
--- /dev/null
+++ b/nuttx/examples/ostest/main.c
@@ -0,0 +1,178 @@
+/************************************************************
+ * main.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Compilation Switches
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/os_external.h>
+#include <stdio.h>
+#include <string.h>
+#include <sched.h>
+#include "ostest.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+#define PRIORITY 100
+#define STACKSIZE 8192
+#define NARGS 4
+
+#define ARG1 "Arg1"
+#define ARG2 "Arg2"
+#define ARG3 "Arg3"
+#define ARG4 "Arg4"
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+static char write_data1[] = "Standard I/O Check: write fd=1\n";
+static char write_data2[] = "Standard I/O Check: write fd=2\n";
+static char *args[NARGS] = { ARG1, ARG2, ARG3, ARG4 };
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+static int user_main(int argc, char *argv[])
+{
+ int i;
+
+ printf("%s: Started with argc=%d\n", __FUNCTION__, argc);
+
+ /* Verify passed arguments */
+
+ if (argc != NARGS + 1)
+ {
+ fprintf(stderr, "%s: Error expected argc=%d got argc=%d\n",
+ __FUNCTION__, NARGS+1, argc);
+ }
+
+ for (i = 0; i <= NARGS; i++)
+ {
+ printf("%s: argv[%d]=\"%s\"\n", __FUNCTION__, i, argv[i]);
+ }
+
+ for (i = 1; i <= NARGS; i++)
+ {
+ if (strcmp(argv[i], args[i-1]) != 0)
+ {
+ fprintf(stderr, "%s: ERROR argv[%d]: Expected \"%s\" found \"%s\"\n",
+ __FUNCTION__, i, argv[i], args[i-1]);
+ }
+ }
+
+ /* Checkout /dev/null */
+
+ dev_null();
+
+ /* Verify pthreads and pthread mutex */
+
+ mutex_test();
+
+ /* Verify pthread cancellation */
+
+ cancel_test();
+
+ /* Verify pthreads and semaphores */
+
+ sem_test();
+
+ /* Verify pthreads and condition variables */
+
+ cond_test();
+
+ /* Verify pthreads and condition variable timed waits */
+
+ timedwait_test();
+
+ /* Verify pthreads and message queues */
+
+ mqueue_test();
+
+ /* Verify signal handlers */
+
+ sighand_test();
+ return 0;
+}
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * user_initialize
+ ************************************************************/
+
+void user_initialize(void)
+{
+ /* stub */
+}
+
+/************************************************************
+ * user_start
+ ************************************************************/
+
+int user_start(int parm1, int parm2, int parm3, int parm4)
+{
+ int result;
+
+ /* Verify that we can communicate */
+
+ write(1, write_data1, sizeof(write_data1));
+ printf("%s: Standard I/O Check: printf\n", __FUNCTION__);
+ write(2, write_data2, sizeof(write_data2));
+ fprintf(stderr, "%s: Standard I/O Check: fprintf to stderr\n", __FUNCTION__);
+
+ /* Verify that we can spawn a new task */
+
+ result = task_create("ostest", PRIORITY, STACKSIZE, user_main,
+ ARG1, ARG2, ARG3, ARG4);
+ if (result == ERROR)
+ {
+ fprintf(stderr, "%s: Failed to start user_main\n", __FUNCTION__);
+ }
+ else
+ {
+ printf("%s: Started user_main at PID=%d\n", __FUNCTION__, result);
+ }
+ return 0;
+}
diff --git a/nuttx/examples/ostest/mqueue.c b/nuttx/examples/ostest/mqueue.c
new file mode 100644
index 000000000..f9e6b6e03
--- /dev/null
+++ b/nuttx/examples/ostest/mqueue.c
@@ -0,0 +1,333 @@
+/**************************************************************************
+ * mqueue.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ **************************************************************************/
+
+/**************************************************************************
+ * Included Files
+ **************************************************************************/
+
+#include <stdio.h>
+#include <string.h>
+#include <pthread.h>
+#include <mqueue.h>
+#include <sched.h>
+
+#include "ostest.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+#define TEST_MESSAGE "This is a test and only a test"
+#define TEST_MSGLEN (strlen(TEST_MESSAGE)+1)
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+static void *sender_thread(void *arg)
+{
+ mqd_t mqfd;
+ char msg_buffer[TEST_MSGLEN];
+ struct mq_attr attr;
+ int status = 0;
+ int nerrors = 0;
+ int i;
+
+ printf("%s: Starting\n", __FUNCTION__);
+
+ /* Fill in attributes for message queue */
+
+ attr.mq_maxmsg = 20;
+ attr.mq_msgsize = TEST_MSGLEN;
+ attr.mq_flags = 0;
+
+ /* Set the flags for the open of the queue.
+ * Make it a blocking open on the queue, meaning it will block if
+ * this process tries to send to the queue and the queue is full.
+ *
+ * O_CREAT - the queue will get created if it does not already exist.
+ * O_WRONLY - we are only planning to write to the queue.
+ *
+ * Open the queue, and create it if the receiving process hasn't
+ * already created it.
+ */
+
+ mqfd = mq_open("testmq", O_WRONLY|O_CREAT, 0666, &attr);
+ if (mqfd < 0)
+ {
+ printf("%s: ERROR mq_open failed\n", __FUNCTION__);
+ pthread_exit((void*)1);
+ }
+
+ /* Fill in a test message buffer to send */
+
+ memcpy(msg_buffer, TEST_MESSAGE, TEST_MSGLEN);
+
+ /* Perform the send 10 times */
+
+ for (i = 0; i < 10; i++)
+ {
+ status = mq_send(mqfd, msg_buffer, TEST_MSGLEN, 42);
+ if (status < 0)
+ {
+ printf("%s: ERROR mq_send failure=%d on msg %d\n", __FUNCTION__, status, i);
+ nerrors++;
+ }
+ else
+ {
+ printf("%s: mq_send succeeded on msg %d\n", __FUNCTION__, i);
+ }
+ }
+
+ /* Close the queue and return success */
+
+ if (mq_close(mqfd) < 0)
+ {
+ printf("%s: ERROR mq_close failed\n", __FUNCTION__);
+ }
+
+ printf("%s: returning nerrors=%d\n", __FUNCTION__, nerrors);
+ return (void*)nerrors;
+}
+
+static void *receiver_thread(void *arg)
+{
+ mqd_t mqfd;
+ char msg_buffer[TEST_MSGLEN];
+ struct mq_attr attr;
+ int nbytes;
+ int nerrors = 0;
+ int i;
+
+ printf("%s: Starting\n", __FUNCTION__);
+
+ /* Fill in attributes for message queue */
+
+ attr.mq_maxmsg = 20;
+ attr.mq_msgsize = TEST_MSGLEN;
+ attr.mq_flags = 0;
+
+ /* Set the flags for the open of the queue.
+ * Make it a blocking open on the queue, meaning it will block if
+ * this process tries to* send to the queue and the queue is full.
+ *
+ * O_CREAT - the queue will get created if it does not already exist.
+ * O_RDONLY - we are only planning to write to the queue.
+ *
+ * Open the queue, and create it if the sending process hasn't
+ * already created it.
+ */
+
+ mqfd = mq_open("testmq", O_RDONLY|O_CREAT, 0666, &attr);
+ if (mqfd < 0)
+ {
+ printf("%s: ERROR mq_open failed\n", __FUNCTION__);
+ pthread_exit((void*)1);
+ }
+
+ /* Perform the receive 10 times */
+
+ for (i = 0; i < 10; i++)
+ {
+ nbytes = mq_receive(mqfd, msg_buffer, TEST_MSGLEN, 0);
+ if (nbytes < 0)
+ {
+ printf("%s: ERROR mq_receive failure on msg %d\n", __FUNCTION__, i);
+ nerrors++;
+ }
+ else if (nbytes != TEST_MSGLEN)
+ {
+ printf("%s: mq_receive return bad size %d on msg %d\n", __FUNCTION__, nbytes, i);
+ nerrors++;
+ }
+ else if (memcmp(TEST_MESSAGE, msg_buffer, nbytes) != 0)
+ {
+ int j;
+
+ printf("%s: mq_receive returned corrupt message on msg %d\n", __FUNCTION__, i);
+ printf("%s: i Expected Received\n", __FUNCTION__);
+
+ for (j = 0; j < TEST_MSGLEN-1; j++)
+ {
+ printf("%s: %2d %02x (%c) %02x\n",
+ __FUNCTION__,
+ j, TEST_MESSAGE[j], TEST_MESSAGE[j], msg_buffer[j] & 0x0ff);
+ }
+ printf("%s: %2d 00 %02x\n",
+ __FUNCTION__, j, msg_buffer[j] & 0xff);
+ }
+ else
+ {
+ printf("%s: mq_receive succeeded on msg %d\n", __FUNCTION__, i);
+ }
+ }
+
+ /* Close the queue and return success */
+
+ if (mq_close(mqfd) < 0)
+ {
+ printf("%s: ERROR mq_close failed\n", __FUNCTION__);
+ nerrors++;
+ }
+
+ pthread_exit((void*)nerrors);
+
+ /* Destroy the queue */
+
+ if (mq_unlink("testmq") < 0)
+ {
+ printf("%s: ERROR mq_close failed\n", __FUNCTION__);
+ nerrors++;
+ }
+
+ printf("%s: returning nerrors=%d\n", __FUNCTION__, nerrors);
+ return (void*)nerrors;
+}
+
+void mqueue_test(void)
+{
+ pthread_t sender;
+ pthread_t receiver;
+ void *result;
+ pthread_attr_t attr;
+ struct sched_param sparam;
+ int prio_min;
+ int prio_max;
+ int prio_mid;
+ int status;
+
+ /* Start the sending thread at higher priority */
+
+ printf("%s: Starting receiver\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ status = pthread_attr_setstacksize(&attr, 16384);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_setstacksize failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ prio_min = sched_get_priority_min(SCHED_FIFO);
+ prio_max = sched_get_priority_max(SCHED_FIFO);
+ prio_mid = (prio_min + prio_max) / 2;
+
+ sparam.sched_priority = prio_mid;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set receiver priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&receiver, &attr, receiver_thread, NULL);
+ if (status != 0)
+ {
+ printf("%s: pthread_create failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Start the sending thread at lower priority */
+
+ printf("%s: Starting sender\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ status = pthread_attr_setstacksize(&attr, 16384);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_setstacksize failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ sparam.sched_priority = (prio_min + prio_mid) / 2;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set sender thread priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&sender, &attr, sender_thread, NULL);
+ if (status != 0)
+ {
+ printf("%s: pthread_create failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ pthread_join(sender, &result);
+ if (result != (void*)0)
+ {
+ printf("%s: ERROR sender thread exited with %d errors\n", __FUNCTION__, (int)result);
+ }
+
+ pthread_cancel(receiver);
+ pthread_join(receiver, &result);
+ if (result != (void*)0)
+ {
+ printf("%s: ERROR receiver thread exited with %d errors\n", __FUNCTION__, (int)result);
+ }
+}
+
+
diff --git a/nuttx/examples/ostest/mutex.c b/nuttx/examples/ostest/mutex.c
new file mode 100644
index 000000000..d6cad9e39
--- /dev/null
+++ b/nuttx/examples/ostest/mutex.c
@@ -0,0 +1,120 @@
+/***********************************************************************
+ * mutex.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***********************************************************************/
+
+#include <stdio.h>
+#include <pthread.h>
+#include "ostest.h"
+
+#ifndef NULL
+# define NULL (void*)0
+#endif
+
+#define NLOOPS 32
+
+static pthread_mutex_t mut;
+static volatile int my_mutex = 0;
+static unsigned long nloops[2] = {0, 0};
+static unsigned long nerrors[2] = {0, 0};
+
+static void *thread_func(void *parameter)
+{
+ int id = (int)parameter;
+ int ndx = id - 1;
+ int i;
+
+ for (nloops[ndx] = 0; nloops[ndx] < NLOOPS; nloops[ndx]++)
+ {
+ int status = pthread_mutex_lock(&mut);
+ if (status != 0)
+ {
+ printf("ERROR thread %d: pthread_mutex_lock failed, status=%d\n",
+ id, status);
+ }
+
+ if (my_mutex == 1)
+ {
+ printf("ERROR thread=%d: "
+ "my_mutex should be zero, instead my_mutex=%d\n",
+ id, my_mutex);
+ nerrors[ndx]++;
+ }
+
+ my_mutex = 1;
+ for (i = 0; i < 10; i++)
+ {
+ pthread_yield();
+ }
+ my_mutex = 0;
+
+ status = pthread_mutex_unlock(&mut);
+ if (status != 0)
+ {
+ printf("ERROR thread %d: pthread_mutex_unlock failed, status=%d\n",
+ id, status);
+ }
+ }
+ pthread_exit(NULL);
+}
+
+void mutex_test(void)
+{
+ pthread_t thread1, thread2;
+
+ /* Initialize the mutex */
+
+ printf("Initializing mutex\n");
+ pthread_mutex_init(&mut, NULL);
+
+ /* Start two thread instances */
+
+ printf("Starting thread 1\n");
+ if ((pthread_create(&thread1, NULL, thread_func, (void*)1)) != 0)
+ {
+ printf("Error in thread#1 creation\n");
+ }
+
+ printf("Starting thread 2\n");
+ if ((pthread_create(&thread2, NULL, thread_func, (void*)2)) != 0)
+ {
+ printf("Error in thread#2 creation\n");
+ }
+
+ pthread_join(thread1, NULL);
+ pthread_join(thread2, NULL);
+
+ printf("%s:\t\tThread1\tThread2\n", __FUNCTION__);
+ printf("%s:\tLoops\t%ld\t%ld\n", __FUNCTION__, nloops[0], nloops[1]);
+ printf("%s:\tErrors\t%ld\t%ld\n", __FUNCTION__, nerrors[0], nerrors[1]);
+}
diff --git a/nuttx/examples/ostest/ostest.h b/nuttx/examples/ostest/ostest.h
new file mode 100644
index 000000000..3871ecc67
--- /dev/null
+++ b/nuttx/examples/ostest/ostest.h
@@ -0,0 +1,91 @@
+/************************************************************
+ * ostest.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+#ifndef __OSTEST_H
+#define __OSTEST_H
+
+/************************************************************
+ * Compilation Switches
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Public Types
+ ************************************************************/
+
+/************************************************************
+ * Public Variables
+ ************************************************************/
+
+/************************************************************
+ * Public Function Prototypes
+ ************************************************************/
+
+/* dev_null.c ***********************************************/
+
+extern int dev_null(void);
+
+/* mutex.c **************************************************/
+
+extern void mutex_test(void);
+
+/* sem.c ****************************************************/
+
+extern void sem_test(void);
+
+/* cond.c ***************************************************/
+
+extern void cond_test(void);
+
+/* queue.c **************************************************/
+
+extern void mqueue_test(void);
+
+/* cancel.c *************************************************/
+
+extern void cancel_test(void);
+
+/* timedwait.c **********************************************/
+
+extern void timedwait_test(void);
+
+#endif /* __OSTEST_H */
diff --git a/nuttx/examples/ostest/sem.c b/nuttx/examples/ostest/sem.c
new file mode 100644
index 000000000..0b532982d
--- /dev/null
+++ b/nuttx/examples/ostest/sem.c
@@ -0,0 +1,238 @@
+/***********************************************************************
+ * sem.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***********************************************************************/
+
+#include <sys/types.h>
+#include <stdio.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <sched.h>
+#include "ostest.h"
+
+#ifndef NULL
+# define NULL (void*)0
+#endif
+
+static sem_t sem;
+
+static void *waiter_func(void *parameter)
+{
+ int id = (int)parameter;
+ int status;
+ int value;
+
+ printf("%s: Thread %d Started\n", __FUNCTION__, id);
+
+ /* Take the semaphore */
+
+ status = sem_getvalue(&sem, &value);
+ if (status < 0)
+ {
+ printf("%s: ERROR thread %d could not get semaphore value\n", __FUNCTION__, id);
+ }
+ else
+ {
+ printf("%s: Thread %d initial semaphore value = %d\n", __FUNCTION__, id, value);
+ }
+
+ printf("%s: Thread %d aiting on semaphore\n", __FUNCTION__, id);
+ status = sem_wait(&sem);
+ if (status != 0)
+ {
+ printf("%s: ERROR thread %d sem_wait failed\n", __FUNCTION__, id);
+ }
+ printf("%s: Thread %d awakened\n", __FUNCTION__, id);
+
+ status = sem_getvalue(&sem, &value);
+ if (status < 0)
+ {
+ printf("%s: ERROR thread %d could not get semaphore value\n", __FUNCTION__, id);
+ }
+ else
+ {
+ printf("%s: Thread %d new semaphore value = %d\n", __FUNCTION__, id, value);
+ }
+
+ printf("%s: Thread %d done\n", __FUNCTION__, id);
+ return NULL;
+}
+
+static void *poster_func(void *parameter)
+{
+ int id = (int)parameter;
+ int status;
+ int value;
+
+ printf("%s: Thread %d started\n", __FUNCTION__, id);
+
+ /* Take the semaphore */
+
+ do
+ {
+ status = sem_getvalue(&sem, &value);
+ if (status < 0)
+ {
+ printf("%s: ERROR thread %d could not get semaphore value\n", __FUNCTION__, id);
+ }
+ else
+ {
+ printf("%s: Thread %d semaphore value = %d\n", __FUNCTION__, id, value);
+ }
+
+ if (value < 0)
+ {
+ printf("%s: Thread %d posting semaphore\n", __FUNCTION__, id);
+ status = sem_post(&sem);
+ if (status != 0)
+ {
+ printf("%s: ERROR thread %d sem_wait failed\n", __FUNCTION__, id);
+ }
+
+ pthread_yield();
+
+ status = sem_getvalue(&sem, &value);
+ if (status < 0)
+ {
+ printf("%s: ERROR thread %d could not get semaphore value\n", __FUNCTION__, id);
+ }
+ else
+ {
+ printf("%s: Thread %d new semaphore value = %d\n", __FUNCTION__, id, value);
+ }
+ }
+ }
+ while (value < 0);
+
+ printf("%s: Thread %d done\n", __FUNCTION__, id);
+ return NULL;
+
+}
+
+void sem_test(void)
+{
+ pthread_t waiter_thread1;
+ pthread_t waiter_thread2;
+ pthread_t poster_thread;
+ struct sched_param sparam;
+ int prio_min;
+ int prio_max;
+ int prio_mid;
+ pthread_attr_t attr;
+ int status;
+
+ printf("%s: Initializing semaphore to 0\n", __FUNCTION__);
+ sem_init(&sem, 0, 0);
+
+ /* Start two waiter thread instances */
+
+ printf("%s: Starting waiter thread 1\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ prio_min = sched_get_priority_min(SCHED_FIFO);
+ prio_max = sched_get_priority_max(SCHED_FIFO);
+ prio_mid = (prio_min + prio_max) / 2;
+
+ sparam.sched_priority = (prio_mid + prio_max) / 2;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set thread 1 priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&waiter_thread1, &attr, waiter_func, (void*)1);
+ if (status != 0)
+ {
+ printf("%s: Error in thread 1 creation, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Starting waiter thread 2\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ sparam.sched_priority = prio_mid;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set thread 2 priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&waiter_thread2, &attr, waiter_func, (void*)2);
+ if (status != 0)
+ {
+ printf("%s: Error in thread 2 creation, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Starting poster thread 3\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ sparam.sched_priority = (prio_min + prio_mid) / 2;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set thread 3 priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&poster_thread, &attr, poster_func, (void*)3);
+ if (status != 0)
+ {
+ printf("%s: Error in thread 3 creation, status=%d\n", __FUNCTION__, status);
+ }
+
+ pthread_join(waiter_thread1, NULL);
+ pthread_join(waiter_thread2, NULL);
+ pthread_join(poster_thread, NULL);
+}
diff --git a/nuttx/examples/ostest/sighand.c b/nuttx/examples/ostest/sighand.c
new file mode 100644
index 000000000..9ffd166f4
--- /dev/null
+++ b/nuttx/examples/ostest/sighand.c
@@ -0,0 +1,254 @@
+/***********************************************************************
+ * sighand.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***********************************************************************/
+
+#include <sys/types.h>
+#include <stdio.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <signal.h>
+#include <sched.h>
+#include <errno.h>
+#include "ostest.h"
+
+#ifndef NULL
+# define NULL (void*)0
+#endif
+
+#define WAKEUP_SIGNAL 17
+#define SIGVALUE_INT 42
+
+static sem_t sem;
+static boolean sigreceived = FALSE;
+static boolean threadexited = FALSE;
+
+static void wakeup_action(int signo, siginfo_t *info, void *ucontext)
+{
+ sigset_t oldset;
+ sigset_t allsigs;
+ int status;
+
+ printf("%s: Received signal %d\n", __FUNCTION__, signo);
+
+ sigreceived = TRUE;
+
+ /* Check signo */
+
+ if (signo != WAKEUP_SIGNAL)
+ {
+ printf("%s: ERROR expected signo=%d\n", __FUNCTION__, WAKEUP_SIGNAL);
+ }
+
+ /* Check siginfo */
+
+ if (info->si_value.sival_int != SIGVALUE_INT)
+ {
+ printf("%s: ERROR sival_int=%d expected %d\n",
+ __FUNCTION__, info->si_value.sival_int, SIGVALUE_INT);
+ }
+ else
+ {
+ printf("%s: sival_int=%d\n", __FUNCTION__, info->si_value.sival_int);
+ }
+
+ if (info->si_signo != WAKEUP_SIGNAL)
+ {
+ printf("%s: ERROR expected si_signo=%d, got=%d\n",
+ __FUNCTION__, WAKEUP_SIGNAL, info->si_signo);
+ }
+
+ printf("%s: si_code=%d\n", __FUNCTION__, info->si_code);
+
+ /* Check ucontext_t */
+
+ printf("%s: ucontext=%p\n", __FUNCTION__, ucontext);
+
+ /* Check sigprocmask */
+
+ (void)sigfillset(&allsigs);
+ status = sigprocmask(SIG_SETMASK, NULL, &oldset);
+ if (status != OK)
+ {
+ printf("%s: ERROR sigprocmask failed, status=%d\n",
+ __FUNCTION__, status);
+ }
+
+ if (oldset != allsigs)
+ {
+ printf("%s: ERROR sigprocmask=%x expected=%x\n",
+ __FUNCTION__, oldset, allsigs);
+ }
+
+}
+
+static int waiter_main(int argc, char *argv[])
+{
+ sigset_t sigset;
+ struct sigaction act;
+ struct sigaction oact;
+ int status;
+
+ printf("%s: Waiter started\n", __FUNCTION__);
+
+ printf("%s: Unmasking signal %d\n", __FUNCTION__, WAKEUP_SIGNAL);
+ (void)sigemptyset(&sigset);
+ (void)sigaddset(&sigset, WAKEUP_SIGNAL);
+ status = sigprocmask(SIG_UNBLOCK, &sigset, NULL);
+ if (status != OK)
+ {
+ printf("%s: ERROR sigprocmask failed, status=%d\n",
+ __FUNCTION__, status);
+ }
+
+ printf("%s: Registering signal handler\n", __FUNCTION__);
+ act.sa_sigaction = wakeup_action;
+ act.sa_flags = SA_SIGINFO;
+
+ (void)sigfillset(&act.sa_mask);
+ (void)sigdelset(&act.sa_mask, WAKEUP_SIGNAL);
+
+ status = sigaction(WAKEUP_SIGNAL, &act, &oact);
+ if (status != OK)
+ {
+ printf("%s: ERROR sigaction failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: oact.sigaction=%p oact.sa_flags=%x oact.sa_mask=%x\n",
+ __FUNCTION__, oact.sa_sigaction, oact.sa_flags, oact.sa_mask);
+
+ /* Take the semaphore */
+
+ printf("%s: Waiting on semaphore\n", __FUNCTION__);
+ fflush(stdout);
+ status = sem_wait(&sem);
+ if (status != 0)
+ {
+ int error = *get_errno_ptr();
+ if (error == EINTR)
+ {
+ printf("%s: sem_wait() successfully interrupted by signal\n", __FUNCTION__);
+ }
+ else
+ {
+ printf("%s: ERROR sem_wait failed, errno=%d\n", __FUNCTION__, error);
+ }
+ }
+ else
+ {
+ printf("%s: ERROR awakened with no error!\n", __FUNCTION__);
+ }
+
+ printf("%s: done\n", __FUNCTION__);
+ fflush(stdout);
+ threadexited = TRUE;
+ return 0;
+}
+
+void sighand_test(void)
+{
+ struct sched_param param;
+ union sigval sigvalue;
+ pid_t waiterpid;
+ int policy;
+ int status;
+
+ printf("%s: Initializing semaphore to 0\n", __FUNCTION__);
+ sem_init(&sem, 0, 0);
+
+ /* Start waiter thread */
+
+ printf("%s: Starting waiter task\n", __FUNCTION__);
+
+
+ status = sched_getparam (0, &param);
+ if (status != OK)
+ {
+ printf("%s: ERROR sched_getparam() failed\n", __FUNCTION__);
+ param.sched_priority = PTHREAD_DEFAULT_PRIORITY;
+ }
+
+ policy = sched_getscheduler(0);
+ if (policy == ERROR)
+ {
+ printf("%s: ERROR sched_getscheduler() failed\n", __FUNCTION__);
+ policy = SCHED_FIFO;
+ }
+
+ waiterpid = task_create("waiter", param.sched_priority,
+ PTHREAD_STACK_DEFAULT, waiter_main, 0, 0, 0, 0);
+ if (waiterpid == ERROR)
+ {
+ printf("%s: ERROR failed to start waiter_main\n", __FUNCTION__);
+ }
+ else
+ {
+ printf("%s: Started waiter_main pid=%d\n", __FUNCTION__, waiterpid);
+ }
+
+ /* Wait a bit */
+
+ fflush(stdout);
+ usleep(500*1000);
+
+ /* Then signal the waiter thread. */
+
+ sigvalue.sival_int = SIGVALUE_INT;
+ status = sigqueue(waiterpid, WAKEUP_SIGNAL, sigvalue);
+ if (status != OK)
+ {
+ printf("%s: ERROR sigqueue failed\n", __FUNCTION__);
+ task_delete(waiterpid);
+ }
+
+ /* Wait a bit */
+
+ fflush(stdout);
+ usleep(500*1000);
+
+ /* Then check the result */
+
+ if (!threadexited)
+ {
+ printf("%s: ERROR waiter task did not exit\n", __FUNCTION__);
+ }
+
+ if (!sigreceived)
+ {
+ printf("%s: ERROR signal handler did not run\n", __FUNCTION__);
+ }
+
+ printf("%s: done\n", __FUNCTION__);
+ fflush(stdout);
+}
diff --git a/nuttx/examples/ostest/timedwait.c b/nuttx/examples/ostest/timedwait.c
new file mode 100644
index 000000000..9f3e61eae
--- /dev/null
+++ b/nuttx/examples/ostest/timedwait.c
@@ -0,0 +1,161 @@
+/***********************************************************************
+ * timedwait.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ***********************************************************************/
+
+#include <stdio.h>
+#include <time.h>
+#include <pthread.h>
+#include <unistd.h>
+#include "ostest.h"
+
+static pthread_mutex_t mutex;
+static pthread_cond_t cond;
+
+static void *thread_waiter(void *parameter)
+{
+ struct timespec time;
+ int status;
+
+ /* Take the mutex */
+
+ printf("%s: Taking mutex\n", __FUNCTION__);
+ status = pthread_mutex_lock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_lock failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Starting 5 second wait for condition\n", __FUNCTION__);
+
+ status = clock_gettime(CLOCK_REALTIME, &time);
+ if (status != 0)
+ {
+ printf("%s: ERROR clock_gettime failed\n", __FUNCTION__);
+ }
+ time.tv_sec += 5;
+
+ /* The wait -- no-one is ever going to awaken us */
+
+ status = pthread_cond_timedwait(&cond, &mutex, &time);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_cond_timedwait failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Release the mutex */
+
+ printf("%s: Releasing mutex\n", __FUNCTION__);
+ status = pthread_mutex_unlock(&mutex);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_unlock failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Exit with status 0x12345678\n", __FUNCTION__);
+ pthread_exit((void*)0x12345678);
+ return NULL;
+}
+
+void timedwait_test(void)
+{
+ pthread_t waiter;
+ pthread_attr_t attr;
+ struct sched_param sparam;
+ void *result;
+ int prio_max;
+ int status;
+
+ /* Initialize the mutex */
+
+ printf("%s: Initializing mutex\n", __FUNCTION__);
+ status = pthread_mutex_init(&mutex, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_mutex_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Initialize the condition variable */
+
+ printf("%s: Initializing cond\n", __FUNCTION__);
+ status = pthread_cond_init(&cond, NULL);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_condinit failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ /* Start the waiter thread at higher priority */
+
+ printf("%s: Starting waiter\n", __FUNCTION__);
+ status = pthread_attr_init(&attr);
+ if (status != 0)
+ {
+ printf("%s: pthread_attr_init failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ prio_max = sched_get_priority_max(SCHED_FIFO);
+ status = sched_getparam (getpid(), &sparam);
+ if (status != 0)
+ {
+ printf("%s: sched_getparam failed\n", __FUNCTION__);
+ sparam.sched_priority = PTHREAD_DEFAULT_PRIORITY;
+ }
+
+ sparam.sched_priority = (prio_max + sparam.sched_priority) / 2;
+ status = pthread_attr_setschedparam(&attr,&sparam);
+ if (status != OK)
+ {
+ printf("%s: pthread_attr_setschedparam failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: Set thread 2 priority to %d\n", __FUNCTION__, sparam.sched_priority);
+ }
+
+ status = pthread_create(&waiter, &attr, thread_waiter, NULL);
+ if (status != 0)
+ {
+ printf("%s: pthread_create failed, status=%d\n", __FUNCTION__, status);
+ }
+
+ printf("%s: Joining\n", __FUNCTION__);
+ status = pthread_join(waiter, &result);
+ if (status != 0)
+ {
+ printf("%s: ERROR pthread_join failed, status=%d\n", __FUNCTION__, status);
+ }
+ else
+ {
+ printf("%s: waiter exited with result=%p\n", __FUNCTION__, result);
+ }
+}