summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_saveusercontext.S237
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_serial.c4
-rw-r--r--nuttx/fs/fs_read.c6
-rw-r--r--nuttx/fs/fs_rmdir.c6
-rw-r--r--nuttx/fs/fs_unlink.c6
-rw-r--r--nuttx/fs/fs_write.c8
-rw-r--r--nuttx/include/unistd.h11
-rw-r--r--nuttx/lib/lib_getopt.c16
-rw-r--r--nuttx/sched/task_activate.c44
-rw-r--r--nuttx/sched/task_create.c40
-rw-r--r--nuttx/sched/task_setup.c54
-rw-r--r--nuttx/sched/task_start.c44
12 files changed, 238 insertions, 238 deletions
diff --git a/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S b/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S
index 8ae7b1775..892f9779e 100644
--- a/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S
+++ b/nuttx/arch/z16/src/z16f/z16f_saveusercontext.S
@@ -1,118 +1,119 @@
-/*************************************************************************
- * arch/z16/src/z16f/z16f_saveusercontext.asm
- *
- * Copyright (C) 2008 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 NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSeqUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- *************************************************************************/
-
-/*************************************************************************
- * Included Files
- *************************************************************************/
-
-#include <nuttx/config.h>
-#include <arch/irq.h>
-#include "chip/chip.h"
-
-/*************************************************************************
- * External References / External Definitions
- *************************************************************************/
-
- xdef _up_saveusercontext
-
-/*************************************************************************
- * Data Allocation
- *************************************************************************/
-
- define CODESEG, SPACE=EROM
- segment CODESEG
-
-/*************************************************************************
- * Code
- *************************************************************************/
-
-/*************************************************************************
- * Name: up_saveusercontext
- *
- * Description:
- * Save the current user context.
- * r0-r7: These are caller saved registers and do not need to be stored
- * here
- * r8-r13: There callee saved registers must be preserved
- * r14: Frame pointer
- * r15: Stack pointer (with return address on stack)
- *
- * Parameters:
- * r1: pointer to the register save array in the XCPT structure
- *
- *************************************************************************/
-
-_up_saveusercontext:
- /* Save the flags (needed to restore the interrupt state) */
-
- ld r3, Z16F_CNTRL_FLAGS /* Fetch the flags register */
- sll r3, #8 /* Pad with zero */
- ld.w 2*REG_FLAGS(r1), r3 /* Save 16-bit value */
-
- /* Save r8-R13 */
-
- ld 2*REG_R8(r1), r8 /* Save r8 */
- ld 2*REG_R9(r1), r9 /* Save r9 */
- ld 2*REG_R10(r1), r10 /* Save r10 */
- ld 2*REG_R11(r1), r11 /* Save r11 */
- ld 2*REG_R12(r1), r12 /* Save r12 */
- ld 2*REG_R13(r1), r13 /* Save r13 */
-
- /* Save the stack pointer and the frame pointer */
-
- ld 2*REG_FP(r1), fp /* Save the frame pointer */
- ld 2*REG_SP(r1), sp /* Save the stack pointer */
-
- /* Save the return address at the top of the stack */
-
- ld r0, (sp) /* Save the return address */
- ld 2*REG_PC(r1), r0
-
- /* Set the return value so that if when the task is restarted
- * (via z16f_restoreusercontext() or via interrupt handling return),
- * the returned value will be 1
- */
-
- ld r0, #1
- ld 2*REG_R0(r1), r0
-
- /* But always return 0 when returning from this function. The
- * apparent return value tells the higher level logic whether the
- * user context was saved or restored (in the spirit of setjmp and longjmp)
- */
-
- clr r0 /* Always returns 0 */
- ret
- end
+/*************************************************************************
+ * arch/z16/src/z16f/z16f_saveusercontext.asm
+ *
+ * Copyright (C) 2008 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 NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSeqUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ *************************************************************************/
+
+/*************************************************************************
+ * Included Files
+ *************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/irq.h>
+#include "chip/chip.h"
+
+/*************************************************************************
+ * External References / External Definitions
+ *************************************************************************/
+
+ xdef _up_saveusercontext
+
+/*************************************************************************
+ * Data Allocation
+ *************************************************************************/
+
+ define CODESEG, SPACE=EROM
+ segment CODESEG
+
+/*************************************************************************
+ * Code
+ *************************************************************************/
+
+/*************************************************************************
+ * Name: up_saveusercontext
+ *
+ * Description:
+ * Save the current user context.
+ * r0-r7: These are caller saved registers and do not need to be stored
+ * here
+ * r8-r13: There callee saved registers must be preserved
+ * r14: Frame pointer
+ * r15: Stack pointer (with return address on stack)
+ *
+ * Parameters:
+ * r1: pointer to the register save array in the XCPT structure
+ *
+ *************************************************************************/
+
+_up_saveusercontext:
+ /* Save the flags (needed to restore the interrupt state) */
+
+ ld.ub r3, Z16F_CNTRL_FLAGS /* Fetch the flags register (zero padded) */
+ ld.w 2*REG_FLAGS(r1), r3 /* Save 16-bit value */
+
+ /* Save r8-R13 */
+
+ ld 2*REG_R8(r1), r8 /* Save r8 */
+ ld 2*REG_R9(r1), r9 /* Save r9 */
+ ld 2*REG_R10(r1), r10 /* Save r10 */
+ ld 2*REG_R11(r1), r11 /* Save r11 */
+ ld 2*REG_R12(r1), r12 /* Save r12 */
+ ld 2*REG_R13(r1), r13 /* Save r13 */
+
+ /* Save the stack pointer and the frame pointer */
+
+ ld 2*REG_FP(r1), fp /* Save the frame pointer */
+ ld r0, #4 /* 4 bytes of return address on stack */
+ add r0, sp /* Value of stack pointer on return */
+ ld 2*REG_SP(r1), r0 /* Save the stack pointer value on return */
+
+ /* Save the return address at the top of the stack */
+
+ ld r0, (sp) /* Save the return address */
+ ld 2*REG_PC(r1), r0
+
+ /* Set the return value so that if when the task is restarted
+ * (via z16f_restoreusercontext() or via interrupt handling return),
+ * the returned value will be 1
+ */
+
+ ld r0, #1
+ ld 2*REG_R0(r1), r0
+
+ /* But always return 0 when returning from this function. The
+ * apparent return value tells the higher level logic whether the
+ * user context was saved or restored (in the spirit of setjmp and longjmp)
+ */
+
+ clr r0 /* Always returns 0 */
+ ret
+ end
diff --git a/nuttx/arch/z16/src/z16f/z16f_serial.c b/nuttx/arch/z16/src/z16f/z16f_serial.c
index 63f40f62a..cf44618f4 100644
--- a/nuttx/arch/z16/src/z16f/z16f_serial.c
+++ b/nuttx/arch/z16/src/z16f/z16f_serial.c
@@ -140,8 +140,8 @@ static struct z16f_uart_s g_uart0priv =
CONFIG_UART0_BAUD, /* baud */
FALSE, /* rxenabled */
FALSE, /* txenabled */
- Z16F_IRQ_UART0TX, /* txirq */
Z16F_IRQ_UART0RX, /* rxirq */
+ Z16F_IRQ_UART0TX, /* txirq */
CONFIG_UART0_PARITY, /* parity */
CONFIG_UART0_2STOP /* stopbits2 */
};
@@ -185,8 +185,8 @@ static struct z16f_uart_s g_uart1priv =
CONFIG_UART1_BAUD, /* baud */
FALSE, /* rxenabled */
FALSE, /* txenabled */
- Z16F_IRQ_UART1TX, /* txirq */
Z16F_IRQ_UART1RX, /* rxirq */
+ Z16F_IRQ_UART1TX, /* txirq */
CONFIG_UART1_PARITY, /* parity */
CONFIG_UART1_2STOP /* stopbits2 */
};
diff --git a/nuttx/fs/fs_read.c b/nuttx/fs/fs_read.c
index 5d7ac2c54..7500d3599 100644
--- a/nuttx/fs/fs_read.c
+++ b/nuttx/fs/fs_read.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs_read.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -53,7 +53,7 @@
* Global Functions
****************************************************************************/
-int read(int fd, void *buf, unsigned int nbytes)
+int read(int fd, FAR void *buf, unsigned int nbytes)
{
FAR struct filelist *list;
int ret = EBADF;
diff --git a/nuttx/fs/fs_rmdir.c b/nuttx/fs/fs_rmdir.c
index 5f31ab89a..6909bbd60 100644
--- a/nuttx/fs/fs_rmdir.c
+++ b/nuttx/fs/fs_rmdir.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs_rmdir.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -72,7 +72,7 @@
*
****************************************************************************/
-int rmdir(const char *pathname)
+int rmdir(FAR const char *pathname)
{
FAR struct inode *inode;
const char *relpath = NULL;
diff --git a/nuttx/fs/fs_unlink.c b/nuttx/fs/fs_unlink.c
index a3a689411..3a70bb830 100644
--- a/nuttx/fs/fs_unlink.c
+++ b/nuttx/fs/fs_unlink.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs_unlink.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -72,7 +72,7 @@
*
****************************************************************************/
-int unlink(const char *pathname)
+int unlink(FAR const char *pathname)
{
FAR struct inode *inode;
const char *relpath = NULL;
diff --git a/nuttx/fs/fs_write.c b/nuttx/fs/fs_write.c
index 8df9c8233..28fa8664c 100644
--- a/nuttx/fs/fs_write.c
+++ b/nuttx/fs/fs_write.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_write.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -59,7 +59,7 @@
****************************************************************************/
/********************************************************************************************
- * Function: send
+ * Function: write
*
* Description:
* write() writes up to nytes bytes to the file referenced by the file
@@ -108,7 +108,7 @@
*
********************************************************************************************/
-int write(int fd, const void *buf, unsigned int nbytes)
+int write(int fd, FAR const void *buf, unsigned int nbytes)
{
#if CONFIG_NFILE_DESCRIPTORS > 0
FAR struct filelist *list;
diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h
index 03f617b6c..ef5bc26b2 100644
--- a/nuttx/include/unistd.h
+++ b/nuttx/include/unistd.h
@@ -132,18 +132,17 @@ EXTERN int dup(int fd);
EXTERN int dup2(int fd1, int fd2);
EXTERN int fsync(int fd);
EXTERN off_t lseek(int fd, off_t offset, int whence);
-EXTERN int read(int fd, void *buf, unsigned int nbytes);
-EXTERN int unlink(const char *path);
-EXTERN int write(int fd, const void *buf, unsigned int nbytes);
+EXTERN int read(int fd, FAR void *buf, unsigned int nbytes);
+EXTERN int write(int fd, FAR const void *buf, unsigned int nbytes);
/* File path operations */
-EXTERN int unlink(const char *pathname);
-EXTERN int rmdir(const char *pathname);
+EXTERN int unlink(FAR const char *pathname);
+EXTERN int rmdir(FAR const char *pathname);
/* Other */
-EXTERN int getopt(int argc, char *const argv[], const char *optstring);
+EXTERN int getopt(int argc, FAR char *const argv[], FAR const char *optstring);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/lib/lib_getopt.c b/nuttx/lib/lib_getopt.c
index 21b7b1aca..e73ae68d5 100644
--- a/nuttx/lib/lib_getopt.c
+++ b/nuttx/lib/lib_getopt.c
@@ -1,7 +1,7 @@
/****************************************************************************
* lib_getopt.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -46,16 +46,16 @@
* Global Variables
****************************************************************************/
-char *optarg; /* Optional argument following option */
-int optind = 1; /* Index into argv */
-int optopt = '?'; /* unrecognized option character */
+FAR char *optarg; /* Optional argument following option */
+int optind = 1; /* Index into argv */
+int optopt = '?'; /* unrecognized option character */
/****************************************************************************
* Private Variables
****************************************************************************/
-static char *g_optptr = NULL;
-static boolean g_binitialized = FALSE;
+static FAR char *g_optptr = NULL;
+static boolean g_binitialized = FALSE;
/****************************************************************************
* Global Functions
@@ -101,7 +101,7 @@ static boolean g_binitialized = FALSE;
*
****************************************************************************/
-int getopt(int argc, char *const argv[], const char *optstring)
+int getopt(int argc, FAR char *const argv[], FAR const char *optstring)
{
if (argv && optstring)
{
diff --git a/nuttx/sched/task_activate.c b/nuttx/sched/task_activate.c
index b216cc316..a9646cefe 100644
--- a/nuttx/sched/task_activate.c
+++ b/nuttx/sched/task_activate.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* task_activate.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -43,35 +43,35 @@
#include <debug.h>
#include <nuttx/arch.h>
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: task_activate
*
* Description:
@@ -86,7 +86,7 @@
* Return Value:
* Always returns OK
*
- ************************************************************/
+ ****************************************************************************/
STATUS task_activate(FAR _TCB *tcb)
{
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 96df1ae60..31b50da0a 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* task_create.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -46,31 +46,31 @@
#include "os_internal.h"
#include "env_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: task_create
*
* Description:
@@ -105,7 +105,7 @@
* ERROR if memory is insufficient or the task cannot be
* created (errno is not set).
*
- ************************************************************/
+ ****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
int task_create(const char *name, int priority,
diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c
index 52596dc7c..6b80d5db0 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* task_setup.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -46,37 +46,37 @@
#include <nuttx/arch.h>
#include "os_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
/* This is the name for un-named tasks */
static const char g_noname[] = "<noname>";
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
static STATUS task_assignpid(FAR _TCB* tcb);
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: task_assignpid
*
* Description:
@@ -88,13 +88,13 @@ static STATUS task_assignpid(FAR _TCB* tcb);
* Return:
* OK on success; ERROR on failure (errno is not set)
*
- ************************************************************/
+ ****************************************************************************/
static STATUS task_assignpid(FAR _TCB *tcb)
{
pid_t next_pid;
int hash_ndx;
- int tries = 0;
+ int tries;
/* Disable pre-emption. This should provide sufficient protection
* for the following operation.
@@ -142,11 +142,11 @@ static STATUS task_assignpid(FAR _TCB *tcb)
return ERROR;
}
-/************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: task_schedsetup
*
* Description:
@@ -168,7 +168,7 @@ static STATUS task_assignpid(FAR _TCB *tcb)
* This function can only failure is it is unable to assign
* a new, unique task ID to the TCB (errno is not set).
*
- ************************************************************/
+ ****************************************************************************/
STATUS task_schedsetup(FAR _TCB *tcb, int priority,
start_t start, main_t main)
@@ -216,7 +216,7 @@ STATUS task_schedsetup(FAR _TCB *tcb, int priority,
return ret;
}
-/************************************************************
+/****************************************************************************
* Name: task_argsetup
*
* Description:
@@ -240,7 +240,7 @@ STATUS task_schedsetup(FAR _TCB *tcb, int priority,
* Return Value:
* OK
*
- ************************************************************/
+ ****************************************************************************/
STATUS task_argsetup(FAR _TCB *tcb, const char *name, const char *argv[])
{
diff --git a/nuttx/sched/task_start.c b/nuttx/sched/task_start.c
index 9e2a013bf..b06fbb981 100644
--- a/nuttx/sched/task_start.c
+++ b/nuttx/sched/task_start.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* task_start.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -44,35 +44,35 @@
#include <debug.h>
#include "os_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: task_start
*
* Description:
@@ -87,7 +87,7 @@
* Return:
* None
*
- ************************************************************/
+ ****************************************************************************/
void task_start(void)
{