summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/os_bringup.c12
-rw-r--r--nuttx/sched/os_internal.h20
-rw-r--r--nuttx/sched/os_start.c1
-rw-r--r--nuttx/sched/pthread_create.c10
-rw-r--r--nuttx/sched/task_create.c170
-rw-r--r--nuttx/sched/task_setup.c3
6 files changed, 162 insertions, 54 deletions
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/os_bringup.c
index 84971ad6c..9f05a3c70 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/os_bringup.c
@@ -141,9 +141,9 @@ int os_bringup(void)
#ifdef CONFIG_PAGING
svdbg("Starting paging thread\n");
- g_pgworker = TASK_CREATE("pgfill", CONFIG_PAGING_DEFPRIO,
- CONFIG_PAGING_STACKSIZE,
- (main_t)pg_worker, (const char **)NULL);
+ g_pgworker = KERNEL_THREAD("pgfill", CONFIG_PAGING_DEFPRIO,
+ CONFIG_PAGING_STACKSIZE,
+ (main_t)pg_worker, (const char **)NULL);
ASSERT(g_pgworker != ERROR);
#endif
@@ -152,9 +152,9 @@ int os_bringup(void)
#ifdef CONFIG_SCHED_WORKQUEUE
svdbg("Starting worker thread\n");
- g_worker = TASK_CREATE("work", CONFIG_SCHED_WORKPRIORITY,
- CONFIG_SCHED_WORKSTACKSIZE,
- (main_t)work_thread, (const char **)NULL);
+ g_worker = KERNEL_THREAD("work", CONFIG_SCHED_WORKPRIORITY,
+ CONFIG_SCHED_WORKSTACKSIZE,
+ (main_t)work_thread, (const char **)NULL);
ASSERT(g_worker != ERROR);
#endif
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 8cd7257b4..ceeb70df1 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -106,6 +106,18 @@ enum os_crash_codes_e
# define sched_releasefiles(t) (OK)
#endif
+/* One processor family supported by NuttX has a single, fixed hardware stack.
+ * That is the 8051 family. So for that family only, there is a variant form
+ * of kernel_thread() that does not take a stack size parameter. The following
+ * helper macro is provided to work around the ugliness of that exception.
+ */
+
+#ifndef CONFIG_CUSTOM_STACK
+# define KERNEL_THREAD(n,p,s,e,a) task_create(n,p,s,e,a)
+#else
+# define KERNEL_THREAD(n,p,s,e,a) task_create(n,p,e,a)
+#endif
+
/* A more efficient ways to access the errno */
#define SET_ERRNO(e) \
@@ -254,7 +266,13 @@ extern int task_schedsetup(FAR _TCB *tcb, int priority, start_t start,
main_t main);
extern int task_argsetup(FAR _TCB *tcb, const char *name, const char *argv[]);
extern int task_deletecurrent(void);
-
+#ifndef CONFIG_CUSTOM_STACK
+extern int kernel_thread(const char *name, int priority,
+ int stack_size, main_t entry, const char *argv[]);
+#else
+extern int kernel_thread(const char *name, int priority,
+ main_t entry, const char *argv[]);
+#endif
extern bool sched_addreadytorun(FAR _TCB *rtrtcb);
extern bool sched_removereadytorun(FAR _TCB *rtrtcb);
extern bool sched_addprioritized(FAR _TCB *newTcb, DSEG dq_queue_t *list);
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index da34ad895..412c24ebc 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -287,6 +287,7 @@ void os_start(void)
/* Initialize the processor-specific portion of the TCB */
+ g_idletcb.flags = TCB_FLAG_TTYPE_KERNEL;
up_initial_state(&g_idletcb);
/* Initialize the memory manager */
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index e247ce372..d51a5956b 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -340,6 +340,12 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
#endif
}
+ /* Mark this task as a pthread (this setting will be needed in
+ * task_schedsetup() when up_initial_state() is called.
+ */
+
+ ptcb->flags |= TCB_FLAG_TTYPE_PTHREAD;
+
/* Initialize the task control block */
status = task_schedsetup(ptcb, priority, pthread_start,
@@ -352,10 +358,6 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
return EBUSY;
}
- /* Mark this task as a pthread */
-
- ptcb->flags |= TCB_FLAG_TTYPE_PTHREAD;
-
/* Configure the TCB for a pthread receiving on parameter
* passed by value
*/
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 3965e61ef..23478c810 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -67,32 +67,21 @@
****************************************************************************/
/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
- * Name: task_create
+ * Name: thread_create
*
* Description:
- * This function creates and activates a new task with a
- * specified priority and returns its system-assigned ID.
- *
- * The entry address entry is the address of the "main"
- * function of the task. This function will be called once
- * the C environment has been set up. The specified
- * function will be called with four arguments. Should
- * the specified routine return, a call to exit() will
- * automatically be made.
- *
- * Note that four (and only four) arguments must be passed for
- * the spawned functions.
+ * This function creates and activates a new thread of the specified type
+ * with a specified priority and returns its system-assigned ID. It is the
+ * internal, commn implementation of task_create() and kernel_thread(). See
+ * comments with task_create() for further information.
*
* Input Parameters:
* name - Name of the new task
+ * type - Type of the new task
* priority - Priority of the new task
* stack_size - size (in bytes) of the stack needed
* entry - Entry point of a new task
@@ -105,40 +94,39 @@
* NULL.
*
* Return Value:
- * Returns the non-zero process ID of the new task or
- * ERROR if memory is insufficient or the task cannot be
- * created (errno is not set).
+ * Returns the non-zero process ID of the new task or ERROR if memory is
+ * insufficient or the task cannot be created. The errno will be set to
+ * indicate the nature of the error (always ENOMEM).
*
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-int task_create(const char *name, int priority,
- int stack_size, main_t entry, const char *argv[])
+static int thread_create(const char *name, uint8_t type, int priority,
+ int stack_size, main_t entry, const char **argv)
#else
-int task_create(const char *name, int priority,
- main_t entry, const char *argv[])
+static int thread_create(const char *name, uint8_t type, int priority,
+ main_t entry, const char **argv)
#endif
{
FAR _TCB *tcb;
- int status;
pid_t pid;
+ int ret;
/* Allocate a TCB for the new task. */
tcb = (FAR _TCB*)kzalloc(sizeof(_TCB));
if (!tcb)
{
- errno = ENOMEM;
- return ERROR;
+ goto errout;
}
/* Associate file descriptors with the new task */
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- if (sched_setuptaskfiles(tcb) != OK)
+ ret = sched_setuptaskfiles(tcb);
+ if (ret != OK)
{
- sched_releasetcb(tcb);
- return ERROR;
+ goto errout_with_tcb;
}
#endif
@@ -149,21 +137,25 @@ 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)
+ ret = up_create_stack(tcb, stack_size);
+ if (ret != OK)
{
- sched_releasetcb(tcb);
- return ERROR;
+ goto errout_with_tcb;
}
#endif
+ /* Mark the type of this thread (this setting will be needed in
+ * task_schedsetup() when up_initial_state() is called.
+ */
+
+ tcb->flags |= type;
+
/* Initialize the task control block */
- status = task_schedsetup(tcb, priority, task_start, entry);
- if (status != OK)
+ ret = task_schedsetup(tcb, priority, task_start, entry);
+ if (ret != OK)
{
- sched_releasetcb(tcb);
- return ERROR;
+ goto errout_with_tcb;
}
/* Setup to pass parameters to the new task */
@@ -176,13 +168,107 @@ int task_create(const char *name, int priority,
/* Activate the task */
- status = task_activate(tcb);
- if (status != OK)
+ ret = task_activate(tcb);
+ if (ret != OK)
{
dq_rem((FAR dq_entry_t*)tcb, (dq_queue_t*)&g_inactivetasks);
- sched_releasetcb(tcb);
- return ERROR;
+ goto errout_with_tcb;
}
return pid;
+
+errout_with_tcb:
+ sched_releasetcb(tcb);
+
+errout:
+ errno = ENOMEM;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: task_create
+ *
+ * Description:
+ * This function creates and activates a new task with a
+ * specified priority and returns its system-assigned ID.
+ *
+ * The entry address entry is the address of the "main"
+ * function of the task. This function will be called once
+ * the C environment has been set up. The specified
+ * function will be called with four arguments. Should
+ * the specified routine return, a call to exit() will
+ * automatically be made.
+ *
+ * Note that four (and only four) arguments must be passed for
+ * the spawned functions.
+ *
+ * Input Parameters:
+ * name - Name of the new task
+ * priority - Priority of the new task
+ * stack_size - size (in bytes) of the stack needed
+ * entry - Entry point of a new task
+ * arg - A pointer to an array of input parameters.
+ * Up to CONFIG_MAX_TASK_ARG parameters may
+ * be provided. If fewer than CONFIG_MAX_TASK_ARG
+ * parameters are passed, the list should be
+ * terminated with a NULL argv[] value.
+ * If no parameters are required, argv may be
+ * NULL.
+ *
+ * Return Value:
+ * Returns the non-zero process ID of the new task or ERROR if memory is
+ * insufficient or the task cannot be created. The errno will be set to
+ * indicate the nature of the error (always ENOMEM).
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_CUSTOM_STACK
+int task_create(const char *name, int priority,
+ int stack_size, main_t entry, const char *argv[])
+#else
+int task_create(const char *name, int priority,
+ main_t entry, const char *argv[])
+#endif
+{
+#ifndef CONFIG_CUSTOM_STACK
+ return thread_create(name, TCB_FLAG_TTYPE_TASK, priority, stack_size, entry, argv);
+#else
+ return thread_create(name, TCB_FLAG_TTYPE_TASK, priority, entry, argv);
+#endif
}
+
+/****************************************************************************
+ * Name: kernel_thread
+ *
+ * Description:
+ * This function creates and activates a kernel thread task with kernel-
+ * mode privileges. It is identical to task_create() except that it
+ * configures the newly started thread to run in kernel model.
+ *
+ * Input Parameters:
+ * (same as task_create())
+ *
+ * Return Value:
+ * (same as task_create())
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_CUSTOM_STACK
+int kernel_thread(const char *name, int priority,
+ int stack_size, main_t entry, const char *argv[])
+#else
+int kernel_thread(const char *name, int priority,
+ main_t entry, const char *argv[])
+#endif
+{
+#ifndef CONFIG_CUSTOM_STACK
+ return thread_create(name, TCB_FLAG_TTYPE_KERNEL, priority, stack_size, entry, argv);
+#else
+ return thread_create(name, TCB_FLAG_TTYPE_KERNEL, priority, entry, argv);
+#endif
+}
+
diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c
index 217bdc892..9fdbf3d25 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/task_setup.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -202,6 +202,7 @@ static inline void task_dupdspace(FAR _TCB *tcb)
* priority - Priority of the new task
* entry - Entry point of a new task
* main - Application start point of the new task
+ * type - Type of the new thread: task, pthread, or kernel thread
*
* Return Value:
* OK on success; ERROR on failure.