From 60275e1ae65633dfc03f6353b7796ed540975803 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 21:59:10 -0700 Subject: Clean the FMUv1 config through menuconfig. --- nuttx-configs/px4fmu-v1/nsh/defconfig | 32 +++++++++++++++++++------------- 1 file changed, 19 insertions(+), 13 deletions(-) (limited to 'nuttx-configs/px4fmu-v1') diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index d33816129..a7a6725c6 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -73,17 +73,16 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set # CONFIG_ARCH_CHIP_NUC1XX is not set -# CONFIG_ARCH_CHIP_SAM3U is not set +# CONFIG_ARCH_CHIP_SAM34 is not set CONFIG_ARCH_CHIP_STM32=y # CONFIG_ARCH_CHIP_STR71X is not set CONFIG_ARCH_CORTEXM4=y -CONFIG_ARCH_HAVE_FPU=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y -CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARCH_HAVE_FPU=y CONFIG_ARCH_FPU=y CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARMV7M_MPU is not set @@ -93,10 +92,8 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y +CONFIG_ARMV7M_STACKCHECK=y CONFIG_SERIAL_TERMIOS=y -CONFIG_SERIAL_DISABLE_REORDERING=y -CONFIG_SERIAL_IFLOWCONTROL=y -CONFIG_SERIAL_OFLOWCONTROL=y # # STM32 Configuration Options @@ -248,6 +245,7 @@ CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y # CONFIG_STM32_FORCEPOWER is not set # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_STM32_DMACAPABLE=y # CONFIG_STM32_TIM4_PWM is not set # CONFIG_STM32_TIM5_PWM is not set # CONFIG_STM32_TIM9_PWM is not set @@ -275,6 +273,7 @@ CONFIG_UART5_RXDMA=y CONFIG_USART6_RXDMA=y # CONFIG_USART7_RXDMA is not set # CONFIG_USART8_RXDMA is not set +CONFIG_SERIAL_DISABLE_REORDERING=y CONFIG_STM32_USART_SINGLEWIRE=y # @@ -342,15 +341,12 @@ CONFIG_BOOT_RUNFROMFLASH=y # # Board Selection # -CONFIG_ARCH_BOARD_PX4FMU_V1=y -# CONFIG_ARCH_BOARD_CUSTOM is not set -CONFIG_ARCH_BOARD="px4fmu-v1" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD="" # # Common Board Options # -CONFIG_ARCH_HAVE_LEDS=y -# CONFIG_ARCH_LEDS is not set CONFIG_NSH_MMCSDMINOR=0 CONFIG_NSH_MMCSDSLOTNO=0 CONFIG_NSH_MMCSDSPIPORTNO=3 @@ -358,8 +354,6 @@ CONFIG_NSH_MMCSDSPIPORTNO=3 # # Board-Specific Options # -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y # # RTOS Features @@ -497,6 +491,8 @@ CONFIG_USART1_BAUD=57600 CONFIG_USART1_BITS=8 CONFIG_USART1_PARITY=0 CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set # # USART2 Configuration @@ -507,6 +503,8 @@ CONFIG_USART2_BAUD=57600 CONFIG_USART2_BITS=8 CONFIG_USART2_PARITY=0 CONFIG_USART2_2STOP=0 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y # # UART5 Configuration @@ -517,6 +515,8 @@ CONFIG_UART5_BAUD=57600 CONFIG_UART5_BITS=8 CONFIG_UART5_PARITY=0 CONFIG_UART5_2STOP=0 +# CONFIG_UART5_IFLOWCONTROL is not set +# CONFIG_UART5_OFLOWCONTROL is not set # # USART6 Configuration @@ -527,6 +527,10 @@ CONFIG_USART6_BAUD=57600 CONFIG_USART6_BITS=8 CONFIG_USART6_PARITY=0 CONFIG_USART6_2STOP=0 +# CONFIG_USART6_IFLOWCONTROL is not set +# CONFIG_USART6_OFLOWCONTROL is not set +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y CONFIG_USBDEV=y # @@ -559,6 +563,7 @@ CONFIG_CDCACM_EPBULKIN_FSSIZE=64 CONFIG_CDCACM_EPBULKIN_HSSIZE=512 CONFIG_CDCACM_NWRREQS=4 CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 CONFIG_CDCACM_RXBUFSIZE=256 CONFIG_CDCACM_TXBUFSIZE=256 CONFIG_CDCACM_VENDORID=0x26ac @@ -747,6 +752,7 @@ CONFIG_EXAMPLES_CDCACM=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set CONFIG_EXAMPLES_MOUNT=y +# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set -- cgit v1.2.3 From de749a3602423f5ee6ca56f3cf2dfff04e31ec6d Mon Sep 17 00:00:00 2001 From: px4dev Date: Tue, 13 Aug 2013 00:34:41 -0700 Subject: Stop expecting CONFIG_HRT_anything since we aren't baking it into the NuttX config anymore. --- nuttx-configs/px4fmu-v1/include/board.h | 12 ++++-------- nuttx-configs/px4io-v1/include/board.h | 12 ++++-------- nuttx-configs/px4io-v1/nsh/defconfig | 22 ---------------------- src/drivers/stm32/drv_hrt.c | 20 ++++++++++---------- src/drivers/stm32/tone_alarm/tone_alarm.cpp | 4 ---- src/systemcmds/tests/test_hrt.c | 2 +- 6 files changed, 19 insertions(+), 53 deletions(-) (limited to 'nuttx-configs/px4fmu-v1') diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h index 5529d5097..839631b3a 100644 --- a/nuttx-configs/px4fmu-v1/include/board.h +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -158,10 +158,8 @@ /* High-resolution timer */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ -#endif +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ /* LED definitions ******************************************************************/ /* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any @@ -241,10 +239,8 @@ * * PPM input is handled by the HRT timer. */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ -# define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) -#endif +#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ +#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) /* * CAN diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h index 668602ea8..6503a94cd 100755 --- a/nuttx-configs/px4io-v1/include/board.h +++ b/nuttx-configs/px4io-v1/include/board.h @@ -118,10 +118,8 @@ /* * High-resolution timer */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ -#endif +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ /* * PPM @@ -130,10 +128,8 @@ * * Pin is PA8, timer 1, channel 1 */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ -# define GPIO_PPM_IN GPIO_TIM1_CH1IN -#endif +#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN GPIO_TIM1_CH1IN /************************************************************************************ * Public Data diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig index 525672233..3785e0367 100755 --- a/nuttx-configs/px4io-v1/nsh/defconfig +++ b/nuttx-configs/px4io-v1/nsh/defconfig @@ -200,28 +200,6 @@ SERIAL_HAVE_CONSOLE_DMA=y CONFIG_USART2_RXDMA=n CONFIG_USART3_RXDMA=y -# -# PX4IO specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# CONFIG_PWM_SERVO -# Enables the PWM servo driver. The driver configuration must be -# supplied by the board support at initialisation time. -# Note that USART2 must be disabled on the PX4 board for this to -# be available. -# -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y - # # General build options # diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c index 7ef3db970..83a1a1abb 100644 --- a/src/drivers/stm32/drv_hrt.c +++ b/src/drivers/stm32/drv_hrt.c @@ -70,7 +70,7 @@ #include "stm32_gpio.h" #include "stm32_tim.h" -#ifdef CONFIG_HRT_TIMER +#ifdef HRT_TIMER /* HRT configuration */ #if HRT_TIMER == 1 @@ -155,7 +155,7 @@ # error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11 # endif #else -# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y +# error HRT_TIMER must be a value between 1 and 11 #endif /* @@ -275,7 +275,7 @@ static void hrt_call_invoke(void); /* * Specific registers and bits used by PPM sub-functions */ -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it. * @@ -326,7 +326,7 @@ static void hrt_call_invoke(void); # define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC4P # else -# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set +# error HRT_PPM_CHANNEL must be a value between 1 and 4 # endif /* @@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status); # define CCMR1_PPM 0 # define CCMR2_PPM 0 # define CCER_PPM 0 -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Initialise the timer we are going to use. @@ -424,7 +424,7 @@ hrt_tim_init(void) up_enable_irq(HRT_TIMER_VECTOR); } -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * Handle the PPM decoder state machine. */ @@ -526,7 +526,7 @@ error: ppm_decoded_channels = 0; } -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Handle the compare interupt by calling the callout dispatcher @@ -546,7 +546,7 @@ hrt_tim_isr(int irq, void *context) /* ack the interrupts we just read */ rSR = ~status; -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* was this a PPM edge? */ if (status & (SR_INT_PPM | SR_OVF_PPM)) { @@ -686,7 +686,7 @@ hrt_init(void) sq_init(&callout_queue); hrt_tim_init(); -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* configure the PPM input pin */ stm32_configgpio(GPIO_PPM_IN); #endif @@ -907,4 +907,4 @@ hrt_latency_update(void) } -#endif /* CONFIG_HRT_TIMER */ +#endif /* HRT_TIMER */ diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 167ef30a8..2284be84d 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -117,10 +117,6 @@ #include -#ifndef CONFIG_HRT_TIMER -# error This driver requires CONFIG_HRT_TIMER -#endif - /* Tone alarm configuration */ #if TONE_ALARM_TIMER == 2 # define TONE_ALARM_BASE STM32_TIM2_BASE diff --git a/src/systemcmds/tests/test_hrt.c b/src/systemcmds/tests/test_hrt.c index f21dd115b..f6e540401 100644 --- a/src/systemcmds/tests/test_hrt.c +++ b/src/systemcmds/tests/test_hrt.c @@ -94,7 +94,7 @@ extern uint16_t ppm_pulse_history[]; int test_ppm(int argc, char *argv[]) { -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL unsigned i; printf("channels: %u\n", ppm_decoded_channels); -- cgit v1.2.3