From 0017d65ee25f15e67e5376ac59340e5835032867 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 8 Feb 2013 00:17:54 +0000 Subject: 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 --- nuttx/arch/arm/Kconfig | 1 + nuttx/arch/arm/src/lpc17xx/Make.defs | 69 ++++++++++++++-------- nuttx/arch/arm/src/lpc17xx/chip.h | 23 +++++++- nuttx/arch/arm/src/lpc17xx/lpc17_start.c | 95 ++++++++++++++++++++++++++++++ nuttx/arch/arm/src/lpc17xx/lpc17_vectors.S | 81 ++++++++++++++++++++++--- nuttx/arch/arm/src/stm32/Make.defs | 92 +++++++++++++++-------------- nuttx/arch/arm/src/stm32/stm32_vectors.S | 1 - 7 files changed, 281 insertions(+), 81 deletions(-) (limited to 'nuttx/arch') 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 -/* 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 + +/* 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 ****************************************************************************/ @@ -83,6 +87,96 @@ # define showprogress(c) #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 + #include +#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 - #include #include "chip.h" -- cgit v1.2.3