summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-08 00:17:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-08 00:17:54 +0000
commit0017d65ee25f15e67e5376ac59340e5835032867 (patch)
tree24ad7c1d7f8d998510e9c25e2cfb12e012506b5f
parent6513234d7d98c48ee6ffdd56e19f3e987eb753fb (diff)
downloadpx4-nuttx-0017d65ee25f15e67e5376ac59340e5835032867.tar.gz
px4-nuttx-0017d65ee25f15e67e5376ac59340e5835032867.tar.bz2
px4-nuttx-0017d65ee25f15e67e5376ac59340e5835032867.zip
LPC17xx now supports FPU needed by LPC1788; LPC17xx can not use Mike's common vectors
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5623 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--apps/nshlib/nsh_proccmds.c37
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/Kconfig1
-rw-r--r--nuttx/arch/arm/src/lpc17xx/Make.defs69
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip.h23
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_start.c95
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S81
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs92
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_vectors.S1
-rw-r--r--nuttx/binfmt/binfmt_execmodule.c10
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/defconfig20
-rw-r--r--nuttx/configs/open1788/README.txt93
-rw-r--r--nuttx/libc/spawn/Make.defs3
13 files changed, 427 insertions, 101 deletions
diff --git a/apps/nshlib/nsh_proccmds.c b/apps/nshlib/nsh_proccmds.c
index 3f206b592..29daec0cd 100644
--- a/apps/nshlib/nsh_proccmds.c
+++ b/apps/nshlib/nsh_proccmds.c
@@ -129,23 +129,42 @@ static void ps_task(FAR struct tcb_s *tcb, FAR void *arg)
/* Show task name and arguments */
- nsh_output(vtbl, "%s(", tcb->argv[0]);
+#if CONFIG_TASK_NAME_SIZE > 0
+ nsh_output(vtbl, "%s(", tcb->name);
+#else
+ nsh_output(vtbl, "<noname>(");
+#endif
- /* Special case 1st argument (no comma) */
+ /* Is this a task or a pthread? */
- if (tcb->argv[1])
+#ifndef CONFIG_DISABLE_PTHREAD
+ if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_PTHREAD)
{
- nsh_output(vtbl, "%p", tcb->argv[1]);
+ FAR struct pthread_tcb_s *ptcb = (FAR struct pthread_tcb_s *)tcb;
+ nsh_output(vtbl, "%p", ptcb->arg);
}
+ else
+#endif
+ {
+ FAR struct task_tcb_s *ttcb = (FAR struct task_tcb_s *)tcb;
+
+ /* Special case 1st argument (no comma) */
- /* Then any additional arguments */
+ if (ttcb->argv[1])
+ {
+ nsh_output(vtbl, "%p", ttcb->argv[1]);
+ }
+
+ /* Then any additional arguments */
#if CONFIG_MAX_TASK_ARGS > 2
- for (i = 2; i <= CONFIG_MAX_TASK_ARGS && tcb->argv[i]; i++)
- {
- nsh_output(vtbl, ", %p", tcb->argv[i]);
- }
+ for (i = 2; i <= CONFIG_MAX_TASK_ARGS && ttcb->argv[i]; i++)
+ {
+ nsh_output(vtbl, ", %p", ttcb->argv[i]);
+ }
#endif
+ }
+
nsh_output(vtbl, ")\n");
}
#endif
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 189a14dfa..5b8730f3c 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4158,4 +4158,7 @@
* configs/stm32f3discovery: This will (eventually) be support for
the STM32F3Discovery board.
* STM32 F3 and STM32F3Discovery port is complete a ready for test.
+ * arch/arm/src/lpc17xx: Add support for the Cortex-M4 FPU and
+ Mikes "common vector" logic. The LPC1788 is going to need
+ these things.
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 5709f890f..12c8ba4d5 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -60,6 +60,7 @@ config ARCH_CHIP_LM
config ARCH_CHIP_LPC17XX
bool "NXP LPC17xx"
select ARCH_CORTEXM3
+ select ARCH_HAVE_CMNVECTOR
select ARCH_HAVE_MPU
---help---
NXP LPC17xx architectures (ARM Cortex-M3)
diff --git a/nuttx/arch/arm/src/lpc17xx/Make.defs b/nuttx/arch/arm/src/lpc17xx/Make.defs
index ed05fff95..20e016de9 100644
--- a/nuttx/arch/arm/src/lpc17xx/Make.defs
+++ b/nuttx/arch/arm/src/lpc17xx/Make.defs
@@ -35,27 +35,37 @@
# The start-up, "head", file
-HEAD_ASRC = lpc17_vectors.S
+ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
+HEAD_ASRC =
+else
+HEAD_ASRC = lpc17_vectors.S
+endif
# Common ARM and Cortex-M3 files
-CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S \
- vfork.S
-CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \
- up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c \
- up_initialstate.c up_interruptcontext.c up_modifyreg8.c \
- up_modifyreg16.c up_modifyreg32.c up_releasepending.c \
- up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \
- up_sigdeliver.c up_unblocktask.c up_usestack.c up_doirq.c \
- up_hardfault.c up_svcall.c up_checkstack.c up_vfork.c
+CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
+CMN_ASRCS += vfork.S
+
+CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c
+CMN_CSRCS += up_mdelay.c up_udelay.c up_exit.c up_initialize.c up_memfault.c
+CMN_CSRCS += up_initialstate.c up_interruptcontext.c up_modifyreg8.c
+CMN_CSRCS += up_modifyreg16.c up_modifyreg32.c up_releasepending.c
+CMN_CSRCS += up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c
+CMN_CSRCS += up_sigdeliver.c up_unblocktask.c up_usestack.c up_doirq.c
+CMN_CSRCS += up_hardfault.c up_svcall.c up_checkstack.c up_vfork.c
+
+ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
+CMN_ASRCS += up_exception.S
+CMN_CSRCS += up_vectors.c
+endif
ifeq ($(CONFIG_ARCH_MEMCPY),y)
-CMN_ASRCS += up_memcpy.S
+CMN_ASRCS += up_memcpy.S
endif
ifeq ($(CONFIG_NET),y)
ifneq ($(CONFIG_LPC17_ETHERNET),y)
-CMN_CSRCS += up_etherstub.c
+CMN_CSRCS += up_etherstub.c
endif
endif
@@ -63,49 +73,58 @@ ifeq ($(CONFIG_ELF),y)
CMN_CSRCS += up_elf.c
endif
+ifeq ($(CONFIG_ARCH_FPU),y)
+CMN_ASRCS += up_fpu.S
+endif
+
# Required LPC17xx files
-CHIP_ASRCS =
-CHIP_CSRCS = lpc17_allocateheap.c lpc17_clockconfig.c lpc17_clrpend.c \
- lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c lpc17_lowputc.c \
- lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c lpc17_timerisr.c
+CHIP_ASRCS =
+
+CHIP_CSRCS = lpc17_allocateheap.c lpc17_clockconfig.c lpc17_clrpend.c
+CHIP_CSRCS += lpc17_gpio.c lpc17_i2c.c lpc17_idle.c lpc17_irq.c lpc17_lowputc.c
+CHIP_CSRCS += lpc17_serial.c lpc17_spi.c lpc17_ssp.c lpc17_start.c lpc17_timerisr.c
# Configuration-dependent LPC17xx files
+ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
+CHIP_ASRCS += lpc17_vectors.S
+endif
+
ifeq ($(CONFIG_GPIO_IRQ),y)
-CHIP_CSRCS += lpc17_gpioint.c
+CHIP_CSRCS += lpc17_gpioint.c
endif
ifeq ($(CONFIG_DEBUG_GPIO),y)
-CHIP_CSRCS += lpc17_gpiodbg.c
+CHIP_CSRCS += lpc17_gpiodbg.c
endif
ifeq ($(CONFIG_USBDEV),y)
-CHIP_CSRCS += lpc17_usbdev.c
+CHIP_CSRCS += lpc17_usbdev.c
endif
ifeq ($(CONFIG_USBHOST),y)
-CHIP_CSRCS += lpc17_usbhost.c
+CHIP_CSRCS += lpc17_usbhost.c
endif
ifeq ($(CONFIG_LPC17_GPDMA),y)
-CHIP_CSRCS += lpc17_gpdma.c
+CHIP_CSRCS += lpc17_gpdma.c
endif
ifeq ($(CONFIG_NET),y)
ifeq ($(CONFIG_LPC17_ETHERNET),y)
-CHIP_CSRCS += lpc17_ethernet.c
+CHIP_CSRCS += lpc17_ethernet.c
endif
endif
ifeq ($(CONFIG_CAN),y)
-CHIP_CSRCS += lpc17_can.c
+CHIP_CSRCS += lpc17_can.c
endif
ifeq ($(CONFIG_LPC17_ADC),y)
-CHIP_CSRCS += lpc17_adc.c
+CHIP_CSRCS += lpc17_adc.c
endif
ifeq ($(CONFIG_LPC17_DAC),y)
-CHIP_CSRCS += lpc17_dac.c
+CHIP_CSRCS += lpc17_dac.c
endif
diff --git a/nuttx/arch/arm/src/lpc17xx/chip.h b/nuttx/arch/arm/src/lpc17xx/chip.h
index 7bc1ab345..1f87c7b44 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip.h
@@ -42,11 +42,28 @@
#include <nuttx/config.h>
-/* Include the memory map and the chip definitions file. Other chip hardware files
- * should then include this file for the proper setup.
- */
+/* Include the chip capabilities file */
#include <arch/lpc17xx/chip.h>
+
+/* If the common ARMv7-M vector handling logic is used, then include the
+ * required vector definitions as well.
+ */
+
+#ifdef CONFIG_ARMV7M_CMNVECTOR
+# if defined(LPC176x)
+# include "chip/lpc176x_vectors.h"
+# elif defined(LPC178x)
+# include "chip/lpc178x_vectors.h"
+# else
+# error "No vector file for this LPC17xx family"
+# endif
+#endif
+
+/* Include the memory map file. Other chip hardware files should then include
+ * this file for the proper setup.
+ */
+
#include "chip/lpc17_memorymap.h"
/************************************************************************************
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_start.c b/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
index 45e5b4551..e13abe15c 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_start.c
@@ -53,6 +53,10 @@
#include "lpc17_clockconfig.h"
#include "lpc17_lowputc.h"
+#ifdef CONFIG_ARCH_FPU
+# include "nvic.h"
+#endif
+
/****************************************************************************
* Private Definitions
****************************************************************************/
@@ -84,6 +88,96 @@
#endif
/****************************************************************************
+ * Name: lpc17_fpuconfig
+ *
+ * Description:
+ * Configure the FPU. Relative bit settings:
+ *
+ * CPACR: Enables access to CP10 and CP11
+ * CONTROL.FPCA: Determines whether the FP extension is active in the
+ * current context:
+ * FPCCR.ASPEN: Enables automatic FP state preservation, then the
+ * processor sets this bit to 1 on successful completion of any FP
+ * instruction.
+ * FPCCR.LSPEN: Enables lazy context save of FP state. When this is
+ * done, the processor reserves space on the stack for the FP state,
+ * but does not save that state information to the stack.
+ *
+ * Software must not change the value of the ASPEN bit or LSPEN bit while either:
+ * - the CPACR permits access to CP10 and CP11, that give access to the FP
+ * extension, or
+ * - the CONTROL.FPCA bit is set to 1
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_FPU
+#ifdef CONFIG_ARMV7M_CMNVECTOR
+
+static inline void lpc17_fpuconfig(void)
+{
+ uint32_t regval;
+
+ /* Set CONTROL.FPCA so that we always get the extended context frame
+ * with the volatile FP registers stacked above the basic context.
+ */
+
+ regval = getcontrol();
+ regval |= (1 << 2);
+ setcontrol(regval);
+
+ /* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend
+ * with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we
+ * are going to turn on CONTROL.FPCA for all contexts.
+ */
+
+ regval = getreg32(NVIC_FPCCR);
+ regval &= ~((1 << 31) | (1 << 30));
+ putreg32(regval, NVIC_FPCCR);
+
+ /* Enable full access to CP10 and CP11 */
+
+ regval = getreg32(NVIC_CPACR);
+ regval |= ((3 << (2*10)) | (3 << (2*11)));
+ putreg32(regval, NVIC_CPACR);
+}
+
+#else
+
+static inline void lpc17_fpuconfig(void)
+{
+ uint32_t regval;
+
+ /* Clear CONTROL.FPCA so that we do not get the extended context frame
+ * with the volatile FP registers stacked in the saved context.
+ */
+
+ regval = getcontrol();
+ regval &= ~(1 << 2);
+ setcontrol(regval);
+
+ /* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend
+ * with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we
+ * are going to keep CONTROL.FPCA off for all contexts.
+ */
+
+ regval = getreg32(NVIC_FPCCR);
+ regval &= ~((1 << 31) | (1 << 30));
+ putreg32(regval, NVIC_FPCCR);
+
+ /* Enable full access to CP10 and CP11 */
+
+ regval = getreg32(NVIC_CPACR);
+ regval |= ((3 << (2*10)) | (3 << (2*11)));
+ putreg32(regval, NVIC_CPACR);
+}
+
+#endif
+
+#else
+# define lpc17_fpuconfig()
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -103,6 +197,7 @@ void __start(void)
/* Configure the uart so that we can get debug output as soon as possible */
lpc17_clockconfig();
+ lpc17_fpuconfig();
lpc17_lowsetup();
showprogress('A');
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
index e2cf91b1c..25d2e7f19 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S
@@ -39,12 +39,14 @@
************************************************************************************************/
#include <nuttx/config.h>
+
#include <arch/irq.h>
+#include "chip.h"
+
/************************************************************************************************
* Preprocessor Definitions
************************************************************************************************/
-
/* Memory Map:
*
* 0x0000:0000 - Beginning of FLASH. Address of vectors
@@ -72,12 +74,16 @@
* Global Symbols
************************************************************************************************/
- .globl __start
-
.syntax unified
.thumb
.file "lpc17_vectors.S"
+/* Check if common ARMv7 interrupt vectoring is used (see arch/arm/src/armv7-m/up_vectors.S) */
+
+#ifndef CONFIG_ARMV7M_CMNVECTOR
+
+ .globl __start
+
/************************************************************************************************
* Macros
************************************************************************************************/
@@ -208,13 +214,18 @@ lpc17_common:
*/
adds r2, r14, #3 /* If R14=0xfffffffd, then r2 == 0 */
- ite ne /* Next two instructions are condition */
+ ite ne /* Next two instructions are conditional */
mrsne r1, msp /* R1=The main stack pointer */
mrseq r1, psp /* R1=The process stack pointer */
#else
mrs r1, msp /* R1=The main stack pointer */
#endif
+ /* r1 holds the value of the stack pointer AFTER the excption handling logic
+ * pushed the various registers onto the stack. Get r2 = the value of the
+ * stack pointer BEFORE the interrupt modified it.
+ */
+
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
#ifdef CONFIG_ARMV7M_USEBASEPRI
@@ -222,7 +233,23 @@ lpc17_common:
#else
mrs r3, primask /* R3=Current PRIMASK setting */
#endif
-#ifdef CONFIG_NUTTX_KERNEL
+
+#ifdef CONFIG_ARCH_FPU
+ /* Skip over the block of memory reserved for floating pointer register save.
+ * Lazy FPU register saving is used. FPU registers will be saved in this
+ * block only if a context switch occurs (this means, of course, that the FPU
+ * cannot be used in interrupt processing).
+ */
+
+ sub r1, #(4*SW_FPU_REGS)
+#endif
+
+ /* Save the the remaining registers on the stack after the registers pushed
+ * by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11,
+ * r14=register values.
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
@@ -258,6 +285,25 @@ lpc17_common:
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
+ /* We are returning with a pending context switch.
+ *
+ * If the FPU is enabled, then we will need to restore FPU registers.
+ * This is not done in normal interrupt save/restore because the cost
+ * is prohibitive. This is only done when switching contexts. A
+ * consequence of this is that floating point operations may not be
+ * performed in interrupt handling logic.
+ *
+ * Here:
+ * r0 = Address of the register save area
+
+ * NOTE: It is a requirement that up_restorefpu() preserve the value of
+ * r0!
+ */
+
+#ifdef CONFIG_ARCH_FPU
+ bl up_restorefpu /* Restore the FPU registers */
+#endif
+
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
@@ -268,7 +314,7 @@ lpc17_common:
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
-#ifdef CONFIG_NUTTX_KERNEL
+#ifdef CONFIG_NUTTX_KERNEL
ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
@@ -277,13 +323,33 @@ lpc17_common:
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
+ *
+ * Here:
+ * r1 = Address of the return stack (same as r0)
*/
1:
-#ifdef CONFIG_NUTTX_KERNEL
+#ifdef CONFIG_NUTTX_KERNEL
ldmia r1!, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
+
+#ifdef CONFIG_ARCH_FPU
+ /* Skip over the block of memory reserved for floating pointer register
+ * save. Then R1 is the address of the HW save area
+ */
+
+ add r1, #(4*SW_FPU_REGS)
+#endif
+
+ /* Set up to return from the exception
+ *
+ * Here:
+ * r1 = Address on the target thread's stack position at the start of
+ * the registers saved by hardware
+ * r3 = primask or basepri
+ * r4-r11 = restored register values
+ */
2:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
@@ -338,6 +404,7 @@ up_interruptstack:
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
+#endif /* CONFIG_ARMV7M_CMNVECTOR */
/************************************************************************************************
* .rodata
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index fd19e3bf6..aea8719b1 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -34,33 +34,34 @@
############################################################################
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
-HEAD_ASRC =
+HEAD_ASRC =
else
-HEAD_ASRC = stm32_vectors.S
+HEAD_ASRC = stm32_vectors.S
endif
-CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S \
- vfork.S
-CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
- up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
- up_initialize.c up_initialstate.c up_interruptcontext.c \
- up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
- up_releasepending.c up_releasestack.c up_reprioritizertr.c \
- up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \
- up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c \
- up_svcall.c up_vfork.c
+CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
+CMN_ASRCS += vfork.S
+
+CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c
+CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c
+CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c
+CMN_CSRCS += up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
+CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c
+CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_systemreset.c
+CMN_CSRCS += up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c
+CMN_CSRCS += up_svcall.c up_vfork.c
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
-CMN_ASRCS += up_exception.S
-CMN_CSRCS += up_vectors.c
+CMN_ASRCS += up_exception.S
+CMN_CSRCS += up_vectors.c
endif
ifeq ($(CONFIG_ARCH_MEMCPY),y)
-CMN_ASRCS += up_memcpy.S
+CMN_ASRCS += up_memcpy.S
endif
ifeq ($(CONFIG_DEBUG_STACK),y)
-CMN_CSRCS += up_checkstack.c
+CMN_CSRCS += up_checkstack.c
endif
ifeq ($(CONFIG_ELF),y)
@@ -68,91 +69,92 @@ CMN_CSRCS += up_elf.c
endif
ifeq ($(CONFIG_ARCH_FPU),y)
-CMN_ASRCS += up_fpu.S
+CMN_ASRCS += up_fpu.S
endif
-CHIP_ASRCS =
-CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \
- stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \
- stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \
- stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c
+CHIP_ASRCS =
+
+CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c
+CHIP_CSRCS += stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c
+CHIP_CSRCS += stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c
+CHIP_CSRCS += stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c
+
+ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
+CHIP_ASRCS += stm32_vectors.S
+endif
ifeq ($(CONFIG_USBDEV),y)
ifeq ($(CONFIG_STM32_USB),y)
-CMN_CSRCS += stm32_usbdev.c
+CHIP_CSRCS += stm32_usbdev.c
endif
ifeq ($(CONFIG_STM32_OTGFS),y)
-CMN_CSRCS += stm32_otgfsdev.c
+CHIP_CSRCS += stm32_otgfsdev.c
endif
endif
ifeq ($(CONFIG_USBHOST),y)
ifeq ($(CONFIG_STM32_OTGFS),y)
-CMN_CSRCS += stm32_otgfshost.c
-endif
+CHIP_CSRCS += stm32_otgfshost.c
endif
-
-ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
-CHIP_ASRCS += stm32_vectors.S
endif
ifneq ($(CONFIG_IDLE_CUSTOM),y)
-CHIP_CSRCS += stm32_idle.c
+CHIP_CSRCS += stm32_idle.c
endif
-CHIP_CSRCS += stm32_pmstop.c stm32_pmstandby.c stm32_pmsleep.c
+CHIP_CSRCS += stm32_pmstop.c stm32_pmstandby.c stm32_pmsleep.c
ifneq ($(CONFIG_PM_CUSTOMINIT),y)
-CHIP_CSRCS += stm32_pminitialize.c
+CHIP_CSRCS += stm32_pminitialize.c
endif
ifeq ($(CONFIG_STM32_ETHMAC),y)
-CHIP_CSRCS += stm32_eth.c
+CHIP_CSRCS += stm32_eth.c
endif
ifeq ($(CONFIG_STM32_PWR),y)
-CHIP_CSRCS += stm32_pwr.c
+CHIP_CSRCS += stm32_pwr.c
endif
ifeq ($(CONFIG_RTC),y)
-CHIP_CSRCS += stm32_rtc.c
+CHIP_CSRCS += stm32_rtc.c
ifeq ($(CONFIG_RTC_ALARM),y)
-CHIP_CSRCS += stm32_exti_alarm.c
+CHIP_CSRCS += stm32_exti_alarm.c
endif
endif
ifeq ($(CONFIG_ADC),y)
-CHIP_CSRCS += stm32_adc.c
+CHIP_CSRCS += stm32_adc.c
endif
ifeq ($(CONFIG_DAC),y)
-CHIP_CSRCS += stm32_dac.c
+CHIP_CSRCS += stm32_dac.c
endif
ifeq ($(CONFIG_DEV_RANDOM),y)
-CHIP_CSRCS += stm32_rng.c
+CHIP_CSRCS += stm32_rng.c
endif
ifeq ($(CONFIG_PWM),y)
-CHIP_CSRCS += stm32_pwm.c
+CHIP_CSRCS += stm32_pwm.c
endif
ifeq ($(CONFIG_QENCODER),y)
-CHIP_CSRCS += stm32_qencoder.c
+CHIP_CSRCS += stm32_qencoder.c
endif
ifeq ($(CONFIG_CAN),y)
-CHIP_CSRCS += stm32_can.c
+CHIP_CSRCS += stm32_can.c
endif
ifeq ($(CONFIG_STM32_IWDG),y)
-CHIP_CSRCS += stm32_iwdg.c
+CHIP_CSRCS += stm32_iwdg.c
endif
ifeq ($(CONFIG_STM32_WWDG),y)
-CHIP_CSRCS += stm32_wwdg.c
+CHIP_CSRCS += stm32_wwdg.c
endif
ifeq ($(CONFIG_DEBUG),y)
-CHIP_CSRCS += stm32_dumpgpio.c
+CHIP_CSRCS += stm32_dumpgpio.c
endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_vectors.S b/nuttx/arch/arm/src/stm32/stm32_vectors.S
index 68a3e498b..ab29c2e14 100644
--- a/nuttx/arch/arm/src/stm32/stm32_vectors.S
+++ b/nuttx/arch/arm/src/stm32/stm32_vectors.S
@@ -40,7 +40,6 @@
#include <nuttx/config.h>
-
#include <arch/irq.h>
#include "chip.h"
diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c
index bb91d78c5..09ad4ee6c 100644
--- a/nuttx/binfmt/binfmt_execmodule.c
+++ b/nuttx/binfmt/binfmt_execmodule.c
@@ -175,13 +175,13 @@ int exec_module(FAR const struct binary_s *binp)
/* Initialize the task */
- ret = task_init(tcb, binp->filename, binp->priority, stack,
- binp->stacksize, binp->entrypt, binp->argv);
+ ret = task_init((FAR struct tcb_s *)tcb, binp->filename, binp->priority,
+ stack, binp->stacksize, binp->entrypt, binp->argv);
#else
/* Initialize the task */
- ret = task_init(tcb, binp->filename, binp->priority, stack,
- binp->entrypt, binp->argv);
+ ret = task_init((FAR struct tcb_s *)tcb, binp->filename, binp->priority,
+ stack, binp->entrypt, binp->argv);
#endif
if (ret < 0)
{
@@ -232,7 +232,7 @@ int exec_module(FAR const struct binary_s *binp)
/* Then activate the task at the provided priority */
- ret = task_activate(tcb);
+ ret = task_activate((FAR struct tcb_s *)tcb);
if (ret < 0)
{
err = errno;
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
index 05ca0fa2e..fc793ec7b 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
@@ -77,6 +77,9 @@ CONFIG_ARCH_CHIP_LPC17XX=y
CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_FAMILY="armv7-m"
CONFIG_ARCH_CHIP="lpc17xx"
+# CONFIG_ARMV7M_USEBASEPRI is not set
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+# CONFIG_ARMV7M_CMNVECTOR is not set
CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARMV7M_MPU is not set
CONFIG_BOARD_LOOPSPERMSEC=8111
@@ -271,6 +274,7 @@ CONFIG_DEV_CONSOLE=y
CONFIG_SDCLONE_DISABLE=y
# CONFIG_SCHED_WORKQUEUE is not set
CONFIG_SCHED_WAITPID=y
+# CONFIG_SCHED_STARTHOOK is not set
# CONFIG_SCHED_ATEXIT is not set
# CONFIG_SCHED_ONEXIT is not set
CONFIG_USER_ENTRYPOINT="nsh_main"
@@ -280,9 +284,7 @@ CONFIG_DISABLE_OS_API=y
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_DISABLE_SIGNALS is not set
# CONFIG_DISABLE_MQUEUE is not set
-# CONFIG_DISABLE_MOUNTPOINT is not set
# CONFIG_DISABLE_ENVIRON is not set
-CONFIG_DISABLE_POLL=y
#
# Signal Numbers
@@ -318,6 +320,7 @@ CONFIG_PTHREAD_STACK_DEFAULT=2048
#
# Device Drivers
#
+CONFIG_DISABLE_POLL=y
CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set
@@ -437,6 +440,7 @@ CONFIG_NET_ARPTAB_SIZE=16
#
# File system configuration
#
+# CONFIG_DISABLE_MOUNTPOINT is not set
# CONFIG_FS_RAMMAP is not set
CONFIG_FS_FAT=y
CONFIG_FAT_LCNAMES=y
@@ -452,6 +456,7 @@ CONFIG_FAT_MAXFNAME=32
#
# System Logging
#
+# CONFIG_SYSLOG_ENABLE is not set
# CONFIG_SYSLOG is not set
#
@@ -496,6 +501,8 @@ CONFIG_LIB_HOMEDIR="/"
# CONFIG_EOL_IS_BOTH_CRLF is not set
CONFIG_EOL_IS_EITHER_CRLF=y
# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
# CONFIG_LIBC_STRERROR is not set
# CONFIG_LIBC_PERROR_STDOUT is not set
CONFIG_ARCH_LOWPUTC=y
@@ -558,7 +565,6 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_OSTEST is not set
# CONFIG_EXAMPLES_PASHELLO is not set
# CONFIG_EXAMPLES_PIPE is not set
-# CONFIG_EXAMPLES_POLL is not set
# CONFIG_EXAMPLES_POSIXSPAWN is not set
# CONFIG_EXAMPLES_QENCODER is not set
# CONFIG_EXAMPLES_RGMP is not set
@@ -678,6 +684,10 @@ CONFIG_NSH_NESTDEPTH=3
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLEBG is not set
CONFIG_NSH_CONSOLE=y
+
+#
+# USB Trace Support
+#
# CONFIG_NSH_CONDEV is not set
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_TELNET=y
@@ -741,3 +751,7 @@ CONFIG_READLINE_ECHO=y
# Sysinfo
#
# CONFIG_SYSTEM_SYSINFO is not set
+
+#
+# USB Monitor
+#
diff --git a/nuttx/configs/open1788/README.txt b/nuttx/configs/open1788/README.txt
index 144be5242..154d4b2f7 100644
--- a/nuttx/configs/open1788/README.txt
+++ b/nuttx/configs/open1788/README.txt
@@ -8,8 +8,101 @@ NXP LPC1788 MCU
CONTENTS
========
+ o FPU
o Configuration
+FPU
+===
+
+FPU Configuration Options
+-------------------------
+
+There are two version of the FPU support built into the LPC17xx port.
+
+1. Lazy Floating Point Register Save.
+
+ This is an untested implementation that saves and restores FPU registers
+ only on context switches. This means: (1) floating point registers are
+ not stored on each context switch and, hence, possibly better interrupt
+ performance. But, (2) since floating point registers are not saved,
+ you cannot use floating point operations within interrupt handlers.
+
+ This logic can be enabled by simply adding the following to your .config
+ file:
+
+ CONFIG_ARCH_FPU=y
+
+2. Non-Lazy Floating Point Register Save
+
+ Mike Smith has contributed an extensive re-write of the ARMv7-M exception
+ handling logic. This includes verified support for the FPU. These changes
+ have not yet been incorporated into the mainline and are still considered
+ experimental. These FPU logic can be enabled with:
+
+ CONFIG_ARCH_FPU=y
+ CONFIG_ARMV7M_CMNVECTOR=y
+
+ You will probably also changes to the ld.script in if this option is selected.
+ This should work:
+
+ -ENTRY(_stext)
+ +ENTRY(__start) /* Treat __start as the anchor for dead code stripping */
+ +EXTERN(_vectors) /* Force the vectors to be included in the output */
+
+CFLAGS
+------
+
+Only the Atollic toolchain has built-in support for the Cortex-M4 FPU. You will see
+the following lines in each Make.defs file:
+
+ ifeq ($(CONFIG_STM32_ATOLLIC_LITE),y)
+ # Atollic toolchain under Windows
+ ...
+ ifeq ($(CONFIG_ARCH_FPU),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+ else
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ endif
+ endif
+
+If you are using a toolchain other than the Atollic toolchain, then to use the FPU
+you will also have to modify the CFLAGS to enable compiler support for the ARMv7-M
+FPU. As of this writing, there are not many GCC toolchains that will support the
+ARMv7-M FPU.
+
+As a minimum you will need to add CFLAG options to (1) enable hardware floating point
+code generation, and to (2) select the FPU implementation. You might try the same
+options as used with the Atollic toolchain in the Make.defs file:
+
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+
+Configuration Changes
+---------------------
+
+Below are all of the configuration changes that I had to make to configs/stm3240g-eval/nsh2
+in order to successfully build NuttX using the Atollic toolchain WITH FPU support:
+
+ -CONFIG_ARCH_FPU=n : Enable FPU support
+ +CONFIG_ARCH_FPU=y
+
+ -CONFIG_STM32_CODESOURCERYW=y : Disable the CodeSourcery toolchain
+ +CONFIG_STM32_CODESOURCERYW=n
+
+ -CONFIG_STM32_ATOLLIC_LITE=n : Enable *one* the Atollic toolchains
+ CONFIG_STM32_ATOLLIC_PRO=n
+ -CONFIG_STM32_ATOLLIC_LITE=y : The "Lite" version
+ CONFIG_STM32_ATOLLIC_PRO=n : The "Pro" version
+
+ -CONFIG_INTELHEX_BINARY=y : Suppress generation FLASH download formats
+ +CONFIG_INTELHEX_BINARY=n : (Only necessary with the "Lite" version)
+
+ -CONFIG_HAVE_CXX=y : Suppress generation of C++ code
+ +CONFIG_HAVE_CXX=n : (Only necessary with the "Lite" version)
+
+See the section above on Toolchains, NOTE 2, for explanations for some of
+the configuration settings. Some of the usual settings are just not supported
+by the "Lite" version of the Atollic toolchain.
+
CONFIGURURATION
===============
diff --git a/nuttx/libc/spawn/Make.defs b/nuttx/libc/spawn/Make.defs
index edbcc4fbb..f453a7d2d 100644
--- a/nuttx/libc/spawn/Make.defs
+++ b/nuttx/libc/spawn/Make.defs
@@ -35,8 +35,6 @@
# Add the spawn C files to the build
-ifeq ($(CONFIG_LIBC_EXECFUNCS),y)
-
CSRCS += lib_psfa_addaction.c lib_psfa_addclose.c lib_psfa_adddup2.c
CSRCS += lib_psfa_addopen.c lib_psfa_destroy.c lib_psfa_init.c
@@ -61,4 +59,3 @@ endif
DEPPATH += --dep-path spawn
VPATH += :spawn
-endif