summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/arch.h24
-rw-r--r--nuttx/include/nuttx/fs/fs.h9
-rw-r--r--nuttx/include/nuttx/page.h18
-rw-r--r--nuttx/include/nuttx/sched.h39
-rw-r--r--nuttx/include/sched.h21
-rw-r--r--nuttx/include/semaphore.h3
6 files changed, 52 insertions, 62 deletions
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index 958986472..c86b66ed1 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -57,7 +57,7 @@
* Public Types
****************************************************************************/
-typedef CODE void (*sig_deliver_t)(FAR _TCB *tcb);
+typedef CODE void (*sig_deliver_t)(FAR struct tcb_s *tcb);
/****************************************************************************
* Public Variables
@@ -129,7 +129,7 @@ void up_idle(void);
*
****************************************************************************/
-void up_initial_state(FAR _TCB *tcb);
+void up_initial_state(FAR struct tcb_s *tcb);
/****************************************************************************
* Name: up_create_stack
@@ -154,7 +154,7 @@ void up_initial_state(FAR _TCB *tcb);
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-int up_create_stack(FAR _TCB *tcb, size_t stack_size);
+int up_create_stack(FAR struct tcb_s *tcb, size_t stack_size);
#endif
/****************************************************************************
@@ -179,7 +179,7 @@ int up_create_stack(FAR _TCB *tcb, size_t stack_size);
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-int up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
+int up_use_stack(FAR struct tcb_s *tcb, FAR void *stack, size_t stack_size);
#endif
/****************************************************************************
@@ -192,7 +192,7 @@ int up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-void up_release_stack(FAR _TCB *dtcb);
+void up_release_stack(FAR struct tcb_s *dtcb);
#endif
/****************************************************************************
@@ -215,7 +215,7 @@ void up_release_stack(FAR _TCB *dtcb);
*
****************************************************************************/
-void up_unblock_task(FAR _TCB *tcb);
+void up_unblock_task(FAR struct tcb_s *tcb);
/****************************************************************************
* Name: up_block_task
@@ -241,7 +241,7 @@ void up_unblock_task(FAR _TCB *tcb);
*
****************************************************************************/
-void up_block_task(FAR _TCB *tcb, tstate_t task_state);
+void up_block_task(FAR struct tcb_s *tcb, tstate_t task_state);
/****************************************************************************
* Name: up_release_pending
@@ -286,7 +286,7 @@ void up_release_pending(void);
*
****************************************************************************/
-void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority);
+void up_reprioritize_rtr(FAR struct tcb_s *tcb, uint8_t priority);
/****************************************************************************
* Name: _exit
@@ -348,7 +348,7 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority);
****************************************************************************/
#ifndef CONFIG_DISABLE_SIGNALS
-void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver);
+void up_schedule_sigaction(FAR struct tcb_s *tcb, sig_deliver_t sigdeliver);
#endif
/****************************************************************************
@@ -542,7 +542,7 @@ int up_addrenv_destroy(task_addrenv_t addrenv);
****************************************************************************/
#ifdef CONFIG_ADDRENV
-int up_addrenv_assign(task_addrenv_t addrenv, FAR _TCB *tcb);
+int up_addrenv_assign(task_addrenv_t addrenv, FAR struct tcb_s *tcb);
#endif
/****************************************************************************
@@ -564,7 +564,7 @@ int up_addrenv_assign(task_addrenv_t addrenv, FAR _TCB *tcb);
****************************************************************************/
#ifdef CONFIG_ADDRENV
-int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb);
+int up_addrenv_share(FAR const struct tcb_s *ptcb, FAR struct tcb_s *ctcb);
#endif
/****************************************************************************
@@ -586,7 +586,7 @@ int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb);
****************************************************************************/
#ifdef CONFIG_ADDRENV
-int up_addrenv_release(FAR _TCB *tcb);
+int up_addrenv_release(FAR struct tcb_s *tcb);
#endif
/****************************************************************************
diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h
index 93ca2a334..c11084dee 100644
--- a/nuttx/include/nuttx/fs/fs.h
+++ b/nuttx/include/nuttx/fs/fs.h
@@ -590,13 +590,8 @@ int close_blockdriver(FAR struct inode *inode);
****************************************************************************/
#if CONFIG_NFILE_STREAMS > 0
-
-#ifndef __TCB_DEFINED__
-typedef struct _TCB _TCB;
-#define __TCB_DEFINED__
-#endif
-
-FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
+struct tcb_s; /* Forward reference */
+FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR struct tcb_s *tcb);
#endif
/* lib/stdio/lib_fflush.c **************************************************/
diff --git a/nuttx/include/nuttx/page.h b/nuttx/include/nuttx/page.h
index 2502e16ee..8098971be 100644
--- a/nuttx/include/nuttx/page.h
+++ b/nuttx/include/nuttx/page.h
@@ -2,7 +2,7 @@
* include/nuttx/page.h
* This file defines interfaces used to support NuttX On-Demand Paging.
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -232,7 +232,8 @@
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -308,7 +309,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN void pg_miss(void);
+void pg_miss(void);
/****************************************************************************
* Public Functions -- Provided by architecture-specific logic to common
@@ -345,7 +346,7 @@ EXTERN void pg_miss(void);
*
****************************************************************************/
-EXTERN bool up_checkmapping(FAR _TCB *tcb);
+bool up_checkmapping(FAR struct tcb_s *tcb);
/****************************************************************************
* Name: up_allocpage()
@@ -396,7 +397,7 @@ EXTERN bool up_checkmapping(FAR _TCB *tcb);
*
****************************************************************************/
-EXTERN int up_allocpage(FAR _TCB *tcb, FAR void **vpage);
+int up_allocpage(FAR struct tcb_s *tcb, FAR void **vpage);
/****************************************************************************
* Name: up_fillpage()
@@ -451,10 +452,11 @@ EXTERN int up_allocpage(FAR _TCB *tcb, FAR void **vpage);
****************************************************************************/
#ifdef CONFIG_PAGING_BLOCKINGFILL
-EXTERN int up_fillpage(FAR _TCB *tcb, FAR void *vpage);
+int up_fillpage(FAR struct tcb_s *tcb, FAR void *vpage);
#else
-typedef void (*up_pgcallback_t)(FAR _TCB *tcb, int result);
-EXTERN int up_fillpage(FAR _TCB *tcb, FAR void *vpage, up_pgcallback_t pg_callback);
+typedef void (*up_pgcallback_t)(FAR struct tcb_s *tcb, int result);
+int up_fillpage(FAR struct tcb_s *tcb, FAR void *vpage,
+ up_pgcallback_t pg_callback);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 082ce65dd..68afb3bf5 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -108,7 +108,7 @@
#define MAX_LOCK_COUNT 127
-/* Values for the _TCB flags bits */
+/* Values for the struct tcb_s flags bits */
#define TCB_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: thread type */
#define TCB_FLAG_TTYPE_MASK (3 << TCB_FLAG_TTYPE_SHIFT)
@@ -140,10 +140,10 @@
#ifndef __ASSEMBLY__
/* General Task Management Types ************************************************/
-
/* This is the type of the task_state field of the TCB. NOTE: the order and
* content of this enumeration is critical since there are some OS tables indexed
- * by these values. The range of values is assumed to fit into a uint8_t in _TCB.
+ * by these values. The range of values is assumed to fit into a uint8_t in
+ * struct tcb_s.
*/
enum tstate_e
@@ -386,17 +386,17 @@ struct task_group_s
};
#endif
-/* _TCB **************************************************************************/
-/* This is the task control block (TCB). Each task or thread is represented by
- * a TCB. The TCB is the heart of the NuttX task-control logic.
+/* struct tcb_s ******************************************************************/
+/* This is the common part of the task control block (TCB). Each task or thread
+ * is represented by a TCB. The TCB is the heart of the NuttX task-control logic.
*/
-struct _TCB
+struct tcb_s
{
/* Fields used to support list management *************************************/
- FAR struct _TCB *flink; /* Doubly linked list */
- FAR struct _TCB *blink;
+ FAR struct tcb_s *flink; /* Doubly linked list */
+ FAR struct tcb_s *blink;
/* Task Group *****************************************************************/
@@ -512,18 +512,9 @@ struct _TCB
#endif
};
-/* Certain other header files may also define this time to avoid circular header
- * file inclusion issues.
- */
-
-#ifndef __TCB_DEFINED__
-typedef struct _TCB _TCB;
-#define __TCB_DEFINED__
-#endif
-
/* This is the callback type used by sched_foreach() */
-typedef void (*sched_foreach_t)(FAR _TCB *tcb, FAR void *arg);
+typedef void (*sched_foreach_t)(FAR struct tcb_s *tcb, FAR void *arg);
#endif /* __ASSEMBLY__ */
@@ -547,7 +538,7 @@ extern "C"
/* TCB helpers */
-FAR _TCB *sched_self(void);
+FAR struct tcb_s *sched_self(void);
/* File system helpers */
@@ -565,7 +556,7 @@ FAR struct socketlist *sched_getsockets(void);
/* Setup up a start hook */
#ifdef CONFIG_SCHED_STARTHOOK
-void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg);
+void task_starthook(FAR struct tcb_s *tcb, starthook_t starthook, FAR void *arg);
#endif
/* Internal vfork support.The overall sequence is:
@@ -590,9 +581,9 @@ void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg);
* task_vforkabort() may be called if an error occurs between steps 3 and 6.
*/
-FAR _TCB *task_vforksetup(start_t retaddr);
-pid_t task_vforkstart(FAR _TCB *child);
-void task_vforkabort(FAR _TCB *child, int errcode);
+FAR struct tcb_s *task_vforksetup(start_t retaddr);
+pid_t task_vforkstart(FAR struct tcb_s *child);
+void task_vforkabort(FAR struct tcb_s *child, int errcode);
/* sched_foreach will enumerate over each task and provide the
* TCB of each task to a user callback functions. Interrupts
diff --git a/nuttx/include/sched.h b/nuttx/include/sched.h
index 804dd47cd..c9ff6d248 100644
--- a/nuttx/include/sched.h
+++ b/nuttx/include/sched.h
@@ -1,7 +1,7 @@
/********************************************************************************
* include/sched.h
*
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -110,17 +110,17 @@ extern "C"
/* Task Control Interfaces (non-standard) */
#ifndef CONFIG_CUSTOM_STACK
-int task_init(FAR _TCB *tcb, const char *name, int priority,
+int task_init(FAR struct tcb_s *tcb, const char *name, int priority,
FAR uint32_t *stack, uint32_t stack_size, main_t entry,
FAR char * const argv[]);
#else
-int task_init(FAR _TCB *tcb, const char *name, int priority, main_t entry,
- FAR char * const argv[]);
+int task_init(FAR struct tcb_s *tcb, const char *name, int priority,
+ main_t entry, FAR char * const argv[]);
#endif
-int task_activate(FAR _TCB *tcb);
+int task_activate(FAR struct tcb_s *tcb);
#ifndef CONFIG_CUSTOM_STACK
-int task_create(FAR const char *name, int priority, int stack_size, main_t entry,
- FAR char * const argv[]);
+int task_create(FAR const char *name, int priority, int stack_size,
+ main_t entry, FAR char * const argv[]);
#else
int task_create(FAR const char *name, int priority, main_t entry,
FAR char * const argv[]);
@@ -152,9 +152,10 @@ int sched_lockcount(void);
#ifdef CONFIG_SCHED_INSTRUMENTATION
-void sched_note_start(FAR _TCB *tcb);
-void sched_note_stop(FAR _TCB *tcb);
-void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
+void sched_note_start(FAR struct tcb_s *tcb);
+void sched_note_stop(FAR struct tcb_s *tcb);
+void sched_note_switch(FAR struct tcb_s *pFromTcb,
+ FAR struct tcb_s *pToTcb);
#else
# define sched_note_start(t)
diff --git a/nuttx/include/semaphore.h b/nuttx/include/semaphore.h
index 203118bd6..46f2c06ea 100644
--- a/nuttx/include/semaphore.h
+++ b/nuttx/include/semaphore.h
@@ -63,12 +63,13 @@ extern "C" {
/* This structure contains information about the holder of a semaphore */
#ifdef CONFIG_PRIORITY_INHERITANCE
+struct tcb_s; /* Forward reference */
struct semholder_s
{
#if CONFIG_SEM_PREALLOCHOLDERS > 0
struct semholder_s *flink; /* Implements singly linked list */
#endif
- void *htcb; /* Holder TCB (actual type is _TCB) */
+ FAR struct tcb_s *htcb; /* Holder TCB */
int16_t counts; /* Number of counts owned by this holder */
};