aboutsummaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-11 00:39:22 -0800
committerpx4dev <px4@purgatory.org>2013-01-11 00:39:22 -0800
commitccf9882dc5dbe38b621110f82c4e2ff63aef900e (patch)
tree18b0af628174bf27815dd52a376c8b72b6a626d4 /nuttx/sched
parent40dfbf0d977729951d73bcb089ca8f89c7b83efe (diff)
parent0f2decb70f505b108999fcdb80e89d7aae6760ce (diff)
downloadpx4-firmware-ccf9882dc5dbe38b621110f82c4e2ff63aef900e.tar.gz
px4-firmware-ccf9882dc5dbe38b621110f82c4e2ff63aef900e.tar.bz2
px4-firmware-ccf9882dc5dbe38b621110f82c4e2ff63aef900e.zip
Merge branch 'master' into nuttx-merge-5447
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig24
-rw-r--r--nuttx/sched/env_clearenv.c2
-rw-r--r--nuttx/sched/env_internal.h2
-rw-r--r--nuttx/sched/env_release.c4
-rw-r--r--nuttx/sched/os_bringup.c19
-rw-r--r--nuttx/sched/os_start.c4
-rw-r--r--nuttx/sched/prctl.c6
-rw-r--r--nuttx/sched/pthread_create.c63
-rw-r--r--nuttx/sched/sched_releasetcb.c6
-rw-r--r--nuttx/sched/task_exithook.c1
-rw-r--r--nuttx/sched/work_thread.c6
11 files changed, 90 insertions, 47 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index 4f7149595..3438ccf2c 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -22,7 +22,13 @@ config SCHED_INSTRUMENTATION
bool "Monitor system performance"
default n
---help---
- enables instrumentation in scheduler to monitor system performance.
+ Enables instrumentation in scheduler to monitor system performance.
+ If enabled, then the board-specific logic must provide the following
+ functions (see include/sched.h):
+
+ void sched_note_start(FAR _TCB *tcb);
+ void sched_note_stop(FAR _TCB *tcb);
+ void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
config TASK_NAME_SIZE
int "Maximum task name size"
@@ -40,7 +46,7 @@ config JULIAN_TIME
config START_YEAR
int "start year"
- default 2010
+ default 2013
config START_MONTH
int "start month"
@@ -57,12 +63,6 @@ config DEV_CONSOLE
Set if architecture-specific logic provides /dev/console. Enables
stdout, stderr, stdin.
-config DEV_LOWCONSOLE
- bool "enable low-level serial console"
- default n
- ---help---
- Use the simple, low-level, write-only serial console driver (minimul support)
-
config MUTEX_TYPES:
bool "Enable mutex types"
default n
@@ -381,14 +381,6 @@ config PREALLOC_TIMERS
comment "Stack and heap information"
-config CUSTOM_STACK
- bool "Enable custom stack"
- default n
- ---help---
- The up_ implementation will handle all stack operations outside of the
- nuttx model. This is necessary for certain architectures that have
- have hardware stacks (such as the 8051 family).
-
config IDLETHREAD_STACKSIZE
int "Idle thread stack size"
default 1024
diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c
index 7fe97a911..75890f3bc 100644
--- a/nuttx/sched/env_clearenv.c
+++ b/nuttx/sched/env_clearenv.c
@@ -79,5 +79,3 @@ int clearenv(void)
#endif /* CONFIG_DISABLE_ENVIRON */
-
-
diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h
index a6205d658..5370da059 100644
--- a/nuttx/sched/env_internal.h
+++ b/nuttx/sched/env_internal.h
@@ -80,7 +80,7 @@ EXTERN int env_dup(FAR _TCB *ptcb);
EXTERN int env_share(FAR _TCB *ptcb);
EXTERN int env_release(FAR _TCB *ptcb);
-/* functions used internally the environment handling logic */
+/* functions used internally by the environment handling logic */
EXTERN FAR char *env_findvar(environ_t *envp, const char *pname);
EXTERN int env_removevar(environ_t *envp, char *pvar);
diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c
index 83e65dbb5..8bc8d2205 100644
--- a/nuttx/sched/env_release.c
+++ b/nuttx/sched/env_release.c
@@ -94,11 +94,11 @@ int env_release(FAR _TCB *ptcb)
{
/* Check the reference count on the environment structure */
- if ( envp->ev_crefs <= 1)
+ if (envp->ev_crefs <= 1)
{
/* Decrementing the reference count will destroy the environment */
- sched_free( envp ); /* plain free() should be fine here */
+ sched_free(envp);
}
else
{
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/os_bringup.c
index ec6152891..e0a236bbe 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/os_bringup.c
@@ -44,6 +44,7 @@
#include <nuttx/config.h>
#include <sched.h>
+#include <stdlib.h>
#include <debug.h>
#include <nuttx/init.h>
@@ -129,6 +130,17 @@ int os_bringup(void)
#endif
int init_taskid;
+ /* Setup up the initial environment for the idle task. At present, this
+ * may consist of only the initial PATH variable. The PATH variable is
+ * (probably) not used by the IDLE task. However, the environment
+ * containing the PATH variable will be inherited by all of the threads
+ * created by the IDLE task.
+ */
+
+#if !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_PATH_INITIAL)
+ (void)setenv("PATH", CONFIG_PATH_INITIAL, 1);
+#endif
+
/* Start the page fill worker kernel thread that will resolve page faults.
* This should always be the first thread started because it may have to
* resolve page faults in other threads
@@ -190,5 +202,12 @@ int os_bringup(void)
(main_t)CONFIG_USER_ENTRYPOINT, (const char **)NULL);
#endif
ASSERT(init_taskid != ERROR);
+
+ /* We an save a few bytes by discarding the IDLE thread's environment. */
+
+#if !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_PATH_INITIAL)
+ (void)clearenv();
+#endif
+
return OK;
}
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index c0b16236d..a53ac2aa8 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -426,7 +426,9 @@ void os_start(void)
lib_initialize();
}
- /* Create stdout, stderr, stdin */
+ /* Create stdout, stderr, stdin on the IDLE task. These will be
+ * inherited by all of the threads created by the IDLE task.
+ */
(void)sched_setupidlefiles(&g_idletcb);
diff --git a/nuttx/sched/prctl.c b/nuttx/sched/prctl.c
index d71a0e174..3db83d3d7 100644
--- a/nuttx/sched/prctl.c
+++ b/nuttx/sched/prctl.c
@@ -157,8 +157,14 @@ int prctl(int option, ...)
goto errout;
}
+ /* Not reachable unless CONFIG_TASK_NAME_SIZE is > 0. NOTE: This might
+ * change if additional commands are supported.
+ */
+
+#if CONFIG_TASK_NAME_SIZE > 0
va_end(ap);
return OK;
+#endif
errout:
va_end(ap);
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index 5fdf3b88d..dc2db2916 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -246,7 +246,7 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
{
FAR _TCB *ptcb;
FAR join_t *pjoin;
- int status;
+ int ret;
int priority;
#if CONFIG_RR_INTERVAL > 0
int policy;
@@ -268,13 +268,27 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
return ENOMEM;
}
+ /* Share the address environment of the parent task. NOTE: Only tasks
+ * created throught the nuttx/binfmt loaders may have an address
+ * environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_share((FAR const _TCB *)g_readytorun.head, ptcb);
+ if (ret < 0)
+ {
+ sched_releasetcb(ptcb);
+ return -ret;
+ }
+#endif
+
/* Associate file descriptors with the new task */
- status = sched_setuppthreadfiles(ptcb);
- if (status != OK)
+ ret = sched_setuppthreadfiles(ptcb);
+ if (ret != OK)
{
sched_releasetcb(ptcb);
- return status;
+ return ret;
}
/* Share the parent's envionment */
@@ -292,8 +306,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Allocate the stack for the TCB */
- status = up_create_stack(ptcb, attr->stacksize);
- if (status != OK)
+ ret = up_create_stack(ptcb, attr->stacksize);
+ if (ret != OK)
{
sched_releasetcb(ptcb);
sched_free(pjoin);
@@ -310,8 +324,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Get the priority for this thread. */
struct sched_param param;
- status = sched_getparam(0, &param);
- if (status == OK)
+ ret = sched_getparam(0, &param);
+ if (ret == OK)
{
priority = param.sched_priority;
}
@@ -348,11 +362,9 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Initialize the task control block */
- status = task_schedsetup(ptcb, priority, pthread_start,
- (main_t)start_routine);
- if (status != OK)
+ ret = task_schedsetup(ptcb, priority, pthread_start, (main_t)start_routine);
+ if (ret != OK)
{
-
sched_releasetcb(ptcb);
sched_free(pjoin);
return EBUSY;
@@ -390,21 +402,21 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Initialize the semaphores in the join structure to zero. */
- status = sem_init(&pjoin->data_sem, 0, 0);
- if (status == OK)
+ ret = sem_init(&pjoin->data_sem, 0, 0);
+ if (ret == OK)
{
- status = sem_init(&pjoin->exit_sem, 0, 0);
+ ret = sem_init(&pjoin->exit_sem, 0, 0);
}
/* Activate the task */
sched_lock();
- if (status == OK)
+ if (ret == OK)
{
- status = task_activate(ptcb);
+ ret = task_activate(ptcb);
}
- if (status == OK)
+ if (ret == OK)
{
/* Wait for the task to actually get running and to register
* its join_t
@@ -414,8 +426,15 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
/* Return the thread information to the caller */
- if (thread) *thread = (pthread_t)pid;
- if (!pjoin->started) status = ERROR;
+ if (thread)
+ {
+ *thread = (pthread_t)pid;
+ }
+
+ if (!pjoin->started)
+ {
+ ret = EINVAL;
+ }
sched_unlock();
(void)sem_destroy(&pjoin->data_sem);
@@ -428,8 +447,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
(void)sem_destroy(&pjoin->exit_sem);
sched_releasetcb(ptcb);
sched_free(pjoin);
- return EIO;
+ ret = EIO;
}
- return OK;
+ return ret;
}
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 21837262d..0557c829b 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -171,6 +171,12 @@ int sched_releasetcb(FAR _TCB *tcb)
(void)env_release(tcb);
+ /* Release this thread's reference to the address environment */
+
+#ifdef CONFIG_ADDRENV
+ ret = up_addrenv_release(tcb);
+#endif
+
/* And, finally, release the TCB itself */
sched_free(tcb);
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index e94476f2a..004d09e20 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -126,6 +126,7 @@ static inline void task_atexit(FAR _TCB *tcb)
tcb->atexitfunc = NULL;
}
#endif
+}
#else
# define task_atexit(tcb)
#endif
diff --git a/nuttx/sched/work_thread.c b/nuttx/sched/work_thread.c
index abd86f771..5646b06a1 100644
--- a/nuttx/sched/work_thread.c
+++ b/nuttx/sched/work_thread.c
@@ -208,10 +208,10 @@ int work_hpthread(int argc, char *argv[])
* that were queued because they could not be freed in that execution
* context (for example, if the memory was freed from an interrupt handler).
* NOTE: If the work thread is disabled, this clean-up is performed by
- * the IDLE thread (at a very, very lower priority).
+ * the IDLE thread (at a very, very low priority).
*/
-#ifdef CONFIG_SCHED_LPWORK
+#ifndef CONFIG_SCHED_LPWORK
sched_garbagecollection();
#endif
@@ -236,7 +236,7 @@ int work_lpthread(int argc, char *argv[])
* that were queued because they could not be freed in that execution
* context (for example, if the memory was freed from an interrupt handler).
* NOTE: If the work thread is disabled, this clean-up is performed by
- * the IDLE thread (at a very, very lower priority).
+ * the IDLE thread (at a very, very low priority).
*/
sched_garbagecollection();