summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-16 17:37:40 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-16 17:37:40 +0000
commita45f710f8fdb5b9cf11fbdcb2a74cb5007ea79fd (patch)
tree8e50d03ca5238eb88b8cc8125f8db19ba72436a9 /nuttx/arch
parentd980ce2cdc1816e4d5df9a1c2ff9e647c6cb7540 (diff)
downloadpx4-nuttx-a45f710f8fdb5b9cf11fbdcb2a74cb5007ea79fd.tar.gz
px4-nuttx-a45f710f8fdb5b9cf11fbdcb2a74cb5007ea79fd.tar.bz2
px4-nuttx-a45f710f8fdb5b9cf11fbdcb2a74cb5007ea79fd.zip
Fix bad conditional logic in mkconfig.c; Add user-mode pthread start-up logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5748 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/armv6-m/svcall.h15
-rw-r--r--nuttx/arch/arm/src/armv6-m/up_svcall.c39
-rw-r--r--nuttx/arch/arm/src/armv7-m/svcall.h15
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_svcall.c39
-rw-r--r--nuttx/arch/arm/src/common/up_pthread_start.c96
-rw-r--r--nuttx/arch/arm/src/lpc17xx/Make.defs2
-rw-r--r--nuttx/arch/arm/src/sam3u/Make.defs2
7 files changed, 190 insertions, 18 deletions
diff --git a/nuttx/arch/arm/src/armv6-m/svcall.h b/nuttx/arch/arm/src/armv6-m/svcall.h
index f453cad55..c7f2013fc 100644
--- a/nuttx/arch/arm/src/armv6-m/svcall.h
+++ b/nuttx/arch/arm/src/armv6-m/svcall.h
@@ -57,9 +57,9 @@
#ifdef CONFIG_NUTTX_KERNEL
# ifndef CONFIG_SYS_RESERVED
-# error "CONFIG_SYS_RESERVED must be defined to the value 5"
-# elif CONFIG_SYS_RESERVED != 5
-# error "CONFIG_SYS_RESERVED must have the value 5"
+# error "CONFIG_SYS_RESERVED must be defined to the value 6"
+# elif CONFIG_SYS_RESERVED != 6
+# error "CONFIG_SYS_RESERVED must have the value 6"
# endif
#endif
@@ -94,12 +94,19 @@
#define SYS_syscall_return (3)
-/* SYS call 3:
+/* SYS call 4:
*
* void up_task_start(main_t taskentry, int argc, FAR char *argv[]) noreturn_function;
*/
#define SYS_task_start (4)
+
+/* SYS call 5:
+ *
+ * void up_pthread_start(pthread_startroutine_t entrypt, pthread_addr_t arg) noreturn_function
+ */
+
+#define SYS_pthread_start (5)
#endif
/************************************************************************************
diff --git a/nuttx/arch/arm/src/armv6-m/up_svcall.c b/nuttx/arch/arm/src/armv6-m/up_svcall.c
index 06d6a61e1..ac99cabe0 100644
--- a/nuttx/arch/arm/src/armv6-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv6-m/up_svcall.c
@@ -196,7 +196,7 @@ int up_svcall(int irq, FAR void *context)
}
break;
- /* R0=SYS_restore_context: This a restore context command:
+ /* R0=SYS_restore_context: This a restore context command:
*
* void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
@@ -218,7 +218,7 @@ int up_svcall(int irq, FAR void *context)
}
break;
- /* R0=SYS_switch_context: This a switch context command:
+ /* R0=SYS_switch_context: This a switch context command:
*
* void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
*
@@ -242,7 +242,7 @@ int up_svcall(int irq, FAR void *context)
}
break;
- /* R0=SYS_syscall_return: This a syscall return command:
+ /* R0=SYS_syscall_return: This a syscall return command:
*
* void up_syscall_return(void);
*
@@ -280,7 +280,7 @@ int up_svcall(int irq, FAR void *context)
break;
#endif
- /* R0=SYS_task_start: This a user task start
+ /* R0=SYS_task_start: This a user task start
*
* void up_task_start(main_t taskentry, int argc, FAR char *argv[]) noreturn_function;
*
@@ -313,6 +313,37 @@ int up_svcall(int irq, FAR void *context)
break;
#endif
+ /* R0=SYS_pthread_start: This a user pthread start
+ *
+ * void up_pthread_start(pthread_startroutine_t entrypt, pthread_addr_t arg) noreturn_function;
+ *
+ * At this point, the following values are saved in context:
+ *
+ * R0 = SYS_pthread_start
+ * R1 = entrypt
+ * R2 = arg
+ */
+
+#if defined(CONFIG_NUTTX_KERNEL) && !defined(CONFIG_DISABLE_PTHREAD)
+ case SYS_pthread_start:
+ {
+ /* Set up to return to the user-space pthread start-up function in
+ * unprivileged mode.
+ */
+
+ regs[REG_PC] = (uint32_t)USERSPACE->pthread_startup;
+ regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
+
+ /* Change the parameter ordering to match the expectation of struct
+ * userpace_s pthread_startup:
+ */
+
+ regs[REG_R0] = regs[REG_R1]; /* pthread entry */
+ regs[REG_R1] = regs[REG_R2]; /* arg */
+ }
+ break;
+#endif
+
/* This is not an architecture-specific system call. If NuttX is built
* as a standalone kernel with a system call interface, then all of the
* additional system calls must be handled as in the default case.
diff --git a/nuttx/arch/arm/src/armv7-m/svcall.h b/nuttx/arch/arm/src/armv7-m/svcall.h
index f6b068f86..333dfb6d0 100644
--- a/nuttx/arch/arm/src/armv7-m/svcall.h
+++ b/nuttx/arch/arm/src/armv7-m/svcall.h
@@ -57,9 +57,9 @@
#ifdef CONFIG_NUTTX_KERNEL
# ifndef CONFIG_SYS_RESERVED
-# error "CONFIG_SYS_RESERVED must be defined to the value 5"
-# elif CONFIG_SYS_RESERVED != 5
-# error "CONFIG_SYS_RESERVED must have the value 5"
+# error "CONFIG_SYS_RESERVED must be defined to the value 6"
+# elif CONFIG_SYS_RESERVED != 6
+# error "CONFIG_SYS_RESERVED must have the value 6"
# endif
#endif
@@ -94,12 +94,19 @@
#define SYS_syscall_return (3)
-/* SYS call 3:
+/* SYS call 4:
*
* void up_task_start(main_t taskentry, int argc, FAR char *argv[]) noreturn_function;
*/
#define SYS_task_start (4)
+
+/* SYS call 5:
+ *
+ * void up_pthread_start(pthread_startroutine_t entrypt, pthread_addr_t arg) noreturn_function
+ */
+
+#define SYS_pthread_start (5)
#endif
/************************************************************************************
diff --git a/nuttx/arch/arm/src/armv7-m/up_svcall.c b/nuttx/arch/arm/src/armv7-m/up_svcall.c
index 950ddd1d3..1a153dead 100644
--- a/nuttx/arch/arm/src/armv7-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv7-m/up_svcall.c
@@ -197,7 +197,7 @@ int up_svcall(int irq, FAR void *context)
}
break;
- /* R0=SYS_restore_context: This a restore context command:
+ /* R0=SYS_restore_context: This a restore context command:
*
* void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
@@ -219,7 +219,7 @@ int up_svcall(int irq, FAR void *context)
}
break;
- /* R0=SYS_switch_context: This a switch context command:
+ /* R0=SYS_switch_context: This a switch context command:
*
* void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
*
@@ -246,7 +246,7 @@ int up_svcall(int irq, FAR void *context)
}
break;
- /* R0=SYS_syscall_return: This a syscall return command:
+ /* R0=SYS_syscall_return: This a syscall return command:
*
* void up_syscall_return(void);
*
@@ -284,7 +284,7 @@ int up_svcall(int irq, FAR void *context)
break;
#endif
- /* R0=SYS_task_start: This a user task start
+ /* R0=SYS_task_start: This a user task start
*
* void up_task_start(main_t taskentry, int argc, FAR char *argv[]) noreturn_function;
*
@@ -317,6 +317,37 @@ int up_svcall(int irq, FAR void *context)
break;
#endif
+ /* R0=SYS_pthread_start: This a user pthread start
+ *
+ * void up_pthread_start(pthread_startroutine_t entrypt, pthread_addr_t arg) noreturn_function;
+ *
+ * At this point, the following values are saved in context:
+ *
+ * R0 = SYS_pthread_start
+ * R1 = entrypt
+ * R2 = arg
+ */
+
+#if defined(CONFIG_NUTTX_KERNEL) && !defined(CONFIG_DISABLE_PTHREAD)
+ case SYS_pthread_start:
+ {
+ /* Set up to return to the user-space pthread start-up function in
+ * unprivileged mode.
+ */
+
+ regs[REG_PC] = (uint32_t)USERSPACE->pthread_startup;
+ regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
+
+ /* Change the parameter ordering to match the expectation of struct
+ * userpace_s pthread_startup:
+ */
+
+ regs[REG_R0] = regs[REG_R1]; /* pthread entry */
+ regs[REG_R1] = regs[REG_R2]; /* arg */
+ }
+ break;
+#endif
+
/* This is not an architecture-specific system call. If NuttX is built
* as a standalone kernel with a system call interface, then all of the
* additional system calls must be handled as in the default case.
diff --git a/nuttx/arch/arm/src/common/up_pthread_start.c b/nuttx/arch/arm/src/common/up_pthread_start.c
new file mode 100644
index 000000000..2f9de8995
--- /dev/null
+++ b/nuttx/arch/arm/src/common/up_pthread_start.c
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * arch/arm/src/common/up_pthread_start.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 <pthread.h>
+#include <nuttx/arch.h>
+
+#include "svcall.h"
+#include "up_internal.h"
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__) && !defined(CONFIG_DISABLE_PTHREAD)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_pthread_start
+ *
+ * Description:
+ * In this kernel mode build, this function will be called to execute a
+ * pthread in user-space. When the pthread is first started, a kernel-mode
+ * stub will first run to perform some housekeeping functions. This
+ * kernel-mode stub will then be called transfer control to the user-mode
+ * pthread.
+ *
+ * Normally the a user-mode start-up stub will also execute before the
+ * pthread actually starts. See libc/pthread/pthread_startup.c
+ *
+ * Input Parameters:
+ * entrypt - The user-space address of the pthread entry point
+ * arg - Standard argument for the pthread entry point
+ *
+ * Returned Value:
+ * This function should not return. It should call the user-mode start-up
+ * stub and that stub should call pthread_exit if/when the user pthread
+ * terminates.
+ *
+ ****************************************************************************/
+
+void up_pthread_start(pthread_startroutine_t entrypt, pthread_addr_t arg)
+{
+ /* Let sys_call2() do all of the work */
+
+ sys_call2(SYS_pthread_start, (uintptr_t)entrypt, (uintptr_t)arg);
+}
+
+#endif /* CONFIG_NUTTX_KERNEL &&& __KERNEL__ && !CONFIG_DISABLE_PTHREAD */
diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs
index 82ce2c4b6..e6d007902 100644
--- a/nuttx/arch/arm/src/lpc17xx/Make.defs
+++ b/nuttx/arch/arm/src/lpc17xx/Make.defs
@@ -64,7 +64,7 @@ CMN_ASRCS += up_memcpy.S
endif
ifeq ($(CONFIG_NUTTX_KERNEL),y)
-CMN_CSRCS += up_mpu.c up_task_start.c
+CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c
endif
ifeq ($(CONFIG_NET),y)
diff --git a/nuttx/arch/arm/src/sam3u/Make.defs b/nuttx/arch/arm/src/sam3u/Make.defs
index 918d40148..a2047a78a 100644
--- a/nuttx/arch/arm/src/sam3u/Make.defs
+++ b/nuttx/arch/arm/src/sam3u/Make.defs
@@ -56,7 +56,7 @@ CMN_ASRCS += up_memcpy.S
endif
ifeq ($(CONFIG_NUTTX_KERNEL),y)
-CMN_CSRCS += up_mpu.c up_task_start.c
+CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c
endif
ifeq ($(CONFIG_ELF),y)