summaryrefslogtreecommitdiff
path: root/nuttx/sched/signal
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-08-08 12:44:44 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-08-08 12:44:44 -0600
commit6b08270554c627bd8034cfd772e4e40cde579648 (patch)
tree16a8c9e6e460805e817c3e304063b25b9b2f9bf8 /nuttx/sched/signal
parentb61c7bebffa7dc52d2edb128086bbbca2d978c48 (diff)
downloadpx4-nuttx-6b08270554c627bd8034cfd772e4e40cde579648.tar.gz
px4-nuttx-6b08270554c627bd8034cfd772e4e40cde579648.tar.bz2
px4-nuttx-6b08270554c627bd8034cfd772e4e40cde579648.zip
Move signal-related files from sched/ to sched/signal
Diffstat (limited to 'nuttx/sched/signal')
-rw-r--r--nuttx/sched/signal/sig_action.c317
-rw-r--r--nuttx/sched/signal/sig_allocatependingsigaction.c137
-rw-r--r--nuttx/sched/signal/sig_cleanup.c134
-rw-r--r--nuttx/sched/signal/sig_deliver.c188
-rw-r--r--nuttx/sched/signal/sig_dispatch.c504
-rw-r--r--nuttx/sched/signal/sig_findaction.c100
-rw-r--r--nuttx/sched/signal/sig_initialize.c271
-rw-r--r--nuttx/sched/signal/sig_kill.c140
-rw-r--r--nuttx/sched/signal/sig_lowest.c91
-rw-r--r--nuttx/sched/signal/sig_mqnotempty.c132
-rw-r--r--nuttx/sched/signal/sig_pause.c110
-rw-r--r--nuttx/sched/signal/sig_pending.c133
-rw-r--r--nuttx/sched/signal/sig_procmask.c180
-rw-r--r--nuttx/sched/signal/sig_queue.c167
-rw-r--r--nuttx/sched/signal/sig_releasependingsigaction.c120
-rw-r--r--nuttx/sched/signal/sig_releasependingsignal.c131
-rw-r--r--nuttx/sched/signal/sig_removependingsignal.c118
-rw-r--r--nuttx/sched/signal/sig_suspend.c177
-rw-r--r--nuttx/sched/signal/sig_timedwait.c357
-rw-r--r--nuttx/sched/signal/sig_unmaskpendingsignal.c143
-rw-r--r--nuttx/sched/signal/sig_waitinfo.c89
-rw-r--r--nuttx/sched/signal/signal.h201
22 files changed, 3940 insertions, 0 deletions
diff --git a/nuttx/sched/signal/sig_action.c b/nuttx/sched/signal/sig_action.c
new file mode 100644
index 000000000..bd17e4f9f
--- /dev/null
+++ b/nuttx/sched/signal/sig_action.c
@@ -0,0 +1,317 @@
+/****************************************************************************
+ * sched/sig_action.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 <stdint.h>
+#include <signal.h>
+#include <queue.h>
+#include <sched.h>
+#include <errno.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define COPY_SIGACTION(t,f) \
+ { (t)->sa_sigaction = (f)->sa_sigaction; \
+ (t)->sa_mask = (f)->sa_mask; \
+ (t)->sa_flags = (f)->sa_flags; }
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sig_allocateaction
+ *
+ * Description:
+ * Allocate a new element for a sigaction queue
+ *
+ ****************************************************************************/
+
+static FAR sigactq_t *sig_allocateaction(void)
+{
+ FAR sigactq_t *sigact;
+
+ /* Try to get the signal action structure from the free list */
+
+ sigact = (FAR sigactq_t*)sq_remfirst(&g_sigfreeaction);
+
+ /* Check if we got one. */
+
+ if (!sigact)
+ {
+ /* Add another block of signal actions to the list */
+
+ sig_allocateactionblock();
+
+ /* And try again */
+
+ sigact = (FAR sigactq_t*)sq_remfirst(&g_sigfreeaction);
+ ASSERT(sigact);
+ }
+
+ return sigact;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigaction
+ *
+ * Description:
+ * This function allows the calling process to examine and/or specify the
+ * action to be associated with a specific signal.
+ *
+ * The structure sigaction, used to describe an action to be taken, is
+ * defined to include the following members:
+ *
+ * - sa_u.sa_handler: Pointer to a signal-catching function
+ * - sa_u.sa_sigaction: Alternative form of the signal-catching function
+ * - sa_mask: An additional set of signals to be blocked during execution
+ * of a signal catching function
+ * - sa_flags. Special flags to affect the behavior of a signal.
+ *
+ * If the argument 'act' is not NULL, it points to a structure specifying
+ * the action to be associated with the specified signal. If the argument
+ * 'oact' is not NULL, the action previously associated with the signal
+ * is stored in the location pointed to by the argument 'oact.'
+ *
+ * When a signal is caught by a signal-catching function installed by
+ * sigaction() function, a new signal mask is calculated and installed for
+ * the duration of the signal-catching function. This mask is formed by
+ * taking the union of the current signal mask and the value of the
+ * sa_mask for the signal being delivered and then including the signal
+ * being delivered. If and when the user's signal handler returns, the
+ * original signal mask is restored.
+ *
+ * Once an action is installed for a specific signal, it remains installed
+ * until another action is explicitly requested by another call to sigaction().
+ *
+ * Parameters:
+ * sig - Signal of interest
+ * act - Location of new handler
+ * oact - Location to store only handler
+ *
+ * Return Value:
+ * 0 (OK), or -1 (ERROR) if the signal number is invalid.
+ * (errno is not set)
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ * - There are no default actions so the special value SIG_DFL is treated
+ * like SIG_IGN.
+ * - All sa_flags in struct sigaction of act input are ignored (all
+ * treated like SA_SIGINFO). The one exception is if CONFIG_SCHED_CHILDSTATUS
+ * is defined; then SA_NOCLDWAIT is supported but only for SIGCHLD
+ *
+ ****************************************************************************/
+
+int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *oact)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ FAR sigactq_t *sigact;
+
+ /* Since sigactions can only be installed from the running thread of
+ * execution, no special precautions should be necessary.
+ */
+
+ /* Verify the signal number */
+
+ if (!GOOD_SIGNO(signo))
+ {
+ set_errno(EINVAL);
+ return ERROR;
+ }
+
+ /* Find the signal in the sigactionq */
+
+ sigact = sig_findaction(rtcb, signo);
+
+ /* Return the old sigaction value if so requested */
+
+ if (oact)
+ {
+ if (sigact)
+ {
+ COPY_SIGACTION(oact, &sigact->act);
+ }
+ else
+ {
+ /* There isn't an old value */
+
+ oact->sa_u._sa_handler = NULL;
+ oact->sa_mask = NULL_SIGNAL_SET;
+ oact->sa_flags = 0;
+ }
+ }
+
+ /* If the argument act is a null pointer, signal handling is unchanged;
+ * thus, the call can be used to enquire about the current handling of
+ * a given signal.
+ */
+
+ if (!act)
+ {
+ return OK;
+ }
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+
+ /* Handle a special case. Retention of child status can be suppressed
+ * if signo == SIGCHLD and sa_flags == SA_NOCLDWAIT.
+ *
+ * POSIX.1 leaves it unspecified whether a SIGCHLD signal is generated
+ * when a child process terminates. In NuttX, a SIGCHLD signal is
+ * generated in this case; but in some other implementations, it may not
+ * be.
+ */
+
+ if (signo == SIGCHLD && (act->sa_flags & SA_NOCLDWAIT) != 0)
+ {
+ irqstate_t flags;
+
+ /* We do require a critical section to muck with the TCB values that
+ * can be modified by the child thread.
+ */
+
+ flags = irqsave();
+
+ /* Mark that status should be not be retained */
+
+ rtcb->group->tg_flags |= GROUP_FLAG_NOCLDWAIT;
+
+ /* Free all pending exit status */
+
+ group_removechildren(rtcb->group);
+ irqrestore(flags);
+ }
+#endif
+
+ /* Handle the case where no sigaction is supplied (SIG_IGN) */
+
+ if (act->sa_u._sa_handler == SIG_IGN)
+ {
+ /* Do we still have a sigaction container from the previous setting? */
+
+ if (sigact)
+ {
+ /* Yes.. Remove it from sigactionq */
+
+ sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
+
+ /* And deallocate it */
+
+ sig_releaseaction(sigact);
+ }
+ }
+
+ /* A sigaction has been supplied */
+
+ else
+ {
+ /* Do we still have a sigaction container from the previous setting?
+ * If so, then re-use for the new signal action.
+ */
+
+ if (!sigact)
+ {
+ /* No.. Then we need to allocate one for the new action. */
+
+ sigact = sig_allocateaction();
+
+ /* An error has occurred if we could not allocate the sigaction */
+
+ if (!sigact)
+ {
+ set_errno(ENOMEM);
+ return ERROR;
+ }
+
+ /* Put the signal number in the queue entry */
+
+ sigact->signo = (uint8_t)signo;
+
+ /* Add the new sigaction to sigactionq */
+
+ sq_addlast((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
+ }
+
+ /* Set the new sigaction */
+
+ COPY_SIGACTION(&sigact->act, act);
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: sig_releaseaction
+ *
+ * Description:
+ * Deallocate a sigaction Q entry
+ *
+ ****************************************************************************/
+
+void sig_releaseaction(FAR sigactq_t *sigact)
+{
+ /* Just put it back on the free list */
+
+ sq_addlast((FAR sq_entry_t*)sigact, &g_sigfreeaction);
+}
diff --git a/nuttx/sched/signal/sig_allocatependingsigaction.c b/nuttx/sched/signal/sig_allocatependingsigaction.c
new file mode 100644
index 000000000..fa8236ee8
--- /dev/null
+++ b/nuttx/sched/signal/sig_allocatependingsigaction.c
@@ -0,0 +1,137 @@
+/************************************************************************
+ * sched/sig_allocatependingsigaction.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 <assert.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Function Prototypes
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_allocatependingsigaction
+ *
+ * Description:
+ * Allocate a new element for the pending signal action queue
+ *
+ ************************************************************************/
+
+FAR sigq_t *sig_allocatependingsigaction(void)
+{
+ FAR sigq_t *sigq;
+ irqstate_t saved_state;
+
+ /* Check if we were called from an interrupt handler. */
+
+ if (up_interrupt_context())
+ {
+ /* Try to get the pending signal action structure from the free list */
+
+ sigq = (FAR sigq_t*)sq_remfirst(&g_sigpendingaction);
+
+ /* If so, then try the special list of structures reserved for
+ * interrupt handlers
+ */
+
+ if (!sigq)
+ {
+ sigq = (FAR sigq_t*)sq_remfirst(&g_sigpendingirqaction);
+ }
+ }
+
+ /* If we were not called from an interrupt handler, then we are
+ * free to allocate pending signal action structures if necessary. */
+
+ else
+ {
+ /* Try to get the pending signal action structure from the free list */
+
+ saved_state = irqsave();
+ sigq = (FAR sigq_t*)sq_remfirst(&g_sigpendingaction);
+ irqrestore(saved_state);
+
+ /* Check if we got one. */
+
+ if (!sigq)
+ {
+ /* No...Try the resource pool */
+
+ if (!sigq)
+ {
+ sigq = (FAR sigq_t *)kmalloc((sizeof (sigq_t)));
+ }
+
+ /* Check if we got an allocated message */
+
+ if (sigq)
+ {
+ sigq->type = SIG_ALLOC_DYN;
+ }
+ }
+ }
+
+ return sigq;
+}
+
diff --git a/nuttx/sched/signal/sig_cleanup.c b/nuttx/sched/signal/sig_cleanup.c
new file mode 100644
index 000000000..535c6273a
--- /dev/null
+++ b/nuttx/sched/signal/sig_cleanup.c
@@ -0,0 +1,134 @@
+/************************************************************************
+ * sched/sig_cleanup.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 <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_cleanup
+ *
+ * Description:
+ * Deallocate all signal-related lists in a TCB. This function is
+ * called only at task deletion time. The caller is expected to have
+ * assured the critical section necessary to perform this action.
+ *
+ ************************************************************************/
+
+void sig_cleanup(FAR struct tcb_s *stcb)
+{
+ FAR sigactq_t *sigact;
+ FAR sigq_t *sigq;
+
+ /* Deallocate all entries in the list of signal actions */
+
+ while ((sigact = (FAR sigactq_t*)sq_remfirst(&stcb->sigactionq)) != NULL)
+ {
+ sig_releaseaction(sigact);
+ }
+
+ /* Deallocate all entries in the list of pending signal actions */
+
+ while ((sigq = (FAR sigq_t*)sq_remfirst(&stcb->sigpendactionq)) != NULL)
+ {
+ sig_releasependingsigaction(sigq);
+ }
+
+ /* Deallocate all entries in the list of posted signal actions */
+
+ while ((sigq = (FAR sigq_t*)sq_remfirst(&stcb->sigpostedq)) != NULL)
+ {
+ sig_releasependingsigaction(sigq);
+ }
+
+ /* Misc. signal-related clean-up */
+
+ stcb->sigprocmask = ALL_SIGNAL_SET;
+ stcb->sigwaitmask = NULL_SIGNAL_SET;
+}
+
+/************************************************************************
+ * Name: sig_release
+ *
+ * Description:
+ * Deallocate all signal-related lists in a group. This function is
+ * called only when the last thread leaves the group. The caller is
+ * expected to have assured the critical section necessary to perform
+ * this action.
+ *
+ ************************************************************************/
+
+void sig_release(FAR struct task_group_s *group)
+{
+ FAR sigpendq_t *sigpend;
+
+ /* Deallocate all entries in the list of pending signals */
+
+ while ((sigpend = (FAR sigpendq_t*)sq_remfirst(&group->sigpendingq)) != NULL)
+ {
+ sig_releasependingsignal(sigpend);
+ }
+}
+
diff --git a/nuttx/sched/signal/sig_deliver.c b/nuttx/sched/signal/sig_deliver.c
new file mode 100644
index 000000000..6e40db179
--- /dev/null
+++ b/nuttx/sched/signal/sig_deliver.c
@@ -0,0 +1,188 @@
+/****************************************************************************
+ * sched/sig_deliver.c
+ *
+ * Copyright (C) 2007, 2008, 2012-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 <signal.h>
+#include <unistd.h>
+#include <sched.h>
+#include <string.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "sem_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sig_deliver
+ *
+ * Description:
+ * This function is called on the thread of execution of the signal
+ * receiving task. It processes all queued signals then returns.
+ *
+ ****************************************************************************/
+
+void sig_deliver(FAR struct tcb_s *stcb)
+{
+ FAR sigq_t *sigq;
+ FAR sigq_t *next;
+ sigset_t savesigprocmask;
+ irqstate_t saved_state;
+ int saved_errno;
+
+ sched_lock();
+
+ /* Save the thread errno. When we finished dispatching the
+ * signal actions and resume the task, the errno value must
+ * be unchanged by the operation of the signal handling. In
+ * particular, the EINTR indication that says that the task
+ * was reawakened by a signal must be retained.
+ */
+
+ saved_errno = stcb->pterrno;
+ for (sigq = (FAR sigq_t*)stcb->sigpendactionq.head; (sigq); sigq = next)
+ {
+ next = sigq->flink;
+ sdbg("Sending signal sigq=0x%x\n", sigq);
+
+ /* Remove the signal structure from the sigpendactionq and place it
+ * in the sigpostedq. NOTE: Since signals are processed one at a
+ * time, there should never be more than one signal in the sigpostedq
+ */
+
+ saved_state = irqsave();
+ sq_rem((FAR sq_entry_t*)sigq, &(stcb->sigpendactionq));
+ sq_addlast((FAR sq_entry_t*)sigq, &(stcb->sigpostedq));
+ irqrestore(saved_state);
+
+ /* Call the signal handler (unless the signal was cancelled)
+ *
+ * Save a copy of the old sigprocmask and install the new
+ * (temporary) sigprocmask. The new sigprocmask is the union
+ * of the current sigprocmask and the sa_mask for the signal being
+ * delivered plus the signal being delivered.
+ */
+
+ savesigprocmask = stcb->sigprocmask;
+ stcb->sigprocmask = savesigprocmask | sigq->mask | SIGNO2SET(sigq->info.si_signo);
+
+ /* Deliver the signal. In the kernel build this has to be handled
+ * differently if we are dispatching to a signal handler in a user-
+ * space task or thread; we have to switch to user-mode before
+ * calling the task.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ if ((stcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_KERNEL)
+ {
+ /* The sigq_t pointed to by sigq resides in kernel space. So we
+ * cannot pass a reference to sigq->info to the user application.
+ * Instead, we will copy the siginfo_t structure onto the stack.
+ * We are currently executing on the stack of the user thread
+ * (albeit temporarily in kernel mode), so the copy of the
+ * siginfo_t structure will be accessible by the user thread.
+ */
+
+ siginfo_t info;
+ memcpy(&info, &sigq->info, sizeof(siginfo_t));
+
+ up_signal_dispatch(sigq->action.sighandler, sigq->info.si_signo,
+ &info, NULL);
+ }
+ else
+#endif
+ {
+ /* The kernel thread signal handler is much simpler. */
+
+ (*sigq->action.sighandler)(sigq->info.si_signo, &sigq->info,
+ NULL);
+ }
+
+ /* Restore the original sigprocmask */
+
+ stcb->sigprocmask = savesigprocmask;
+
+ /* Now, handle the (rare?) case where (a) a blocked signal was
+ * received while the signal handling executed but (b) restoring the
+ * original sigprocmask will unblock the signal.
+ */
+
+ sig_unmaskpendingsignal();
+
+ /* Remove the signal from the sigpostedq */
+
+ saved_state = irqsave();
+ sq_rem((FAR sq_entry_t*)sigq, &(stcb->sigpostedq));
+ irqrestore(saved_state);
+
+ /* Then deallocate it */
+
+ sig_releasependingsigaction(sigq);
+ }
+
+ stcb->pterrno = saved_errno;
+ sched_unlock();
+}
+
diff --git a/nuttx/sched/signal/sig_dispatch.c b/nuttx/sched/signal/sig_dispatch.c
new file mode 100644
index 000000000..6cada00af
--- /dev/null
+++ b/nuttx/sched/signal/sig_dispatch.c
@@ -0,0 +1,504 @@
+/****************************************************************************
+ * sched/sig_dispatch.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 <string.h>
+#include <signal.h>
+#include <unistd.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "sem_internal.h"
+#include "signal/signal.h"
+#include "mqueue/mqueue.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sig_queueaction
+ *
+ * Description:
+ * Queue a signal action for delivery to a task.
+ *
+ * Returned Value:
+ * Returns 0 (OK) on success or a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int sig_queueaction(FAR struct tcb_s *stcb, siginfo_t *info)
+{
+ FAR sigactq_t *sigact;
+ FAR sigq_t *sigq;
+ irqstate_t saved_state;
+ int ret = OK;
+
+ sched_lock();
+
+ /* Find the sigaction associated with this signal */
+
+ sigact = sig_findaction(stcb, info->si_signo);
+
+ /* Check if a valid signal handler is available and if the signal is
+ * unblocked. NOTE: There is no default action.
+ */
+
+ if ((sigact) && (sigact->act.sa_u._sa_sigaction))
+ {
+ /* Allocate a new element for the signal queue. NOTE:
+ * sig_allocatependingsigaction will force a system crash if it is
+ * unable to allocate memory for the signal data */
+
+ sigq = sig_allocatependingsigaction();
+ if (!sigq)
+ {
+ ret = -ENOMEM;
+ }
+ else
+ {
+ /* Populate the new signal queue element */
+
+ sigq->action.sighandler = sigact->act.sa_u._sa_sigaction;
+ sigq->mask = sigact->act.sa_mask;
+ memcpy(&sigq->info, info, sizeof(siginfo_t));
+
+ /* Put it at the end of the pending signals list */
+
+ saved_state = irqsave();
+ sq_addlast((FAR sq_entry_t*)sigq, &(stcb->sigpendactionq));
+ irqrestore(saved_state);
+ }
+ }
+
+ sched_unlock();
+ return ret;
+}
+
+/****************************************************************************
+ * Name: sig_allocatependingsignal
+ *
+ * Description:
+ * Allocate a pending signal list entry
+ *
+ ****************************************************************************/
+
+static FAR sigpendq_t *sig_allocatependingsignal(void)
+{
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
+
+ /* Check if we were called from an interrupt handler. */
+
+ if (up_interrupt_context())
+ {
+ /* Try to get the pending signal structure from the free list */
+
+ sigpend = (FAR sigpendq_t*)sq_remfirst(&g_sigpendingsignal);
+ if (!sigpend)
+ {
+ /* If no pending signal structure is available in the free list,
+ * then try the special list of structures reserved for
+ * interrupt handlers
+ */
+
+ sigpend = (FAR sigpendq_t*)sq_remfirst(&g_sigpendingirqsignal);
+ }
+ }
+
+ /* If we were not called from an interrupt handler, then we are
+ * free to allocate pending action structures if necessary. */
+
+ else
+ {
+ /* Try to get the pending signal structure from the free list */
+
+ saved_state = irqsave();
+ sigpend = (FAR sigpendq_t*)sq_remfirst(&g_sigpendingsignal);
+ irqrestore(saved_state);
+
+ /* Check if we got one. */
+
+ if (!sigpend)
+ {
+ /* No... Allocate the pending signal */
+
+ if (!sigpend)
+ {
+ sigpend = (FAR sigpendq_t *)kmalloc((sizeof (sigpendq_t)));
+ }
+
+ /* Check if we got an allocated message */
+
+ if (sigpend)
+ {
+ sigpend->type = SIG_ALLOC_DYN;
+ }
+ }
+ }
+
+ return sigpend;
+}
+
+/****************************************************************************
+ * Name: sig_findpendingsignal
+ *
+ * Description:
+ * Find a specified element in the pending signal list
+ *
+ ****************************************************************************/
+
+static FAR sigpendq_t *sig_findpendingsignal(FAR struct task_group_s *group,
+ int signo)
+{
+ FAR sigpendq_t *sigpend = NULL;
+ irqstate_t saved_state;
+
+ DEBUGASSERT(group);
+
+ /* Pending sigals can be added from interrupt level. */
+
+ saved_state = irqsave();
+
+ /* Seach the list for a sigpendion on this signal */
+
+ for (sigpend = (FAR sigpendq_t*)group->sigpendingq.head;
+ (sigpend && sigpend->info.si_signo != signo);
+ sigpend = sigpend->flink);
+
+ irqrestore(saved_state);
+ return sigpend;
+}
+
+/****************************************************************************
+ * Name: sig_addpendingsignal
+ *
+ * Description:
+ * Add the specified signal to the signal pending list. NOTE: This
+ * function will queue only one entry for each pending signal. This
+ * was done intentionally so that a run-away sender cannot consume
+ * all of memory.
+ *
+ ****************************************************************************/
+
+static FAR sigpendq_t *sig_addpendingsignal(FAR struct tcb_s *stcb,
+ FAR siginfo_t *info)
+{
+ FAR struct task_group_s *group = stcb->group;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
+
+ DEBUGASSERT(group);
+
+ /* Check if the signal is already pending */
+
+ sigpend = sig_findpendingsignal(group, info->si_signo);
+ if (sigpend)
+ {
+ /* The signal is already pending... retain only one copy */
+
+ memcpy(&sigpend->info, info, sizeof(siginfo_t));
+ }
+
+ /* No... There is nothing pending for this signo */
+
+ else
+ {
+ /* Allocate a new pending signal entry */
+
+ sigpend = sig_allocatependingsignal();
+ if (sigpend)
+ {
+ /* Put the signal information into the allocated structure */
+
+ memcpy(&sigpend->info, info, sizeof(siginfo_t));
+
+ /* Add the structure to the pending signal list */
+
+ saved_state = irqsave();
+ sq_addlast((FAR sq_entry_t*)sigpend, &group->sigpendingq);
+ irqrestore(saved_state);
+ }
+ }
+
+ return sigpend;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sig_tcbdispatch
+ *
+ * Description:
+ * All signals received the task (whatever the source) go through this
+ * function to be processed. This function is responsible for:
+ *
+ * - Determining if the signal is blocked.
+ * - Queuing and dispatching signal actions
+ * - Unblocking tasks that are waiting for signals
+ * - Queuing pending signals.
+ *
+ * This function will deliver the signal to the task associated with
+ * the specified TCB. This function should *not* typically be used
+ * to dispatch signals since it will *not* follow the group signal
+ * deliver algorithms.
+ *
+ * Returned Value:
+ * Returns 0 (OK) on success or a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int sig_tcbdispatch(FAR struct tcb_s *stcb, siginfo_t *info)
+{
+ irqstate_t saved_state;
+ int ret = OK;
+
+ sdbg("TCB=0x%08x signo=%d code=%d value=%d mask=%08x\n",
+ stcb, info->si_signo, info->si_code,
+ info->si_value.sival_int, stcb->sigprocmask);
+
+ DEBUGASSERT(stcb && info);
+
+ /************************* MASKED SIGNAL HANDLING ************************/
+
+ /* Check if the signal is masked -- if it is, it will be added to the list
+ * of pending signals.
+ */
+
+ if (sigismember(&stcb->sigprocmask, info->si_signo))
+ {
+ /* Check if the task is waiting for this pending signal. If so, then unblock it.
+ * This must be performed in a critical section because signals can be queued
+ * from the interrupt level.
+ */
+
+ saved_state = irqsave();
+ if (stcb->task_state == TSTATE_WAIT_SIG &&
+ sigismember(&stcb->sigwaitmask, info->si_signo))
+ {
+ memcpy(&stcb->sigunbinfo, info, sizeof(siginfo_t));
+ stcb->sigwaitmask = NULL_SIGNAL_SET;
+ up_unblock_task(stcb);
+ irqrestore(saved_state);
+ }
+
+ /* Its not one we are waiting for... Add it to the list of pending
+ * signals.
+ */
+
+ else
+ {
+ irqrestore(saved_state);
+ ASSERT(sig_addpendingsignal(stcb, info));
+ }
+ }
+
+ /************************ UNMASKED SIGNAL HANDLING ***********************/
+
+ else
+ {
+ /* Queue any sigaction's requested by this task. */
+
+ ret = sig_queueaction(stcb, info);
+
+ /* Then schedule execution of the signal handling action on the
+ * recipient's thread.
+ */
+
+ up_schedule_sigaction(stcb, sig_deliver);
+
+ /* Check if the task is waiting for an unmasked signal. If so, then
+ * unblock it. This must be performed in a critical section because
+ * signals can be queued from the interrupt level.
+ */
+
+ saved_state = irqsave();
+ if (stcb->task_state == TSTATE_WAIT_SIG)
+ {
+ memcpy(&stcb->sigunbinfo, info, sizeof(siginfo_t));
+ stcb->sigwaitmask = NULL_SIGNAL_SET;
+ up_unblock_task(stcb);
+ }
+
+ irqrestore(saved_state);
+
+ /* If the task neither was waiting for the signal nor had a signal
+ * handler attached to the signal, then the default action is
+ * simply to ignore the signal
+ */
+
+ /*********************** OTHER SIGNAL HANDLING ***********************/
+
+ /* If the task is blocked waiting for a semaphore, then that task must
+ * be unblocked when a signal is received.
+ */
+
+ if (stcb->task_state == TSTATE_WAIT_SEM)
+ {
+ sem_waitirq(stcb, EINTR);
+ }
+
+ /* If the task is blocked waiting on a message queue, then that task
+ * must be unblocked when a signal is received.
+ */
+
+#ifndef CONFIG_DISABLE_MQUEUE
+ if (stcb->task_state == TSTATE_WAIT_MQNOTEMPTY ||
+ stcb->task_state == TSTATE_WAIT_MQNOTFULL)
+ {
+ mq_waitirq(stcb, EINTR);
+ }
+#endif
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: sig_dispatch
+ *
+ * Description:
+ * This is the front-end for sig_tcbdispatch that should be typically
+ * be used to dispatch a signal. If HAVE_GROUP_MEMBERS is defined,
+ * then function will follow the group signal delivery algorthrims:
+ *
+ * This front-end does the following things before calling
+ * sig_tcbdispatch.
+ *
+ * With HAVE_GROUP_MEMBERS defined:
+ * - Get the TCB associated with the pid.
+ * - If the TCB was found, get the group from the TCB.
+ * - If the PID has already exited, lookup the group that that was
+ * started by this task.
+ * - Use the group to pick the TCB to receive the signal
+ * - Call sig_tcbdispatch with the TCB
+ *
+ * With HAVE_GROUP_MEMBERS *not* defined
+ * - Get the TCB associated with the pid.
+ * - Call sig_tcbdispatch with the TCB
+ *
+ * Returned Value:
+ * Returns 0 (OK) on success or a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int sig_dispatch(pid_t pid, FAR siginfo_t *info)
+{
+#ifdef HAVE_GROUP_MEMBERS
+
+ FAR struct tcb_s *stcb;
+ FAR struct task_group_s *group;
+
+ /* Get the TCB associated with the pid */
+
+ stcb = sched_gettcb(pid);
+ if (stcb)
+ {
+ /* The task/thread associated with this PID is still active. Get its
+ * task group.
+ */
+
+ group = stcb->group;
+ }
+ else
+ {
+ /* The task/thread associated with this PID has exited. In the normal
+ * usage model, the PID should correspond to the PID of the task that
+ * created the task group. Try looking it up.
+ */
+
+ group = group_findbypid(pid);
+ }
+
+ /* Did we locate the group? */
+
+ if (group)
+ {
+ /* Yes.. call group_signal() to send the signal to the correct group
+ * member.
+ */
+
+ return group_signal(group, info);
+ }
+ else
+ {
+ return -ESRCH;
+ }
+
+#else
+
+ FAR struct tcb_s *stcb;
+
+ /* Get the TCB associated with the pid */
+
+ stcb = sched_gettcb(pid);
+ if (!stcb)
+ {
+ return -ESRCH;
+ }
+
+ return sig_tcbdispatch(stcb, info);
+
+#endif
+}
+
diff --git a/nuttx/sched/signal/sig_findaction.c b/nuttx/sched/signal/sig_findaction.c
new file mode 100644
index 000000000..be8149698
--- /dev/null
+++ b/nuttx/sched/signal/sig_findaction.c
@@ -0,0 +1,100 @@
+/************************************************************************
+ * sched/sig_findaction.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/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Function Prototypes
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_findaction
+ *
+ * Description:
+ * Allocate a new element for a signal queue
+ *
+ ************************************************************************/
+
+FAR sigactq_t *sig_findaction(FAR struct tcb_s *stcb, int signo)
+{
+ FAR sigactq_t *sigact = NULL;
+
+ /* Verify the caller's sanity */
+
+ if (stcb)
+ {
+ /* Sigactions can only be assigned to the currently executing
+ * thread. So, a simple lock ought to give us sufficient
+ * protection.
+ */
+
+ sched_lock();
+
+ /* Seach the list for a sigaction on this signal */
+
+ for (sigact = (FAR sigactq_t*)stcb->sigactionq.head;
+ ((sigact) && (sigact->signo != signo));
+ sigact = sigact->flink);
+
+ sched_unlock();
+ }
+
+ return sigact;
+}
diff --git a/nuttx/sched/signal/sig_initialize.c b/nuttx/sched/signal/sig_initialize.c
new file mode 100644
index 000000000..cd76c6795
--- /dev/null
+++ b/nuttx/sched/signal/sig_initialize.c
@@ -0,0 +1,271 @@
+/************************************************************************
+ * sched/sig_initialize.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 <queue.h>
+#include <nuttx/kmalloc.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/* The g_sigfreeaction data structure is a list of available signal
+ * action structures.
+ */
+
+sq_queue_t g_sigfreeaction;
+
+/* The g_sigpendingaction data structure is a list of available pending
+ * signal action structures.
+ */
+
+sq_queue_t g_sigpendingaction;
+
+/* The g_sigpendingirqaction is a list of available pending signal actions
+ * that are reserved for use by interrupt handlers.
+ */
+
+sq_queue_t g_sigpendingirqaction;
+
+/* The g_sigpendingsignal data structure is a list of available pending
+ * signal structures.
+ */
+
+sq_queue_t g_sigpendingsignal;
+
+/* The g_sigpendingirqsignal data structure is a list of available
+ * pending signal structures that are reserved for use by interrupt
+ * handlers.
+ */
+
+sq_queue_t g_sigpendingirqsignal;
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/* g_sigactionalloc is a pointer to the start of the allocated blocks of
+ * signal actions.
+ */
+
+static sigactq_t *g_sigactionalloc;
+
+/* g_sigpendingactionalloc is a pointer to the start of the allocated
+ * blocks of pending signal actions.
+ */
+
+static sigq_t *g_sigpendingactionalloc;
+
+/* g_sigpendingirqactionalloc is a pointer to the start of the allocated
+ * block of pending signal actions.
+ */
+
+static sigq_t *g_sigpendingirqactionalloc;
+
+/* g_sigpendingsignalalloc is a pointer to the start of the allocated
+ * blocks of pending signals.
+ */
+
+static sigpendq_t *g_sigpendingsignalalloc;
+
+/* g_sigpendingirqsignalalloc is a pointer to the start of the allocated
+ * blocks of pending signals.
+ */
+
+static sigpendq_t *g_sigpendingirqsignalalloc;
+
+/************************************************************************
+ * Private Function Prototypes
+ ************************************************************************/
+
+static sigq_t *sig_allocateblock(sq_queue_t *siglist, uint16_t nsigs,
+ uint8_t sigtype);
+static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *siglist,
+ uint16_t nsigs, uint8_t sigtype);
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_allocateblock
+ *
+ * Description:
+ * Allocate a block of pending signal actions and place them
+ * on the free list.
+ *
+ ************************************************************************/
+
+static sigq_t *sig_allocateblock(sq_queue_t *siglist, uint16_t nsigs,
+ uint8_t sigtype)
+{
+ sigq_t *sigqalloc;
+ sigq_t *sigq;
+ int i;
+
+ /* Allocate a block of pending signal actions */
+
+ sigqalloc = (sigq_t*)kmalloc((sizeof(sigq_t)) * nsigs);
+
+ sigq = sigqalloc;
+ for (i = 0; i < nsigs; i++)
+ {
+ sigq->type = sigtype;
+ sq_addlast((FAR sq_entry_t*)sigq++, siglist);
+ }
+
+ return sigqalloc;
+}
+
+/************************************************************************
+ * Name: sig_allocatependingsignalblock
+ *
+ * Description:
+ * Allocate a block of pending signal structures and place them on
+ * the free list.
+ *
+ ************************************************************************/
+
+static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *siglist,
+ uint16_t nsigs, uint8_t sigtype)
+{
+ sigpendq_t *sigpendalloc;
+ sigpendq_t *sigpend;
+ int i;
+
+ /* Allocate a block of pending signal structures */
+
+ sigpendalloc =
+ (sigpendq_t*)kmalloc((sizeof(sigpendq_t)) * nsigs);
+
+ sigpend = sigpendalloc;
+ for (i = 0; i < nsigs; i++)
+ {
+ sigpend->type = sigtype;
+ sq_addlast((FAR sq_entry_t*)sigpend++, siglist);
+ }
+
+ return sigpendalloc;
+}
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_initialize
+ *
+ * Description:
+ * Perform one-time power-up initialization
+ *
+ ************************************************************************/
+
+void sig_initialize(void)
+{
+ /* Initialize free lists */
+
+ sq_init(&g_sigfreeaction);
+ sq_init(&g_sigpendingaction);
+ sq_init(&g_sigpendingirqaction);
+ sq_init(&g_sigpendingsignal);
+ sq_init(&g_sigpendingirqsignal);
+
+ /* Add a block of signal structures to each list */
+
+ g_sigpendingactionalloc =
+ sig_allocateblock(&g_sigpendingaction,
+ NUM_PENDING_ACTIONS,
+ SIG_ALLOC_FIXED);
+
+ g_sigpendingirqactionalloc =
+ sig_allocateblock(&g_sigpendingirqaction,
+ NUM_PENDING_INT_ACTIONS,
+ SIG_ALLOC_IRQ);
+
+ sig_allocateactionblock();
+
+ g_sigpendingsignalalloc =
+ sig_allocatependingsignalblock(&g_sigpendingsignal,
+ NUM_SIGNALS_PENDING,
+ SIG_ALLOC_FIXED);
+
+ g_sigpendingirqsignalalloc =
+ sig_allocatependingsignalblock(&g_sigpendingirqsignal,
+ NUM_INT_SIGNALS_PENDING,
+ SIG_ALLOC_IRQ);
+}
+
+/************************************************************************
+ * Name: sig_allocateactionblock
+ *
+ * Description:
+ * Allocate a block of signal actions and place them
+ * on the free list.
+ *
+ ************************************************************************/
+
+void sig_allocateactionblock(void)
+{
+ sigactq_t *sigact;
+ int i;
+
+ /* Allocate a block of signal actions */
+
+ g_sigactionalloc =
+ (sigactq_t*)kmalloc((sizeof(sigactq_t)) * NUM_SIGNAL_ACTIONS);
+
+ sigact = g_sigactionalloc;
+ for (i = 0; i < NUM_SIGNAL_ACTIONS; i++)
+ {
+ sq_addlast((FAR sq_entry_t*)sigact++, &g_sigfreeaction);
+ }
+}
diff --git a/nuttx/sched/signal/sig_kill.c b/nuttx/sched/signal/sig_kill.c
new file mode 100644
index 000000000..e9d110b61
--- /dev/null
+++ b/nuttx/sched/signal/sig_kill.c
@@ -0,0 +1,140 @@
+/************************************************************************
+ * sched/sig_kill.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 <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Global Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: kill
+ *
+ * Description:
+ * The kill() system call can be used to send any signal to any task.
+ *
+ * Limitation: Sending of signals to 'process groups' is not
+ * supported in NuttX
+ *
+ * Parameters:
+ * pid - The id of the task to receive the signal. The POSIX kill
+ * specification encodes process group information as zero and
+ * negative pid values. Only positive, non-zero values of pid are
+ * supported by this implementation.
+ * signo - The signal number to send. If signo is zero, no signal is
+ * sent, but all error checking is performed.
+ *
+ * Returned Value:
+ * On success (at least one signal was sent), zero is returned. On
+ * error, -1 is returned, and errno is set appropriately:
+ *
+ * EINVAL An invalid signal was specified.
+ * EPERM The process does not have permission to send the
+ * signal to any of the target processes.
+ * ESRCH The pid or process group does not exist.
+ * ENOSYS Do not support sending signals to process groups.
+ *
+ * Assumptions:
+ *
+ ************************************************************************/
+
+int kill(pid_t pid, int signo)
+{
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s *)g_readytorun.head;
+#endif
+ siginfo_t info;
+ int ret;
+
+ /* We do not support sending signals to process groups */
+
+ if (pid <= 0)
+ {
+ ret = -ENOSYS;
+ goto errout;
+ }
+
+ /* Make sure that the signal is valid */
+
+ if (!GOOD_SIGNO(signo))
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Keep things stationary through the following */
+
+ sched_lock();
+
+ /* Create the siginfo structure */
+
+ info.si_signo = signo;
+ info.si_code = SI_USER;
+ info.si_value.sival_ptr = NULL;
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = rtcb->pid;
+ info.si_status = OK;
+#endif
+
+ /* Send the signal */
+
+ ret = sig_dispatch(pid, &info);
+ sched_unlock();
+
+ if (ret < 0)
+ {
+ goto errout;
+ }
+
+ return OK;
+
+errout:
+ set_errno(-ret);
+ return ERROR;
+}
+
+
diff --git a/nuttx/sched/signal/sig_lowest.c b/nuttx/sched/signal/sig_lowest.c
new file mode 100644
index 000000000..c84d7bfee
--- /dev/null
+++ b/nuttx/sched/signal/sig_lowest.c
@@ -0,0 +1,91 @@
+/************************************************************************
+ * sched/sig_lowest.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 "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_lowest
+ *
+ * Description:
+ * Return the lowest signal number that is a member of a set of signals.
+ *
+ ************************************************************************/
+
+int sig_lowest(sigset_t *set)
+{
+ int signo;
+
+ for (signo = MIN_SIGNO; signo <= MAX_SIGNO; signo++)
+ {
+ if (sigismember(set, signo))
+ {
+ return signo;
+ }
+ }
+
+ return ERROR;
+}
diff --git a/nuttx/sched/signal/sig_mqnotempty.c b/nuttx/sched/signal/sig_mqnotempty.c
new file mode 100644
index 000000000..3e7412ecd
--- /dev/null
+++ b/nuttx/sched/signal/sig_mqnotempty.c
@@ -0,0 +1,132 @@
+/****************************************************************************
+ * sched/sig_mqnotempty.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 <signal.h>
+#include <sched.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functionss
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sig_mqnotempty
+ *
+ * Description:
+ * This function is equivalent to sigqueue(), but supports the messaging
+ * system's requirement to signal a task when a message queue becomes
+ * non-empty. It is identical to sigqueue(), except that it sets the
+ * si_code field in the siginfo structure to SI_MESGQ rather than SI_QUEUE.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+int sig_mqnotempty(int pid, int signo, union sigval value)
+#else
+int sig_mqnotempty(int pid, int signo, void *sival_ptr)
+#endif
+{
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s *)g_readytorun.head;
+#endif
+ siginfo_t info;
+ int ret;
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ sdbg("pid=%p signo=%d value=%d\n", pid, signo, value.sival_int);
+#else
+ sdbg("pid=%p signo=%d sival_ptr=%p\n", pid, signo, sival_ptr);
+#endif
+
+ /* Verify that we can perform the signalling operation */
+
+ if (!GOOD_SIGNO(signo))
+ {
+ return -EINVAL;
+ }
+
+ /* Create the siginfo structure */
+
+ info.si_signo = signo;
+ info.si_code = SI_MESGQ;
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ info.si_value = value;
+#else
+ info.si_value.sival_ptr = sival_ptr;
+#endif
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = rtcb->pid;
+ info.si_status = OK;
+#endif
+
+ /* Process the receipt of the signal */
+
+ sched_lock();
+ ret = sig_dispatch(pid, &info);
+ sched_unlock();
+
+ return ret;
+}
diff --git a/nuttx/sched/signal/sig_pause.c b/nuttx/sched/signal/sig_pause.c
new file mode 100644
index 000000000..f75afa6c9
--- /dev/null
+++ b/nuttx/sched/signal/sig_pause.c
@@ -0,0 +1,110 @@
+/****************************************************************************
+ * sched/pause.c
+ *
+ * Copyright (C) 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 <signal.h>
+
+/****************************************************************************
+ * Preprocessor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pause
+ *
+ * Description:
+ * The pause() function will suspend the calling thread until delivery of a
+ * non-blocked signal.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * Since pause() suspends thread execution indefinitely unless interrupted
+ * a signal, there is no successful completion return value. A value of -1
+ * will always be returned and errno set to indicate the error (EINTR).
+ *
+ * POSIX compatibility:
+ * In the POSIX description of this function is the pause() function will
+ * suspend the calling thread until delivery of a signal whose action is
+ * either to execute a signal-catching function or to terminate the
+ * process. This implementation only waits for any non-blocked signal
+ * to be received.
+ *
+ ****************************************************************************/
+
+int pause(void)
+{
+ sigset_t set;
+ struct siginfo value;
+
+ /* Set up for the sleep. Using the empty set means that we are not
+ * waiting for any particular signal. However, any unmasked signal
+ * can still awaken sigtimedwait().
+ */
+
+ (void)sigemptyset(&set);
+
+ /* sigtwaitinfo() cannot succeed. It should always return error EINTR
+ * meaning that some unblocked signal was caught.
+ */
+
+ return sigwaitinfo(&set, &value);
+}
diff --git a/nuttx/sched/signal/sig_pending.c b/nuttx/sched/signal/sig_pending.c
new file mode 100644
index 000000000..916960475
--- /dev/null
+++ b/nuttx/sched/signal/sig_pending.c
@@ -0,0 +1,133 @@
+/****************************************************************************
+ * sched/sig_pending.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 <signal.h>
+#include <sched.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigpending
+ *
+ * Description:
+ * This function returns the set of signals that are blocked from deliveryi
+ * and that are pending for the calling process in the space pointed to by
+ * set.
+ *
+ * Parameters:
+ * set - The location to return the pending signal set.
+ *
+ * Return Value:
+ * 0 (OK) or -1 (ERROR)
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int sigpending(FAR sigset_t *set)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ int ret = ERROR;
+
+ if (set)
+ {
+ *set = sig_pendingset(rtcb);
+ ret = OK;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: sig_pendingset
+ *
+ * Description:
+ * Convert the list of pending signals into a signal set
+ *
+ ****************************************************************************/
+
+sigset_t sig_pendingset(FAR struct tcb_s *stcb)
+{
+ FAR struct task_group_s *group = stcb->group;
+ sigset_t sigpendset;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
+
+ DEBUGASSERT(group);
+
+ sigpendset = NULL_SIGNAL_SET;
+
+ saved_state = irqsave();
+ for (sigpend = (FAR sigpendq_t*)group->sigpendingq.head;
+ (sigpend); sigpend = sigpend->flink)
+ {
+ sigaddset(&sigpendset, sigpend->info.si_signo);
+ }
+
+ irqrestore(saved_state);
+
+ return sigpendset;
+}
diff --git a/nuttx/sched/signal/sig_procmask.c b/nuttx/sched/signal/sig_procmask.c
new file mode 100644
index 000000000..eb065af3a
--- /dev/null
+++ b/nuttx/sched/signal/sig_procmask.c
@@ -0,0 +1,180 @@
+/****************************************************************************
+ * sched/sig_procmask.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 <signal.h>
+#include <time.h>
+#include <wdog.h>
+#include <assert.h>
+#include <debug.h>
+#include <sched.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigprocmask
+ *
+ * Description:
+ * This function allows the calling process to examine and/or change its
+ * signal mask. If the 'set' is not NULL, then it points to a set of
+ * signals to be used to change the currently blocked set. The value of
+ * 'how' indicates the manner in which the set is changed.
+ *
+ * If there any pending unblocked signals after the call to sigprocmask(),
+ * those signals will be delivered before sigprocmask() returns.
+ *
+ * If sigprocmask() fails, the signal mask of the process is not changed
+ * by this function call.
+ *
+ * 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 -1 (ERROR) if how is invalid.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int sigprocmask(int how, FAR const sigset_t *set, FAR sigset_t *oset)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ sigset_t oldsigprocmask;
+ irqstate_t saved_state;
+ int ret = OK;
+
+ sched_lock();
+
+ /* Return the old signal mask if requested */
+
+ oldsigprocmask = rtcb->sigprocmask;
+ if (oset)
+ {
+ *oset = oldsigprocmask;
+ }
+
+ /* Modify the current signal mask if so requested */
+
+ if (set)
+ {
+ /* Some of these operations are non-atomic. We need to protect
+ * ourselves from attempts to process signals from interrupts
+ */
+
+ saved_state = irqsave();
+
+ /* Okay, determine what we are supposed to do */
+
+ switch (how)
+ {
+ /* The resulting set is the union of the current set and the
+ * signal set pointed to by set.
+ */
+
+ case SIG_BLOCK:
+ rtcb->sigprocmask |= *set;
+ break;
+
+ /* The resulting set is the intersection of the current set and
+ * the complement of the signal set pointed to by _set.
+ */
+
+ case SIG_UNBLOCK:
+ rtcb->sigprocmask &= ~(*set);
+ break;
+
+ /* The resulting set is the signal set pointed to by set. */
+
+ case SIG_SETMASK:
+ rtcb->sigprocmask = *set;
+ break;
+
+ default:
+ ret = ERROR;
+ break;
+ }
+
+ irqrestore(saved_state);
+
+ /* Now, process any pending signals that were just unmasked */
+
+ sig_unmaskpendingsignal();
+ }
+
+ sched_unlock();
+ return ret;
+}
diff --git a/nuttx/sched/signal/sig_queue.c b/nuttx/sched/signal/sig_queue.c
new file mode 100644
index 000000000..515662250
--- /dev/null
+++ b/nuttx/sched/signal/sig_queue.c
@@ -0,0 +1,167 @@
+/****************************************************************************
+ * sched/sig_queue.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 <signal.h>
+#include <debug.h>
+#include <sched.h>
+#include <errno.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigqueue
+ *
+ * Description:
+ * This function sends the signal specified by signo with the signal
+ * parameter value to the process specified by pid.
+ *
+ * If the receiving process has the signal blocked via the sigprocmask,
+ * the signal will pend until it is unmasked. Only one pending signal (per
+ * signo) is retained. This is consistent with POSIX which states, "If
+ * a subsequent occurrence of a pending signal is generated, it is
+ * implementation defined as to whether the signal is delivered more than
+ * once."
+ *
+ * Parameters:
+ * pid - Process ID of task to receive signal
+ * signo - Signal number
+ * value - Value to pass to task with signal
+ *
+ * Return Value:
+ * On success (at least one signal was sent), zero is returned. On
+ * error, -1 is returned, and errno is set appropriately:
+ *
+ * EGAIN The limit of signals which may be queued has been reached.
+ * EINVAL sig was invalid.
+ * EPERM The process does not have permission to send the
+ * signal to the receiving process.
+ * ESRCH No process has a PID matching pid.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+int sigqueue (int pid, int signo, union sigval value)
+#else
+int sigqueue(int pid, int signo, void *sival_ptr)
+#endif
+{
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s *)g_readytorun.head;
+#endif
+ siginfo_t info;
+ int ret;
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ sdbg("pid=0x%08x signo=%d value=%d\n", pid, signo, value.sival_int);
+#else
+ sdbg("pid=0x%08x signo=%d value=%p\n", pid, signo, sival_ptr);
+#endif
+
+ /* Sanity checks */
+
+ if (!GOOD_SIGNO(signo))
+ {
+ ret = -EINVAL;
+ goto errout;
+ }
+
+ /* Create the siginfo structure */
+
+ info.si_signo = signo;
+ info.si_code = SI_QUEUE;
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ info.si_value = value;
+#else
+ info.si_value.sival_ptr = sival_ptr;
+#endif
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = rtcb->pid;
+ info.si_status = OK;
+#endif
+
+ /* Send the signal */
+
+ sched_lock();
+ ret = sig_dispatch(pid, &info);
+ sched_unlock();
+
+ /* Check for errors */
+
+ if (ret < 0)
+ {
+ goto errout;
+ }
+
+ return OK;
+
+errout:
+ set_errno(-ret);
+ return ERROR;
+}
+
diff --git a/nuttx/sched/signal/sig_releasependingsigaction.c b/nuttx/sched/signal/sig_releasependingsigaction.c
new file mode 100644
index 000000000..e5fbf8a7a
--- /dev/null
+++ b/nuttx/sched/signal/sig_releasependingsigaction.c
@@ -0,0 +1,120 @@
+/************************************************************************
+ * sched/sig_releasependingsigaction.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 "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_releasependingsigaction
+ *
+ * Description:
+ * Deallocate a pending signal action Q entry
+ *
+ ************************************************************************/
+
+void sig_releasependingsigaction(FAR sigq_t *sigq)
+{
+ irqstate_t saved_state;
+
+ /* If this is a generally available pre-allocated structyre,
+ * then just put it back in the free list.
+ */
+
+ if (sigq->type == SIG_ALLOC_FIXED)
+ {
+ /* Make sure we avoid concurrent access to the free
+ * list from interrupt handlers. */
+
+ saved_state = irqsave();
+ sq_addlast((FAR sq_entry_t*)sigq, &g_sigpendingaction);
+ irqrestore(saved_state);
+ }
+
+ /* If this is a message pre-allocated for interrupts,
+ * then put it back in the correct free list.
+ */
+
+ else if (sigq->type == SIG_ALLOC_IRQ)
+ {
+ /* Make sure we avoid concurrent access to the free
+ * list from interrupt handlers. */
+
+ saved_state = irqsave();
+ sq_addlast((FAR sq_entry_t*)sigq, &g_sigpendingirqaction);
+ irqrestore(saved_state);
+ }
+
+ /* Otherwise, deallocate it. Note: interrupt handlers
+ * will never deallocate signals because they will not
+ * receive them.
+ */
+
+ else if (sigq->type == SIG_ALLOC_DYN)
+ {
+ sched_kfree(sigq);
+ }
+}
diff --git a/nuttx/sched/signal/sig_releasependingsignal.c b/nuttx/sched/signal/sig_releasependingsignal.c
new file mode 100644
index 000000000..392b825b3
--- /dev/null
+++ b/nuttx/sched/signal/sig_releasependingsignal.c
@@ -0,0 +1,131 @@
+/************************************************************************
+ * sched/sig_releasependingsignal.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 <signal.h>
+#include <time.h>
+#include <wdog.h>
+#include <assert.h>
+#include <debug.h>
+#include <sched.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_releasependingsignal
+ *
+ * Description:
+ * Deallocate a pending signal list entry
+ *
+ ************************************************************************/
+
+void sig_releasependingsignal(FAR sigpendq_t *sigpend)
+{
+ irqstate_t saved_state;
+
+ /* If this is a generally available pre-allocated structyre,
+ * then just put it back in the free list.
+ */
+
+ if (sigpend->type == SIG_ALLOC_FIXED)
+ {
+ /* Make sure we avoid concurrent access to the free
+ * list from interrupt handlers.
+ */
+
+ saved_state = irqsave();
+ sq_addlast((FAR sq_entry_t*)sigpend, &g_sigpendingsignal);
+ irqrestore(saved_state);
+ }
+
+ /* If this is a message pre-allocated for interrupts,
+ * then put it back in the correct free list.
+ */
+
+ else if (sigpend->type == SIG_ALLOC_IRQ)
+ {
+ /* Make sure we avoid concurrent access to the free
+ * list from interrupt handlers.
+ */
+
+ saved_state = irqsave();
+ sq_addlast((FAR sq_entry_t*)sigpend, &g_sigpendingirqsignal);
+ irqrestore(saved_state);
+ }
+
+ /* Otherwise, deallocate it. Note: interrupt handlers
+ * will never deallocate signals because they will not
+ * receive them.
+ */
+
+ else if (sigpend->type == SIG_ALLOC_DYN)
+ {
+ sched_kfree(sigpend);
+ }
+}
diff --git a/nuttx/sched/signal/sig_removependingsignal.c b/nuttx/sched/signal/sig_removependingsignal.c
new file mode 100644
index 000000000..723ab3b74
--- /dev/null
+++ b/nuttx/sched/signal/sig_removependingsignal.c
@@ -0,0 +1,118 @@
+/************************************************************************
+ * sched/sig_removependingsignal.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 <unistd.h>
+#include <signal.h>
+#include <time.h>
+#include <wdog.h>
+#include <assert.h>
+#include <debug.h>
+#include <sched.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_removependingsignal
+ *
+ * Description:
+ * Remove the specified signal from the signal pending list
+ *
+ ************************************************************************/
+
+FAR sigpendq_t *sig_removependingsignal(FAR struct tcb_s *stcb, int signo)
+{
+ FAR struct task_group_s *group = stcb->group;
+ FAR sigpendq_t *currsig;
+ FAR sigpendq_t *prevsig;
+ irqstate_t saved_state;
+
+ DEBUGASSERT(group);
+
+ saved_state = irqsave();
+
+ for (prevsig = NULL, currsig = (FAR sigpendq_t*)group->sigpendingq.head;
+ (currsig && currsig->info.si_signo != signo);
+ prevsig = currsig, currsig = currsig->flink);
+
+ if (currsig)
+ {
+ if (prevsig)
+ {
+ sq_remafter((FAR sq_entry_t*)prevsig, &group->sigpendingq);
+ }
+ else
+ {
+ sq_remfirst(&group->sigpendingq);
+ }
+ }
+
+ irqrestore(saved_state);
+
+ return currsig;
+}
diff --git a/nuttx/sched/signal/sig_suspend.c b/nuttx/sched/signal/sig_suspend.c
new file mode 100644
index 000000000..d434761c8
--- /dev/null
+++ b/nuttx/sched/signal/sig_suspend.c
@@ -0,0 +1,177 @@
+/****************************************************************************
+ * sched/sig_suspend.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 <signal.h>
+#include <assert.h>
+#include <debug.h>
+#include <sched.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigsuspend
+ *
+ * Description:
+ *
+ * The sigsuspend() function replaces the signal mask of the task with the
+ * set of signals pointed to by the argument 'set' and then suspends the
+ * process until delivery of a signal to the task.
+ *
+ * If the effect of the set argument is to unblock a pending signal, then
+ * no wait is performed.
+ *
+ * The original signal mask is restored when this function returns.
+ *
+ * Waiting for an empty signal set stops a task without freeing any
+ * resources.
+ *
+ * Parameters:
+ * set - signal mask to use while suspended.
+ *
+ * Return Value:
+ * -1 (ERROR) always
+ *
+ * Assumptions:
+ *
+ * POSIX Compatibility:
+ * int sigsuspend(const sigset_t *set);
+ *
+ * POSIX states that sigsuspend() "suspends the process until delivery of
+ * a signal whose action is either to execute a signal-catching function
+ * or to terminate the process." Only the deliver of a signal is required
+ * in the present implementation (even if the signal is ignored).
+ *
+ ****************************************************************************/
+
+int sigsuspend(FAR const sigset_t *set)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ sigset_t intersection;
+ sigset_t saved_sigprocmask;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
+ int unblocksigno;
+
+ /* Several operations must be performed below: We must determine if any
+ * signal is pending and, if not, wait for the signal. Since signals can
+ * be posted from the interrupt level, there is a race condition that
+ * can only be eliminated by disabling interrupts!
+ */
+
+ sched_lock(); /* Not necessary */
+ saved_state = irqsave();
+
+ /* Check if there is a pending signal corresponding to one of the
+ * signals that will be unblocked by the new sigprocmask.
+ */
+
+ intersection = ~(*set) & sig_pendingset(rtcb);
+ if (intersection != NULL_SIGNAL_SET)
+ {
+ /* One or more of the signals in intersections is sufficient to cause
+ * us to not wait. Pick the lowest numbered signal and mark it not
+ * pending.
+ */
+
+ unblocksigno = sig_lowest(&intersection);
+ sigpend = sig_removependingsignal(rtcb, unblocksigno);
+ ASSERT(sigpend);
+
+ sig_releasependingsignal(sigpend);
+ irqrestore(saved_state);
+ }
+ else
+ {
+ /* Its time to wait. Save a copy of the old sigprocmask and install
+ * the new (temporary) sigprocmask
+ */
+
+ saved_sigprocmask = rtcb->sigprocmask;
+ rtcb->sigprocmask = *set;
+ rtcb->sigwaitmask = NULL_SIGNAL_SET;
+
+ /* And wait until one of the unblocked signals is posted */
+
+ up_block_task(rtcb, TSTATE_WAIT_SIG);
+
+ /* We are running again, restore the original sigprocmask */
+
+ rtcb->sigprocmask = saved_sigprocmask;
+ irqrestore(saved_state);
+
+ /* Now, handle the (rare?) case where (a) a blocked signal was received
+ * while the task was suspended but (b) restoring the original
+ * sigprocmask will unblock the signal.
+ */
+
+ sig_unmaskpendingsignal();
+ }
+
+ sched_unlock();
+ return ERROR;
+}
diff --git a/nuttx/sched/signal/sig_timedwait.c b/nuttx/sched/signal/sig_timedwait.c
new file mode 100644
index 000000000..0e4635ad6
--- /dev/null
+++ b/nuttx/sched/signal/sig_timedwait.c
@@ -0,0 +1,357 @@
+/****************************************************************************
+ * sched/sig_timedwait.c
+ *
+ * Copyright (C) 2007-2009, 2012-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 <string.h>
+#include <signal.h>
+#include <time.h>
+#include <wdog.h>
+#include <assert.h>
+#include <debug.h>
+#include <sched.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+
+#include "os_internal.h"
+#include "signal/signal.h"
+#include "clock_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* This is a special value of si_signo that means that it was the timeout
+ * that awakened the wait... not the receipt of a signal.
+ */
+
+#define SIG_WAIT_TIMEOUT 0xff
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sig_timeout
+ *
+ * Description:
+ * A timeout elapsed while waiting for signals to be queued.
+ *
+ ****************************************************************************/
+
+static void sig_timeout(int argc, uint32_t itcb)
+{
+ /* On many small machines, pointers are encoded and cannot be simply cast
+ * from uint32_t to struct tcb_s*. The following union works around this
+ * (see wdogparm_t). This odd logic could be conditioned on
+ * CONFIG_CAN_CAST_POINTERS, but it is not too bad in any case.
+ */
+
+ union
+ {
+ FAR struct tcb_s *wtcb;
+ uint32_t itcb;
+ } u;
+
+ u.itcb = itcb;
+ ASSERT(u.wtcb);
+
+ /* There may be a race condition -- make sure the task is
+ * still waiting for a signal
+ */
+
+ if (u.wtcb->task_state == TSTATE_WAIT_SIG)
+ {
+ u.wtcb->sigunbinfo.si_signo = SIG_WAIT_TIMEOUT;
+ u.wtcb->sigunbinfo.si_code = SI_TIMER;
+ u.wtcb->sigunbinfo.si_value.sival_int = 0;
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ u.wtcb->sigunbinfo.si_pid = 0; /* Not applicable */
+ u.wtcb->sigunbinfo.si_status = OK;
+#endif
+ up_unblock_task(u.wtcb);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigtimedwait
+ *
+ * Description:
+ * This function selects the pending signal set specified by the argument
+ * set. If multiple signals are pending in set, it will remove and return
+ * the lowest numbered one. If no signals in set are pending at the time
+ * of the call, the calling process will be suspended until one of the
+ * signals in set becomes pending, OR until the process is interrupted by
+ * an unblocked signal, OR until the time interval specified by timeout
+ * (if any), has expired. If timeout is NULL, then the timeout interval
+ * is forever.
+ *
+ * If the info argument is non-NULL, the selected signal number is stored
+ * in the si_signo member and the cause of the signal is store din the
+ * si_code member. The content of si_value is only meaningful if the
+ * signal was generated by sigqueue().
+ *
+ * The following values for si_code are defined in signal.h:
+ * SI_USER - Signal sent from kill, raise, or abort
+ * SI_QUEUE - Signal sent from sigqueue
+ * SI_TIMER - Signal is result of timer expiration
+ * SI_ASYNCIO - Signal is the result of asynch IO completion
+ * SI_MESGQ - Signal generated by arrival of a message on an
+ * empty message queue.
+ *
+ * Parameters:
+ * set - The pending signal set.
+ * info - The returned value
+ * timeout - The amount of time to wait
+ *
+ * Return Value:
+ * Signal number that cause the wait to be terminated, otherwise -1 (ERROR)
+ * is returned with errno set to either:
+ *
+ * EAGAIN - No signal specified by set was generated within the specified
+ * timeout period.
+ * EINTR - The wait was interrupted by an unblocked, caught signal.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int sigtimedwait(FAR const sigset_t *set, FAR struct siginfo *info,
+ FAR const struct timespec *timeout)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ sigset_t intersection;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
+ int32_t waitticks;
+ int ret = ERROR;
+
+ DEBUGASSERT(rtcb->waitdog == NULL);
+
+ sched_lock(); /* Not necessary */
+
+ /* Several operations must be performed below: We must determine if any
+ * signal is pending and, if not, wait for the signal. Since signals can
+ * be posted from the interrupt level, there is a race condition that
+ * can only be eliminated by disabling interrupts!
+ */
+
+ saved_state = irqsave();
+
+ /* Check if there is a pending signal corresponding to one of the
+ * signals in the pending signal set argument.
+ */
+
+ intersection = *set & sig_pendingset(rtcb);
+ if (intersection != NULL_SIGNAL_SET)
+ {
+ /* One or more of the signals in intersections is sufficient to cause
+ * us to not wait. Pick the lowest numbered signal and mark it not
+ * pending.
+ */
+
+ sigpend = sig_removependingsignal(rtcb, sig_lowest(&intersection));
+ ASSERT(sigpend);
+
+ /* Return the signal info to the caller if so requested */
+
+ if (info)
+ {
+ memcpy(info, &sigpend->info, sizeof(struct siginfo));
+ }
+
+ /* Then dispose of the pending signal structure properly */
+
+ sig_releasependingsignal(sigpend);
+ irqrestore(saved_state);
+
+ /* The return value is the number of the signal that awakened us */
+
+ ret = sigpend->info.si_signo;
+ }
+
+ /* We will have to wait for a signal to be posted to this task. */
+
+ else
+ {
+ /* Save the set of pending signals to wait for */
+
+ rtcb->sigwaitmask = *set;
+
+ /* Check if we should wait for the timeout */
+
+ if (timeout)
+ {
+ /* Convert the timespec to system clock ticks, making sure that
+ * the resulting delay is greater than or equal to the requested
+ * time in nanoseconds.
+ */
+
+#ifdef CONFIG_HAVE_LONG_LONG
+ uint64_t waitticks64 = ((uint64_t)timeout->tv_sec * NSEC_PER_SEC +
+ (uint64_t)timeout->tv_nsec + NSEC_PER_TICK - 1) /
+ NSEC_PER_TICK;
+ DEBUGASSERT(waitticks64 <= UINT32_MAX);
+ waitticks = (uint32_t)waitticks64;
+#else
+ uint32_t waitmsec;
+
+ DEBUGASSERT(timeout->tv_sec < UINT32_MAX / MSEC_PER_SEC);
+ waitmsec = timeout->tv_sec * MSEC_PER_SEC +
+ (timeout->tv_nsec + NSEC_PER_MSEC - 1) / NSEC_PER_MSEC;
+ waitticks = MSEC2TICK(waitmsec);
+#endif
+
+ /* Create a watchdog */
+
+ rtcb->waitdog = wd_create();
+ DEBUGASSERT(rtcb->waitdog);
+
+ if (rtcb->waitdog)
+ {
+ /* This little bit of nonsense is necessary for some
+ * processors where sizeof(pointer) < sizeof(uint32_t).
+ * see wdog.h.
+ */
+
+ wdparm_t wdparm;
+ wdparm.pvarg = (FAR void *)rtcb;
+
+ /* Start the watchdog */
+
+ wd_start(rtcb->waitdog, waitticks, (wdentry_t)sig_timeout, 1,
+ wdparm.dwarg);
+
+ /* Now wait for either the signal or the watchdog */
+
+ up_block_task(rtcb, TSTATE_WAIT_SIG);
+
+ /* We no longer need the watchdog */
+
+ wd_delete(rtcb->waitdog);
+ rtcb->waitdog = NULL;
+ }
+
+ /* REVISIT: And do what if there are no watchdog timers? The wait
+ * will fail and we will return something bogus.
+ */
+ }
+
+ /* No timeout, just wait */
+
+ else
+ {
+ /* And wait until one of the unblocked signals is posted */
+
+ up_block_task(rtcb, TSTATE_WAIT_SIG);
+ }
+
+ /* We are running again, clear the sigwaitmask */
+
+ rtcb->sigwaitmask = NULL_SIGNAL_SET;
+
+ /* When we awaken, the cause will be in the TCB. Get the signal number
+ * or timeout) that awakened us.
+ */
+
+ if (GOOD_SIGNO(rtcb->sigunbinfo.si_signo))
+ {
+ /* We were awakened by a signal... but is it one of the signals that
+ * we were waiting for?
+ */
+
+ if (sigismember(set, rtcb->sigunbinfo.si_signo))
+ {
+ /* Yes.. the return value is the number of the signal that
+ * awakened us.
+ */
+
+ ret = rtcb->sigunbinfo.si_signo;
+ }
+ else
+ {
+ /* No... then set EINTR and report an error */
+
+ set_errno(EINTR);
+ ret = ERROR;
+ }
+ }
+ else
+ {
+ /* Otherwise, we must have been awakened by the timeout. Set EGAIN
+ * and return an error.
+ */
+
+ DEBUGASSERT(rtcb->sigunbinfo.si_signo == SIG_WAIT_TIMEOUT);
+ set_errno(EAGAIN);
+ ret = ERROR;
+ }
+
+ /* Return the signal info to the caller if so requested */
+
+ if (info)
+ {
+ memcpy(info, &rtcb->sigunbinfo, sizeof(struct siginfo));
+ }
+
+ irqrestore(saved_state);
+ }
+
+ sched_unlock();
+ return ret;
+}
diff --git a/nuttx/sched/signal/sig_unmaskpendingsignal.c b/nuttx/sched/signal/sig_unmaskpendingsignal.c
new file mode 100644
index 000000000..8d13b7a0f
--- /dev/null
+++ b/nuttx/sched/signal/sig_unmaskpendingsignal.c
@@ -0,0 +1,143 @@
+/************************************************************************
+ * sched/sig_unmaskpendingsignal.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 "os_internal.h"
+#include "signal/signal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Function Prototypes
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: sig_unmaskpendingsignal
+ *
+ * Description:
+ * Based upon the current setting of the sigprocmask, this function
+ * unmasks and processes any pending signals. This function should
+ * be called whenever the sigprocmask is changed.
+ *
+ ************************************************************************/
+
+void sig_unmaskpendingsignal(void)
+{
+ FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ sigset_t unmaskedset;
+ FAR sigpendq_t *pendingsig;
+ int signo;
+
+ /* Prohibit any context switches until we are done with this.
+ * We may still be performing signal operations from interrupt
+ * handlers, however, none of the pending signals that we
+ * are concerned with here should be effected.
+ */
+
+ sched_lock();
+
+ /* Get the set of pending signals that were just unmasked. The
+ * following operation should be safe because the sigprocmask
+ * can only be changed on this thread of execution.
+ */
+
+ unmaskedset = ~(rtcb->sigprocmask) & sig_pendingset(rtcb);
+
+ /* Loop while there are unmasked pending signals to be processed. */
+
+ while (unmaskedset != NULL_SIGNAL_SET)
+ {
+ /* Pending signals will be processed from lowest numbered signal
+ * to highest
+ */
+
+ signo = sig_lowest(&unmaskedset);
+ if (signo != ERROR)
+ {
+ /* Remove the signal from the set of unmasked signals. NOTE:
+ * this implicitly assumes that only one instance for a given
+ * signal number is pending.
+ */
+
+ sigdelset(&unmaskedset, signo);
+
+ /* Remove the pending signal from the list of pending signals */
+
+ if ((pendingsig = sig_removependingsignal(rtcb, signo)) != NULL)
+ {
+ /* If there is one, then process it like a normal signal.
+ * Since the signal was pending, then unblocked on this
+ * thread, we can skip the normal group signal dispatching
+ * rules; there can be no other recipient for the signal
+ * other than this thread.
+ */
+
+ sig_tcbdispatch(rtcb, &pendingsig->info);
+
+ /* Then remove it from the pending signal list */
+
+ sig_releasependingsignal(pendingsig);
+ }
+ }
+ }
+
+ sched_unlock();
+}
+
diff --git a/nuttx/sched/signal/sig_waitinfo.c b/nuttx/sched/signal/sig_waitinfo.c
new file mode 100644
index 000000000..0172ec47d
--- /dev/null
+++ b/nuttx/sched/signal/sig_waitinfo.c
@@ -0,0 +1,89 @@
+/****************************************************************************
+ * sched/sig_waitinfo.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>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sigwaitinfo
+ *
+ * Description:
+ * This function is equivalent to sigtimedwait with a NULL timeout
+ * parameter.
+ *
+ * Parameters:
+ * set - The pending signal set
+ * info - The returned value
+ *
+ * Return Value:
+ * Signal number that cause the wait to be terminated, otherwise -1 (ERROR)
+ * is returned.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int sigwaitinfo(FAR const sigset_t *set, FAR struct siginfo *info)
+{
+ return sigtimedwait(set, info, NULL);
+}
diff --git a/nuttx/sched/signal/signal.h b/nuttx/sched/signal/signal.h
new file mode 100644
index 000000000..2277dea1a
--- /dev/null
+++ b/nuttx/sched/signal/signal.h
@@ -0,0 +1,201 @@
+/****************************************************************************
+ * sched/signal/signal.h
+ *
+ * Copyright (C) 2007-2009, 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_SIGNAL_SIGNAL_H
+#define __SCHED_SIGNAL_SIGNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/compiler.h>
+
+#include <stdint.h>
+#include <queue.h>
+#include <sched.h>
+
+#include <nuttx/kmalloc.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* The following definition determines the number of signal structures to
+ * allocate in a block
+ */
+
+#define NUM_SIGNAL_ACTIONS 16
+#define NUM_PENDING_ACTIONS 16
+#define NUM_PENDING_INT_ACTIONS 8
+#define NUM_SIGNALS_PENDING 16
+#define NUM_INT_SIGNALS_PENDING 8
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+enum sigalloc_e
+{
+ SIG_ALLOC_FIXED = 0, /* pre-allocated; never freed */
+ SIG_ALLOC_DYN, /* dynamically allocated; free when unused */
+ SIG_ALLOC_IRQ /* Preallocated, reserved for interrupt handling */
+};
+typedef enum sigalloc_e sigalloc_t;
+
+/* The following defines the sigaction queue entry */
+
+struct sigactq
+{
+ FAR struct sigactq *flink; /* Forward link */
+ struct sigaction act; /* Sigaction data */
+ uint8_t signo; /* Signal associated with action */
+};
+typedef struct sigactq sigactq_t;
+
+/* The following defines the queue structure within each TCB to hold pending
+ * signals received by the task. These are signals that cannot be processed
+ * because: (1) the task is not waiting for them, or (2) the task has no
+ * action associated with the signal.
+ */
+
+struct sigpendq
+{
+ FAR struct sigpendq *flink; /* Forward link */
+ siginfo_t info; /* Signal information */
+ uint8_t type; /* (Used to manage allocations) */
+};
+typedef struct sigpendq sigpendq_t;
+
+/* The following defines the queue structure within each TCB to hold queued
+ * signal actions that need action by the task
+ */
+
+struct sigq_s
+{
+ FAR struct sigq_s *flink; /* Forward link */
+ union
+ {
+ void (*sighandler)(int signo, siginfo_t *info, void *context);
+ } action; /* Signal action */
+ sigset_t mask; /* Additional signals to mask while the
+ * the signal-catching function executes */
+ siginfo_t info; /* Signal information */
+ uint8_t type; /* (Used to manage allocations) */
+};
+typedef struct sigq_s sigq_t;
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/* The g_sigfreeaction data structure is a list of available signal action
+ * structures.
+ */
+
+extern sq_queue_t g_sigfreeaction;
+
+/* The g_sigpendingaction data structure is a list of available pending
+ * signal action structures.
+ */
+
+extern sq_queue_t g_sigpendingaction;
+
+/* The g_sigpendingirqaction is a list of available pending signal actions
+ * that are reserved for use by interrupt handlers.
+ */
+
+extern sq_queue_t g_sigpendingirqaction;
+
+/* The g_sigpendingsignal data structure is a list of available pending
+ * signal structures.
+ */
+
+extern sq_queue_t g_sigpendingsignal;
+
+/* The g_sigpendingirqsignal data structure is a list of available pending
+ * signal structures that are reserved for use by interrupt handlers.
+ */
+
+extern sq_queue_t g_sigpendingirqsignal;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/* Internal signal-related interfaces ***************************************/
+/* Forward references */
+
+struct task_group_s;
+
+/* sig_initializee.c */
+
+void weak_function sig_initialize(void);
+void sig_allocateactionblock(void);
+
+/* sig_action.c */
+
+void sig_releaseaction(FAR sigactq_t *sigact);
+
+/* sig_pending.c */
+
+sigset_t sig_pendingset(FAR struct tcb_s *stcb);
+
+/* sig_dispatch.c */
+
+int sig_tcbdispatch(FAR struct tcb_s *stcb, FAR siginfo_t *info);
+int sig_dispatch(pid_t pid, FAR siginfo_t *info);
+
+/* sig_cleanup.c */
+
+void sig_cleanup(FAR struct tcb_s *stcb);
+void sig_release(FAR struct task_group_s *group);
+
+/* In files of the same name */
+
+FAR sigq_t *sig_allocatependingsigaction(void);
+void sig_deliver(FAR struct tcb_s *stcb);
+FAR sigactq_t *sig_findaction(FAR struct tcb_s *stcb, int signo);
+int sig_lowest(FAR sigset_t *set);
+#ifdef CONFIG_CAN_PASS_STRUCTS
+int sig_mqnotempty(int tid, int signo, union sigval value);
+#else
+int sig_mqnotempty(int tid, int signo, FAR void *sival_ptr);
+#endif
+void sig_releasependingsigaction(FAR sigq_t *sigq);
+void sig_releasependingsignal(FAR sigpendq_t *sigpend);
+FAR sigpendq_t *sig_removependingsignal(FAR struct tcb_s *stcb, int signo);
+void sig_unmaskpendingsignal(void);
+
+#endif /* __SCHED_SIGNAL_SIGNAL_H */