summaryrefslogtreecommitdiff
path: root/nuttx/libc/spawn
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-02 19:31:30 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-02 19:31:30 +0000
commit60185fe969614b01d5dc57f3aa157b24d2901af6 (patch)
treed63a6a6a97cae8d4fe62b41e900fbcd5c29aceaf /nuttx/libc/spawn
parentf1851b468b62b448a0d9ed343d4ca8b9987e0d53 (diff)
downloadpx4-nuttx-60185fe969614b01d5dc57f3aa157b24d2901af6.tar.gz
px4-nuttx-60185fe969614b01d5dc57f3aa157b24d2901af6.tar.bz2
px4-nuttx-60185fe969614b01d5dc57f3aa157b24d2901af6.zip
New interface task_spawn(); exec_builtin() now uses task_spawn(); All argv types should be char * const * not const char **
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5598 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/libc/spawn')
-rw-r--r--nuttx/libc/spawn/Make.defs5
-rw-r--r--nuttx/libc/spawn/lib_psa_getschedparam.c2
-rw-r--r--nuttx/libc/spawn/lib_psa_getstacksize.c74
-rw-r--r--nuttx/libc/spawn/lib_psa_init.c26
-rw-r--r--nuttx/libc/spawn/lib_psa_setstacksize.c73
-rw-r--r--nuttx/libc/spawn/lib_psfa_dump.c5
6 files changed, 175 insertions, 10 deletions
diff --git a/nuttx/libc/spawn/Make.defs b/nuttx/libc/spawn/Make.defs
index 8cb086fee..edbcc4fbb 100644
--- a/nuttx/libc/spawn/Make.defs
+++ b/nuttx/libc/spawn/Make.defs
@@ -45,8 +45,9 @@ CSRCS += lib_psfa_dump.c
endif
CSRCS += lib_psa_getflags.c lib_psa_getschedparam.c lib_psa_getschedpolicy.c
-CSRCS += lib_psa_init.c lib_psa_setflags.c lib_psa_setschedparam.c
-CSRCS += lib_psa_setschedpolicy.c
+CSRCS += lib_psa_getstacksize.c lib_psa_init.c lib_psa_setflags.c
+CSRCS += lib_psa_setschedparam.c lib_psa_setschedpolicy.c
+CSRCS += lib_psa_setstacksize.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CSRCS += lib_psa_getsigmask.c lib_psa_setsigmask.c
diff --git a/nuttx/libc/spawn/lib_psa_getschedparam.c b/nuttx/libc/spawn/lib_psa_getschedparam.c
index ed8cb1f70..51b2cb38e 100644
--- a/nuttx/libc/spawn/lib_psa_getschedparam.c
+++ b/nuttx/libc/spawn/lib_psa_getschedparam.c
@@ -57,7 +57,7 @@
*
* Input Parameters:
* attr - The address spawn attributes to be queried.
- * flags - The location to return the spawn-schedparam value.
+ * param - The location to return the spawn-schedparam value.
*
* Returned Value:
* On success, these functions return 0; on failure they return an error
diff --git a/nuttx/libc/spawn/lib_psa_getstacksize.c b/nuttx/libc/spawn/lib_psa_getstacksize.c
new file mode 100644
index 000000000..ab499f5de
--- /dev/null
+++ b/nuttx/libc/spawn/lib_psa_getstacksize.c
@@ -0,0 +1,74 @@
+/****************************************************************************
+ * libc/string/lib_psa_getstacksize.c
+ *
+ * Copyright (C) 2013 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sched.h>
+#include <spawn.h>
+#include <assert.h>
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: task_spawnattr_getstacksize
+ *
+ * Description:
+ * The task_spawnattr_getstacksize() function will obtain the value of
+ * the spawn-stacksize attribute from the attributes object referenced
+ * by attr.
+ *
+ * Input Parameters:
+ * attr - The address spawn attributes to be queried.
+ * stacksize - The location to return the spawn-stacksize value.
+ *
+ * Returned Value:
+ * On success, these functions return 0; on failure they return an error
+ * number from <errno.h>.
+ *
+ ****************************************************************************/
+
+int task_spawnattr_getstacksize(FAR const posix_spawnattr_t *attr,
+ size_t *stacksize)
+{
+ DEBUGASSERT(attr && stacksize);
+ *stacksize = attr->stacksize;
+ return OK;
+}
diff --git a/nuttx/libc/spawn/lib_psa_init.c b/nuttx/libc/spawn/lib_psa_init.c
index f76188c52..c016cc6cd 100644
--- a/nuttx/libc/spawn/lib_psa_init.c
+++ b/nuttx/libc/spawn/lib_psa_init.c
@@ -45,7 +45,15 @@
#include <errno.h>
/****************************************************************************
- * Global Functions
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifndef TASK_SPAWN_DEFAULT_STACKSIZE
+# define TASK_SPAWN_DEFAULT_STACKSIZE 2048
+#endif
+
+/****************************************************************************
+ * Public Functions
****************************************************************************/
/****************************************************************************
@@ -76,10 +84,6 @@ int posix_spawnattr_init(posix_spawnattr_t *attr)
attr->flags = 0;
- /* Set the default scheduler policy to the policy of this task */
-
- attr->policy = sched_getscheduler(0);
-
/* Set the default priority to the same priority as this task */
ret = sched_getparam(0, &param);
@@ -89,5 +93,17 @@ int posix_spawnattr_init(posix_spawnattr_t *attr)
}
attr->priority = param.sched_priority;
+
+ /* Set the default scheduler policy to the policy of this task */
+
+ attr->policy = sched_getscheduler(0);
+
+ /* Empty signal masek */
+
+ attr->sigmask = 0;
+
+ /* Default stack size */
+
+ attr->stacksize = TASK_SPAWN_DEFAULT_STACKSIZE;
return OK;
}
diff --git a/nuttx/libc/spawn/lib_psa_setstacksize.c b/nuttx/libc/spawn/lib_psa_setstacksize.c
new file mode 100644
index 000000000..d49a1d611
--- /dev/null
+++ b/nuttx/libc/spawn/lib_psa_setstacksize.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ * libc/string/lib_psa_setstacksize.c
+ *
+ * Copyright (C) 2013 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sched.h>
+#include <spawn.h>
+#include <assert.h>
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: task_spawnattr_setstacksize
+ *
+ * Description:
+ * The task_spawnattr_setstacksize() function shall set the spawn-
+ * stacksize attribute in an initialized attributes object referenced
+ * by attr.
+ *
+ * Input Parameters:
+ * attr - The address spawn attributes to be used.
+ * stacksize - The new stacksize to set.
+ *
+ * Returned Value:
+ * On success, these functions return 0; on failure they return an error
+ * number from <errno.h>.
+ *
+ ****************************************************************************/
+
+int task_spawnattr_setstacksize(FAR posix_spawnattr_t *attr, size_t stacksize)
+{
+ DEBUGASSERT(attr);
+ attr->stacksize = stacksize;
+ return OK;
+}
diff --git a/nuttx/libc/spawn/lib_psfa_dump.c b/nuttx/libc/spawn/lib_psfa_dump.c
index 0dbaeb023..f71f2701e 100644
--- a/nuttx/libc/spawn/lib_psfa_dump.c
+++ b/nuttx/libc/spawn/lib_psfa_dump.c
@@ -56,7 +56,7 @@
****************************************************************************/
/****************************************************************************
- * Name: lib_psfa_dump
+ * Name: posix_spawn_file_actions_dump
*
* Description:
* Show the entryent file actions.
@@ -126,4 +126,5 @@ void posix_spawn_file_actions_dump(FAR posix_spawn_file_actions_t *file_actions)
}
}
-#endif /* CONFIG_DEBUG */ \ No newline at end of file
+#endif /* CONFIG_DEBUG */
+