summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-08-08 15:30:59 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-08-08 15:30:59 -0600
commitb415d5f6e7f3bb0e4eca3c51d8a121a9ce4adcfc (patch)
treefb1eb4603a497ffcad2e2eae6e802363f5faca91 /nuttx/sched
parent0dc82c9ce3122c309e91981ed62a4d2a08744b86 (diff)
downloadpx4-nuttx-b415d5f6e7f3bb0e4eca3c51d8a121a9ce4adcfc.tar.gz
px4-nuttx-b415d5f6e7f3bb0e4eca3c51d8a121a9ce4adcfc.tar.bz2
px4-nuttx-b415d5f6e7f3bb0e4eca3c51d8a121a9ce4adcfc.zip
Move initialization functions from sched/ to sched/init
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile7
-rw-r--r--nuttx/sched/init/Make.defs41
-rw-r--r--nuttx/sched/init/init.h115
-rw-r--r--nuttx/sched/init/os_bringup.c (renamed from nuttx/sched/os_bringup.c)9
-rw-r--r--nuttx/sched/init/os_start.c (renamed from nuttx/sched/os_start.c)16
-rw-r--r--nuttx/sched/os_internal.h17
6 files changed, 182 insertions, 23 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index a14080eed..b7675f84a 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -41,8 +41,8 @@ DEPPATH = --dep-path .
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-MISC_SRCS = os_start.c os_bringup.c errno_getptr.c sched_garbage.c
-MISC_SRCS += sched_getfiles.c sched_getsockets.c sched_getstreams.c
+MISC_SRCS = errno_getptr.c sched_garbage.c sched_getfiles.c
+MISC_SRCS += sched_getsockets.c sched_getstreams.c
ifeq ($(CONFIG_NUTTX_KERNEL),y)
MISC_SRCS += errno_get.c errno_set.c
@@ -110,6 +110,7 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y)
TIME_SRCS += nanosleep.c
endif
+include init/Make.defs
include irq/Make.defs
include paging/Make.defs
include group/Make.defs
@@ -123,7 +124,7 @@ include timer/Make.defs
include environ/Make.defs
CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(SCHED_SRCS) $(TIME_SRCS)
-CSRCS += $(IRQ_SRCS) $(PG_SRCS) $(GRP_SRCS) $(WDOG_SRCS) $(SEM_SRCS) $(SIGNAL_SRCS) $(PTHREAD_SRCS) $(MQUEUE_SRCS) $(CLOCK_SRCS) $(TIMER_SRCS) $(ENV_SRCS)
+CSRCS += $(INIT_SRCS) $(IRQ_SRCS) $(PG_SRCS) $(GRP_SRCS) $(WDOG_SRCS) $(SEM_SRCS) $(SIGNAL_SRCS) $(PTHREAD_SRCS) $(MQUEUE_SRCS) $(CLOCK_SRCS) $(TIMER_SRCS) $(ENV_SRCS)
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/sched/init/Make.defs b/nuttx/sched/init/Make.defs
new file mode 100644
index 000000000..d48d73617
--- /dev/null
+++ b/nuttx/sched/init/Make.defs
@@ -0,0 +1,41 @@
+############################################################################
+# sched/init/Make.defs
+#
+# Copyright (C) 2014 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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.
+#
+############################################################################
+
+INIT_SRCS = os_start.c os_bringup.c
+
+# Include init build support
+
+DEPPATH += --dep-path init
+VPATH += :init
diff --git a/nuttx/sched/init/init.h b/nuttx/sched/init/init.h
new file mode 100644
index 000000000..b52920a5c
--- /dev/null
+++ b/nuttx/sched/init/init.h
@@ -0,0 +1,115 @@
+/****************************************************************************
+ * sched/init/init.h
+ *
+ * Copyright (C) 2007-2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __SCHED_INIT_INIT_H
+#define __SCHED_INIT_INIT_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+#include <queue.h>
+#include <sched.h>
+
+#include <nuttx/kmalloc.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/****************************************************************************
+ * Name: os_start
+ *
+ * Description:
+ * This function is called to initialize the operating system and to spawn
+ * the user initialization thread of execution. This is the initial entry
+ * point into NuttX
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned value:
+ * Does not return.
+ *
+ ****************************************************************************/
+
+void os_start(void);
+
+/****************************************************************************
+ * Name: os_bringup
+ *
+ * Description:
+ * Start all initial system tasks. This does the "system bring-up" after
+ * the conclusion of basic OS initialization. These initial system tasks
+ * may include:
+ *
+ * - pg_worker: The page-fault worker thread (only if CONFIG_PAGING is
+ * defined.
+ * - work_thread: The work thread. This general thread can be used to
+ * perform most any kind of queued work. Its primary
+ * function is to serve as the "bottom half" of device
+ * drivers.
+ *
+ * And the main application entry point:
+ * symbols:
+ *
+ * - USER_ENTRYPOINT: This is the default user application entry point.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+int os_bringup(void);
+
+#endif /* __SCHED_INIT_INIT_H */
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/init/os_bringup.c
index 22ced49f1..4701b47ff 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/init/os_bringup.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * sched/os_bringup.c
+ * sched/init/os_bringup.c
*
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -57,6 +57,7 @@
#ifdef CONFIG_PAGING
# include "paging/paging.h"
#endif
+# include "init/init.h"
/****************************************************************************
* Pre-processor Definitions
@@ -126,6 +127,12 @@
*
* - USER_ENTRYPOINT: This is the default user application entry point.
*
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
****************************************************************************/
int os_bringup(void)
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/init/os_start.c
index a338a1c91..57ef6d5fa 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/init/os_start.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * sched/os_start.c
+ * sched/init/os_start.c
*
* Copyright (C) 2007-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -67,6 +67,7 @@
#ifdef HAVE_TASK_GROUP
#include "group/group.h"
#endif
+#include "init/init.h"
/****************************************************************************
* Pre-processor Definitions
@@ -168,7 +169,7 @@ volatile pid_t g_lastpid;
* the number of tasks to CONFIG_MAX_TASKS.
*/
-pidhash_t g_pidhash[CONFIG_MAX_TASKS];
+struct pidhash_s g_pidhash[CONFIG_MAX_TASKS];
/* This is a table of task lists. This table is indexed by
* the task state enumeration type (tstate_t) and provides
@@ -177,7 +178,7 @@ pidhash_t g_pidhash[CONFIG_MAX_TASKS];
* is an ordered list or not.
*/
-const tasklist_t g_tasklisttable[NUM_TASK_STATES] =
+const struct tasklist_s g_tasklisttable[NUM_TASK_STATES] =
{
{ NULL, false }, /* TSTATE_TASK_INVALID */
{ &g_pendingtasks, true }, /* TSTATE_TASK_PENDING */
@@ -228,7 +229,14 @@ static FAR const char g_idlename[] = "Idle Task";
*
* Description:
* This function is called to initialize the operating system and to spawn
- * the user initization thread of execution
+ * the user initialization thread of execution. This is the initial entry
+ * point into NuttX
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned value:
+ * Does not return.
*
****************************************************************************/
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 6ec20bda0..6ce7a9757 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -69,14 +69,6 @@
#define MAX_TASKS_MASK (CONFIG_MAX_TASKS-1)
#define PIDHASH(pid) ((pid) & MAX_TASKS_MASK)
-/* A more efficient ways to access the errno */
-
-#define SET_ERRNO(e) \
- { struct tcb_s *rtcb = struct tcb_s*)g_readytorun.head; rtcb->pterrno = (e); }
-
-#define _SET_TCB_ERRNO(t,e) \
- { (t)->pterrno = (e); }
-
/****************************************************************************
* Public Type Definitions
****************************************************************************/
@@ -101,8 +93,6 @@ struct pidhash_s
#endif
};
-typedef struct pidhash_s pidhash_t;
-
/* This structure defines an element of the g_tasklisttable[].
* This table is used to map a task_state enumeration to the
* corresponding task list.
@@ -114,8 +104,6 @@ struct tasklist_s
bool prioritized; /* true if the list is prioritized */
};
-typedef struct tasklist_s tasklist_t;
-
/****************************************************************************
* Global Variables
****************************************************************************/
@@ -209,7 +197,7 @@ extern volatile pid_t g_lastpid;
* of tasks to CONFIG_MAX_TASKS.
*/
-extern pidhash_t g_pidhash[CONFIG_MAX_TASKS];
+extern struct pidhash_s g_pidhash[CONFIG_MAX_TASKS];
/* 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
@@ -217,7 +205,7 @@ extern pidhash_t g_pidhash[CONFIG_MAX_TASKS];
* if the list is an ordered list or not.
*/
-extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
+extern const struct tasklist_s g_tasklisttable[NUM_TASK_STATES];
#ifdef CONFIG_SCHED_CPULOAD
/* This is the total number of clock tick counts. Essentially the
@@ -231,7 +219,6 @@ extern volatile uint32_t g_cpuload_total;
* Public Function Prototypes
****************************************************************************/
-int os_bringup(void);
#ifdef CONFIG_SCHED_CHILD_STATUS
void weak_function task_initialize(void);
#endif