summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/c5471/defconfig3
-rw-r--r--nuttx/arch/c5471/src/up_irq.c4
-rw-r--r--nuttx/arch/sim/defconfig3
-rw-r--r--nuttx/examples/ostest/main.c5
-rw-r--r--nuttx/include/nuttx/arch.h8
-rw-r--r--nuttx/include/nuttx/irq.h4
-rw-r--r--nuttx/include/sched.h15
-rw-r--r--nuttx/include/string.h10
-rw-r--r--nuttx/lib/lib_memcmp.c2
-rw-r--r--nuttx/lib/lib_memcpy.c2
-rw-r--r--nuttx/lib/lib_memmove.c2
-rw-r--r--nuttx/lib/lib_memset.c2
-rw-r--r--nuttx/sched/Makefile2
-rw-r--r--nuttx/sched/get_errno_ptr.c2
-rw-r--r--nuttx/sched/os_internal.h1
-rw-r--r--nuttx/sched/os_start.c5
-rw-r--r--nuttx/sched/sched_releasetcb.c2
-rw-r--r--nuttx/sched/task_create.c135
-rw-r--r--nuttx/sched/task_init.c114
19 files changed, 225 insertions, 96 deletions
diff --git a/nuttx/arch/c5471/defconfig b/nuttx/arch/c5471/defconfig
index d0d7c755b..90ae4c898 100644
--- a/nuttx/arch/c5471/defconfig
+++ b/nuttx/arch/c5471/defconfig
@@ -200,6 +200,8 @@ CONFIG_PREALLOC_WDOGS=32
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
# operation from FLASH.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
# CONFIG_PROC_STACK_SIZE - The size of the initial stack
# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
@@ -208,6 +210,7 @@ CONFIG_PREALLOC_WDOGS=32
# CONFIG_HEAP_SIZE - The size of the heap
#
CONFIG_BOOT_FROM_FLASH=n
+CONFIG_CUSTOM_STACK=n
CONFIG_STACK_POINTER=
CONFIG_PROC_STACK_SIZE=4096
CONFIG_PTHREAD_STACK_MIN=256
diff --git a/nuttx/arch/c5471/src/up_irq.c b/nuttx/arch/c5471/src/up_irq.c
index 3c8a17371..9c05bc91b 100644
--- a/nuttx/arch/c5471/src/up_irq.c
+++ b/nuttx/arch/c5471/src/up_irq.c
@@ -189,7 +189,7 @@ void up_irqinitialize(void)
void up_disable_irq(int irq)
{
- if (irq < NR_IRQS)
+ if ((unsigned)irq < NR_IRQS)
{
uint32 reg = getreg32(MASK_IT_REG);
putreg32(reg | (1 << irq), MASK_IT_REG);
@@ -206,7 +206,7 @@ void up_disable_irq(int irq)
void up_enable_irq(int irq)
{
- if (irq < NR_IRQS)
+ if ((unsigned)irq < NR_IRQS)
{
uint32 reg = getreg32(MASK_IT_REG);
putreg32(reg & ~(1 << irq), MASK_IT_REG);
diff --git a/nuttx/arch/sim/defconfig b/nuttx/arch/sim/defconfig
index 58648c509..9a3cb893c 100644
--- a/nuttx/arch/sim/defconfig
+++ b/nuttx/arch/sim/defconfig
@@ -167,6 +167,8 @@ CONFIG_PREALLOC_WDOGS=32
#
# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
# operation from FLASH.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
# CONFIG_STACK_POINTER - The initial stack pointer
# CONFIG_PROC_STACK_SIZE - The size of the initial stack
# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
@@ -175,6 +177,7 @@ CONFIG_PREALLOC_WDOGS=32
# CONFIG_HEAP_SIZE - The size of the heap
#
CONFIG_BOOT_FROM_FLASH=n
+CONFIG_CUSTOM_STACK=n
CONFIG_PROC_STACK_SIZE=0x00001000
CONFIG_PTHREAD_STACK_MIN=256
CONFIG_PTHREAD_STACK_DEFAULT=8192
diff --git a/nuttx/examples/ostest/main.c b/nuttx/examples/ostest/main.c
index 69d783c7f..8e09230f5 100644
--- a/nuttx/examples/ostest/main.c
+++ b/nuttx/examples/ostest/main.c
@@ -191,8 +191,13 @@ int user_start(int parm1, int parm2, int parm3, int parm4)
/* Verify that we can spawn a new task */
+#ifndef CONFIG_CUSTOM_STACK
result = task_create("ostest", PRIORITY, STACKSIZE, user_main,
arg1, arg2, arg3, arg4);
+#else
+ result = task_create("ostest", PRIORITY, user_main,
+ arg1, arg2, arg3, arg4);
+#endif
if (result == ERROR)
{
printf("user_start: ERROR Failed to start user_main\n");
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index 11e6a96fc..a243a3f6a 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -150,7 +150,9 @@ EXTERN void up_initial_state(FAR _TCB *tcb);
* must be allocated.
************************************************************/
+#ifndef CONFIG_CUSTOM_STACK
EXTERN STATUS up_create_stack(FAR _TCB *tcb, size_t stack_size);
+#endif
/************************************************************
* Name: up_use_stack
@@ -173,7 +175,9 @@ EXTERN STATUS up_create_stack(FAR _TCB *tcb, size_t stack_size);
*
************************************************************/
+#ifndef CONFIG_CUSTOM_STACK
EXTERN STATUS up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
+#endif
/************************************************************
* Name: up_release_stack
@@ -184,7 +188,9 @@ EXTERN STATUS up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
*
************************************************************/
+#ifndef CONFIG_CUSTOM_STACK
EXTERN void up_release_stack(FAR _TCB *dtcb);
+#endif
/************************************************************
* Name: up_unblock_task
@@ -314,7 +320,9 @@ EXTERN void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority);
*
************************************************************/
+#ifndef CONFIG_DISABLE_SIGNALS
EXTERN void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver);
+#endif
/************************************************************
* Name: up_allocate_heap
diff --git a/nuttx/include/nuttx/irq.h b/nuttx/include/nuttx/irq.h
index a806adb15..e9b66293c 100644
--- a/nuttx/include/nuttx/irq.h
+++ b/nuttx/include/nuttx/irq.h
@@ -73,10 +73,6 @@ typedef int (*swint_t)(int code, int parm2, int parm3,
* Public Variables
************************************************************/
-#ifndef __ASSEMBLY__
-struct xcptcontext *current_xcp;
-#endif
-
/************************************************************
* Public Function Prototypes
************************************************************/
diff --git a/nuttx/include/sched.h b/nuttx/include/sched.h
index f83cfbe53..0cf8d58d5 100644
--- a/nuttx/include/sched.h
+++ b/nuttx/include/sched.h
@@ -190,6 +190,7 @@ struct _TCB
/* Stack-Related Fields *********************************************/
+#ifndef CONFIG_CUSTOM_STACK
size_t adj_stack_size; /* Stack size after adjustment */
/* for hardware, processor, etc. */
/* (for debug purposes only) */
@@ -197,6 +198,7 @@ struct _TCB
/* Need to deallocate stack */
FAR void *adj_stack_ptr; /* Adjusted StatckAllocPtr for HW */
/* The initial stack pointer value */
+#endif
/* POSIX thread Specific Data ***************************************/
@@ -269,14 +271,27 @@ extern "C" {
/* Task Control Interfaces (non-standard) */
+#ifndef CONFIG_CUSTOM_STACK
EXTERN 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);
+#else
+EXTERN STATUS task_init(FAR _TCB *tcb, const char *name, int priority,
+ main_t entry,
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4);
+#endif
EXTERN STATUS task_activate(FAR _TCB *tcb);
+#ifndef CONFIG_CUSTOM_STACK
EXTERN int task_create(const char *name, int priority, int stack_size, main_t main,
FAR char *arg1, FAR char *arg2,
FAR char *arg3, FAR char *arg4);
+#else
+EXTERN int task_create(const char *name, int priority, main_t main,
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4);
+#endif
EXTERN STATUS task_delete(pid_t pid);
EXTERN STATUS task_restart(pid_t pid);
diff --git a/nuttx/include/string.h b/nuttx/include/string.h
index 0b05eccc5..a5c1a1a9e 100644
--- a/nuttx/include/string.h
+++ b/nuttx/include/string.h
@@ -74,12 +74,12 @@ EXTERN char *strrchr(const char *, int);
EXTERN size_t strspn(const char *, const char *);
EXTERN size_t strcspn(const char *, const char *);
EXTERN char *strstr(const char *, const char *);
-EXTERN char *strtok(FAR char *, const char *);
+EXTERN char *strtok(char *, const char *);
-EXTERN void *memset(FAR void *s, int c, size_t n);
-EXTERN void *memcpy(FAR void *dest, FAR const void *src, size_t n);
-EXTERN int memcmp(FAR const void *s1, FAR const void *s2, size_t n);
-EXTERN void *memmove(FAR void *dest, FAR const void *src, size_t count);
+EXTERN void *memset(void *s, int c, size_t n);
+EXTERN void *memcpy(void *dest, const void *src, size_t n);
+EXTERN int memcmp(const void *s1, const void *s2, size_t n);
+EXTERN void *memmove(void *dest, const void *src, size_t count);
#ifndef CONFIG_ARCH_BZERO
# define bzero(s,n) (void)memset(s,0,n)
diff --git a/nuttx/lib/lib_memcmp.c b/nuttx/lib/lib_memcmp.c
index 5de0b1c49..b433eda90 100644
--- a/nuttx/lib/lib_memcmp.c
+++ b/nuttx/lib/lib_memcmp.c
@@ -50,7 +50,7 @@
************************************************************/
#ifndef CONFIG_ARCH_MEMCMP
-int memcmp(FAR const void *s1, FAR const void *s2, size_t n)
+int memcmp(const void *s1, const void *s2, size_t n)
{
unsigned char *p1 = (unsigned char *)s1;
unsigned char *p2 = (unsigned char *)s2;
diff --git a/nuttx/lib/lib_memcpy.c b/nuttx/lib/lib_memcpy.c
index 417fdc82f..0953b4d28 100644
--- a/nuttx/lib/lib_memcpy.c
+++ b/nuttx/lib/lib_memcpy.c
@@ -50,7 +50,7 @@
************************************************************/
#ifndef CONFIG_ARCH_MEMCPY
-void *memcpy(FAR void *dest, FAR const void *src, size_t n)
+void *memcpy(void *dest, const void *src, size_t n)
{
unsigned char *pout = (unsigned char*)dest;
unsigned char *pin = (unsigned char*)src;
diff --git a/nuttx/lib/lib_memmove.c b/nuttx/lib/lib_memmove.c
index c64045204..cad0fa2fc 100644
--- a/nuttx/lib/lib_memmove.c
+++ b/nuttx/lib/lib_memmove.c
@@ -50,7 +50,7 @@
************************************************************/
#ifndef CONFIG_ARCH_MEMMOVE
-void *memmove(FAR void *dest, FAR const void *src, size_t count)
+void *memmove(void *dest, const void *src, size_t count)
{
char *tmp, *s;
if (dest <= src)
diff --git a/nuttx/lib/lib_memset.c b/nuttx/lib/lib_memset.c
index 33bead8db..25b4929eb 100644
--- a/nuttx/lib/lib_memset.c
+++ b/nuttx/lib/lib_memset.c
@@ -50,7 +50,7 @@
************************************************************/
#ifndef CONFIG_ARCH_MEMSET
-void *memset(FAR void *s, int c, size_t n)
+void *memset(void *s, int c, size_t n)
{
unsigned char *p = (unsigned char*)s;
while (n-- > 0) *p++ = c;
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index af11ede39..d110cb664 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -44,7 +44,7 @@ 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
-TSK_SRCS = task_create.c task_delete.c task_restart.c \
+TSK_SRCS = task_create.c task_init.c task_delete.c task_restart.c \
exit.c abort.c atexit.c getpid.c \
sched_addreadytorun.c sched_removereadytorun.c sched_addprioritized.c \
sched_mergepending.c sched_addblocked.c sched_removeblocked.c \
diff --git a/nuttx/sched/get_errno_ptr.c b/nuttx/sched/get_errno_ptr.c
index 7a8084c71..23503243b 100644
--- a/nuttx/sched/get_errno_ptr.c
+++ b/nuttx/sched/get_errno_ptr.c
@@ -41,6 +41,8 @@
#include <errno.h>
#include "os_internal.h"
+#undef get_errno_ptr
+
/************************************************************
* Global Functions
************************************************************/
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 900484d9b..26a709a99 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -239,6 +239,7 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
* Public Function Prototypes
************************************************************/
+extern void task_start(void);
extern STATUS _task_init(FAR _TCB *tcb, const char *name, int priority,
start_t start, main_t main,
boolean pthread,
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 1238342c4..18b8945ee 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -405,9 +405,14 @@ void os_start(void)
*/
dbg("Starting init thread\n");
+#ifndef CONFIG_CUSTOM_STACK
init_taskid = task_create("init", SCHED_PRIORITY_DEFAULT,
CONFIG_PROC_STACK_SIZE,
(main_t)user_start, 0, 0, 0, 0);
+#else
+ init_taskid = task_create("init", SCHED_PRIORITY_DEFAULT,
+ (main_t)user_start, 0, 0, 0, 0);
+#endif
ASSERT(init_taskid != ERROR);
/* When control is return to this point, the system is idle. */
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 5e644839d..6415fba2b 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -110,10 +110,12 @@ int sched_releasetcb(FAR _TCB *tcb)
/* Delete the thread's stack if one has been allocated */
+#ifndef CONFIG_CUSTOM_STACK
if (tcb->stack_alloc_ptr)
{
up_release_stack(tcb);
}
+#endif
/* Release command line arguments that were allocated
* for task start/re-start.
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 399bba20c..7b73c15fa 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -70,7 +70,6 @@ static FAR char g_noname[] = "no name";
* Private Function Prototypes
************************************************************/
-static void task_start(void);
static STATUS task_assignpid(FAR _TCB* tcb);
/************************************************************
@@ -78,46 +77,6 @@ static STATUS task_assignpid(FAR _TCB* tcb);
************************************************************/
/************************************************************
- * Name: task_start
- *
- * Description:
- * This function is the low level entry point
- * into the main thread of execution of a task. It receives
- * initial control when the task is started and calls main
- * entry point of the newly started task.
- *
- * Inputs:
- * None
- *
- * Return:
- * None
- *
- ************************************************************/
-
-static void task_start(void)
-{
- FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
- int argc;
-
- /* Count how many non-null arguments we are passing */
-
- for (argc = 1; argc <= NUM_TASK_ARGS; argc++)
- {
- /* The first non-null argument terminates the list */
-
- if (!tcb->argv[argc])
- {
- break;
- }
- }
-
- /* Call the 'main' entry point passing argc and argv. If/when
- * the task returns, */
-
- exit(tcb->entry.main(argc, tcb->argv));
-}
-
-/************************************************************
* Name: task_assignpid
*
* Description:
@@ -188,15 +147,55 @@ static STATUS task_assignpid(FAR _TCB *tcb)
************************************************************/
/************************************************************
- * Name: _task_init and task_init
+ * Name: task_start
+ *
+ * Description:
+ * This function is the low level entry point
+ * into the main thread of execution of a task. It receives
+ * initial control when the task is started and calls main
+ * entry point of the newly started task.
+ *
+ * Inputs:
+ * None
+ *
+ * Return:
+ * None
+ *
+ ************************************************************/
+
+void task_start(void)
+{
+ FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
+ int argc;
+
+ /* Count how many non-null arguments we are passing */
+
+ for (argc = 1; argc <= NUM_TASK_ARGS; argc++)
+ {
+ /* The first non-null argument terminates the list */
+
+ if (!tcb->argv[argc])
+ {
+ break;
+ }
+ }
+
+ /* Call the 'main' entry point passing argc and argv. If/when
+ * the task returns, */
+
+ exit(tcb->entry.main(argc, tcb->argv));
+}
+
+/************************************************************
+ * Name: _task_init
*
* Description:
- * These functions initializes a Task Control Block (TCB)
+ * This functions initializes a Task Control Block (TCB)
* in preparation for starting a new thread. _task_init()
- * is an internal version of the function that has some
- * additional control arguments and task_init() is a wrapper
- * function that creates a VxWorks-like user API.
- * task_init() is, otherwise, not used by the OS.
+ * is an internal version of the task_init() function that
+ * has some additional control arguments and task_init()
+ * is a wrapper function that creates a VxWorks-like user
+ * API. task_init() is, otherwise, not used by the OS.
*
* _task_init() is called from task_init() and task_start().\
* It is also called from pthread_create() to create a
@@ -333,39 +332,6 @@ STATUS _task_init(FAR _TCB *tcb, const char *name, int priority,
}
/************************************************************
- * Name: _task_init and task_init
- *
- * Description:
- * This is a wrapper around the internal _task_init() that
- * provides a VxWorks-like API. See _task_init() for
- * further information.
- *
- * Input Parameters:
- * tcb - Address of the new task's TCB
- * name - Name of the new task (not used)
- * priority - Priority of the new task
- * stack - start of the pre-allocated stack
- * stack_size - size (in bytes) of the stack allocated
- * entry - Application start point of the new task
- * arg1-4 - Four required task arguments to pass to
- * the task when it is started.
- *
- * Return Value:
- * see _task_init()
- *
- ************************************************************/
-
-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,
- FALSE, arg1, arg2, arg3, arg4);
-}
-
-/************************************************************
* Name: task_activate
*
* Description:
@@ -441,10 +407,17 @@ STATUS task_activate(FAR _TCB *tcb)
*
************************************************************/
+#ifndef CONFIG_CUSTOM_STACK
int task_create(const char *name, int priority,
int stack_size, main_t entry,
FAR char *arg1, FAR char *arg2,
FAR char *arg3, FAR char *arg4)
+#else
+int task_create(const char *name, int priority,
+ main_t entry,
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4)
+#endif
{
FAR _TCB *tcb;
STATUS status;
@@ -469,12 +442,14 @@ int task_create(const char *name, int priority,
/* Allocate the stack for the TCB */
+#ifndef CONFIG_CUSTOM_STACK
status = up_create_stack(tcb, stack_size);
if (status != OK)
{
sched_releasetcb(tcb);
return ERROR;
}
+#endif
/* Initialize the task control block */
diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c
new file mode 100644
index 000000000..17596378b
--- /dev/null
+++ b/nuttx/sched/task_init.c
@@ -0,0 +1,114 @@
+/************************************************************
+ * task_init.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 <sched.h>
+#include "os_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Type Declarations
+ ************************************************************/
+
+/************************************************************
+ * Global Variables
+ ************************************************************/
+
+/************************************************************
+ * Private Variables
+ ************************************************************/
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: task_init
+ *
+ * Description:
+ * This is a wrapper around the internal _task_init() that
+ * provides a VxWorks-like API. See _task_init() for
+ * further information.
+ *
+ * Input Parameters:
+ * tcb - Address of the new task's TCB
+ * name - Name of the new task (not used)
+ * priority - Priority of the new task
+ * stack - start of the pre-allocated stack
+ * stack_size - size (in bytes) of the stack allocated
+ * entry - Application start point of the new task
+ * arg1-4 - Four required task arguments to pass to
+ * the task when it is started.
+ *
+ * Return Value:
+ * see _task_init()
+ *
+ ************************************************************/
+
+#ifndef CONFIG_CUSTOM_STACK
+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,
+ FALSE, arg1, arg2, arg3, arg4);
+}
+#else
+STATUS task_init(FAR _TCB *tcb, const char *name, int priority,
+ main_t entry,
+ FAR char *arg1, FAR char *arg2,
+ FAR char *arg3, FAR char *arg4)
+{
+ return _task_init(tcb, name, priority, task_start, entry,
+ FALSE, arg1, arg2, arg3, arg4);
+}
+#endif