summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile4
-rw-r--r--nuttx/sched/get_errno_ptr.c4
-rw-r--r--nuttx/sched/get_errorptr.c83
-rw-r--r--nuttx/sched/irq_attach.c4
-rw-r--r--nuttx/sched/irq_dispatch.c6
-rw-r--r--nuttx/sched/irq_internal.h2
-rw-r--r--nuttx/sched/irq_unexpectedisr.c2
-rw-r--r--nuttx/sched/mq_close.c15
-rw-r--r--nuttx/sched/mq_descreate.c4
-rw-r--r--nuttx/sched/mq_findnamed.c6
-rw-r--r--nuttx/sched/mq_initialize.c6
-rw-r--r--nuttx/sched/mq_internal.h55
-rw-r--r--nuttx/sched/mq_msgfree.c6
-rw-r--r--nuttx/sched/mq_msgqfree.c8
-rw-r--r--nuttx/sched/mq_open.c12
-rw-r--r--nuttx/sched/mq_receive.c20
-rw-r--r--nuttx/sched/mq_send.c42
-rw-r--r--nuttx/sched/mq_unlink.c9
-rw-r--r--nuttx/sched/os_internal.h42
-rw-r--r--nuttx/sched/os_start.c7
-rw-r--r--nuttx/sched/pthread_completejoin.c8
-rw-r--r--nuttx/sched/pthread_condtimedwait.c125
-rw-r--r--nuttx/sched/pthread_create.c24
-rw-r--r--nuttx/sched/pthread_detach.c2
-rw-r--r--nuttx/sched/pthread_exit.c3
-rw-r--r--nuttx/sched/pthread_findjoininfo.c4
-rw-r--r--nuttx/sched/pthread_getspecific.c7
-rw-r--r--nuttx/sched/pthread_initialize.c5
-rw-r--r--nuttx/sched/pthread_internal.h14
-rw-r--r--nuttx/sched/pthread_join.c5
-rw-r--r--nuttx/sched/pthread_removejoininfo.c7
-rw-r--r--nuttx/sched/pthread_setspecific.c5
-rw-r--r--nuttx/sched/sched_addblocked.c5
-rw-r--r--nuttx/sched/sched_addprioritized.c25
-rw-r--r--nuttx/sched/sched_addreadytorun.c4
-rw-r--r--nuttx/sched/sched_free.c5
-rw-r--r--nuttx/sched/sched_getfiles.c4
-rw-r--r--nuttx/sched/sched_getparam.c7
-rw-r--r--nuttx/sched/sched_getstreams.c4
-rw-r--r--nuttx/sched/sched_gettcb.c5
-rw-r--r--nuttx/sched/sched_mergepending.c14
-rw-r--r--nuttx/sched/sched_processtimer.c1
-rw-r--r--nuttx/sched/sched_releasetcb.c4
-rw-r--r--nuttx/sched/sched_removeblocked.c5
-rw-r--r--nuttx/sched/sched_removereadytorun.c4
-rw-r--r--nuttx/sched/sched_rrgetinterval.c4
-rw-r--r--nuttx/sched/sched_setparam.c8
-rw-r--r--nuttx/sched/sched_setscheduler.c3
-rw-r--r--nuttx/sched/sched_setupidlefiles.c2
-rw-r--r--nuttx/sched/sched_setuppthreadfiles.c4
-rw-r--r--nuttx/sched/sched_setupstreams.c2
-rw-r--r--nuttx/sched/sched_setuptaskfiles.c4
-rw-r--r--nuttx/sched/sched_yield.c2
-rw-r--r--nuttx/sched/sem_close.c9
-rw-r--r--nuttx/sched/sem_findnamed.c6
-rw-r--r--nuttx/sched/sem_internal.h16
-rw-r--r--nuttx/sched/sem_open.c17
-rw-r--r--nuttx/sched/sem_post.c6
-rw-r--r--nuttx/sched/sem_unlink.c9
-rw-r--r--nuttx/sched/sem_wait.c5
-rw-r--r--nuttx/sched/sem_waitirq.c3
-rw-r--r--nuttx/sched/sig_action.c22
-rw-r--r--nuttx/sched/sig_allocatependingsigaction.c12
-rw-r--r--nuttx/sched/sig_cleanup.c16
-rw-r--r--nuttx/sched/sig_deliver.c22
-rw-r--r--nuttx/sched/sig_findaction.c30
-rw-r--r--nuttx/sched/sig_initialize.c34
-rw-r--r--nuttx/sched/sig_internal.h41
-rw-r--r--nuttx/sched/sig_mqnotempty.c3
-rw-r--r--nuttx/sched/sig_pending.c14
-rw-r--r--nuttx/sched/sig_procmask.c63
-rw-r--r--nuttx/sched/sig_queue.c3
-rw-r--r--nuttx/sched/sig_received.c46
-rw-r--r--nuttx/sched/sig_releasependingsigaction.c6
-rw-r--r--nuttx/sched/sig_releasependingsignal.c6
-rw-r--r--nuttx/sched/sig_removependingsignal.c10
-rw-r--r--nuttx/sched/sig_suspend.c12
-rw-r--r--nuttx/sched/sig_timedwait.c18
-rw-r--r--nuttx/sched/sig_unmaskpendingsignal.c9
-rw-r--r--nuttx/sched/task_create.c33
-rw-r--r--nuttx/sched/task_delete.c9
-rw-r--r--nuttx/sched/task_restart.c12
-rw-r--r--nuttx/sched/wd_cancel.c2
-rw-r--r--nuttx/sched/wd_delete.c4
-rw-r--r--nuttx/sched/wd_initialize.c8
-rw-r--r--nuttx/sched/wd_internal.h2
-rw-r--r--nuttx/sched/wd_start.c10
87 files changed, 595 insertions, 585 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 5efa4a6f0..e5dc3881d 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -40,7 +40,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
ASRCS =
AOBJS = $(ASRCS:.S=.o)
-MISC_SRCS = os_start.c get_errno_ptr.c get_errorptr.c \
+MISC_SRCS = os_start.c get_errno_ptr.c \
sched_setupstreams.c sched_getfiles.c sched_getstreams.c \
sched_setupidlefiles.c sched_setuptaskfiles.c sched_setuppthreadfiles.c \
sched_releasefiles.c
@@ -124,7 +124,7 @@ $(BIN): $(OBJS)
depend: .depend
clean:
- rm -f $(BIN) *.o *.asm *.lst *.sym *~
+ rm -f $(BIN) *.o *.asm *.lst *.sym *.adb *~
distclean: clean
rm -f Make.dep .depend
diff --git a/nuttx/sched/get_errno_ptr.c b/nuttx/sched/get_errno_ptr.c
index c9f0d52c8..7a8084c71 100644
--- a/nuttx/sched/get_errno_ptr.c
+++ b/nuttx/sched/get_errno_ptr.c
@@ -61,9 +61,9 @@
*
************************************************************/
-int *get_errno_ptr(void)
+FAR int *get_errno_ptr(void)
{
- _TCB *ptcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head;
return &ptcb->errno;
}
diff --git a/nuttx/sched/get_errorptr.c b/nuttx/sched/get_errorptr.c
deleted file mode 100644
index 7cfad6cb1..000000000
--- a/nuttx/sched/get_errorptr.c
+++ /dev/null
@@ -1,83 +0,0 @@
-/************************************************************
- * get_errorptr.c
- *
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************/
-
-/************************************************************
- * Included Files
- ************************************************************/
-
-#include <sys/types.h>
-#include <errno.h>
-
-/************************************************************
- * Global Functions
- ************************************************************/
-
-/************************************************************
- * Function: get_errorptr
- *
- * Description:
- * Return a pointer that is just ERROR cast to void *.
- * most fully performing processors don't need anything
- * like this. Hoever, this little of nonsense is necessary
- * for some processors where sizeof(pointer) < sizeof(uint32)
- * and which do not support casts of integers to pointers.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * ERROR cast as a pointer value
- *
- * Assumptions:
- *
- ************************************************************/
-
-void *get_errnorptr(void)
-{
-#ifdef CONFIG_CAN_CAST_POINTERS
- return (void*)ERROR;
-#else
- union
- {
- void *verror;
- sint32 ierror;
- } u;
-
- u.ierror = ERROR;
- return u.verror;
-#endif
-}
-
-
diff --git a/nuttx/sched/irq_attach.c b/nuttx/sched/irq_attach.c
index d67a04a49..3032bf1b6 100644
--- a/nuttx/sched/irq_attach.c
+++ b/nuttx/sched/irq_attach.c
@@ -76,6 +76,7 @@
int irq_attach(int irq, xcpt_t isr)
{
+#if NR_IRQS > 0
int ret = ERROR;
if ((unsigned)irq < NR_IRQS)
@@ -102,6 +103,9 @@ int irq_attach(int irq, xcpt_t isr)
}
return ret;
+#else
+ return OK;
+#endif
}
diff --git a/nuttx/sched/irq_dispatch.c b/nuttx/sched/irq_dispatch.c
index d6466cbc0..1dc388a40 100644
--- a/nuttx/sched/irq_dispatch.c
+++ b/nuttx/sched/irq_dispatch.c
@@ -76,12 +76,13 @@
*
***********************************************************/
-void irq_dispatch(int irq, void *context)
+void irq_dispatch(int irq, FAR void *context)
{
xcpt_t vector;
/* Perform some sanity checks */
+#if NR_IRQS > 0
if ((unsigned)irq >= NR_IRQS || g_irqvector[irq] == NULL)
{
vector = irq_unexpected_isr;
@@ -90,6 +91,9 @@ void irq_dispatch(int irq, void *context)
{
vector = g_irqvector[irq];
}
+#else
+ vector = irq_unexpected_isr;
+#endif
/* Then dispatch to the interrupt handler */
diff --git a/nuttx/sched/irq_internal.h b/nuttx/sched/irq_internal.h
index 211779bc3..a1216fa9d 100644
--- a/nuttx/sched/irq_internal.h
+++ b/nuttx/sched/irq_internal.h
@@ -71,7 +71,7 @@ extern "C" {
#endif
EXTERN void weak_function irq_initialize(void);
-EXTERN int irq_unexpected_isr(int irq, void *context);
+EXTERN int irq_unexpected_isr(int irq, FAR void *context);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/sched/irq_unexpectedisr.c b/nuttx/sched/irq_unexpectedisr.c
index 6ca3e1da8..b7b6b4ae2 100644
--- a/nuttx/sched/irq_unexpectedisr.c
+++ b/nuttx/sched/irq_unexpectedisr.c
@@ -75,7 +75,7 @@
*
************************************************************/
-int irq_unexpected_isr(int irq, void *context)
+int irq_unexpected_isr(int irq, FAR void *context)
{
(void)irqsave();
PANIC(OSERR_UNEXPECTEDISR);
diff --git a/nuttx/sched/mq_close.c b/nuttx/sched/mq_close.c
index 88fe0e043..6643cc5e9 100644
--- a/nuttx/sched/mq_close.c
+++ b/nuttx/sched/mq_close.c
@@ -75,7 +75,7 @@
*
************************************************************/
-#define mq_desfree(mqdes) sq_addlast((sq_entry_t*)mqdes, &g_desfree)
+#define mq_desfree(mqdes) sq_addlast((FAR sq_entry_t*)mqdes, &g_desfree)
/************************************************************
* Public Functions
@@ -113,10 +113,10 @@
int mq_close(mqd_t mqdes)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- msgq_t *msgq;
- irqstate_t saved_state;
- int ret = ERROR;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR msgq_t *msgq;
+ irqstate_t saved_state;
+ int ret = ERROR;
/* Verify the inputs */
@@ -128,7 +128,7 @@ int mq_close(mqd_t mqdes)
* list of message descriptors.
*/
- sq_rem((sq_entry_t*)mqdes, &rtcb->msgdesq);
+ sq_rem((FAR sq_entry_t*)mqdes, &rtcb->msgdesq);
/* Find the message queue associated with the message descriptor */
@@ -165,7 +165,7 @@ int mq_close(mqd_t mqdes)
*/
saved_state = irqsave();
- (void)sq_rem((sq_entry_t*)msgq, &g_msgqueues);
+ (void)sq_rem((FAR sq_entry_t*)msgq, &g_msgqueues);
irqrestore(saved_state);
/* Then deallocate it (and any messages left in it) */
@@ -183,3 +183,4 @@ int mq_close(mqd_t mqdes)
return ret;
}
+
diff --git a/nuttx/sched/mq_descreate.c b/nuttx/sched/mq_descreate.c
index f631cfd2b..98026ad19 100644
--- a/nuttx/sched/mq_descreate.c
+++ b/nuttx/sched/mq_descreate.c
@@ -132,7 +132,7 @@ static mqd_t mq_desalloc(void)
*
************************************************************/
-mqd_t mq_descreate(_TCB* mtcb, msgq_t* msgq, int oflags)
+mqd_t mq_descreate(FAR _TCB* mtcb, FAR msgq_t* msgq, int oflags)
{
mqd_t mqdes;
@@ -149,7 +149,7 @@ mqd_t mq_descreate(_TCB* mtcb, msgq_t* msgq, int oflags)
/* And add it to the specified tasks's TCB */
- sq_addlast((sq_entry_t*)mqdes, &mtcb->msgdesq);
+ sq_addlast((FAR sq_entry_t*)mqdes, &mtcb->msgdesq);
}
return mqdes;
diff --git a/nuttx/sched/mq_findnamed.c b/nuttx/sched/mq_findnamed.c
index f01e24d1f..a74caba7b 100644
--- a/nuttx/sched/mq_findnamed.c
+++ b/nuttx/sched/mq_findnamed.c
@@ -81,13 +81,13 @@
*
************************************************************/
-msgq_t *mq_findnamed(const char *mq_name)
+FAR msgq_t *mq_findnamed(const char *mq_name)
{
- msgq_t *msgq;
+ FAR msgq_t *msgq;
/* Search the list of named message queues */
- for (msgq = (msgq_t*)g_msgqueues.head; (msgq); msgq = msgq->flink)
+ for (msgq = (FAR msgq_t*)g_msgqueues.head; (msgq); msgq = msgq->flink)
{
/* Break out of the lloop with a non-NULL msgq if the
* name matches.
diff --git a/nuttx/sched/mq_initialize.c b/nuttx/sched/mq_initialize.c
index deff6a254..df8e981e6 100644
--- a/nuttx/sched/mq_initialize.c
+++ b/nuttx/sched/mq_initialize.c
@@ -144,7 +144,7 @@ static mqmsg_t *mq_msgblockalloc(sq_queue_t *queue, uint16 nmsgs,
for (i = 0; i < nmsgs; i++)
{
mqmsg->type = alloc_type;
- sq_addlast((sq_entry_t*)mqmsg++, queue);
+ sq_addlast((FAR sq_entry_t*)mqmsg++, queue);
}
}
@@ -233,13 +233,13 @@ void mq_desblockalloc(void)
* we ever need to reclaim the memory.
*/
- sq_addlast(&mqdesblock->queue, &g_desalloc);
+ sq_addlast((FAR sq_entry_t*)&mqdesblock->queue, &g_desalloc);
/* Then add each message queue descriptor to the free list */
for (i = 0; i < NUM_MSG_DESCRIPTORS; i++)
{
- sq_addlast((sq_entry_t*)&mqdesblock->mqdes[i], &g_desfree);
+ sq_addlast((FAR sq_entry_t*)&mqdesblock->mqdes[i], &g_desfree);
}
}
}
diff --git a/nuttx/sched/mq_internal.h b/nuttx/sched/mq_internal.h
index ba2368e43..4e55a9316 100644
--- a/nuttx/sched/mq_internal.h
+++ b/nuttx/sched/mq_internal.h
@@ -95,13 +95,12 @@ struct mqmsg
* MQ_type.
*/
- struct mqmsg *next; /* Forward link to next message */
- ubyte type; /* (Used to manage allocations) */
+ FAR struct mqmsg *next; /* Forward link to next message */
+ ubyte type; /* (Used to manage allocations) */
- ubyte priority; /* priority of message */
- ubyte msglen; /* Message data length */
- ubyte pad; /* Not used */
- uint16 mail[MQ_MAX_HWORDS]; /* Message data */
+ ubyte priority; /* priority of message */
+ ubyte msglen; /* Message data length */
+ uint16 mail[MQ_MAX_HWORDS]; /* Message data */
};
typedef struct mqmsg mqmsg_t;
@@ -111,20 +110,20 @@ struct mq_des; /* forward reference */
struct msgq_s
{
- struct msgq_s *flink; /* Forward link to next message queue */
- sq_queue_t msglist; /* Prioritized message list */
- sint16 maxmsgs; /* Maximum number of messages in the queue */
- sint16 nmsgs; /* Number of message in the queue */
- sint16 nconnect; /* Number of connections to message queue */
- sint16 nwaitnotfull; /* Number tasks waiting for not full */
- sint16 nwaitnotempty; /* Number tasks waiting for not empty */
- ubyte maxmsgsize; /* Max size of message in message queue */
- boolean unlinked; /* TRUE if the msg queue has been unlinked */
- struct mq_des *ntmqdes; /* Notification: Owning mqdes (NULL if none) */
- pid_t ntpid; /* Notification: Receiving Task's PID */
- int ntsigno; /* Notification: Signal number */
- union sigval ntvalue; /* Notification: Signal value */
- char name[1]; /* Start of the queue name */
+ FAR struct msgq_s *flink; /* Forward link to next message queue */
+ sq_queue_t msglist; /* Prioritized message list */
+ sint16 maxmsgs; /* Maximum number of messages in the queue */
+ sint16 nmsgs; /* Number of message in the queue */
+ sint16 nconnect; /* Number of connections to message queue */
+ sint16 nwaitnotfull; /* Number tasks waiting for not full */
+ sint16 nwaitnotempty; /* Number tasks waiting for not empty */
+ ubyte maxmsgsize; /* Max size of message in message queue */
+ boolean unlinked; /* TRUE if the msg queue has been unlinked */
+ FAR struct mq_des *ntmqdes; /* Notification: Owning mqdes (NULL if none) */
+ pid_t ntpid; /* Notification: Receiving Task's PID */
+ int ntsigno; /* Notification: Signal number */
+ union sigval ntvalue; /* Notification: Signal value */
+ char name[1]; /* Start of the queue name */
};
#define SIZEOF_MQ_HEADER ((int)(((msgq_t*)NULL)->name))
@@ -135,9 +134,9 @@ struct msgq_s
struct mq_des
{
- struct mq_des *flink; /* Forward link to next message descriptor */
- msgq_t *msgq; /* Pointer to associated message queue */
- int oflags; /* Flags set when message queue was opened */
+ FAR struct mq_des *flink; /* Forward link to next message descriptor */
+ FAR msgq_t *msgq; /* Pointer to associated message queue */
+ int oflags; /* Flags set when message queue was opened */
};
/************************************************************
@@ -182,12 +181,12 @@ extern "C" {
/* Functions defined in mq_initialized.c *******************/
EXTERN void weak_function mq_initialize(void);
-EXTERN void mq_desblockalloc(void);
+EXTERN void mq_desblockalloc(void);
-EXTERN mqd_t mq_descreate(_TCB* mtcb, msgq_t* msgq, int oflags);
-EXTERN msgq_t *mq_findnamed(const char *mq_name);
-EXTERN void mq_msgfree(mqmsg_t *mqmsg);
-EXTERN void mq_msgqfree(msgq_t *msgq);
+EXTERN mqd_t mq_descreate(FAR _TCB* mtcb, FAR msgq_t* msgq, int oflags);
+EXTERN FAR msgq_t *mq_findnamed(const char *mq_name);
+EXTERN void mq_msgfree(FAR mqmsg_t *mqmsg);
+EXTERN void mq_msgqfree(FAR msgq_t *msgq);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/sched/mq_msgfree.c b/nuttx/sched/mq_msgfree.c
index f9246d8fc..f7a236f15 100644
--- a/nuttx/sched/mq_msgfree.c
+++ b/nuttx/sched/mq_msgfree.c
@@ -84,7 +84,7 @@
*
************************************************************/
-void mq_msgfree(mqmsg_t * mqmsg)
+void mq_msgfree(FAR mqmsg_t *mqmsg)
{
irqstate_t saved_state;
@@ -99,7 +99,7 @@ void mq_msgfree(mqmsg_t * mqmsg)
*/
saved_state = irqsave();
- sq_addlast((sq_entry_t*)mqmsg, &g_msgfree);
+ sq_addlast((FAR sq_entry_t*)mqmsg, &g_msgfree);
irqrestore(saved_state);
}
@@ -114,7 +114,7 @@ void mq_msgfree(mqmsg_t * mqmsg)
*/
saved_state = irqsave();
- sq_addlast((sq_entry_t*)mqmsg, &g_msgfreeirq);
+ sq_addlast((FAR sq_entry_t*)mqmsg, &g_msgfreeirq);
irqrestore(saved_state);
}
diff --git a/nuttx/sched/mq_msgqfree.c b/nuttx/sched/mq_msgqfree.c
index 59a27603e..06d5da815 100644
--- a/nuttx/sched/mq_msgqfree.c
+++ b/nuttx/sched/mq_msgqfree.c
@@ -84,14 +84,14 @@
*
************************************************************/
-void mq_msgqfree(msgq_t *msgq)
+void mq_msgqfree(FAR msgq_t *msgq)
{
- mqmsg_t *curr;
- mqmsg_t *next;
+ FAR mqmsg_t *curr;
+ FAR mqmsg_t *next;
/* Deallocate any stranded messages in the message queue. */
- curr = (mqmsg_t*)msgq->msglist.head;
+ curr = (FAR mqmsg_t*)msgq->msglist.head;
while (curr)
{
/* Deallocate the message structure. */
diff --git a/nuttx/sched/mq_open.c b/nuttx/sched/mq_open.c
index d4ad2a322..e3e239180 100644
--- a/nuttx/sched/mq_open.c
+++ b/nuttx/sched/mq_open.c
@@ -103,8 +103,8 @@
mqd_t mq_open(const char *mq_name, int oflags, ...)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- msgq_t *msgq;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR msgq_t *msgq;
mqd_t mqdes = NULL;
va_list arg; /* Points to each un-named argument */
mode_t mode; /* MQ creation mode parameter (ignored) */
@@ -151,7 +151,7 @@ mqd_t mq_open(const char *mq_name, int oflags, ...)
* of the message queue name+1.
*/
- msgq = (msgq_t*)kzmalloc(SIZEOF_MQ_HEADER + namelen + 1);
+ msgq = (FAR msgq_t*)kzmalloc(SIZEOF_MQ_HEADER + namelen + 1);
if (msgq)
{
/* Create a message queue descriptor for the TCB */
@@ -196,7 +196,7 @@ mqd_t mq_open(const char *mq_name, int oflags, ...)
* message queues
*/
- sq_addlast((sq_entry_t*)msgq, &g_msgqueues);
+ sq_addlast((FAR sq_entry_t*)msgq, &g_msgqueues);
/* Clean-up variable argument stuff */
@@ -218,11 +218,7 @@ mqd_t mq_open(const char *mq_name, int oflags, ...)
if (mqdes == NULL)
{
-#ifdef CONFIG_CAN_CAST_POINTERS
return (mqd_t)ERROR;
-#else
- return get_errorptr();
-#endif
}
else
{
diff --git a/nuttx/sched/mq_receive.c b/nuttx/sched/mq_receive.c
index 4e7555e13..649dfae7a 100644
--- a/nuttx/sched/mq_receive.c
+++ b/nuttx/sched/mq_receive.c
@@ -114,13 +114,13 @@
int mq_receive(mqd_t mqdes, void *msg, size_t msglen, int *prio)
{
- _TCB *rtcb;
- _TCB *btcb;
- msgq_t *msgq;
- mqmsg_t *curr;
- irqstate_t saved_state;
- ubyte rcvmsglen;
- int ret = ERROR;
+ FAR _TCB *rtcb;
+ FAR _TCB *btcb;
+ FAR msgq_t *msgq;
+ FAR mqmsg_t *curr;
+ irqstate_t saved_state;
+ ubyte rcvmsglen;
+ int ret = ERROR;
/* Verify the input parameters */
@@ -142,7 +142,7 @@ int mq_receive(mqd_t mqdes, void *msg, size_t msglen, int *prio)
/* Get the message from the head of the queue */
- while ((curr = (mqmsg_t*)sq_remfirst(&msgq->msglist)) == NULL)
+ while ((curr = (FAR mqmsg_t*)sq_remfirst(&msgq->msglist)) == NULL)
{
/* Should we block until there the above condition has been
* satisfied?
@@ -152,7 +152,7 @@ int mq_receive(mqd_t mqdes, void *msg, size_t msglen, int *prio)
{
/* Block and try again */
- rtcb = (_TCB*)g_readytorun.head;
+ rtcb = (FAR _TCB*)g_readytorun.head;
rtcb->msgwaitq = msgq;
msgq->nwaitnotempty++;
up_block_task(rtcb, TSTATE_WAIT_MQNOTEMPTY);
@@ -207,7 +207,7 @@ int mq_receive(mqd_t mqdes, void *msg, size_t msglen, int *prio)
*/
saved_state = irqsave();
- for (btcb = (_TCB*)g_waitingformqnotfull.head;
+ for (btcb = (FAR _TCB*)g_waitingformqnotfull.head;
btcb && btcb->msgwaitq != msgq;
btcb = btcb->flink);
diff --git a/nuttx/sched/mq_send.c b/nuttx/sched/mq_send.c
index 0a9a12515..aaf700a45 100644
--- a/nuttx/sched/mq_send.c
+++ b/nuttx/sched/mq_send.c
@@ -37,6 +37,7 @@
* Included Files
************************************************************/
+#include <nuttx/compiler.h>
#include <nuttx/kmalloc.h>
#include <sys/types.h> /* uint32, etc. */
#include <mqueue.h>
@@ -92,10 +93,10 @@
*
************************************************************/
-mqmsg_t *mq_msgalloc(void)
+FAR mqmsg_t *mq_msgalloc(void)
{
- mqmsg_t *mqmsg;
- irqstate_t saved_state;
+ FAR mqmsg_t *mqmsg;
+ irqstate_t saved_state;
/* If we were called from an interrupt handler, then try to
* get the message from generally available list of messages.
@@ -107,12 +108,12 @@ mqmsg_t *mq_msgalloc(void)
{
/* Try the general free list */
- mqmsg = (mqmsg_t*)sq_remfirst(&g_msgfree);
+ mqmsg = (FAR mqmsg_t*)sq_remfirst(&g_msgfree);
if (!mqmsg)
{
/* Try the free list reserved for interrupt handlers */
- mqmsg = (mqmsg_t*)sq_remfirst(&g_msgfreeirq);
+ mqmsg = (FAR mqmsg_t*)sq_remfirst(&g_msgfreeirq);
}
}
@@ -125,14 +126,14 @@ mqmsg_t *mq_msgalloc(void)
*/
saved_state = irqsave();
- mqmsg = (mqmsg_t*)sq_remfirst(&g_msgfree);
+ mqmsg = (FAR mqmsg_t*)sq_remfirst(&g_msgfree);
irqrestore(saved_state);
/* If we cannot a message from the free list, then we will have to allocate one. */
if (!mqmsg)
{
- mqmsg = (mqmsg_t *)kmalloc((sizeof (mqmsg_t)));
+ mqmsg = (FAR mqmsg_t *)kmalloc((sizeof (mqmsg_t)));
/* Check if we got an allocated message */
@@ -152,7 +153,6 @@ mqmsg_t *mq_msgalloc(void)
}
return(mqmsg);
-
}
/************************************************************
@@ -202,14 +202,14 @@ mqmsg_t *mq_msgalloc(void)
int mq_send(mqd_t mqdes, const void *msg, size_t msglen, int prio)
{
- _TCB *rtcb;
- _TCB *btcb;
- msgq_t *msgq;
- mqmsg_t *curr;
- mqmsg_t *next;
- mqmsg_t *prev;
- irqstate_t saved_state;
- int ret = ERROR;
+ FAR _TCB *rtcb;
+ FAR _TCB *btcb;
+ FAR msgq_t *msgq;
+ FAR mqmsg_t *curr;
+ FAR mqmsg_t *next;
+ FAR mqmsg_t *prev;
+ irqstate_t saved_state;
+ int ret = ERROR;
/* Verify the input parameters */
@@ -267,7 +267,7 @@ int mq_send(mqd_t mqdes, const void *msg, size_t msglen, int prio)
* When we are unblocked, we will try again
*/
- rtcb = (_TCB*)g_readytorun.head;
+ rtcb = (FAR _TCB*)g_readytorun.head;
rtcb->msgwaitq = msgq;
(msgq->nwaitnotfull)++;
up_block_task(rtcb, TSTATE_WAIT_MQNOTFULL);
@@ -314,7 +314,7 @@ int mq_send(mqd_t mqdes, const void *msg, size_t msglen, int prio)
* message. Each is list is maintained in ascending priority order.
*/
- for (prev = NULL, next = (mqmsg_t*)msgq->msglist.head;
+ for (prev = NULL, next = (FAR mqmsg_t*)msgq->msglist.head;
next && prio <= next->priority;
prev = next, next = next->next);
@@ -322,12 +322,12 @@ int mq_send(mqd_t mqdes, const void *msg, size_t msglen, int prio)
if (prev)
{
- sq_addafter((sq_entry_t*)prev, (sq_entry_t*)curr,
+ sq_addafter((FAR sq_entry_t*)prev, (FAR sq_entry_t*)curr,
&msgq->msglist);
}
else
{
- sq_addfirst((sq_entry_t*)curr, &msgq->msglist);
+ sq_addfirst((FAR sq_entry_t*)curr, &msgq->msglist);
}
/* Increment the count of message in the queue */
@@ -378,7 +378,7 @@ int mq_send(mqd_t mqdes, const void *msg, size_t msglen, int prio)
* interrupts should never cause a change in this list
*/
- for (btcb = (_TCB*)g_waitingformqnotempty.head;
+ for (btcb = (FAR _TCB*)g_waitingformqnotempty.head;
btcb && btcb->msgwaitq != msgq;
btcb = btcb->flink);
diff --git a/nuttx/sched/mq_unlink.c b/nuttx/sched/mq_unlink.c
index 066bcacab..17b5767ae 100644
--- a/nuttx/sched/mq_unlink.c
+++ b/nuttx/sched/mq_unlink.c
@@ -89,9 +89,9 @@
int mq_unlink(const char *mq_name)
{
- msgq_t *msgq;
- irqstate_t saved_state;
- int ret = ERROR;
+ FAR msgq_t *msgq;
+ irqstate_t saved_state;
+ int ret = ERROR;
/* Verify the input values */
@@ -115,7 +115,7 @@ int mq_unlink(const char *mq_name)
*/
saved_state = irqsave();
- (void)sq_rem((sq_entry_t*)msgq, &g_msgqueues);
+ (void)sq_rem((FAR sq_entry_t*)msgq, &g_msgqueues);
irqrestore(saved_state);
/* Then deallocate it (and any messages left in it) */
@@ -140,3 +140,4 @@ int mq_unlink(const char *mq_name)
return ret;
}
+
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 4e4cdf7d6..75807e930 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -123,8 +123,8 @@ enum os_crash_codes_e
struct pidhash_s
{
- _TCB *tcb;
- pid_t pid;
+ FAR _TCB *tcb;
+ pid_t pid;
};
typedef struct pidhash_s pidhash_t;
@@ -135,8 +135,8 @@ typedef struct pidhash_s pidhash_t;
struct tasklist_s
{
- dq_queue_t *list; /* Pointer to the task list */
- boolean prioritized; /* TRUE if the list is prioritized */
+ NEAR dq_queue_t *list; /* Pointer to the task list */
+ boolean prioritized; /* TRUE if the list is prioritized */
};
typedef struct tasklist_s tasklist_t;
@@ -232,32 +232,32 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
* Public Function Prototypes
************************************************************/
-extern STATUS _task_init(_TCB *tcb, char *name, int priority,
+extern STATUS _task_init(FAR _TCB *tcb, const char *name, int priority,
start_t start, main_t main,
boolean pthread,
- char *arg1, char *arg2,
- char *arg3, char *arg4);
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4);
-extern boolean sched_addreadytorun(_TCB *rtrtcb);
-extern boolean sched_removereadytorun(_TCB *rtrtcb);
-extern boolean sched_addprioritized(_TCB *newTcb,
- dq_queue_t *list);
+extern boolean sched_addreadytorun(FAR _TCB *rtrtcb);
+extern boolean sched_removereadytorun(FAR _TCB *rtrtcb);
+extern boolean sched_addprioritized(FAR _TCB *newTcb,
+ NEAR dq_queue_t *list);
extern boolean sched_mergepending(void);
-extern void sched_addblocked(_TCB *btcb, tstate_t task_state);
-extern void sched_removeblocked(_TCB *btcb);
-extern _TCB *sched_gettcb(pid_t pid);
+extern void sched_addblocked(FAR _TCB *btcb, tstate_t task_state);
+extern void sched_removeblocked(FAR _TCB *btcb);
+extern FAR _TCB *sched_gettcb(pid_t pid);
#if CONFIG_NFILE_DESCRIPTORS > 0
-extern int sched_setupidlefiles(_TCB *tcb);
-extern int sched_setuptaskfiles(_TCB *tcb);
-extern int sched_setuppthreadfiles(_TCB *tcb);
+extern int sched_setupidlefiles(FAR _TCB *tcb);
+extern int sched_setuptaskfiles(FAR _TCB *tcb);
+extern int sched_setuppthreadfiles(FAR _TCB *tcb);
#if CONFIG_NFILE_STREAMS > 0
-extern int sched_setupstreams(_TCB *tcb);
-extern int sched_flushfiles(_TCB *tcb);
+extern int sched_setupstreams(FAR _TCB *tcb);
+extern int sched_flushfiles(FAR _TCB *tcb);
#endif
-extern int sched_releasefiles(_TCB *tcb);
+extern int sched_releasefiles(FAR _TCB *tcb);
#endif
-extern int sched_releasetcb(_TCB *tcb);
+extern int sched_releasetcb(FAR _TCB *tcb);
#endif /* __OS_INTERNAL_H */
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 09de22ce3..249134a98 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -42,6 +42,7 @@
#include <string.h>
#include <nuttx/arch.h>
+#include <nuttx/compiler.h>
#include <nuttx/fs.h>
#include <nuttx/lib.h>
#include <nuttx/os_external.h>
@@ -170,7 +171,7 @@ const tasklist_t g_tasklisttable[NUM_TASK_STATES] =
* for bringing up the rest of the system
*/
-static _TCB g_idletcb;
+static FAR _TCB g_idletcb;
/************************************************************
* Private Function Prototypes
@@ -239,7 +240,7 @@ void os_start(void)
/* Then add the idle task's TCB to the head of the ready to run list */
- dq_addfirst((dq_entry_t*)&g_idletcb, &g_readytorun);
+ dq_addfirst((FAR dq_entry_t*)&g_idletcb, &g_readytorun);
/* Initialize the processor-specific portion of the TCB */
@@ -249,7 +250,7 @@ void os_start(void)
#ifndef CONFIG_HEAP_BASE
{
- void *heap_start;
+ FAR void *heap_start;
size_t heap_size;
up_allocate_heap(&heap_start, &heap_size);
mm_initialize(heap_start, heap_size);
diff --git a/nuttx/sched/pthread_completejoin.c b/nuttx/sched/pthread_completejoin.c
index 8e57ada8b..571bb6862 100644
--- a/nuttx/sched/pthread_completejoin.c
+++ b/nuttx/sched/pthread_completejoin.c
@@ -74,7 +74,7 @@
*
************************************************************/
-static void pthread_destroyjoininfo(join_t *pjoin)
+static void pthread_destroyjoininfo(FAR join_t *pjoin)
{
int ntasks_waiting;
int status;
@@ -145,9 +145,9 @@ static void pthread_destroyjoininfo(join_t *pjoin)
*
************************************************************/
-int pthread_completejoin(pid_t pid, void *exit_value)
+int pthread_completejoin(pid_t pid, FAR void *exit_value)
{
- join_t *pjoin;
+ FAR join_t *pjoin;
boolean detached = FALSE;
dbg("process_id=%d exit_value=%p\n", pid, exit_value);
@@ -186,7 +186,7 @@ int pthread_completejoin(pid_t pid, void *exit_value)
/* Deallocate the join entry if it was detached. */
- sched_free((void*)pjoin);
+ sched_free((FAR void*)pjoin);
}
/* No, then we can assume that some other thread is waiting for the join info */
diff --git a/nuttx/sched/pthread_condtimedwait.c b/nuttx/sched/pthread_condtimedwait.c
index 9ebaf6917..43cd1501c 100644
--- a/nuttx/sched/pthread_condtimedwait.c
+++ b/nuttx/sched/pthread_condtimedwait.c
@@ -37,6 +37,7 @@
* Included Files
************************************************************/
+#include <nuttx/compiler.h>
#include <sys/types.h>
#include <unistd.h>
#include <pthread.h>
@@ -71,6 +72,25 @@
* Private Functions
************************************************************/
+/************************************************************
+ * Function: pthread_condtimedout
+ *
+ * Description:
+ * This function is called if the timeout elapses before
+ * the condition is signaled.
+ *
+ * Parameters:
+ * argc - the number of arguments (should be 2)
+ * pid - the task ID of the task to wateup
+ * signo - The signal to use to wake up the task
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ************************************************************/
+
static void pthread_condtimedout(int argc, uint32 pid, uint32 signo, ...)
{
#ifdef CONFIG_CAN_PASS_STRUCTS
@@ -86,6 +106,70 @@ static void pthread_condtimedout(int argc, uint32 pid, uint32 signo, ...)
}
/************************************************************
+ * Function: pthread_timeoutticks
+ *
+ * Description:
+ * Convert a timespec delay to system timer ticks.
+ *
+ * Parameters:
+ * abstime - wait until this absolute time
+ *
+ * Return Value:
+ * The relative number of ticks to wait (or ERROR on
+ * failure;
+ *
+ * Assumptions:
+ * Interrupts should be disabled so that the time is
+ * not changing during the calculation
+ *
+ ************************************************************/
+
+int pthread_timeouticks(const struct timespec *abstime, int *ticks)
+{
+ struct timespec currtime;
+ struct timespec reltime;
+ sint32 relusec;
+ int ret;
+
+ /* Convert the timespec to clock ticks. NOTE: Here we use
+ * internal knowledge that CLOCK_REALTIME is defined to be zero!
+ */
+
+ ret = clock_gettime(0, &currtime);
+ if (ret)
+ {
+ return EINVAL;
+ }
+
+ /* The relative time to wait is the absolute time minus the
+ * current time.
+ */
+
+ reltime.tv_nsec = (abstime->tv_nsec - currtime.tv_nsec);
+ reltime.tv_sec = (abstime->tv_sec - currtime.tv_sec);
+
+ /* Check if we were supposed to borrow from the seconds to
+ * borrow from the seconds
+ */
+
+ if (reltime.tv_nsec < 0)
+ {
+ reltime.tv_nsec += NSEC_PER_SEC;
+ reltime.tv_sec -= 1;
+ }
+
+ /* Convert this relative time into microseconds.*/
+
+ relusec = reltime.tv_sec * USEC_PER_SEC +
+ reltime.tv_nsec / NSEC_PER_USEC;
+
+ /* Convert microseconds to clock ticks */
+
+ *ticks = relusec / USEC_PER_TICK;
+ return OK;
+}
+
+/************************************************************
* Public Functions
************************************************************/
@@ -96,10 +180,13 @@ static void pthread_condtimedout(int argc, uint32 pid, uint32 signo, ...)
* A thread can perform a timed wait on a condition variable.
*
* Parameters:
- * None
+ * cond - the condition variable to wait on
+ * mutex - the mutex that protects the condition variable
+ * abstime - wait until this absolute time
*
* Return Value:
- * None
+ * OK (0) on success; ERROR (-1) on failure with errno
+ * set appropriately.
*
* Assumptions:
* Timing is of resolution 1 msec, with +/-1 millisecond
@@ -110,10 +197,7 @@ static void pthread_condtimedout(int argc, uint32 pid, uint32 signo, ...)
int pthread_cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *mutex,
const struct timespec *abstime)
{
- struct timespec currtime;
- struct timespec reltime;
WDOG_ID wdog;
- sint32 relusec;
sint32 ticks;
int mypid = (int)getpid();
irqstate_t int_state;
@@ -169,11 +253,9 @@ int pthread_cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *mutex,
/* Convert the timespec to clock ticks. We must disable pre-emption
* here so that this time stays valid until the wait begins.
- * NOTE: Here we use internal knowledge that CLOCK_REALTIME is
- * defined to be zero!
*/
- ret = clock_gettime(0, &currtime);
+ ret = pthread_timeouticks(abstime, &ticks);
if (ret)
{
/* Restore interrupts (pre-emption will be enabled when
@@ -184,33 +266,6 @@ int pthread_cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *mutex,
}
else
{
- /* The relative time to wait is the absolute time minus the
- * the current time.
- */
-
- reltime.tv_nsec = (abstime->tv_nsec - currtime.tv_nsec);
- reltime.tv_sec = (abstime->tv_sec - currtime.tv_sec);
-
- /* Check if we were supposed to borrow from the seconds
- * to borrow from the seconds
- */
-
- if (reltime.tv_nsec < 0)
- {
- reltime.tv_nsec += NSEC_PER_SEC;
- reltime.tv_sec -= 1;
- }
-
- /* Convert this relative time into microseconds.*/
-
- relusec =
- reltime.tv_sec * USEC_PER_SEC +
- reltime.tv_nsec / NSEC_PER_USEC;
-
- /* Convert microseconds to clock ticks */
-
- ticks = relusec / USEC_PER_TICK;
-
/* Check the absolute time to wait. If it is now or in the past, then
* just return with the timedout condition.
*/
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index a369f0b49..ebf212516 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -63,7 +63,7 @@
/* Default pthread attributes */
-pthread_attr_t g_default_pthread_attr =
+FAR pthread_attr_t g_default_pthread_attr =
{
PTHREAD_STACK_DEFAULT, /* stacksize */
PTHREAD_DEFAULT_PRIORITY, /* priority */
@@ -96,7 +96,7 @@ pthread_attr_t g_default_pthread_attr =
*
************************************************************/
-static void pthread_addjoininfo(join_t *pjoin)
+static void pthread_addjoininfo(FAR join_t *pjoin)
{
pjoin->next = NULL;
if (!g_pthread_tail)
@@ -124,8 +124,8 @@ static void pthread_addjoininfo(join_t *pjoin)
static void pthread_start(void)
{
- _TCB *ptcb = (_TCB*)g_readytorun.head;
- join_t *pjoin = (join_t*)ptcb->joininfo;
+ FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head;
+ FAR join_t *pjoin = (FAR join_t*)ptcb->joininfo;
pthread_addr_t exit_status;
/* Sucessfully spawned, add the pjoin to our data set.
@@ -175,8 +175,8 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
pthread_startroutine_t startRoutine,
pthread_addr_t arg)
{
- _TCB *ptcb;
- join_t *pjoin;
+ FAR _TCB *ptcb;
+ FAR join_t *pjoin;
STATUS status;
int priority;
#if CONFIG_RR_INTERVAL > 0
@@ -193,7 +193,7 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
/* Allocate a TCB for the new task. */
- ptcb = (_TCB*)kzmalloc(sizeof(_TCB));
+ ptcb = (FAR _TCB*)kzmalloc(sizeof(_TCB));
if (!ptcb)
{
*get_errno_ptr() = ENOMEM;
@@ -210,7 +210,7 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
/* Allocate a detachable structure to support pthread_join logic */
- pjoin = (join_t*)kzmalloc(sizeof(join_t));
+ pjoin = (FAR join_t*)kzmalloc(sizeof(join_t));
if (!pjoin)
{
sched_releasetcb(ptcb);
@@ -242,6 +242,10 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
{
priority = param.sched_priority;
}
+ else
+ {
+ priority = SCHED_FIFO;
+ }
/* Get the scheduler policy for this thread */
@@ -266,7 +270,7 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
/* Initialize the task */
status = _task_init(ptcb, NULL, priority, pthread_start, (main_t)startRoutine,
- TRUE, (char*)arg, NULL, NULL, NULL);
+ TRUE, (FAR char*)arg, NULL, NULL, NULL);
if (status != OK)
{
@@ -331,7 +335,7 @@ int pthread_create(pthread_t *thread, pthread_attr_t *attr,
else
{
sched_unlock();
- dq_rem((dq_entry_t*)ptcb, &g_inactivetasks);
+ dq_rem((FAR dq_entry_t*)ptcb, &g_inactivetasks);
(void)sem_destroy(&pjoin->data_sem);
(void)sem_destroy(&pjoin->exit_sem);
sched_releasetcb(ptcb);
diff --git a/nuttx/sched/pthread_detach.c b/nuttx/sched/pthread_detach.c
index 4306b28e4..ca3f732f4 100644
--- a/nuttx/sched/pthread_detach.c
+++ b/nuttx/sched/pthread_detach.c
@@ -87,7 +87,7 @@
int pthread_detach(pthread_t thread)
{
- join_t *pjoin;
+ FAR join_t *pjoin;
int ret;
dbg("Thread=%d\n", thread);
diff --git a/nuttx/sched/pthread_exit.c b/nuttx/sched/pthread_exit.c
index e6ed040d4..cd0833ba6 100644
--- a/nuttx/sched/pthread_exit.c
+++ b/nuttx/sched/pthread_exit.c
@@ -86,7 +86,7 @@
*
************************************************************/
-void pthread_exit(void *exit_value)
+void pthread_exit(FAR void *exit_value)
{
int error_code = (int)exit_value;
int status;
@@ -117,3 +117,4 @@ void pthread_exit(void *exit_value)
_exit(error_code);
}
+
diff --git a/nuttx/sched/pthread_findjoininfo.c b/nuttx/sched/pthread_findjoininfo.c
index 1d33c50e0..893e06551 100644
--- a/nuttx/sched/pthread_findjoininfo.c
+++ b/nuttx/sched/pthread_findjoininfo.c
@@ -81,9 +81,9 @@
*
************************************************************/
-join_t *pthread_findjoininfo(pid_t pid)
+FAR join_t *pthread_findjoininfo(pid_t pid)
{
- join_t *pjoin;
+ FAR join_t *pjoin;
/* Find the entry with the matching pid */
diff --git a/nuttx/sched/pthread_getspecific.c b/nuttx/sched/pthread_getspecific.c
index afcfba55c..c3eec886f 100644
--- a/nuttx/sched/pthread_getspecific.c
+++ b/nuttx/sched/pthread_getspecific.c
@@ -103,11 +103,11 @@
*
************************************************************/
-void *pthread_getspecific(pthread_key_t key)
+FAR void *pthread_getspecific(pthread_key_t key)
{
#if CONFIG_NPTHREAD_KEYS > 0
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- void *ret = NULL;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR void *ret = NULL;
/* Check if the key is valid. */
@@ -123,3 +123,4 @@ void *pthread_getspecific(pthread_key_t key)
return NULL;
#endif
}
+
diff --git a/nuttx/sched/pthread_initialize.c b/nuttx/sched/pthread_initialize.c
index e1b24f432..599d63ebf 100644
--- a/nuttx/sched/pthread_initialize.c
+++ b/nuttx/sched/pthread_initialize.c
@@ -58,8 +58,8 @@
* is used to retain information about the spawned threads.
*/
-join_t *g_pthread_head = NULL;
-join_t *g_pthread_tail = NULL;
+FAR join_t *g_pthread_head = NULL;
+FAR join_t *g_pthread_tail = NULL;
/* Mutually exclusive access to this data set is enforced with
* the following (un-named) semaphore.
@@ -191,3 +191,4 @@ int pthread_givesemaphore(sem_t *sem)
return ERROR;
}
}
+
diff --git a/nuttx/sched/pthread_internal.h b/nuttx/sched/pthread_internal.h
index f23bafe5c..34a2f518d 100644
--- a/nuttx/sched/pthread_internal.h
+++ b/nuttx/sched/pthread_internal.h
@@ -63,7 +63,7 @@
struct join_s
{
- struct join_s *next; /* Implements link list */
+ FAR struct join_s *next; /* Implements link list */
boolean started; /* TRUE: pthread started. */
boolean detached; /* TRUE: pthread_detached'ed */
boolean terminated; /* TRUE: detach'ed+exit'ed */
@@ -83,8 +83,8 @@ typedef struct join_s join_t;
* is used to retain information about the spawned threads.
*/
-extern join_t *g_pthread_head;
-extern join_t *g_pthread_tail;
+extern FAR join_t *g_pthread_head;
+extern FAR join_t *g_pthread_tail;
/* Mutually exclusive access to this data set is enforced with
* the following (un-named) semaphore.
@@ -100,7 +100,7 @@ extern ubyte g_pthread_num_keys;
/* Default pthread attributes */
-extern pthread_attr_t g_default_pthread_attr;
+extern FAR pthread_attr_t g_default_pthread_attr;
/************************************************************
* Public Function Prototypes
@@ -114,10 +114,10 @@ extern "C" {
#endif
EXTERN void weak_function pthread_initialize(void);
-EXTERN int pthread_completejoin(pid_t pid, void *exit_value);
-EXTERN join_t *pthread_findjoininfo(pid_t pid);
+EXTERN int pthread_completejoin(pid_t pid, FAR void *exit_value);
+EXTERN FAR join_t *pthread_findjoininfo(pid_t pid);
EXTERN int pthread_givesemaphore(sem_t *sem);
-EXTERN join_t *pthread_removejoininfo(pid_t pid);
+EXTERN FAR join_t *pthread_removejoininfo(pid_t pid);
EXTERN int pthread_takesemaphore(sem_t *sem);
#undef EXTERN
diff --git a/nuttx/sched/pthread_join.c b/nuttx/sched/pthread_join.c
index 28c8bf1c9..2754a35fe 100644
--- a/nuttx/sched/pthread_join.c
+++ b/nuttx/sched/pthread_join.c
@@ -95,7 +95,7 @@
int pthread_join(pthread_t thread, pthread_addr_t *pexit_value)
{
- join_t *pjoin;
+ FAR join_t *pjoin;
int ret;
dbg("thread=%d\n", thread);
@@ -129,7 +129,7 @@ int pthread_join(pthread_t thread, pthread_addr_t *pexit_value)
{
/* Determine what kind of error to return */
- _TCB *tcb = sched_gettcb((pthread_t)thread);
+ FAR _TCB *tcb = sched_gettcb((pthread_t)thread);
dbg("Could not find thread data\n");
@@ -211,3 +211,4 @@ int pthread_join(pthread_t thread, pthread_addr_t *pexit_value)
dbg("Returning %d\n", ret);
return ret;
}
+
diff --git a/nuttx/sched/pthread_removejoininfo.c b/nuttx/sched/pthread_removejoininfo.c
index 33fb24391..e989d9ab8 100644
--- a/nuttx/sched/pthread_removejoininfo.c
+++ b/nuttx/sched/pthread_removejoininfo.c
@@ -81,10 +81,10 @@
*
************************************************************/
-join_t *pthread_removejoininfo(pid_t pid)
+FAR join_t *pthread_removejoininfo(pid_t pid)
{
- join_t *prev;
- join_t *join;
+ FAR join_t *prev;
+ FAR join_t *join;
/* Find the entry with the matching pid */
@@ -134,3 +134,4 @@ join_t *pthread_removejoininfo(pid_t pid)
return join;
}
+
diff --git a/nuttx/sched/pthread_setspecific.c b/nuttx/sched/pthread_setspecific.c
index 5e9ba7fb6..4e8414dcf 100644
--- a/nuttx/sched/pthread_setspecific.c
+++ b/nuttx/sched/pthread_setspecific.c
@@ -111,10 +111,10 @@
*
************************************************************/
-int pthread_setspecific(pthread_key_t key, void *value)
+int pthread_setspecific(pthread_key_t key, FAR void *value)
{
#if CONFIG_NPTHREAD_KEYS > 0
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
int ret = EINVAL;
/* Check if the key is valid. */
@@ -136,4 +136,3 @@ int pthread_setspecific(pthread_key_t key, void *value)
#endif
}
-
diff --git a/nuttx/sched/sched_addblocked.c b/nuttx/sched/sched_addblocked.c
index 195937832..648d3f581 100644
--- a/nuttx/sched/sched_addblocked.c
+++ b/nuttx/sched/sched_addblocked.c
@@ -86,7 +86,7 @@
*
************************************************************/
-void sched_addblocked(_TCB *btcb, tstate_t task_state)
+void sched_addblocked(FAR _TCB *btcb, tstate_t task_state)
{
/* Make sure that we received a valid blocked state */
@@ -108,10 +108,11 @@ void sched_addblocked(_TCB *btcb, tstate_t task_state)
{
/* Add the task to a non-prioritized list */
- dq_addlast((dq_entry_t*)btcb, g_tasklisttable[task_state].list);
+ dq_addlast((FAR dq_entry_t*)btcb, g_tasklisttable[task_state].list);
}
/* Make sure the TCB's state corresponds to the list */
btcb->task_state = task_state;
}
+
diff --git a/nuttx/sched/sched_addprioritized.c b/nuttx/sched/sched_addprioritized.c
index 54e792048..9b0c89e81 100644
--- a/nuttx/sched/sched_addprioritized.c
+++ b/nuttx/sched/sched_addprioritized.c
@@ -91,10 +91,10 @@
* match the state associated with the list.
************************************************************/
-boolean sched_addprioritized(_TCB *tcb, dq_queue_t *list)
+boolean sched_addprioritized(FAR _TCB *tcb, NEAR dq_queue_t *list)
{
- _TCB *next;
- _TCB *prev;
+ FAR _TCB *next;
+ FAR _TCB *prev;
ubyte sched_priority = tcb->sched_priority;
boolean ret = FALSE;
@@ -106,7 +106,7 @@ boolean sched_addprioritized(_TCB *tcb, dq_queue_t *list)
* Each is list is maintained in ascending sched_priority order.
*/
- for (next = (_TCB*)list->head;
+ for (next = (FAR _TCB*)list->head;
(next && sched_priority <= next->sched_priority);
next = next->flink);
@@ -119,15 +119,15 @@ boolean sched_addprioritized(_TCB *tcb, dq_queue_t *list)
{
/* The tcb goes at the end of the list. */
- prev = (_TCB*)list->tail;
+ prev = (FAR _TCB*)list->tail;
if (!prev)
{
/* Special case: The list is empty */
tcb->flink = NULL;
tcb->blink = NULL;
- list->head = (dq_entry_t*)tcb;
- list->tail = (dq_entry_t*)tcb;
+ list->head = (FAR dq_entry_t*)tcb;
+ list->tail = (FAR dq_entry_t*)tcb;
ret = TRUE;
}
else
@@ -137,22 +137,22 @@ boolean sched_addprioritized(_TCB *tcb, dq_queue_t *list)
tcb->flink = NULL;
tcb->blink = prev;
prev->flink = tcb;
- list->tail = (dq_entry_t*)tcb;
+ list->tail = (FAR dq_entry_t*)tcb;
}
}
else
{
/* The tcb goes just before next */
- prev = (_TCB*)next->blink;
+ prev = (FAR _TCB*)next->blink;
if (!prev)
{
/* Special case: Insert at the head of the list */
- tcb->flink = next;
- tcb->blink = NULL;
+ tcb->flink = next;
+ tcb->blink = NULL;
next->blink = tcb;
- list->head = (dq_entry_t*)tcb;
+ list->head = (FAR dq_entry_t*)tcb;
ret = TRUE;
}
else
@@ -168,3 +168,4 @@ boolean sched_addprioritized(_TCB *tcb, dq_queue_t *list)
return ret;
}
+
diff --git a/nuttx/sched/sched_addreadytorun.c b/nuttx/sched/sched_addreadytorun.c
index c52da3670..3192fc7f9 100644
--- a/nuttx/sched/sched_addreadytorun.c
+++ b/nuttx/sched/sched_addreadytorun.c
@@ -94,9 +94,9 @@
* the head of the g_readytorun list is changed.
************************************************************/
-boolean sched_addreadytorun(_TCB *btcb)
+boolean sched_addreadytorun(FAR _TCB *btcb)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
boolean ret;
/* Check if pre-emption is disabled for the current running task and
diff --git a/nuttx/sched/sched_free.c b/nuttx/sched/sched_free.c
index dc1d34789..96292426e 100644
--- a/nuttx/sched/sched_free.c
+++ b/nuttx/sched/sched_free.c
@@ -80,7 +80,7 @@
*
************************************************************/
-void sched_free(void *address)
+void sched_free(FAR void *address)
{
/* Check if this is an attempt to deallocate memory from
* an exception handler.
@@ -91,7 +91,7 @@ void sched_free(void *address)
/* Yes.. Delay the deallocation until a more appropriate time. */
irqstate_t saved_state = irqsave();
- sq_addlast((sq_entry_t*)address, &g_delayeddeallocations);
+ sq_addlast((FAR sq_entry_t*)address, &g_delayeddeallocations);
irqrestore(saved_state);
}
else
@@ -101,3 +101,4 @@ void sched_free(void *address)
kfree(address);
}
}
+
diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c
index d6986a5bc..7478e7cf0 100644
--- a/nuttx/sched/sched_getfiles.c
+++ b/nuttx/sched/sched_getfiles.c
@@ -68,9 +68,9 @@
*
************************************************************/
-struct filelist *sched_getfiles(void)
+FAR struct filelist *sched_getfiles(void)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
return rtcb->filelist;
}
diff --git a/nuttx/sched/sched_getparam.c b/nuttx/sched/sched_getparam.c
index 85d8c55c7..e78c07fc5 100644
--- a/nuttx/sched/sched_getparam.c
+++ b/nuttx/sched/sched_getparam.c
@@ -96,8 +96,8 @@
int sched_getparam (pid_t pid, struct sched_param * param)
{
- _TCB *rtcb;
- _TCB *tcb;
+ FAR _TCB *rtcb;
+ FAR _TCB *tcb;
int ret = OK;
if (!param)
@@ -107,7 +107,7 @@ int sched_getparam (pid_t pid, struct sched_param * param)
/* Check if the task to restart is the calling task */
- rtcb = (_TCB*)g_readytorun.head;
+ rtcb = (FAR _TCB*)g_readytorun.head;
if ((pid == 0) || (pid == rtcb->pid))
{
/* Return the priority if the calling task. */
@@ -140,3 +140,4 @@ int sched_getparam (pid_t pid, struct sched_param * param)
return ret;
}
+
diff --git a/nuttx/sched/sched_getstreams.c b/nuttx/sched/sched_getstreams.c
index fef913bc4..ba7f3a23d 100644
--- a/nuttx/sched/sched_getstreams.c
+++ b/nuttx/sched/sched_getstreams.c
@@ -68,9 +68,9 @@
*
************************************************************/
-struct streamlist *sched_getstreams(void)
+FAR struct streamlist *sched_getstreams(void)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
return rtcb->streams;
}
diff --git a/nuttx/sched/sched_gettcb.c b/nuttx/sched/sched_gettcb.c
index 7073b796a..7f65f9342 100644
--- a/nuttx/sched/sched_gettcb.c
+++ b/nuttx/sched/sched_gettcb.c
@@ -75,9 +75,9 @@
*
************************************************************/
-_TCB *sched_gettcb(pid_t pid)
+FAR _TCB *sched_gettcb(pid_t pid)
{
- _TCB *ret = NULL;
+ FAR _TCB *ret = NULL;
int hash_ndx;
/* Verify that the PID is within range */
@@ -102,3 +102,4 @@ _TCB *sched_gettcb(pid_t pid)
return ret;
}
+
diff --git a/nuttx/sched/sched_mergepending.c b/nuttx/sched/sched_mergepending.c
index db03bccc3..ab61db6ef 100644
--- a/nuttx/sched/sched_mergepending.c
+++ b/nuttx/sched/sched_mergepending.c
@@ -90,19 +90,19 @@
boolean sched_mergepending(void)
{
- _TCB *pndtcb;
- _TCB *pndnext;
- _TCB *rtrtcb;
- _TCB *rtrprev;
+ FAR _TCB *pndtcb;
+ FAR _TCB *pndnext;
+ FAR _TCB *rtrtcb;
+ FAR _TCB *rtrprev;
boolean ret = FALSE;
/* Initialize the inner search loop */
- rtrtcb = (_TCB*)g_readytorun.head;
+ rtrtcb = (FAR _TCB*)g_readytorun.head;
/* Process every TCB in the g_pendingtasks list */
- for (pndtcb = (_TCB*)g_pendingtasks.head; pndtcb; pndtcb = pndnext)
+ for (pndtcb = (FAR _TCB*)g_pendingtasks.head; pndtcb; pndtcb = pndnext)
{
pndnext = pndtcb->flink;
@@ -137,7 +137,7 @@ boolean sched_mergepending(void)
pndtcb->flink = rtrtcb;
pndtcb->blink = NULL;
rtrtcb->blink = pndtcb;
- g_readytorun.head = (dq_entry_t*)pndtcb;
+ g_readytorun.head = (FAR dq_entry_t*)pndtcb;
rtrtcb->task_state = TSTATE_TASK_READYTORUN;
pndtcb->task_state = TSTATE_TASK_RUNNING;
ret = TRUE;
diff --git a/nuttx/sched/sched_processtimer.c b/nuttx/sched/sched_processtimer.c
index bb56dbacb..eff439a5b 100644
--- a/nuttx/sched/sched_processtimer.c
+++ b/nuttx/sched/sched_processtimer.c
@@ -42,6 +42,7 @@
************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <sys/types.h>
#if CONFIG_RR_INTERVAL > 0
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index ffbfc6c58..5e644839d 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -90,7 +90,7 @@ static void sched_releasepid(pid_t pid)
*
************************************************************/
-int sched_releasetcb(_TCB *tcb)
+int sched_releasetcb(FAR _TCB *tcb)
{
int ret = OK;
int i;
@@ -138,5 +138,3 @@ int sched_releasetcb(_TCB *tcb)
return ret;
}
-
-
diff --git a/nuttx/sched/sched_removeblocked.c b/nuttx/sched/sched_removeblocked.c
index f3ed363ae..2b9294003 100644
--- a/nuttx/sched/sched_removeblocked.c
+++ b/nuttx/sched/sched_removeblocked.c
@@ -90,7 +90,7 @@
*
************************************************************/
-void sched_removeblocked(_TCB *btcb)
+void sched_removeblocked(FAR _TCB *btcb)
{
tstate_t task_state = btcb->task_state;
@@ -103,7 +103,7 @@ void sched_removeblocked(_TCB *btcb)
* with this state
*/
- dq_rem((dq_entry_t*)btcb, g_tasklisttable[task_state].list);
+ dq_rem((FAR dq_entry_t*)btcb, g_tasklisttable[task_state].list);
/* Make sure the TCB's state corresponds to not being in
* any list
@@ -111,3 +111,4 @@ void sched_removeblocked(_TCB *btcb)
btcb->task_state = TSTATE_TASK_INVALID;
}
+
diff --git a/nuttx/sched/sched_removereadytorun.c b/nuttx/sched/sched_removereadytorun.c
index 24057f3b7..1c17feba0 100644
--- a/nuttx/sched/sched_removereadytorun.c
+++ b/nuttx/sched/sched_removereadytorun.c
@@ -87,7 +87,7 @@
* the head of the g_readytorun list is changed.
************************************************************/
-boolean sched_removereadytorun(_TCB *rtcb)
+boolean sched_removereadytorun(FAR _TCB *rtcb)
{
boolean ret = FALSE;
@@ -110,7 +110,7 @@ boolean sched_removereadytorun(_TCB *rtcb)
/* Remove the TCB from the ready-to-run list */
- dq_rem((dq_entry_t*)rtcb, &g_readytorun);
+ dq_rem((FAR dq_entry_t*)rtcb, &g_readytorun);
rtcb->task_state = TSTATE_TASK_INVALID;
return ret;
diff --git a/nuttx/sched/sched_rrgetinterval.c b/nuttx/sched/sched_rrgetinterval.c
index 8dfe99ff3..dff4ebb4c 100644
--- a/nuttx/sched/sched_rrgetinterval.c
+++ b/nuttx/sched/sched_rrgetinterval.c
@@ -106,7 +106,7 @@
int sched_rr_get_interval(pid_t pid, struct timespec *interval)
{
#if CONFIG_RR_INTERVAL > 0
- _TCB *rrtcb;
+ FAR _TCB *rrtcb;
/* If pid is zero, the timeslice for the calling process is
* written into 'interval.'
@@ -114,7 +114,7 @@ int sched_rr_get_interval(pid_t pid, struct timespec *interval)
if (!pid)
{
- rrtcb = (_TCB*)g_readytorun.head;
+ rrtcb = (FAR _TCB*)g_readytorun.head;
}
/* Return a special error code on invalid PID */
diff --git a/nuttx/sched/sched_setparam.c b/nuttx/sched/sched_setparam.c
index a1e5af97f..c9a935a4d 100644
--- a/nuttx/sched/sched_setparam.c
+++ b/nuttx/sched/sched_setparam.c
@@ -105,8 +105,8 @@
int sched_setparam(pid_t pid, const struct sched_param *param)
{
- _TCB *rtcb;
- _TCB *tcb;
+ FAR _TCB *rtcb;
+ FAR _TCB *tcb;
tstate_t task_state;
irqstate_t saved_state;
int sched_priority = param->sched_priority;
@@ -129,7 +129,7 @@ int sched_setparam(pid_t pid, const struct sched_param *param)
/* Check if the task to reprioritize is the calling task */
- rtcb = (_TCB*)g_readytorun.head;
+ rtcb = (FAR _TCB*)g_readytorun.head;
if (pid == 0 || pid == rtcb->pid)
{
tcb = rtcb;
@@ -236,7 +236,7 @@ int sched_setparam(pid_t pid, const struct sched_param *param)
{
/* Remove the TCB from the prioritized task list */
- dq_rem((dq_entry_t*)tcb, g_tasklisttable[task_state].list);
+ dq_rem((FAR dq_entry_t*)tcb, g_tasklisttable[task_state].list);
/* Change the task priority */
diff --git a/nuttx/sched/sched_setscheduler.c b/nuttx/sched/sched_setscheduler.c
index 7d1b11ba4..4d4978a62 100644
--- a/nuttx/sched/sched_setscheduler.c
+++ b/nuttx/sched/sched_setscheduler.c
@@ -110,7 +110,7 @@
int sched_setscheduler(pid_t pid, int policy,
const struct sched_param *param)
{
- _TCB *tcb;
+ FAR _TCB *tcb;
#if CONFIG_RR_INTERVAL > 0
irqstate_t saved_state;
#endif
@@ -186,3 +186,4 @@ int sched_setscheduler(pid_t pid, int policy,
return SCHED_FIFO;
}
}
+
diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c
index c8be5478c..29d5dd3e0 100644
--- a/nuttx/sched/sched_setupidlefiles.c
+++ b/nuttx/sched/sched_setupidlefiles.c
@@ -71,7 +71,7 @@
*
************************************************************/
-int sched_setupidlefiles(_TCB *tcb)
+int sched_setupidlefiles(FAR _TCB *tcb)
{
int fd;
diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c
index 0935b487d..5cc20c6d1 100644
--- a/nuttx/sched/sched_setuppthreadfiles.c
+++ b/nuttx/sched/sched_setuppthreadfiles.c
@@ -71,9 +71,9 @@
*
************************************************************/
-int sched_setuppthreadfiles(_TCB *tcb)
+int sched_setuppthreadfiles(FAR _TCB *tcb)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
/* The child thread inherits the parent file descriptors */
diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c
index 325ba92e9..97509fc68 100644
--- a/nuttx/sched/sched_setupstreams.c
+++ b/nuttx/sched/sched_setupstreams.c
@@ -53,7 +53,7 @@
* Public Functions
************************************************************/
-int sched_setupstreams(_TCB *tcb)
+int sched_setupstreams(FAR _TCB *tcb)
{
/* Allocate file strems for the TCB */
diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c
index 269e98e51..175398031 100644
--- a/nuttx/sched/sched_setuptaskfiles.c
+++ b/nuttx/sched/sched_setuptaskfiles.c
@@ -71,10 +71,10 @@
*
************************************************************/
-int sched_setuptaskfiles(_TCB *tcb)
+int sched_setuptaskfiles(FAR _TCB *tcb)
{
#ifdef CONFIG_DEV_CONSOLE
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
int i;
#endif /* CONFIG_DEV_CONSOLE */
diff --git a/nuttx/sched/sched_yield.c b/nuttx/sched/sched_yield.c
index e91f8ecf6..ae4db7178 100644
--- a/nuttx/sched/sched_yield.c
+++ b/nuttx/sched/sched_yield.c
@@ -90,7 +90,7 @@
int sched_yield (void)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
struct sched_param param;
/* This equivalent to just resetting the task priority to
diff --git a/nuttx/sched/sem_close.c b/nuttx/sched/sem_close.c
index 3113b5156..9c278fb58 100644
--- a/nuttx/sched/sem_close.c
+++ b/nuttx/sched/sem_close.c
@@ -101,9 +101,9 @@
*
************************************************************/
-int sem_close (sem_t *sem)
+int sem_close(FAR sem_t *sem)
{
- nsem_t *psem;
+ FAR nsem_t *psem;
int ret = ERROR;
/* Verify the inputs */
@@ -114,7 +114,7 @@ int sem_close (sem_t *sem)
/* Search the list of named semaphores */
- for (psem = (nsem_t*)g_nsems.head;
+ for (psem = (FAR nsem_t*)g_nsems.head;
((psem) && (sem != &psem->sem));
psem = psem->flink);
@@ -132,7 +132,7 @@ int sem_close (sem_t *sem)
if (!psem->nconnect && psem->unlinked)
{
- dq_rem((dq_entry_t*)psem, &g_nsems);
+ dq_rem((FAR dq_entry_t*)psem, &g_nsems);
sched_free(psem);
}
ret = OK;
@@ -142,3 +142,4 @@ int sem_close (sem_t *sem)
return ret;
}
+
diff --git a/nuttx/sched/sem_findnamed.c b/nuttx/sched/sem_findnamed.c
index d513f7a31..f626da42d 100644
--- a/nuttx/sched/sem_findnamed.c
+++ b/nuttx/sched/sem_findnamed.c
@@ -84,13 +84,13 @@
*
************************************************************/
-nsem_t *sem_findnamed(const char *name)
+FAR nsem_t *sem_findnamed(const char *name)
{
- nsem_t *psem;
+ FAR nsem_t *psem;
/* Search the list of named semaphores */
- for (psem = (nsem_t*)g_nsems.head; (psem); psem = psem->flink)
+ for (psem = (FAR nsem_t*)g_nsems.head; (psem); psem = psem->flink)
{
if (!strcmp(name, psem->name))
{
diff --git a/nuttx/sched/sem_internal.h b/nuttx/sched/sem_internal.h
index 460b358fc..9908d6e4c 100644
--- a/nuttx/sched/sem_internal.h
+++ b/nuttx/sched/sem_internal.h
@@ -58,12 +58,12 @@
struct nsem_s
{
- struct nsem_s *flink; /* Forward link */
- struct nsem_s *blink; /* Backward link */
- uint16 nconnect; /* Number of connections to semaphore */
- char *name; /* Semaphore name (NULL if un-named) */
- boolean unlinked; /* TRUE if the semaphore has been unlinked */
- sem_t sem; /* The semaphore itself */
+ FAR struct nsem_s *flink; /* Forward link */
+ FAR struct nsem_s *blink; /* Backward link */
+ uint16 nconnect; /* Number of connections to semaphore */
+ FAR char *name; /* Semaphore name (NULL if un-named) */
+ boolean unlinked; /* TRUE if the semaphore has been unlinked */
+ sem_t sem; /* The semaphore itself */
};
typedef struct nsem_s nsem_t;
@@ -87,8 +87,8 @@ extern "C" {
#endif
EXTERN void weak_function sem_initialize(void);
-EXTERN void sem_waitirq(_TCB *wtcb);
-EXTERN nsem_t *sem_findnamed(const char *name);
+EXTERN void sem_waitirq(FAR _TCB *wtcb);
+EXTERN FAR nsem_t *sem_findnamed(const char *name);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/sched/sem_open.c b/nuttx/sched/sem_open.c
index 6a8c38a4c..e9f6335c6 100644
--- a/nuttx/sched/sem_open.c
+++ b/nuttx/sched/sem_open.c
@@ -114,15 +114,11 @@
*
************************************************************/
-sem_t *sem_open (const char *name, int oflag, ...)
+FAR sem_t *sem_open (const char *name, int oflag, ...)
{
int namelen;
- nsem_t *psem;
-#ifdef CONFIG_CAN_CAST_POINTERS
- sem_t *sem = (sem_t*)ERROR;
-#else
- sem_t *sem = get_errorptr();
-#endif
+ FAR nsem_t *psem;
+ FAR sem_t *sem = (FAR sem_t*)ERROR;
va_list arg; /* Points to each un-named argument */
mode_t mode; /* Creation mode parameter (ignored) */
unsigned int value; /* Semaphore value parameter */
@@ -178,7 +174,7 @@ sem_t *sem_open (const char *name, int oflag, ...)
{
/* Allocate memory for the new semaphore */
- psem = (nsem_t*)kmalloc((sizeof(nsem_t) + namelen + 1));
+ psem = (FAR nsem_t*)kmalloc((sizeof(nsem_t) + namelen + 1));
if (psem)
{
/* Initialize the named semaphore */
@@ -188,14 +184,14 @@ sem_t *sem_open (const char *name, int oflag, ...)
psem->nconnect = 1;
psem->unlinked = FALSE;
- psem->name = (char*)psem + sizeof(nsem_t);
+ psem->name = (FAR char*)psem + sizeof(nsem_t);
strcpy(psem->name, name);
/* Add the new semaphore to the list of named
* semaphores
*/
- dq_addfirst((dq_entry_t*)psem, &g_nsems);
+ dq_addfirst((FAR dq_entry_t*)psem, &g_nsems);
}
/* Clean-up variable argument stuff */
@@ -209,3 +205,4 @@ sem_t *sem_open (const char *name, int oflag, ...)
return sem;
}
+
diff --git a/nuttx/sched/sem_post.c b/nuttx/sched/sem_post.c
index 348e88c80..3b4fac368 100644
--- a/nuttx/sched/sem_post.c
+++ b/nuttx/sched/sem_post.c
@@ -104,9 +104,9 @@
*
************************************************************/
-int sem_post (sem_t *sem)
+int sem_post(sem_t *sem)
{
- _TCB *stcb;
+ FAR _TCB *stcb;
STATUS ret = ERROR;
irqstate_t saved_state;
@@ -138,7 +138,7 @@ int sem_post (sem_t *sem)
* that we want.
*/
- for (stcb = (_TCB*)g_waitingforsemaphore.head;
+ for (stcb = (FAR _TCB*)g_waitingforsemaphore.head;
((stcb) && (stcb->waitsem != sem));
stcb = stcb->flink);
diff --git a/nuttx/sched/sem_unlink.c b/nuttx/sched/sem_unlink.c
index 467db622e..cc249ff8d 100644
--- a/nuttx/sched/sem_unlink.c
+++ b/nuttx/sched/sem_unlink.c
@@ -95,10 +95,10 @@
*
************************************************************/
-int sem_unlink (const char *name)
+int sem_unlink(const char *name)
{
- nsem_t *psem;
- int ret = ERROR;
+ FAR nsem_t *psem;
+ int ret = ERROR;
/* Verify the input values */
@@ -119,7 +119,7 @@ int sem_unlink (const char *name)
*/
if (!psem->nconnect)
{
- dq_rem((dq_entry_t*)psem, &g_nsems);
+ dq_rem((FAR dq_entry_t*)psem, &g_nsems);
sched_free(psem);
}
@@ -139,3 +139,4 @@ int sem_unlink (const char *name)
return ret;
}
+
diff --git a/nuttx/sched/sem_wait.c b/nuttx/sched/sem_wait.c
index 78aa7d5e9..7893b39ba 100644
--- a/nuttx/sched/sem_wait.c
+++ b/nuttx/sched/sem_wait.c
@@ -97,9 +97,9 @@
*
************************************************************/
-int sem_wait (sem_t *sem)
+int sem_wait(sem_t *sem)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
int ret = ERROR;
irqstate_t saved_state;
@@ -172,3 +172,4 @@ int sem_wait (sem_t *sem)
return ret;
}
+
diff --git a/nuttx/sched/sem_waitirq.c b/nuttx/sched/sem_waitirq.c
index 810663732..b7cbdce21 100644
--- a/nuttx/sched/sem_waitirq.c
+++ b/nuttx/sched/sem_waitirq.c
@@ -92,7 +92,7 @@
*
************************************************************/
-void sem_waitirq (_TCB *wtcb)
+void sem_waitirq(FAR _TCB *wtcb)
{
irqstate_t saved_state;
@@ -126,3 +126,4 @@ void sem_waitirq (_TCB *wtcb)
irqrestore(saved_state);
}
+
diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c
index 7f9a1c343..f7fe7cdb5 100644
--- a/nuttx/sched/sig_action.c
+++ b/nuttx/sched/sig_action.c
@@ -77,13 +77,13 @@
*
************************************************************/
-static sigactq_t *sig_allocateaction(void)
+static FAR sigactq_t *sig_allocateaction(void)
{
- sigactq_t *sigact;
+ FAR sigactq_t *sigact;
/* Try to get the signal action structure from the free list */
- sigact = (sigactq_t*)sq_remfirst(&g_sigfreeaction);
+ sigact = (FAR sigactq_t*)sq_remfirst(&g_sigfreeaction);
/* Check if we got one. */
@@ -95,7 +95,7 @@ static sigactq_t *sig_allocateaction(void)
/* And try again */
- sigact = (sigactq_t*)sq_remfirst(&g_sigfreeaction);
+ sigact = (FAR sigactq_t*)sq_remfirst(&g_sigfreeaction);
if (!sigact)
{
PANIC(OSERR_OUTOFMEMORY);
@@ -171,9 +171,9 @@ static sigactq_t *sig_allocateaction(void)
int sigaction(int signo, const struct sigaction *act,
struct sigaction *oact)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- sigactq_t *sigact;
- int ret = ERROR; /* Assume failure */
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR sigactq_t *sigact;
+ int ret = ERROR; /* Assume failure */
/* Since sigactions can only be installed from the running
* thread of execution, no special precautions should be
@@ -229,7 +229,7 @@ int sigaction(int signo, const struct sigaction *act,
/* Add the new sigaction to sigactionq */
- sq_addlast((sq_entry_t*)sigact, &rtcb->sigactionq);
+ sq_addlast((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
}
}
@@ -250,7 +250,7 @@ int sigaction(int signo, const struct sigaction *act,
{
/* Remove the old sigaction from sigactionq */
- sq_rem((sq_entry_t*)sigact, &rtcb->sigactionq);
+ sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
/* And deallocate it */
@@ -270,9 +270,9 @@ int sigaction(int signo, const struct sigaction *act,
*
************************************************************/
-void sig_releaseaction(sigactq_t *sigact)
+void sig_releaseaction(FAR sigactq_t *sigact)
{
/* Just put it back on the free list */
- sq_addlast((sq_entry_t*)sigact, &g_sigfreeaction);
+ sq_addlast((FAR sq_entry_t*)sigact, &g_sigfreeaction);
}
diff --git a/nuttx/sched/sig_allocatependingsigaction.c b/nuttx/sched/sig_allocatependingsigaction.c
index 610596457..5356058cf 100644
--- a/nuttx/sched/sig_allocatependingsigaction.c
+++ b/nuttx/sched/sig_allocatependingsigaction.c
@@ -75,9 +75,9 @@
* Allocate a new element for the pending signal action queue
************************************************************/
-sigq_t *sig_allocatependingsigaction(void)
+FAR sigq_t *sig_allocatependingsigaction(void)
{
- sigq_t *sigq;
+ FAR sigq_t *sigq;
irqstate_t saved_state;
/* Check if we were called from an interrupt handler. */
@@ -86,7 +86,7 @@ sigq_t *sig_allocatependingsigaction(void)
{
/* Try to get the pending signal action structure from the free list */
- sigq = (sigq_t*)sq_remfirst(&g_sigpendingaction);
+ sigq = (FAR sigq_t*)sq_remfirst(&g_sigpendingaction);
/* If so, then try the special list of structures reserved for
* interrupt handlers
@@ -94,7 +94,7 @@ sigq_t *sig_allocatependingsigaction(void)
if (!sigq)
{
- sigq = (sigq_t*)sq_remfirst(&g_sigpendingirqaction);
+ sigq = (FAR sigq_t*)sq_remfirst(&g_sigpendingirqaction);
}
}
@@ -106,7 +106,7 @@ sigq_t *sig_allocatependingsigaction(void)
/* Try to get the pending signal action structure from the free list */
saved_state = irqsave();
- sigq = (sigq_t*)sq_remfirst(&g_sigpendingaction);
+ sigq = (FAR sigq_t*)sq_remfirst(&g_sigpendingaction);
irqrestore(saved_state);
/* Check if we got one. */
@@ -117,7 +117,7 @@ sigq_t *sig_allocatependingsigaction(void)
if (!sigq)
{
- sigq = (sigq_t *)kmalloc((sizeof (sigq_t)));
+ sigq = (FAR sigq_t *)kmalloc((sizeof (sigq_t)));
}
/* Check if we got an allocated message */
diff --git a/nuttx/sched/sig_cleanup.c b/nuttx/sched/sig_cleanup.c
index d9e1073df..019e7fbe5 100644
--- a/nuttx/sched/sig_cleanup.c
+++ b/nuttx/sched/sig_cleanup.c
@@ -76,36 +76,36 @@
* to perform this action.
************************************************************/
-void sig_cleanup(_TCB *stcb)
+void sig_cleanup(FAR _TCB *stcb)
{
- sigactq_t *sigact;
- sigq_t *sigq;
- sigpendq_t *sigpend;
+ FAR sigactq_t *sigact;
+ FAR sigq_t *sigq;
+ FAR sigpendq_t *sigpend;
/* Deallocate all entries in the list of signal actions */
- while ((sigact = (sigactq_t*)sq_remfirst(&stcb->sigactionq)) != NULL)
+ while ((sigact = (FAR sigactq_t*)sq_remfirst(&stcb->sigactionq)) != NULL)
{
sig_releaseaction(sigact);
}
/* Deallocate all entries in the list of pending signals */
- while ((sigpend = (sigpendq_t*)sq_remfirst(&stcb->sigpendingq)) != NULL)
+ while ((sigpend = (FAR sigpendq_t*)sq_remfirst(&stcb->sigpendingq)) != NULL)
{
sig_releasependingsignal(sigpend);
}
/* Deallocate all entries in the list of pending signal actions */
- while ((sigq = (sigq_t*)sq_remfirst(&stcb->sigpendactionq)) != NULL)
+ 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 = (sigq_t*)sq_remfirst(&stcb->sigpostedq)) != NULL)
+ while ((sigq = (FAR sigq_t*)sq_remfirst(&stcb->sigpostedq)) != NULL)
{
sig_releasependingsigaction(sigq);
}
diff --git a/nuttx/sched/sig_deliver.c b/nuttx/sched/sig_deliver.c
index c10633797..5eb24d307 100644
--- a/nuttx/sched/sig_deliver.c
+++ b/nuttx/sched/sig_deliver.c
@@ -81,14 +81,14 @@
*
************************************************************/
-void sig_deliver(_TCB *stcb)
+void sig_deliver(FAR _TCB *stcb)
{
- pid_t rpid;
- sigq_t *sigq;
- sigq_t *next;
- sigset_t savesigprocmask;
- irqstate_t saved_state;
- int saved_errno;
+ pid_t rpid;
+ FAR sigq_t *sigq;
+ FAR sigq_t *next;
+ sigset_t savesigprocmask;
+ irqstate_t saved_state;
+ int saved_errno;
sched_lock();
@@ -100,7 +100,7 @@ void sig_deliver(_TCB *stcb)
*/
saved_errno = stcb->errno;
- for (sigq = (sigq_t*)stcb->sigpendactionq.head; (sigq); sigq = next)
+ for (sigq = (FAR sigq_t*)stcb->sigpendactionq.head; (sigq); sigq = next)
{
next = sigq->flink;
dbg("sig_deliver: Sending signal sigq=0x%x\n", sigq);
@@ -111,8 +111,8 @@ void sig_deliver(_TCB *stcb)
*/
saved_state = irqsave();
- sq_rem((sq_entry_t*)sigq, &(stcb->sigpendactionq));
- sq_addlast((sq_entry_t*)sigq, &(stcb->sigpostedq));
+ 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)
@@ -150,7 +150,7 @@ void sig_deliver(_TCB *stcb)
/* Remove the signal from the sigpostedq */
saved_state = irqsave();
- sq_rem((sq_entry_t*)sigq, &(stcb->sigpostedq));
+ sq_rem((FAR sq_entry_t*)sigq, &(stcb->sigpostedq));
irqrestore(saved_state);
/* Then deallocate it */
diff --git a/nuttx/sched/sig_findaction.c b/nuttx/sched/sig_findaction.c
index 98df313ec..be5675d62 100644
--- a/nuttx/sched/sig_findaction.c
+++ b/nuttx/sched/sig_findaction.c
@@ -72,28 +72,28 @@
*
************************************************************/
-sigactq_t *sig_findaction(_TCB *stcb, int signo)
+FAR sigactq_t *sig_findaction(FAR _TCB *stcb, int signo)
{
- sigactq_t *sigact = NULL;
+ FAR sigactq_t *sigact = NULL;
- /* Verify the caller's sanity */
+ /* 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.
- */
+ if (stcb)
+ {
+ /* Sigactions can only be assigned to the currently executing
+ * thread. So, a simple lock ought to give us sufficient
+ * protection.
+ */
- sched_lock();
+ sched_lock();
- /* Seach the list for a sigaction on this signal */
+ /* Seach the list for a sigaction on this signal */
- for(sigact = (sigactq_t*)stcb->sigactionq.head;
- ((sigact) && (sigact->signo != signo));
- sigact = sigact->flink);
+ for(sigact = (FAR sigactq_t*)stcb->sigactionq.head;
+ ((sigact) && (sigact->signo != signo));
+ sigact = sigact->flink);
- sched_unlock();
+ sched_unlock();
}
return sigact;
diff --git a/nuttx/sched/sig_initialize.c b/nuttx/sched/sig_initialize.c
index 1c1e8c23c..d3bd10860 100644
--- a/nuttx/sched/sig_initialize.c
+++ b/nuttx/sched/sig_initialize.c
@@ -124,10 +124,10 @@ static sigpendq_t *g_sigpendingirqsignalalloc;
* Private Function Prototypes
************************************************************/
-static sigq_t *sig_allocateblock(sq_queue_t *sigList, uint16 nSigs,
- ubyte sigType);
-static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *sigList,
- uint16 nSigs, ubyte sigType);
+static sigq_t *sig_allocateblock(sq_queue_t *siglist, uint16 nsigs,
+ ubyte sigtype);
+static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *siglist,
+ uint16 nsigs, ubyte sigtype);
/************************************************************
* Private Functions
@@ -142,8 +142,8 @@ static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *sigList,
*
************************************************************/
-static sigq_t *sig_allocateblock(sq_queue_t *sigList, uint16 nSigs,
- ubyte sigType)
+static sigq_t *sig_allocateblock(sq_queue_t *siglist, uint16 nsigs,
+ ubyte sigtype)
{
sigq_t *sigqalloc;
sigq_t *sigq;
@@ -151,13 +151,13 @@ static sigq_t *sig_allocateblock(sq_queue_t *sigList, uint16 nSigs,
/* Allocate a block of pending signal actions */
- sigqalloc = (sigq_t*)kmalloc((sizeof(sigq_t)) * nSigs);
+ sigqalloc = (sigq_t*)kmalloc((sizeof(sigq_t)) * nsigs);
sigq = sigqalloc;
- for (i = 0; i < nSigs; i++)
+ for (i = 0; i < nsigs; i++)
{
- sigq->type = sigType;
- sq_addlast((sq_entry_t*)sigq++, sigList);
+ sigq->type = sigtype;
+ sq_addlast((FAR sq_entry_t*)sigq++, siglist);
}
return sigqalloc;
@@ -171,8 +171,8 @@ static sigq_t *sig_allocateblock(sq_queue_t *sigList, uint16 nSigs,
* on the free list.
************************************************************/
-static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *sigList,
- uint16 nSigs, ubyte sigType)
+static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *siglist,
+ uint16 nsigs, ubyte sigtype)
{
sigpendq_t *sigpendalloc;
sigpendq_t *sigpend;
@@ -181,13 +181,13 @@ static sigpendq_t *sig_allocatependingsignalblock(sq_queue_t *sigList,
/* Allocate a block of pending signal structures */
sigpendalloc =
- (sigpendq_t*)kmalloc((sizeof(sigpendq_t)) * nSigs);
+ (sigpendq_t*)kmalloc((sizeof(sigpendq_t)) * nsigs);
sigpend = sigpendalloc;
- for (i = 0; i < nSigs; i++)
+ for (i = 0; i < nsigs; i++)
{
- sigpend->type = sigType;
- sq_addlast((sq_entry_t*)sigpend++, sigList);
+ sigpend->type = sigtype;
+ sq_addlast((FAR sq_entry_t*)sigpend++, siglist);
}
return sigpendalloc;
@@ -255,7 +255,7 @@ void sig_allocateactionblock(void)
sigact = g_sigactionalloc;
for (i = 0; i < NUM_SIGNAL_ACTIONS; i++)
{
- sq_addlast((sq_entry_t*)sigact++, &g_sigfreeaction);
+ sq_addlast((FAR sq_entry_t*)sigact++, &g_sigfreeaction);
}
}
diff --git a/nuttx/sched/sig_internal.h b/nuttx/sched/sig_internal.h
index b03b2ec0e..8ae975e42 100644
--- a/nuttx/sched/sig_internal.h
+++ b/nuttx/sched/sig_internal.h
@@ -40,6 +40,7 @@
* Included Files
************************************************************/
+#include <nuttx/compiler.h>
#include <queue.h>
#include <sched.h>
#include <nuttx/kmalloc.h>
@@ -75,9 +76,9 @@ typedef enum sigalloc_e sigalloc_t;
struct sigactq
{
- struct sigactq *flink; /* Forward link */
- struct sigaction act; /* Sigaction data */
- ubyte signo; /* Signal associated with action */
+ FAR struct sigactq *flink; /* Forward link */
+ struct sigaction act; /* Sigaction data */
+ ubyte signo; /* Signal associated with action */
};
typedef struct sigactq sigactq_t;
@@ -89,9 +90,9 @@ typedef struct sigactq sigactq_t;
struct sigpendq
{
- struct sigpendq *flink; /* Forward link */
- siginfo_t info; /* Signal information */
- ubyte type; /* (Used to manage allocations) */
+ FAR struct sigpendq *flink; /* Forward link */
+ siginfo_t info; /* Signal information */
+ ubyte type; /* (Used to manage allocations) */
};
typedef struct sigpendq sigpendq_t;
@@ -101,15 +102,15 @@ typedef struct sigpendq sigpendq_t;
struct sigq_s
{
- struct sigq_s *flink; /* Forward link */
+ 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
+ sigset_t mask; /* Additional signals to mask while the
* the signal-catching functin executes */
- siginfo_t info; /* Signal information */
- ubyte type; /* (Used to manage allocations) */
+ siginfo_t info; /* Signal information */
+ ubyte type; /* (Used to manage allocations) */
};
typedef struct sigq_s sigq_t;
@@ -162,18 +163,18 @@ extern void sig_allocateactionblock(void);
/* sig_action.c */
-extern void sig_releaseaction(sigactq_t *sigact);
+extern void sig_releaseaction(FAR sigactq_t *sigact);
/* sig_pending.c */
-extern sigset_t sig_pendingset(_TCB *stcb);
+extern sigset_t sig_pendingset(FAR _TCB *stcb);
/* In files of the same name */
-extern sigq_t *sig_allocatependingsigaction(void);
-extern void sig_cleanup(_TCB *stcb);
-extern void sig_deliver(_TCB *stcb);
-extern sigactq_t *sig_findaction(_TCB *stcb, int signo);
+extern FAR sigq_t *sig_allocatependingsigaction(void);
+extern void sig_cleanup(FAR _TCB *stcb);
+extern void sig_deliver(FAR _TCB *stcb);
+extern FAR sigactq_t *sig_findaction(FAR _TCB *stcb, int signo);
extern int sig_lowest(sigset_t *set);
#ifdef CONFIG_CAN_PASS_STRUCTS
extern int sig_mqnotempty(int tid, int signo,
@@ -182,10 +183,10 @@ extern int sig_mqnotempty(int tid, int signo,
extern int sig_mqnotempty(int tid, int signo,
void *sival_ptr);
#endif
-extern int sig_received(_TCB *stcb, siginfo_t *info);
-extern void sig_releasependingsigaction(sigq_t *sigq);
-extern void sig_releasependingsignal(sigpendq_t *sigpend);
-extern sigpendq_t *sig_removependingsignal(_TCB *stcb, int signo);
+extern int sig_received(FAR _TCB *stcb, siginfo_t *info);
+extern void sig_releasependingsigaction(FAR sigq_t *sigq);
+extern void sig_releasependingsignal(FAR sigpendq_t *sigpend);
+extern FAR sigpendq_t *sig_removependingsignal(FAR _TCB *stcb, int signo);
extern void sig_unmaskpendingsignal(void);
#endif /* __SIG_INTERNAL_H */
diff --git a/nuttx/sched/sig_mqnotempty.c b/nuttx/sched/sig_mqnotempty.c
index ab395db2e..a55d3138e 100644
--- a/nuttx/sched/sig_mqnotempty.c
+++ b/nuttx/sched/sig_mqnotempty.c
@@ -37,6 +37,7 @@
* Included Files
************************************************************/
+#include <nuttx/compiler.h>
#include <sys/types.h>
#include <signal.h>
#include <sched.h>
@@ -86,7 +87,7 @@ int sig_mqnotempty (int pid, int signo, const union sigval value)
int sig_mqnotempty (int pid, int signo, void *sival_ptr)
#endif
{
- _TCB *stcb;
+ FAR _TCB *stcb;
siginfo_t info;
int ret = ERROR;
diff --git a/nuttx/sched/sig_pending.c b/nuttx/sched/sig_pending.c
index 62b98f3ca..a2ee01d4e 100644
--- a/nuttx/sched/sig_pending.c
+++ b/nuttx/sched/sig_pending.c
@@ -87,8 +87,8 @@
int sigpending(sigset_t *set)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- int ret = ERROR;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ int ret = ERROR;
if (set)
{
@@ -106,16 +106,16 @@ int sigpending(sigset_t *set)
* Convert the list of pending signals into a signal set
************************************************************/
-sigset_t sig_pendingset(_TCB *stcb)
+sigset_t sig_pendingset(FAR _TCB *stcb)
{
- sigset_t sigpendset;
- sigpendq_t *sigpend;
- irqstate_t saved_state;
+ sigset_t sigpendset;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
sigpendset = NULL_SIGNAL_SET;
saved_state = irqsave();
- for (sigpend = (sigpendq_t*)stcb->sigpendingq.head;
+ for (sigpend = (FAR sigpendq_t*)stcb->sigpendingq.head;
(sigpend); sigpend = sigpend->flink)
{
sigaddset(&sigpendset, sigpend->info.si_signo);
diff --git a/nuttx/sched/sig_procmask.c b/nuttx/sched/sig_procmask.c
index dd5dd9eb8..339e6dda5 100644
--- a/nuttx/sched/sig_procmask.c
+++ b/nuttx/sched/sig_procmask.c
@@ -114,7 +114,7 @@
int sigprocmask(int how, const sigset_t *set, sigset_t *oset)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
sigset_t oldsigprocmask;
irqstate_t saved_state;
int ret = OK;
@@ -124,48 +124,57 @@ int sigprocmask(int how, const sigset_t *set, sigset_t *oset)
/* Return the old signal mask if requested */
oldsigprocmask = rtcb->sigprocmask;
- if (oset) *oset = oldsigprocmask;
+ 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();
+ if (set)
+ {
+ /* Some of these operations are non-atomic. We need to protect
+ * ourselves from attempts to process signals from interrupts
+ */
- /* Okay, determine what we are supposed to do */
+ saved_state = irqsave();
- switch (how) {
- /* The resulting set is the union of the current set and the
- * signal set pointed to by set. */
+ /* Okay, determine what we are supposed to do */
- case SIG_BLOCK:
- rtcb->sigprocmask |= *set;
- break;
+ switch (how)
+ {
+ /* The resulting set is the union of the current set and the
+ * signal set pointed to by set.
+ */
- /* The resulting set is the intersection of the current set and
- * the complement of the signal set pointed to by _set. */
+ case SIG_BLOCK:
+ rtcb->sigprocmask |= *set;
+ break;
- case SIG_UNBLOCK:
- 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.
+ */
- /* The resulting set is the signal set pointed to by set. */
+ case SIG_UNBLOCK:
+ rtcb->sigprocmask &= ~(*set);
+ break;
- case SIG_SETMASK:
- rtcb->sigprocmask = *set;
- break;
+ /* The resulting set is the signal set pointed to by set. */
- default:
- ret = ERROR;
- break;
- } /* end switch */
+ 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();
- } /* end if */
+ }
sched_unlock();
return ret;
diff --git a/nuttx/sched/sig_queue.c b/nuttx/sched/sig_queue.c
index b9d71efcc..dcae4e0a5 100644
--- a/nuttx/sched/sig_queue.c
+++ b/nuttx/sched/sig_queue.c
@@ -38,6 +38,7 @@
************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <sys/types.h>
#include <signal.h>
#include <debug.h>
@@ -103,7 +104,7 @@ int sigqueue (int pid, int signo, const union sigval value)
int sigqueue(int pid, int signo, void *sival_ptr)
#endif
{
- _TCB *stcb;
+ FAR _TCB *stcb;
siginfo_t info;
int ret = ERROR;
diff --git a/nuttx/sched/sig_received.c b/nuttx/sched/sig_received.c
index 922d4b778..9df9e797c 100644
--- a/nuttx/sched/sig_received.c
+++ b/nuttx/sched/sig_received.c
@@ -76,12 +76,12 @@
*
************************************************************/
-static int sig_queueaction(_TCB *stcb, siginfo_t *info)
+static int sig_queueaction(FAR _TCB *stcb, siginfo_t *info)
{
- sigactq_t *sigact;
- sigq_t *sigq;
- irqstate_t saved_state;
- int ret = OK;
+ FAR sigactq_t *sigact;
+ FAR sigq_t *sigq;
+ irqstate_t saved_state;
+ int ret = OK;
sched_lock();
@@ -112,7 +112,7 @@ static int sig_queueaction(_TCB *stcb, siginfo_t *info)
/* Put it at the end of the pending signals list */
saved_state = irqsave();
- sq_addlast((sq_entry_t*)sigq, &(stcb->sigpendactionq));
+ sq_addlast((FAR sq_entry_t*)sigq, &(stcb->sigpendactionq));
irqrestore(saved_state);
}
}
@@ -129,10 +129,10 @@ static int sig_queueaction(_TCB *stcb, siginfo_t *info)
*
************************************************************/
-static sigpendq_t *sig_findpendingsignal(_TCB *stcb, int signo)
+static FAR sigpendq_t *sig_findpendingsignal(FAR _TCB *stcb, int signo)
{
- sigpendq_t *sigpend = NULL;
- irqstate_t saved_state;
+ FAR sigpendq_t *sigpend = NULL;
+ irqstate_t saved_state;
/* Verify the caller's sanity */
@@ -144,7 +144,7 @@ static sigpendq_t *sig_findpendingsignal(_TCB *stcb, int signo)
/* Seach the list for a sigpendion on this signal */
- for(sigpend = (sigpendq_t*)stcb->sigpendingq.head;
+ for(sigpend = (FAR sigpendq_t*)stcb->sigpendingq.head;
(sigpend && sigpend->info.si_signo != signo);
sigpend = sigpend->flink);
irqrestore(saved_state);
@@ -161,10 +161,10 @@ static sigpendq_t *sig_findpendingsignal(_TCB *stcb, int signo)
*
************************************************************/
-static sigpendq_t *sig_allocatependingsignal(void)
+static FAR sigpendq_t *sig_allocatependingsignal(void)
{
- sigpendq_t *sigpend;
- irqstate_t saved_state;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
/* Check if we were called from an interrupt handler. */
@@ -172,13 +172,13 @@ static sigpendq_t *sig_allocatependingsignal(void)
{
/* Try to get the pending signal structure from the free list */
- sigpend = (sigpendq_t*)sq_remfirst(&g_sigpendingsignal);
+ sigpend = (FAR sigpendq_t*)sq_remfirst(&g_sigpendingsignal);
/* If so, then try the special list of structures reserved for
* interrupt handlers
*/
- sigpend = (sigpendq_t*)sq_remfirst(&g_sigpendingirqsignal);
+ sigpend = (FAR sigpendq_t*)sq_remfirst(&g_sigpendingirqsignal);
}
/* If we were not called from an interrupt handler, then we are
@@ -189,18 +189,18 @@ static sigpendq_t *sig_allocatependingsignal(void)
/* Try to get the pending signal structure from the free list */
saved_state = irqsave();
- sigpend = (sigpendq_t*)sq_remfirst(&g_sigpendingsignal);
+ sigpend = (FAR sigpendq_t*)sq_remfirst(&g_sigpendingsignal);
irqrestore(saved_state);
/* Check if we got one. */
if (!sigpend)
{
- /* No...Try the resource pool */
+ /* No... Allocate the pending signal */
if (!sigpend)
{
- sigpend = (sigpendq_t *)kmalloc((sizeof (sigpendq_t)));
+ sigpend = (FAR sigpendq_t *)kmalloc((sizeof (sigpendq_t)));
}
/* Check if we got an allocated message */
@@ -225,10 +225,10 @@ static sigpendq_t *sig_allocatependingsignal(void)
* run-away sender cannot consume all of memory.
************************************************************/
-static sigpendq_t *sig_addpendingsignal(_TCB *stcb, siginfo_t *info)
+static FAR sigpendq_t *sig_addpendingsignal(FAR _TCB *stcb, siginfo_t *info)
{
- sigpendq_t *sigpend;
- irqstate_t saved_state;
+ FAR sigpendq_t *sigpend;
+ irqstate_t saved_state;
/* Check if the signal is already pending */
@@ -256,7 +256,7 @@ static sigpendq_t *sig_addpendingsignal(_TCB *stcb, siginfo_t *info)
/* Add the structure to the pending signal list */
saved_state = irqsave();
- sq_addlast((sq_entry_t*)sigpend, &stcb->sigpendingq);
+ sq_addlast((FAR sq_entry_t*)sigpend, &stcb->sigpendingq);
irqrestore(saved_state);
}
}
@@ -283,7 +283,7 @@ static sigpendq_t *sig_addpendingsignal(_TCB *stcb, siginfo_t *info)
*
************************************************************/
-int sig_received(_TCB *stcb, siginfo_t *info)
+int sig_received(FAR _TCB *stcb, siginfo_t *info)
{
irqstate_t saved_state;
int ret = ERROR;
diff --git a/nuttx/sched/sig_releasependingsigaction.c b/nuttx/sched/sig_releasependingsigaction.c
index b25ee79e3..9ddedc711 100644
--- a/nuttx/sched/sig_releasependingsigaction.c
+++ b/nuttx/sched/sig_releasependingsigaction.c
@@ -74,7 +74,7 @@
*
************************************************************/
-void sig_releasependingsigaction(sigq_t *sigq)
+void sig_releasependingsigaction(FAR sigq_t *sigq)
{
irqstate_t saved_state;
@@ -88,7 +88,7 @@ void sig_releasependingsigaction(sigq_t *sigq)
* list from interrupt handlers. */
saved_state = irqsave();
- sq_addlast((sq_entry_t*)sigq, &g_sigpendingaction);
+ sq_addlast((FAR sq_entry_t*)sigq, &g_sigpendingaction);
irqrestore(saved_state);
}
@@ -102,7 +102,7 @@ void sig_releasependingsigaction(sigq_t *sigq)
* list from interrupt handlers. */
saved_state = irqsave();
- sq_addlast((sq_entry_t*)sigq, &g_sigpendingirqaction);
+ sq_addlast((FAR sq_entry_t*)sigq, &g_sigpendingirqaction);
irqrestore(saved_state);
}
diff --git a/nuttx/sched/sig_releasependingsignal.c b/nuttx/sched/sig_releasependingsignal.c
index 43601d7db..198c145df 100644
--- a/nuttx/sched/sig_releasependingsignal.c
+++ b/nuttx/sched/sig_releasependingsignal.c
@@ -82,7 +82,7 @@
* Deallocate a pending signal list entry
************************************************************/
-void sig_releasependingsignal(sigpendq_t *sigpend)
+void sig_releasependingsignal(FAR sigpendq_t *sigpend)
{
irqstate_t saved_state;
@@ -96,7 +96,7 @@ void sig_releasependingsignal(sigpendq_t *sigpend)
* list from interrupt handlers. */
saved_state = irqsave();
- sq_addlast((sq_entry_t*)sigpend, &g_sigpendingsignal);
+ sq_addlast((FAR sq_entry_t*)sigpend, &g_sigpendingsignal);
irqrestore(saved_state);
}
@@ -111,7 +111,7 @@ void sig_releasependingsignal(sigpendq_t *sigpend)
*/
saved_state = irqsave();
- sq_addlast((sq_entry_t*)sigpend, &g_sigpendingirqsignal);
+ sq_addlast((FAR sq_entry_t*)sigpend, &g_sigpendingirqsignal);
irqrestore(saved_state);
}
diff --git a/nuttx/sched/sig_removependingsignal.c b/nuttx/sched/sig_removependingsignal.c
index 917d6d7e1..c31c0bbe7 100644
--- a/nuttx/sched/sig_removependingsignal.c
+++ b/nuttx/sched/sig_removependingsignal.c
@@ -82,21 +82,21 @@
* Remove the specified signal from the signal pending list
************************************************************/
-sigpendq_t *sig_removependingsignal(_TCB *stcb, int signo)
+FAR sigpendq_t *sig_removependingsignal(FAR _TCB *stcb, int signo)
{
- sigpendq_t *currsig;
- sigpendq_t *prevsig;
+ FAR sigpendq_t *currsig;
+ FAR sigpendq_t *prevsig;
irqstate_t saved_state;
saved_state = irqsave();
- for (prevsig = NULL, currsig = (sigpendq_t*)stcb->sigpendingq.head;
+ for (prevsig = NULL, currsig = (FAR sigpendq_t*)stcb->sigpendingq.head;
(currsig && currsig->info.si_signo != signo);
prevsig = currsig, currsig = currsig->flink);
if (currsig)
{
if (prevsig)
{
- sq_remafter((sq_entry_t*)prevsig, &stcb->sigpendingq);
+ sq_remafter((FAR sq_entry_t*)prevsig, &stcb->sigpendingq);
}
else
{
diff --git a/nuttx/sched/sig_suspend.c b/nuttx/sched/sig_suspend.c
index 92771578f..7f7acfce2 100644
--- a/nuttx/sched/sig_suspend.c
+++ b/nuttx/sched/sig_suspend.c
@@ -111,12 +111,12 @@
int sigsuspend(const sigset_t *set)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- sigset_t intersection;
- sigset_t saved_sigprocmask;
- sigpendq_t *sigpend;
- irqstate_t saved_state;
- int unblocksigno;
+ FAR _TCB *rtcb = (FAR _TCB*)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
diff --git a/nuttx/sched/sig_timedwait.c b/nuttx/sched/sig_timedwait.c
index bba138fa7..eb3151dfa 100644
--- a/nuttx/sched/sig_timedwait.c
+++ b/nuttx/sched/sig_timedwait.c
@@ -88,8 +88,8 @@ static void sig_timeout(int argc, uint32 itcb, ...)
union
{
- _TCB *wtcb;
- uint32 itcb;
+ FAR _TCB *wtcb;
+ uint32 itcb;
} u;
u.itcb = itcb;
@@ -160,13 +160,13 @@ static void sig_timeout(int argc, uint32 itcb, ...)
int sigtimedwait(const sigset_t *set, struct siginfo *info,
const struct timespec *timeout)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- sigset_t intersection;
- sigpendq_t *sigpend;
- WDOG_ID wdog;
- irqstate_t saved_state;
- sint32 waitticks;
- int ret = ERROR;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ sigset_t intersection;
+ FAR sigpendq_t *sigpend;
+ WDOG_ID wdog;
+ irqstate_t saved_state;
+ sint32 waitticks;
+ int ret = ERROR;
sched_lock(); /* Not necessary */
diff --git a/nuttx/sched/sig_unmaskpendingsignal.c b/nuttx/sched/sig_unmaskpendingsignal.c
index c27ad1266..77892dfc9 100644
--- a/nuttx/sched/sig_unmaskpendingsignal.c
+++ b/nuttx/sched/sig_unmaskpendingsignal.c
@@ -78,10 +78,10 @@
void sig_unmaskpendingsignal(void)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- sigset_t unmaskedset;
- sigpendq_t *pendingsig;
- int signo;
+ FAR _TCB *rtcb = (FAR _TCB*)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
@@ -133,3 +133,4 @@ void sig_unmaskpendingsignal(void)
sched_unlock();
}
+
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 79f487a11..fe449b85f 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -67,7 +67,7 @@
************************************************************/
static void task_start(void);
-static STATUS task_assignpid(_TCB* tcb);
+static STATUS task_assignpid(FAR _TCB* tcb);
/************************************************************
* Private Functions
@@ -92,7 +92,7 @@ static STATUS task_assignpid(_TCB* tcb);
static void task_start(void)
{
- _TCB *tcb = (_TCB*)g_readytorun.head;
+ FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
int argc;
/* Count how many non-null arguments we are passing */
@@ -127,7 +127,7 @@ static void task_start(void)
*
************************************************************/
-static STATUS task_assignpid(_TCB *tcb)
+static STATUS task_assignpid(FAR _TCB *tcb)
{
pid_t next_pid;
int hash_ndx;
@@ -220,9 +220,10 @@ static STATUS task_assignpid(_TCB *tcb)
*
************************************************************/
-STATUS _task_init(_TCB *tcb, char *name, int priority,
+STATUS _task_init(FAR _TCB *tcb, const char *name, int priority,
start_t start, main_t main, boolean pthread,
- char *arg1, char *arg2, char *arg3, char *arg4)
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4)
{
STATUS ret;
@@ -317,7 +318,7 @@ STATUS _task_init(_TCB *tcb, char *name, int priority,
/* Add the task to the inactive task list */
sched_lock();
- dq_addfirst((dq_entry_t*)tcb, &g_inactivetasks);
+ dq_addfirst((FAR dq_entry_t*)tcb, &g_inactivetasks);
tcb->task_state = TSTATE_TASK_INACTIVE;
sched_unlock();
}
@@ -348,9 +349,10 @@ STATUS _task_init(_TCB *tcb, char *name, int priority,
*
************************************************************/
-STATUS task_init(_TCB *tcb, char *name, int priority,
- uint32 *stack, uint32 stack_size, main_t entry,
- char *arg1, char *arg2, char *arg3, char *arg4)
+STATUS task_init(FAR _TCB *tcb, const char *name, int priority,
+ FAR uint32 *stack, uint32 stack_size, main_t entry,
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4)
{
up_use_stack(tcb, stack, stack_size);
return _task_init(tcb, name, priority, task_start, entry,
@@ -374,7 +376,7 @@ STATUS task_init(_TCB *tcb, char *name, int priority,
*
************************************************************/
-STATUS task_activate(_TCB *tcb)
+STATUS task_activate(FAR _TCB *tcb)
{
#ifdef CONFIG_SCHED_INSTRUMENTATION
irqstate_t flags = irqsave();
@@ -433,17 +435,18 @@ STATUS task_activate(_TCB *tcb)
*
************************************************************/
-int task_create(char *name, int priority,
+int task_create(const char *name, int priority,
int stack_size, main_t entry,
- char *arg1, char *arg2, char *arg3, char *arg4)
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4)
{
- _TCB *tcb;
+ FAR _TCB *tcb;
STATUS status;
pid_t pid;
/* Allocate a TCB for the new task. */
- tcb = (_TCB*)kzmalloc(sizeof(_TCB));
+ tcb = (FAR _TCB*)kzmalloc(sizeof(_TCB));
if (!tcb)
{
*get_errno_ptr() = ENOMEM;
@@ -486,7 +489,7 @@ int task_create(char *name, int priority,
status = task_activate(tcb);
if (status != OK)
{
- dq_rem((dq_entry_t*)tcb, &g_inactivetasks);
+ dq_rem((FAR dq_entry_t*)tcb, &g_inactivetasks);
sched_releasetcb(tcb);
return ERROR;
}
diff --git a/nuttx/sched/task_delete.c b/nuttx/sched/task_delete.c
index ed169217d..47d9a868f 100644
--- a/nuttx/sched/task_delete.c
+++ b/nuttx/sched/task_delete.c
@@ -95,14 +95,14 @@
STATUS task_delete(pid_t pid)
{
- _TCB *rtcb;
- _TCB *dtcb;
+ FAR _TCB *rtcb;
+ FAR _TCB *dtcb;
irqstate_t saved_state;
STATUS ret = ERROR;
/* Check if the task to delete is the calling task */
- rtcb = (_TCB*)g_readytorun.head;
+ rtcb = (FAR _TCB*)g_readytorun.head;
if (pid == 0 || pid == rtcb->pid)
{
/* If it is, then what we really wanted to do was exit.
@@ -146,7 +146,7 @@ STATUS task_delete(pid_t pid)
/* Remove the task from the OS's tasks lists. */
- dq_rem((dq_entry_t*)dtcb, g_tasklisttable[dtcb->task_state].list);
+ dq_rem((FAR dq_entry_t*)dtcb, g_tasklisttable[dtcb->task_state].list);
dtcb->task_state = TSTATE_TASK_INVALID;
irqrestore(saved_state);
@@ -163,3 +163,4 @@ STATUS task_delete(pid_t pid)
sched_releasetcb(dtcb);
return ret;
}
+
diff --git a/nuttx/sched/task_restart.c b/nuttx/sched/task_restart.c
index 60478c258..eb6ef8d72 100644
--- a/nuttx/sched/task_restart.c
+++ b/nuttx/sched/task_restart.c
@@ -99,8 +99,8 @@
STATUS task_restart(pid_t pid)
{
- _TCB *rtcb;
- _TCB *tcb;
+ FAR _TCB *rtcb;
+ FAR _TCB *tcb;
STATUS status;
irqstate_t state;
@@ -112,7 +112,7 @@ STATUS task_restart(pid_t pid)
/* Check if the task to restart is the calling task */
- rtcb = (_TCB*)g_readytorun.head;
+ rtcb = (FAR _TCB*)g_readytorun.head;
if ((pid == 0) || (pid == rtcb->pid))
{
/* Not implemented */
@@ -139,7 +139,7 @@ STATUS task_restart(pid_t pid)
*/
state = irqsave();
- dq_rem((dq_entry_t*)tcb, g_tasklisttable[tcb->task_state].list);
+ dq_rem((FAR dq_entry_t*)tcb, g_tasklisttable[tcb->task_state].list);
tcb->task_state = TSTATE_TASK_INVALID;
irqrestore(state);
@@ -159,7 +159,7 @@ STATUS task_restart(pid_t pid)
/* Add the task to the inactive task list */
- dq_addfirst((dq_entry_t*)tcb, &g_inactivetasks);
+ dq_addfirst((FAR dq_entry_t*)tcb, &g_inactivetasks);
tcb->task_state = TSTATE_TASK_INACTIVE;
/* Activate the task */
@@ -167,7 +167,7 @@ STATUS task_restart(pid_t pid)
status = task_activate(tcb);
if (status != OK)
{
- dq_rem((dq_entry_t*)tcb, &g_inactivetasks);
+ dq_rem((FAR dq_entry_t*)tcb, &g_inactivetasks);
sched_releasetcb(tcb);
return ERROR;
}
diff --git a/nuttx/sched/wd_cancel.c b/nuttx/sched/wd_cancel.c
index c0181e43b..2872ce052 100644
--- a/nuttx/sched/wd_cancel.c
+++ b/nuttx/sched/wd_cancel.c
@@ -135,7 +135,7 @@ STATUS wd_cancel (WDOG_ID wdid)
/* Now, remove the watchdog from the timer queue */
if (prev)
- (void)sq_remafter((sq_entry_t*)prev, &g_wdactivelist);
+ (void)sq_remafter((FAR sq_entry_t*)prev, &g_wdactivelist);
else
(void)sq_remfirst(&g_wdactivelist);
wdid->next = NULL;
diff --git a/nuttx/sched/wd_delete.c b/nuttx/sched/wd_delete.c
index 96168ec2c..7e2a4328e 100644
--- a/nuttx/sched/wd_delete.c
+++ b/nuttx/sched/wd_delete.c
@@ -88,7 +88,7 @@
*
************************************************************/
-STATUS wd_delete (WDOG_ID wdId)
+STATUS wd_delete(WDOG_ID wdId)
{
irqstate_t saved_state;
@@ -99,7 +99,7 @@ STATUS wd_delete (WDOG_ID wdId)
/* Put the watchdog back on the free list */
- sq_addlast((sq_entry_t*)wdId, &g_wdfreelist);
+ sq_addlast((FAR sq_entry_t*)wdId, &g_wdfreelist);
irqrestore(saved_state);
/* Return success */
diff --git a/nuttx/sched/wd_initialize.c b/nuttx/sched/wd_initialize.c
index 5d979bb3d..a1d943079 100644
--- a/nuttx/sched/wd_initialize.c
+++ b/nuttx/sched/wd_initialize.c
@@ -67,7 +67,7 @@ sq_queue_t g_wdfreelist;
* item.
*/
-wdog_t *g_wdpool;
+FAR wdog_t *g_wdpool;
/* The g_wdactivelist data structure is a singly linked list
* ordered by watchdog expiration time. When watchdog timers
@@ -118,15 +118,15 @@ void wd_initialize(void)
* configured number of watchdogs.
*/
- g_wdpool = (wdog_t*)kmalloc(sizeof(wdog_t) * CONFIG_PREALLOC_WDOGS);
+ g_wdpool = (FAR wdog_t*)kmalloc(sizeof(wdog_t) * CONFIG_PREALLOC_WDOGS);
if (g_wdpool)
{
- wdog_t *wdog = g_wdpool;
+ FAR wdog_t *wdog = g_wdpool;
int i;
for (i = 0; i < CONFIG_PREALLOC_WDOGS; i++)
{
- sq_addlast((sq_entry_t*)wdog++, &g_wdfreelist);
+ sq_addlast((FAR sq_entry_t*)wdog++, &g_wdfreelist);
}
}
diff --git a/nuttx/sched/wd_internal.h b/nuttx/sched/wd_internal.h
index 7794d8c12..26ee264ad 100644
--- a/nuttx/sched/wd_internal.h
+++ b/nuttx/sched/wd_internal.h
@@ -88,7 +88,7 @@ extern sq_queue_t g_wdfreelist;
* item.
*/
-extern wdog_t *g_wdpool;
+extern FAR wdog_t *g_wdpool;
/* The g_wdactivelist data structure is a singly linked list
* ordered by watchdog expiration time. When watchdog timers
diff --git a/nuttx/sched/wd_start.c b/nuttx/sched/wd_start.c
index b3534593d..a0fb469de 100644
--- a/nuttx/sched/wd_start.c
+++ b/nuttx/sched/wd_start.c
@@ -185,7 +185,7 @@ STATUS wd_start(WDOG_ID wdog, int delay, wdentry_t wdentry,
if (g_wdactivelist.head == NULL)
{
- sq_addlast((sq_entry_t*)wdog,&g_wdactivelist);
+ sq_addlast((FAR sq_entry_t*)wdog,&g_wdactivelist);
}
/* There are other active watchdogs in the timer queue */
@@ -228,11 +228,11 @@ STATUS wd_start(WDOG_ID wdog, int delay, wdentry_t wdentry,
if (curr == (wdog_t*)g_wdactivelist.head)
{
- sq_addfirst((sq_entry_t*)wdog, &g_wdactivelist);
+ sq_addfirst((FAR sq_entry_t*)wdog, &g_wdactivelist);
}
else
{
- sq_addafter((sq_entry_t*)prev, (sq_entry_t*)wdog,
+ sq_addafter((FAR sq_entry_t*)prev, (FAR sq_entry_t*)wdog,
&g_wdactivelist);
}
}
@@ -247,13 +247,13 @@ STATUS wd_start(WDOG_ID wdog, int delay, wdentry_t wdentry,
delay -= now;
if (!curr->next)
{
- sq_addlast((sq_entry_t*)wdog, &g_wdactivelist);
+ sq_addlast((FAR sq_entry_t*)wdog, &g_wdactivelist);
}
else
{
next = curr->next;
next->lag -= delay;
- sq_addafter((sq_entry_t*)curr, (sq_entry_t*)wdog,
+ sq_addafter((FAR sq_entry_t*)curr, (FAR sq_entry_t*)wdog,
&g_wdactivelist);
}
}