summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-11 21:42:15 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-12-11 21:42:15 +0000
commitf0e320ceb9ba49bc6133547e25c520c2155b38d7 (patch)
treefddaccb5f325a2ab18f593609e63b46e98733620 /nuttx/sched
parentcdbb7040cc2ba10d5c86fccc448660a401dad7b9 (diff)
downloadpx4-nuttx-f0e320ceb9ba49bc6133547e25c520c2155b38d7.tar.gz
px4-nuttx-f0e320ceb9ba49bc6133547e25c520c2155b38d7.tar.bz2
px4-nuttx-f0e320ceb9ba49bc6133547e25c520c2155b38d7.zip
configs/p112: Add a configuration for the Z180 P112 board
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5429 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig8
-rw-r--r--nuttx/sched/env_internal.h2
-rw-r--r--nuttx/sched/pthread_create.c63
-rw-r--r--nuttx/sched/sched_releasetcb.c6
4 files changed, 55 insertions, 24 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index afb35c1c0..bfaec3b5d 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"
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/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);