Merge pull request #355 from PX4/kconfig-cleanup

Kconfig cleanup
This commit is contained in:
Lorenz Meier 2013-08-14 08:35:01 -07:00
commit 01d354effc
13 changed files with 78 additions and 69 deletions

View File

@ -148,14 +148,40 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)/nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@$(ECHO) %% Exporting NuttX for $(board)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
$(Q) mkdir -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
#
# The user can run the NuttX 'menuconfig' tool for a single board configuration with
# make BOARDS=<boardname> menuconfig
#
ifeq ($(MAKECMDGOALS),menuconfig)
ifneq ($(words $(BOARDS)),1)
$(error BOARDS must specify exactly one board for the menuconfig goal)
endif
BOARD = $(BOARDS)
menuconfig: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(BOARD)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
@$(ECHO) %% Running menuconfig for $(BOARD)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
@$(ECHO) %% Saving configuration file
$(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
else
menuconfig:
@$(ECHO) ""
@$(ECHO) "The menuconfig goal must be invoked without any other goal being specified"
@$(ECHO) ""
endif
$(NUTTX_SRC):
@$(ECHO) ""
@$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again."

View File

@ -6,5 +6,6 @@
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM4F
CONFIG_BOARD = PX4FMU_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk

View File

@ -6,5 +6,6 @@
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM3
CONFIG_BOARD = PX4IO_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk

View File

@ -153,6 +153,7 @@ ifeq ($(BOARD_FILE),)
$(error Config $(CONFIG) references board $(BOARD), but no board definition file found)
endif
export BOARD
export BOARD_FILE
include $(BOARD_FILE)
$(info % BOARD = $(BOARD))

View File

@ -98,6 +98,7 @@
#
# CONFIG
# BOARD
# BOARD_FILE
# MODULE_WORK_DIR
# MODULE_OBJ
# MODULE_MK
@ -117,7 +118,7 @@ $(info %% MODULE_MK = $(MODULE_MK))
#
# Get the board/toolchain config
#
include $(PX4_MK_DIR)/board_$(BOARD).mk
include $(BOARD_FILE)
#
# Get the module's config

View File

@ -85,6 +85,13 @@ ifeq ($(ARCHCPUFLAGS),)
$(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3)
endif
# Set the board flags
#
ifeq ($(CONFIG_BOARD),)
$(error Board config does not define CONFIG_BOARD)
endif
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD)
# optimisation flags
#
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \

View File

@ -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

View File

@ -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
#
@ -560,6 +564,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
@ -748,6 +753,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

View File

@ -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

View File

@ -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
#

View File

@ -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 */

View File

@ -117,10 +117,6 @@
#include <systemlib/err.h>
#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

View File

@ -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);