summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-04-25 15:19:59 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-04-25 15:19:59 -0600
commit1ffc15c3233c8d61953fc2ebc80b5d3c46fc429f (patch)
tree95050f5e635b87d26f4dd98612b05edf632b2a96 /nuttx/sched
parent5f6e91b0ed1b373d0b4f963b0e0f8f7fe05ec766 (diff)
downloadpx4-nuttx-1ffc15c3233c8d61953fc2ebc80b5d3c46fc429f.tar.gz
px4-nuttx-1ffc15c3233c8d61953fc2ebc80b5d3c46fc429f.tar.bz2
px4-nuttx-1ffc15c3233c8d61953fc2ebc80b5d3c46fc429f.zip
Remove up_assert_code
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/irq_unexpectedisr.c4
-rw-r--r--nuttx/sched/mq_msgfree.c4
-rw-r--r--nuttx/sched/mq_rcvinternal.c17
-rw-r--r--nuttx/sched/mq_sndinternal.c29
-rw-r--r--nuttx/sched/mq_waitirq.c32
-rw-r--r--nuttx/sched/os_internal.h30
-rw-r--r--nuttx/sched/sched_mergepending.c59
-rw-r--r--nuttx/sched/sem_wait.c5
-rw-r--r--nuttx/sched/sig_action.c5
-rw-r--r--nuttx/sched/sig_dispatch.c5
-rw-r--r--nuttx/sched/sig_suspend.c5
-rw-r--r--nuttx/sched/sig_timedwait.c13
-rw-r--r--nuttx/sched/task_delete.c2
-rw-r--r--nuttx/sched/wd_cancel.c48
-rw-r--r--nuttx/sched/wd_start.c2
15 files changed, 78 insertions, 182 deletions
diff --git a/nuttx/sched/irq_unexpectedisr.c b/nuttx/sched/irq_unexpectedisr.c
index c0090ead4..e0291b026 100644
--- a/nuttx/sched/irq_unexpectedisr.c
+++ b/nuttx/sched/irq_unexpectedisr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/irq_unexpectedisr.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * 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
@@ -83,6 +83,6 @@ int irq_unexpected_isr(int irq, FAR void *context)
{
(void)irqsave();
lldbg("irq: %d\n", irq);
- PANIC(OSERR_UNEXPECTEDISR);
+ PANIC();
return OK; /* Won't get here */
}
diff --git a/nuttx/sched/mq_msgfree.c b/nuttx/sched/mq_msgfree.c
index 61b0e1055..23ccc3a8e 100644
--- a/nuttx/sched/mq_msgfree.c
+++ b/nuttx/sched/mq_msgfree.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/mq_msgfree.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -129,6 +129,6 @@ void mq_msgfree(FAR mqmsg_t *mqmsg)
}
else
{
- PANIC(OSERR_BADMSGTYPE);
+ PANIC();
}
}
diff --git a/nuttx/sched/mq_rcvinternal.c b/nuttx/sched/mq_rcvinternal.c
index 44f0edcb2..3ccc60dca 100644
--- a/nuttx/sched/mq_rcvinternal.c
+++ b/nuttx/sched/mq_rcvinternal.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/mq_rcvinternal.c
*
- * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
+ * 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
@@ -292,16 +292,11 @@ ssize_t mq_doreceive(mqd_t mqdes, mqmsg_t *mqmsg, void *ubuffer, int *prio)
* time the task is unblocked
*/
- if (!btcb)
- {
- PANIC(OSERR_MQNOTFULLCOUNT);
- }
- else
- {
- btcb->msgwaitq = NULL;
- msgq->nwaitnotfull--;
- up_unblock_task(btcb);
- }
+ ASSERT(btcb);
+
+ btcb->msgwaitq = NULL;
+ msgq->nwaitnotfull--;
+ up_unblock_task(btcb);
irqrestore(saved_state);
}
diff --git a/nuttx/sched/mq_sndinternal.c b/nuttx/sched/mq_sndinternal.c
index e65b51c5a..9b004ef91 100644
--- a/nuttx/sched/mq_sndinternal.c
+++ b/nuttx/sched/mq_sndinternal.c
@@ -203,18 +203,8 @@ FAR mqmsg_t *mq_msgalloc(void)
/* Check if we got an allocated message */
- if (mqmsg)
- {
- mqmsg->type = MQ_ALLOC_DYN;
- }
-
- /* No? We are dead */
-
- else
- {
- sdbg("Out of messages\n");
- PANIC((uint32_t)OSERR_OUTOFMESSAGES);
- }
+ ASSERT(mqmsg);
+ mqmsg->type = MQ_ALLOC_DYN;
}
}
@@ -436,16 +426,11 @@ int mq_dosend(mqd_t mqdes, FAR mqmsg_t *mqmsg, const void *msg, size_t msglen, i
/* If one was found, unblock it */
- if (!btcb)
- {
- PANIC(OSERR_MQNONEMPTYCOUNT);
- }
- else
- {
- btcb->msgwaitq = NULL;
- msgq->nwaitnotempty--;
- up_unblock_task(btcb);
- }
+ ASSERT(btcb);
+
+ btcb->msgwaitq = NULL;
+ msgq->nwaitnotempty--;
+ up_unblock_task(btcb);
}
irqrestore(saved_state);
diff --git a/nuttx/sched/mq_waitirq.c b/nuttx/sched/mq_waitirq.c
index c12de1675..c30bdf836 100644
--- a/nuttx/sched/mq_waitirq.c
+++ b/nuttx/sched/mq_waitirq.c
@@ -113,46 +113,20 @@ void mq_waitirq(FAR struct tcb_s *wtcb, int errcode)
/* Get the message queue associated with the waiter from the TCB */
msgq = wtcb->msgwaitq;
-#ifdef CONFIG_DEBUG
- if (!msgq)
- {
- /* In these states there must always be an associated message queue */
+ DEBUGASSERT(msgq);
- PANIC((uint32_t)OSERR_MQNOWAITER);
- }
-#endif
wtcb->msgwaitq = NULL;
/* Decrement the count of waiters and cancel the wait */
if (wtcb->task_state == TSTATE_WAIT_MQNOTEMPTY)
{
-#ifdef CONFIG_DEBUG
- if (msgq->nwaitnotempty <= 0)
- {
- /* This state, there should be a positive, non-zero waiter
- * count.
- */
-
- PANIC((uint32_t)OSERR_MQNONEMPTYCOUNT);
-
- }
-#endif
+ DEBUGASSERT(msgq->nwaitnotempty > 0);
msgq->nwaitnotempty--;
}
else
{
-#ifdef CONFIG_DEBUG
- if (msgq->nwaitnotfull <= 0)
- {
- /* This state, there should be a positive, non-zero waiter
- * count.
- */
-
- PANIC((uint32_t)OSERR_MQNOTFULLCOUNT);
-
- }
-#endif
+ DEBUGASSERT(msgq->nwaitnotfull > 0);
msgq->nwaitnotfull--;
}
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index d13eb9cad..06cb3cf01 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -53,36 +53,6 @@
* Pre-processor Definitions
****************************************************************************/
-/* OS CRASH CODES: All must lie in the range 0-99 */
-
-enum os_crash_codes_e
-{
- OSERR_NOERROR = 0, /* No error */
- OSERR_NOTIMPLEMENTED, /* Feature is not implemented */
- OSERR_INTERNAL, /* Internal logic error */
- OSERR_UNEXPECTEDISR, /* Received unexpected interrupt */
- OSERR_UNDEFINEDINSN, /* Undefined instruction */
- OSERR_ERREXCEPTION, /* Other CPU-detected errors */
- OSERR_OUTOFMEMORY, /* Insufficient memory */
- OSERR_OUTOFMESSAGES, /* Out of messages */
- OSERR_NOIDLETASK, /* There is no idle task */
- OSERR_MQNONEMPTYCOUNT, /* Expected waiter for non-empty queue */
- OSERR_MQNOTFULLCOUNT, /* Expected waiter for non-full queue */
- OSERR_MQNOWAITER, /* Expected a queue for the waiter */
- OSERR_BADWAITSEM, /* Already waiting for a semaphore */
- OSERR_BADMSGTYPE, /* Tried to free a bad message type */
- OSERR_FAILEDTOADDSIGNAL, /* Failed to add pending signal */
- OSERR_FAILEDTOREMOVESIGNAL, /* Failed to remove pending signal */
- OSERR_TIMEOUTNOTCB, /* Timed out, but not TCB registered */
- OSERR_NOPENDINGSIGNAL, /* Expected a signal to be pending */
- OSERR_BADDELETESTATE, /* Bad state in task deletion */
- OSERR_WDOGNOTFOUND, /* Active watchdog not found */
- OSERR_EXITFROMINTERRUPT, /* Interrupt code attempted to exit */
- OSERR_BADUNBLOCKSTATE, /* Attempt to unblock from bad state */
- OSERR_BADBLOCKSTATE, /* Attempt to block from bad state */
- OSERR_BADREPRIORITIZESTATE /* Attempt to reprioritize in bad state or priority */
-};
-
/* Special task IDS. Any negative PID is invalid. */
#define NULL_TASK_PROCESS_ID (pid_t)0
diff --git a/nuttx/sched/sched_mergepending.c b/nuttx/sched/sched_mergepending.c
index 1364d2b1c..c400fee4d 100644
--- a/nuttx/sched/sched_mergepending.c
+++ b/nuttx/sched/sched_mergepending.c
@@ -125,42 +125,37 @@ bool sched_mergepending(void)
* the g_readytorun list!
*/
- if (!rtrtcb)
+ ASSERT(rtrtcb);
+
+ /* The pndtcb goes just before rtrtcb */
+
+ rtrprev = rtrtcb->blink;
+ if (!rtrprev)
{
- PANIC(OSERR_NOIDLETASK);
+ /* Special case: Inserting pndtcb at the head of the list */
+ /* Inform the instrumentation layer that we are switching tasks */
+
+ sched_note_switch(rtrtcb, pndtcb);
+
+ /* Then insert at the head of the list */
+
+ pndtcb->flink = rtrtcb;
+ pndtcb->blink = NULL;
+ rtrtcb->blink = pndtcb;
+ g_readytorun.head = (FAR dq_entry_t*)pndtcb;
+ rtrtcb->task_state = TSTATE_TASK_READYTORUN;
+ pndtcb->task_state = TSTATE_TASK_RUNNING;
+ ret = true;
}
else
{
- /* The pndtcb goes just before rtrtcb */
-
- rtrprev = rtrtcb->blink;
- if (!rtrprev)
- {
- /* Special case: Inserting pndtcb at the head of the list */
- /* Inform the instrumentation layer that we are switching tasks */
-
- sched_note_switch(rtrtcb, pndtcb);
-
- /* Then insert at the head of the list */
-
- pndtcb->flink = rtrtcb;
- pndtcb->blink = NULL;
- rtrtcb->blink = pndtcb;
- g_readytorun.head = (FAR dq_entry_t*)pndtcb;
- rtrtcb->task_state = TSTATE_TASK_READYTORUN;
- pndtcb->task_state = TSTATE_TASK_RUNNING;
- ret = true;
- }
- else
- {
- /* Insert in the middle of the list */
-
- pndtcb->flink = rtrtcb;
- pndtcb->blink = rtrprev;
- rtrprev->flink = pndtcb;
- rtrtcb->blink = pndtcb;
- pndtcb->task_state = TSTATE_TASK_READYTORUN;
- }
+ /* Insert in the middle of the list */
+
+ pndtcb->flink = rtrtcb;
+ pndtcb->blink = rtrprev;
+ rtrprev->flink = pndtcb;
+ rtrtcb->blink = pndtcb;
+ pndtcb->task_state = TSTATE_TASK_READYTORUN;
}
/* Set up for the next time through */
diff --git a/nuttx/sched/sem_wait.c b/nuttx/sched/sem_wait.c
index 06884e595..b7d16434c 100644
--- a/nuttx/sched/sem_wait.c
+++ b/nuttx/sched/sem_wait.c
@@ -139,10 +139,7 @@ int sem_wait(FAR sem_t *sem)
* semaphore
*/
- if (rtcb->waitsem != NULL)
- {
- PANIC(OSERR_BADWAITSEM);
- }
+ ASSERT(rtcb->waitsem == NULL);
/* Handle the POSIX semaphore (but don't set the owner yet) */
diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c
index ac2c24cfb..84a7ff6b6 100644
--- a/nuttx/sched/sig_action.c
+++ b/nuttx/sched/sig_action.c
@@ -101,10 +101,7 @@ static FAR sigactq_t *sig_allocateaction(void)
/* And try again */
sigact = (FAR sigactq_t*)sq_remfirst(&g_sigfreeaction);
- if (!sigact)
- {
- PANIC(OSERR_OUTOFMEMORY);
- }
+ ASSERT(sigact);
}
return sigact;
diff --git a/nuttx/sched/sig_dispatch.c b/nuttx/sched/sig_dispatch.c
index 7c4d34138..82c891b46 100644
--- a/nuttx/sched/sig_dispatch.c
+++ b/nuttx/sched/sig_dispatch.c
@@ -349,10 +349,7 @@ int sig_tcbdispatch(FAR struct tcb_s *stcb, siginfo_t *info)
else
{
irqrestore(saved_state);
- if (!sig_addpendingsignal(stcb, info))
- {
- PANIC(OSERR_FAILEDTOADDSIGNAL);
- }
+ ASSERT(sig_addpendingsignal(stcb, info));
}
}
diff --git a/nuttx/sched/sig_suspend.c b/nuttx/sched/sig_suspend.c
index bc26aa35a..e57ac4396 100644
--- a/nuttx/sched/sig_suspend.c
+++ b/nuttx/sched/sig_suspend.c
@@ -140,10 +140,7 @@ int sigsuspend(FAR const sigset_t *set)
unblocksigno = sig_lowest(&intersection);
sigpend = sig_removependingsignal(rtcb, unblocksigno);
- if (!sigpend)
- {
- PANIC(OSERR_FAILEDTOREMOVESIGNAL);
- }
+ ASSERT(sigpend);
sig_releasependingsignal(sigpend);
irqrestore(saved_state);
diff --git a/nuttx/sched/sig_timedwait.c b/nuttx/sched/sig_timedwait.c
index fd8939a1d..3d70f33db 100644
--- a/nuttx/sched/sig_timedwait.c
+++ b/nuttx/sched/sig_timedwait.c
@@ -104,12 +104,8 @@ static void sig_timeout(int argc, uint32_t itcb)
uint32_t itcb;
} u;
- u.itcb = itcb;
-
- if (!u.wtcb)
- {
- PANIC(OSERR_TIMEOUTNOTCB);
- }
+ u.itcb = itcb;
+ ASSERT(u.wtcb);
/* There may be a race condition -- make sure the task is
* still waiting for a signal
@@ -210,10 +206,7 @@ int sigtimedwait(FAR const sigset_t *set, FAR struct siginfo *info,
*/
sigpend = sig_removependingsignal(rtcb, sig_lowest(&intersection));
- if (!sigpend)
- {
- PANIC(OSERR_NOPENDINGSIGNAL);
- }
+ ASSERT(sigpend);
/* Return the signal info to the caller if so requested */
diff --git a/nuttx/sched/task_delete.c b/nuttx/sched/task_delete.c
index 637b536ec..1cf9f97e5 100644
--- a/nuttx/sched/task_delete.c
+++ b/nuttx/sched/task_delete.c
@@ -145,7 +145,7 @@ int task_terminate(pid_t pid, bool nonblocking)
dtcb->task_state >= NUM_TASK_STATES)
{
sched_unlock();
- PANIC(OSERR_BADDELETESTATE);
+ PANIC();
}
/* Perform common task termination logic (flushing streams, calling
diff --git a/nuttx/sched/wd_cancel.c b/nuttx/sched/wd_cancel.c
index 0bd59cf89..a1c220873 100644
--- a/nuttx/sched/wd_cancel.c
+++ b/nuttx/sched/wd_cancel.c
@@ -123,38 +123,34 @@ int wd_cancel (WDOG_ID wdid)
* error has occurred because the watchdog is marked active!
*/
- if (!curr)
+ ASSERT(curr);
+
+ /* If there is a watchdog in the timer queue after the one that
+ * is being canceled, then it inherits the remaining ticks.
+ */
+
+ if (curr->next)
+ {
+ curr->next->lag += curr->lag;
+ }
+
+ /* Now, remove the watchdog from the timer queue */
+
+ if (prev)
{
- PANIC(OSERR_WDOGNOTFOUND);
+ (void)sq_remafter((FAR sq_entry_t*)prev, &g_wdactivelist);
}
else
{
- /* If there is a watchdog in the timer queue after the one that
- * is being canceled, then it inherits the remaining ticks.
- */
-
- if (curr->next)
- {
- curr->next->lag += curr->lag;
- }
-
- /* Now, remove the watchdog from the timer queue */
-
- if (prev)
- {
- (void)sq_remafter((FAR sq_entry_t*)prev, &g_wdactivelist);
- }
- else
- {
- (void)sq_remfirst(&g_wdactivelist);
- }
- wdid->next = NULL;
-
- /* Return success */
-
- ret = OK;
+ (void)sq_remfirst(&g_wdactivelist);
}
+ wdid->next = NULL;
+
+ /* Return success */
+
+ ret = OK;
+
/* Mark the watchdog inactive */
wdid->active = false;
diff --git a/nuttx/sched/wd_start.c b/nuttx/sched/wd_start.c
index 2a69d131a..440c83b0c 100644
--- a/nuttx/sched/wd_start.c
+++ b/nuttx/sched/wd_start.c
@@ -337,7 +337,7 @@ void wd_timer(void)
{
default:
#ifdef CONFIG_DEBUG
- PANIC(OSERR_INTERNAL);
+ PANIC();
#endif
case 0:
(*((wdentry0_t)(wdog->func)))(0);