summaryrefslogtreecommitdiff
path: root/nuttx/sched/os_start.c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-02-17 23:21:28 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-02-17 23:21:28 +0000
commite3940eb2080711edac189cca3f642ee89dc215f2 (patch)
tree1c390958fae49e34dce698b175487e6d4681e540 /nuttx/sched/os_start.c
parent2223612deb2cc6322992f8595b6d6f86fcb53ae1 (diff)
downloadpx4-nuttx-e3940eb2080711edac189cca3f642ee89dc215f2.tar.gz
px4-nuttx-e3940eb2080711edac189cca3f642ee89dc215f2.tar.bz2
px4-nuttx-e3940eb2080711edac189cca3f642ee89dc215f2.zip
NuttX RTOS
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched/os_start.c')
-rw-r--r--nuttx/sched/os_start.c382
1 files changed, 382 insertions, 0 deletions
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
new file mode 100644
index 000000000..b4bae75c5
--- /dev/null
+++ b/nuttx/sched/os_start.c
@@ -0,0 +1,382 @@
+/************************************************************
+ * os_start.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 <debug.h>
+#include <string.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/fs.h>
+#include <nuttx/lib.h>
+#include <nuttx/os_external.h>
+#include "os_internal.h"
+#include "sig_internal.h"
+#include "wd_internal.h"
+#include "sem_internal.h"
+#include "mq_internal.h"
+#include "pthread_internal.h"
+#include "clock_internal.h"
+#include "irq_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Type Declarations
+ ************************************************************/
+
+/************************************************************
+ * Global Variables
+ ************************************************************/
+
+/* Task Lists ***********************************************/
+/* The state of a task is indicated both by the task_state field
+ * of the TCB and by a series of task lists. All of these
+ * tasks lists are declared below. Although it is not always
+ * necessary, most of these lists are prioritized so that common
+ * list handling logic can be used (only the g_readytorun,
+ * the g_pendingtasks, and the g_waitingforsemaphore lists need
+ * to be prioritized).
+ */
+
+/* This is the list of all tasks that are ready to run. The head
+ * of this list is the currently active task; the tail of this
+ * list is always the idle task.
+ */
+
+dq_queue_t g_readytorun;
+
+/* This is the list of all tasks that are ready-to-run, but
+ * cannot be placed in the g_readytorun list because: (1) They
+ * are higher priority than the currently active task at the head
+ * of the g_readytorun list, and (2) the currenly active task has
+ * disabled pre-emption.
+ */
+
+dq_queue_t g_pendingtasks;
+
+/* This is the list of all tasks that are blocked waiting for a semaphore */
+
+dq_queue_t g_waitingforsemaphore;
+
+/* This is the list of all tasks that are blocked waiting for a signal */
+
+dq_queue_t g_waitingforsignal;
+
+/* This is the list of all tasks that are blocked waiting for a message
+ * queue to become non-empty.
+ */
+
+dq_queue_t g_waitingformqnotempty;
+
+/* This is the list of all tasks that are blocked waiting for a message
+ * queue to become non-full.
+ */
+
+dq_queue_t g_waitingformqnotfull;
+
+/* This the list of all tasks that have been initialized, but not yet
+ * activated. NOTE: This is the only list that is not prioritized.
+ */
+
+dq_queue_t g_inactivetasks;
+
+/* This is the list of dayed memory deallocations that need to be handled
+ * within the IDLE loop. These deallocations get queued by sched_free()
+ * if the OS attempts to deallocate memory while it is within an interrupt
+ * handler.
+ */
+
+sq_queue_t g_delayeddeallocations;
+
+/* This is the value of the last process ID assigned to a task */
+
+pid_t g_lastpid;
+
+/* The following hash table is used for two things:
+ * 1. This hash table greatly speeds the determination of
+ * a new unique process ID for a task, and
+ * 2. Is used to quickly map a process ID into a TCB.
+ * It has the side effects of using more memory and limiting
+ * the number of tasks to MAX_TASKS_ALLOWED.
+ */
+
+pidhash_t g_pidhash[MAX_TASKS_ALLOWED];
+
+/* This is a table of task lists. This table is indexed by
+ * the task state enumeration type (tstate_t) and provides
+ * a pointer to the associated static task list (if there
+ * is one) as well as a boolean indication as to if the list
+ * is an ordered list or not.
+ */
+
+const tasklist_t g_tasklisttable[NUM_TASK_STATES] =
+{
+ { NULL, FALSE }, /* TSTATE_TASK_INVALID */
+ { &g_pendingtasks, TRUE }, /* TSTATE_TASK_PENDING */
+ { &g_readytorun, TRUE }, /* TSTATE_TASK_READYTORUN */
+ { &g_readytorun, TRUE }, /* TSTATE_TASK_RUNNING */
+ { &g_inactivetasks, FALSE }, /* TSTATE_TASK_INACTIVE */
+ { &g_waitingforsemaphore, TRUE }, /* TSTATE_WAIT_SEM */
+ { &g_waitingforsignal, FALSE }, /* TSTATE_WAIT_SIG */
+ { &g_waitingformqnotempty, TRUE }, /* TSTATE_WAIT_MQNOTEMPTY */
+ { &g_waitingformqnotfull, TRUE } /* TSTATE_WAIT_MQNOTFULL */
+};
+
+/************************************************************
+ * Private Variables
+ ************************************************************/
+/* This is the task control block for this thread of execution.
+ * This thread of execution is the idle task. NOTE: the
+ * system boots into the idle task. The idle task spawns
+ * the user init task and the user init task is responsible
+ * for bringing up the rest of the system
+ */
+
+static _TCB g_idletcb;
+
+/************************************************************
+ * Private Function Prototypes
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: os_start
+ * Description: This function is called to initialize the
+ * operating system and to spawn the user init thread of
+ * execution
+ ************************************************************/
+
+void os_start(void)
+{
+ int init_taskid;
+ int i;
+
+ lldbg("os_start:\n");
+
+ /* Initialize all task lists */
+
+ dq_init(&g_readytorun);
+ dq_init(&g_pendingtasks);
+ dq_init(&g_waitingforsemaphore);
+ dq_init(&g_waitingforsignal);
+ dq_init(&g_waitingformqnotfull);
+ dq_init(&g_waitingformqnotempty);
+ dq_init(&g_inactivetasks);
+ sq_init(&g_delayeddeallocations);
+
+ /* Initialize the logic that determine unique process IDs. */
+
+ g_lastpid = 0;
+ for (i = 0; i < MAX_TASKS_ALLOWED; i++)
+ {
+ g_pidhash[i].tcb = NULL;
+ g_pidhash[i].pid = INVALID_PROCESS_ID;
+ }
+
+ /* Assign the process ID of ZERO to the idle task */
+
+ g_pidhash[ PIDHASH(0)].tcb = &g_idletcb;
+ g_pidhash[ PIDHASH(0)].pid = 0;
+
+ /* Initialize a TCB for this thread of execution. NOTE: The default
+ * value for most components of the g_idletcb are zero. The entire
+ * structure is set to zero. Then only the (potentially) non-zero
+ * elements are initialized. NOTE: The idle task is the only task in
+ * that has pid == 0 and sched_priority == 0.
+ */
+
+ bzero((void*)&g_idletcb, sizeof(_TCB));
+ g_idletcb.task_state = TSTATE_TASK_RUNNING;
+ g_idletcb.entry.main = (main_t)os_start;
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ strncpy(g_idletcb.name, "Idle Task", CONFIG_TASK_NAME_SIZE-1);
+ g_idletcb.argv[0] = g_idletcb.name;
+#else
+ g_idletcb.argv[0] = "Idle Task";
+#endif /* CONFIG_TASK_NAME_SIZE */
+
+ /* 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);
+
+ /* Initialize the processor-specific portion of the TCB */
+
+ up_initial_state(&g_idletcb);
+
+ /* Initialize the memory manager */
+
+#ifndef CONFIG_HEAP_BASE
+ {
+ void *heap_start;
+ size_t heap_size;
+ up_allocate_heap(&heap_start, &heap_size);
+ mm_initialize(heap_start, heap_size);
+ }
+#else
+ mm_initialize((void*)CONFIG_HEAP_BASE, CONFIG_HEAP_SIZE);
+#endif
+
+ /* Initialize the interrupt handling subsystem (if included) */
+
+ if (irq_initialize != NULL)
+ {
+ irq_initialize();
+ }
+
+ /* Provide an access point to initialize any user-specific logic very
+ * early in the initialization sequence. Note that user_ininitialize()
+ * is called only if it is provided in the link.
+ */
+
+ if (user_initialize != NULL)
+ {
+ user_initialize();
+ }
+
+ /* Initialize the POSIX timer facility (if included in the link) */
+
+ if (clock_initialize != NULL)
+ {
+ clock_initialize();
+ }
+
+ /* Initialize the watchdog facility (if included in the link) */
+
+ if (wd_initialize != NULL)
+ {
+ wd_initialize();
+ }
+
+ /* Initialize the signal facility (if in link) */
+
+ if (sig_initialize != NULL)
+ {
+ sig_initialize();
+ }
+
+ /* Initialize the semaphore facility. (if in link) */
+
+ if (sem_initialize != NULL)
+ {
+ sem_initialize();
+ }
+
+ /* Initialize the named message queue facility (if in link) */
+
+ if (mq_initialize != NULL)
+ {
+ mq_initialize();
+ }
+
+ /* Initialize the thread-specific data facility (if in link) */
+
+ if (pthread_initialize != NULL)
+ {
+ pthread_initialize();
+ }
+
+ /* Initialize the file system (needed to support device drivers) */
+
+ if (fs_initialize != NULL)
+ {
+ fs_initialize();
+ }
+
+ /* The processor specific details of running the operating system
+ * will be handled here. Such things as setting up interrupt
+ * service routines and starting the clock are some of the things
+ * that are different for each processor and hardware platform.
+ */
+
+ up_initialize();
+
+ /* Initialize the C libraries (if included in the link). This
+ * is done last because the libraries may depend on the above.
+ */
+
+ if (lib_initialize != NULL)
+ {
+ lib_initialize();
+ }
+
+ /* Create stdout, stderr, stdin */
+
+ (void)sched_setupidlefiles(&g_idletcb);
+
+ /* Once the operating system has been initialized, the system must be
+ * started by spawning the user init thread of execution.
+ */
+
+ dbg("os_start: Starting init thread\n");
+ init_taskid = task_create("init", SCHED_PRIORITY_DEFAULT,
+ CONFIG_PROC_STACK_SIZE,
+ (main_t)user_start, 0, 0, 0, 0);
+ ASSERT(init_taskid != ERROR);
+
+ /* When control is return to this point, the system is idle. */
+
+ dbg("os_start: Beginning Idle Loop\n");
+ for (;;)
+ {
+ /* Check if there is anything in the delayed deallocation list. */
+
+ while (g_delayeddeallocations.head)
+ {
+ /* Remove the first delayed deallocation. */
+
+ uint32 savedState = irqsave();
+ void *address = (void*)sq_remfirst(&g_delayeddeallocations);
+ irqrestore(savedState);
+
+ /* Then deallocate it */
+
+ if (address) sched_free(address);
+ }
+
+ /* Perform idle state operations */
+
+ up_idle();
+ }
+}