summaryrefslogtreecommitdiff
path: root/apps/examples
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-09-28 13:02:36 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-09-28 13:02:36 -0600
commit8aed46c0d53be355372066ed2cb7eeb5993c65d7 (patch)
tree3ce834f96629b6f333a48f705f1ab2643645572d /apps/examples
parent4ea6d399799d8bb94cca45b26e2bc2d5784a1792 (diff)
downloadpx4-nuttx-8aed46c0d53be355372066ed2cb7eeb5993c65d7.tar.gz
px4-nuttx-8aed46c0d53be355372066ed2cb7eeb5993c65d7.tar.bz2
px4-nuttx-8aed46c0d53be355372066ed2cb7eeb5993c65d7.zip
Add a simple named semaphore test to the OS test
Diffstat (limited to 'apps/examples')
-rw-r--r--apps/examples/ostest/Makefile3
-rw-r--r--apps/examples/ostest/nsem.c230
-rw-r--r--apps/examples/ostest/ostest_main.c6
-rw-r--r--apps/examples/ostest/sem.c20
4 files changed, 259 insertions, 0 deletions
diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile
index 375526f66..27957b892 100644
--- a/apps/examples/ostest/Makefile
+++ b/apps/examples/ostest/Makefile
@@ -59,6 +59,9 @@ endif
ifneq ($(CONFIG_DISABLE_PTHREAD),y)
CSRCS += cancel.c cond.c mutex.c sem.c semtimed.c barrier.c
+ifeq ($(CONFIG_FS_NAMED_SEMAPHORES),y)
+CSRCS += nsem.c
+endif
ifneq ($(CONFIG_RR_INTERVAL),0)
CSRCS += roundrobin.c
endif # CONFIG_RR_INTERVAL
diff --git a/apps/examples/ostest/nsem.c b/apps/examples/ostest/nsem.c
new file mode 100644
index 000000000..921b052b1
--- /dev/null
+++ b/apps/examples/ostest/nsem.c
@@ -0,0 +1,230 @@
+/***********************************************************************
+ * apps/examples/nsem.c
+ *
+ * Copyright (C) 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 <stdio.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <sched.h>
+#include "ostest.h"
+
+#ifdef CONFIG_FS_NAMED_SEMAPHORES
+
+/***********************************************************************
+ * Pre-processor Definitions
+ ***********************************************************************/
+
+#define SEM1_NAME "foo"
+#define SEM2_NAME "bar"
+
+#ifndef NULL
+# define NULL (void*)0
+#endif
+
+/***********************************************************************
+ * Private Data
+ ***********************************************************************/
+
+/***********************************************************************
+ * Private Functions
+ ***********************************************************************/
+
+static void *nsem_peer(void *parameter)
+{
+ FAR sem_t *sem1;
+ FAR sem_t *sem2;
+
+ /* Open semaphore 1. This should have already been created by
+ * nsem_test().
+ */
+
+ printf("nsem_peer: Open semaphore 1\n");
+ sem1 = sem_open(SEM1_NAME, 0);
+ if (sem1 == (FAR sem_t*)ERROR)
+ {
+ int errcode = errno;
+ printf("nsem_peer: ERROR: sem_open(1) failed: %d\n", errcode);
+ return NULL;
+ }
+
+ /* Open semaphore 2. We will create that one */
+
+ printf("nsem_peer: Create semaphore 2 with value == 0\n");
+ sem2 = sem_open(SEM2_NAME, O_CREATE|O_EXCL, 0644, 0);
+ if (sem1 == (FAR sem_t*)ERROR)
+ {
+ int errcode = errno;
+ printf("nsem_peer: ERROR: sem_open(2) failed: %d\n", errcode);
+ return NULL;
+ }
+
+ /* Post and discard semaphore 1 */
+
+ printf("nsem_peer: Post, close, and unlink semaphore 1\n");
+ sem_post(sem1);
+ sem_close(sem1);
+ sem_unlink(SEM1_NAME);
+
+ /* Now post and close semaphore 2 */
+
+ printf("nsem_peer: Post and close semaphore 2\n");
+ sem_post(sem2);
+ sem_close(sem2);
+ return NULL;
+}
+
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
+void nsem_test(void)
+{
+ pthread_t peer = (pthread_t)0;
+#ifdef SDCC
+ pthread_addr_t result;
+#endif
+ FAR sem_t *sem1;
+ FAR sem_t *sem2;
+ struct sched_param sparam;
+ int prio_min;
+ int prio_max;
+ int prio_mid;
+ pthread_attr_t attr;
+ int status;
+
+ /* Open semaphore 2. We will create that one */
+
+ printf("nsem_test: Create semaphore 1 with value == 0\n");
+ sem2 = sem_open(SEM1_NAME, O_CREATE|O_EXCL, 0644, 0);
+ if (sem1 == (FAR sem_t*)ERROR)
+ {
+ int errcode = errno;
+ printf("nsem_peer: ERROR: sem_open(1) failed: %d\n", errcode);
+ return NULL;
+ }
+
+ /* Start the peer thread */
+
+ printf("nsem_test: Starting peer peer\n");
+ status = pthread_attr_init(&attr);
+ if (status != OK)
+ {
+ printf("nsem_test: pthread_attr_init failed, status=%d\n", 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("nsem_test: ERROR: pthread_attr_setschedparam failed, status=%d\n", status);
+ }
+ else
+ {
+ printf("nsem_test: Set peer priority to %d\n", sparam.sched_priority);
+ }
+
+ status = pthread_create(&peer, &attr, nsem_peer, NULL);
+ if (status != 0)
+ {
+ printf("nsem_test: ERROR: Peer thread creation failed: %d\n", status);
+ return;
+ }
+
+ /* Wait for the peer to post semaphore 1 */
+
+ status = sem_wait(sem1);
+ if (status < 0)
+ {
+ int errcode = errno;
+ printf("nsem_test: ERROR: sem_wait(1) failed: %d\n", errcode);
+ pthread_cancel(peer);
+ return;
+ }
+
+ /* Close sem1. It should already have been unlinked by the nsem_peer */
+
+ sem_close(sem1);
+
+ /* Open semaphore 2. This should have already been created by
+ * nsem_peer().
+ */
+
+ printf("nsem_test: Open semaphore 2\n");
+ sem1 = sem_open(SEM2_NAME, 0);
+ if (sem1 == (FAR sem_t*)ERROR)
+ {
+ int errcode = errno;
+ printf("nsem_test: ERROR: sem_open(2) failed: %d\n", errcode);
+ pthread_cancel(peer);
+ return NULL;
+ }
+
+ /* Wait for the peer to post semaphore 2 */
+
+ status = sem_wait(sem1);
+ if (status < 0)
+ {
+ int errcode = errno;
+ printf("nsem_test: ERROR: sem_wait(1) failed: %d\n", errcode);
+ pthread_cancel(peer);
+ return;
+ }
+
+ /* Close and unlink semaphore 2 */
+
+ sem_close(sem1);
+ sem_unlink(SEM2_NAME);
+
+#ifdef SDCC
+ if (peer != (pthread_t)0)
+ {
+ pthread_join(peer, &result);
+ }
+#else
+ if (peer != (pthread_t)0)
+ {
+ pthread_join(peer, NULL);
+ }
+#endif
+}
+
+#endif /* CONFIG_FS_NAMED_SEMAPHORES */
diff --git a/apps/examples/ostest/ostest_main.c b/apps/examples/ostest/ostest_main.c
index 0f538f5e9..4f2bf559d 100644
--- a/apps/examples/ostest/ostest_main.c
+++ b/apps/examples/ostest/ostest_main.c
@@ -382,6 +382,12 @@ static int user_main(int argc, char *argv[])
semtimed_test();
check_test_memory_usage();
+#ifdef CONFIG_FS_NAMED_SEMAPHORES
+ printf("\nuser_main: Named semaphore test\n");
+ nsem_test();
+ check_test_memory_usage();
+
+#endif
#endif
#ifndef CONFIG_DISABLE_PTHREAD
diff --git a/apps/examples/ostest/sem.c b/apps/examples/ostest/sem.c
index 5c7f39cce..14d0c0725 100644
--- a/apps/examples/ostest/sem.c
+++ b/apps/examples/ostest/sem.c
@@ -33,18 +33,34 @@
*
***********************************************************************/
+/***********************************************************************
+ * Included Files
+ ***********************************************************************/
+
#include <stdio.h>
#include <pthread.h>
#include <semaphore.h>
#include <sched.h>
#include "ostest.h"
+/***********************************************************************
+ * Pre-processor Definitions
+ ***********************************************************************/
+
#ifndef NULL
# define NULL (void*)0
#endif
+/***********************************************************************
+ * Private Data
+ ***********************************************************************/
+
static sem_t sem;
+/***********************************************************************
+ * Private Functions
+ ***********************************************************************/
+
static void *waiter_func(void *parameter)
{
int id = (int)parameter;
@@ -138,6 +154,10 @@ static void *poster_func(void *parameter)
}
+/***********************************************************************
+ * Public Functions
+ ***********************************************************************/
+
void sem_test(void)
{
pthread_t waiter_thread1 = (pthread_t)0;