From 4044fbd4a077986ec07ce71b9f810ecfe2bbf526 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Thu, 11 Mar 2021 19:39:01 +0100 Subject: [PATCH] Initial Kconfig implementation in CMake Used fmuk66-v3 as test case --- CMakeLists.txt | 2 + Kconfig | 9 + boards/nxp/fmuk66-v3/default-boardconfig | 189 +++++++++++++++++++ cmake/kconfig.cmake | 82 ++++++++ src/drivers/Kconfig | 227 +++++++++++++++++++---- src/drivers/adc/Kconfig | 11 ++ src/drivers/barometer/Kconfig | 53 ++++++ src/drivers/imu/Kconfig | 59 ++++++ src/drivers/lights/Kconfig | 26 +++ 9 files changed, 617 insertions(+), 41 deletions(-) create mode 100644 boards/nxp/fmuk66-v3/default-boardconfig create mode 100644 cmake/kconfig.cmake create mode 100644 src/drivers/adc/Kconfig create mode 100644 src/drivers/barometer/Kconfig create mode 100644 src/drivers/imu/Kconfig create mode 100644 src/drivers/lights/Kconfig diff --git a/CMakeLists.txt b/CMakeLists.txt index 5e9d253c7a..346383d1ff 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -149,6 +149,8 @@ include(${PX4_CONFIG_FILE}) message(STATUS "PX4 config: ${PX4_CONFIG}") message(STATUS "PX4 platform: ${PX4_PLATFORM}") +include(kconfig) + if(${PX4_PLATFORM} STREQUAL "posix") if(ENABLE_LOCKSTEP_SCHEDULER) add_definitions(-DENABLE_LOCKSTEP_SCHEDULER) diff --git a/Kconfig b/Kconfig index 15eee4135d..b6582a28ef 100644 --- a/Kconfig +++ b/Kconfig @@ -3,6 +3,15 @@ mainmenu "PX4 Firmware Configuration" +comment "Platform: $(PLATFORM)" +comment "Vendor: $(VENDOR)" +comment "Model: $(MODEL)" +comment "Label: $(LABEL)" +comment "Toolchain: $(TOOLCHAIN)" +comment "Architecture: $(ARCHITECTURE)" +comment "Romfsroot: $(ROMFSROOT)" + + menu "drivers" source src/drivers/Kconfig endmenu diff --git a/boards/nxp/fmuk66-v3/default-boardconfig b/boards/nxp/fmuk66-v3/default-boardconfig new file mode 100644 index 0000000000..df6f91de12 --- /dev/null +++ b/boards/nxp/fmuk66-v3/default-boardconfig @@ -0,0 +1,189 @@ +# Generated by Kconfiglib (https://github.com/ulfalizer/Kconfiglib) + +# +# Platform: nuttx +# + +# +# Vendor: nxp +# + +# +# Model: fmuk66-v3 +# + +# +# Label: default +# + +# +# Toolchain: Toolchain-arm-none-eabi +# + +# +# Architecture: cortex-m4 +# + +# +# Romfsroot: px4fmu_common +# + +# +# drivers +# + +# +# ADC +# +# CONFIG_DRIVERS_ADC_ADS1115 is not set +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER=y +# CONFIG_DRIVERS_BAROMETER_BMP280 is not set +# CONFIG_DRIVERS_BAROMETER_BMP388 is not set +# CONFIG_DRIVERS_BAROMETER_DPS310 is not set +# CONFIG_DRIVERS_BAROMETER_LPS22HB is not set +# CONFIG_DRIVERS_BAROMETER_LPS25H is not set +# CONFIG_DRIVERS_BAROMETER_LPS33HW is not set +CONFIG_DRIVERS_BAROMETER_MPL3115A2=y +# CONFIG_DRIVERS_BAROMETER_MS5611 is not set +# CONFIG_DRIVERS_BAROMETER_TCBP001TA is not set +CONFIG_DRIVERS_BATT_SMBUS=y +# CONFIG_DRIVERS_BOOTLOADERS is not set +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DISTANCE_SENSOR=y +# CONFIG_DRIVERS_DSHOT is not set +CONFIG_DRIVERS_GPS=y +# CONFIG_DRIVERS_HEATER is not set + +# +# IMU +# +# CONFIG_DRIVERS_IMU_ADIS16477 is not set +# CONFIG_DRIVERS_IMU_ADIS16497 is not set +# CONFIG_DRIVERS_IMU_ANALOG_DEVICES is not set +# CONFIG_DRIVERS_IMU_BOSCH is not set +CONFIG_DRIVERS_IMU_FXAS21002C=y +CONFIG_DRIVERS_IMU_FXOS8701CQ=y +# CONFIG_DRIVERS_IMU_INVENSENSE is not set +# CONFIG_DRIVERS_IMU_L3GD20 is not set +# CONFIG_DRIVERS_IMU_LSM303D is not set +# CONFIG_DRIVERS_IMU_ST is not set +CONFIG_DRIVERS_IRLOCK=y + +# +# Lights +# +CONFIG_DRIVERS_LIGHTS_BLINKM=y +# CONFIG_DRIVERS_LIGHTS_NEOPIXEL is not set +CONFIG_DRIVERS_LIGHTS_RGBLED=y +CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y +CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y +# CONFIG_DRIVERS_LINUX_PWM_OUT is not set +# CONFIG_DRIVERS_MAGNETOMETER is not set +# CONFIG_DRIVERS_OPTICAL_FLOW is not set +# CONFIG_DRIVERS_OSD is not set +# CONFIG_DRIVERS_PCA9685 is not set +# CONFIG_DRIVERS_PCA9685_PWM_OUT is not set +# CONFIG_DRIVERS_POWER_MONITOR is not set +# CONFIG_DRIVERS_PROTOCOL_SPLITTER is not set +# CONFIG_DRIVERS_PWM_INPUT is not set +# CONFIG_DRIVERS_PWM_OUT is not set +# CONFIG_DRIVERS_PWM_OUT_SIM is not set +# CONFIG_DRIVERS_PX4IO is not set +# CONFIG_DRIVERS_QSHELL is not set +# CONFIG_DRIVERS_RC_INPUT is not set +# CONFIG_DRIVERS_ROBOCLAW is not set +# CONFIG_DRIVERS_RPI_RC_IN is not set +# CONFIG_DRIVERS_RPM is not set +# CONFIG_DRIVERS_SAFETY_BUTTON is not set +# CONFIG_DRIVERS_SPEKTRUM_RC is not set +# CONFIG_DRIVERS_TELEMETRY is not set +# CONFIG_DRIVERS_TEST_PPM is not set +# CONFIG_DRIVERS_TONE_ALARM is not set +# CONFIG_DRIVERS_UAVCAN is not set +# CONFIG_DRIVERS_UAVCAN_V1 is not set + +# +# modules +# +# CONFIG_AIRSHIP_ATT_CONTROL is not set +# CONFIG_AIRSPEED_SELECTOR is not set +# CONFIG_ANGULAR_VELOCITY_CONTROLLER is not set +# CONFIG_ATTITUDE_ESTIMATOR_Q is not set +# CONFIG_BATTERY_STATUS is not set +# CONFIG_CAMERA_FEEDBACK is not set +# CONFIG_COMMANDER is not set +# CONFIG_CONTROL_ALLOCATOR is not set +# CONFIG_DATAMAN is not set +# CONFIG_EKF2 is not set +# CONFIG_ESC_BATTERY is not set +# CONFIG_EVENTS is not set +# CONFIG_FLIGHT_MODE_MANAGER is not set +# CONFIG_FW_ATT_CONTROL is not set +# CONFIG_FW_POS_CONTROL_L1 is not set +# CONFIG_GYRO_FFT is not set +# CONFIG_LAND_DETECTOR is not set +# CONFIG_LANDING_TARGET_ESTIMATOR is not set +# CONFIG_LOAD_MON is not set +# CONFIG_LOCAL_POSITION_ESTIMATOR is not set +# CONFIG_LOGGER is not set +# CONFIG_MAVLINK is not set +# CONFIG_MC_ATT_CONTROL is not set +# CONFIG_MC_HOVER_THRUST_ESTIMATOR is not set +# CONFIG_MC_POS_CONTROL is not set +# CONFIG_MC_RATE_CONTROL is not set +# CONFIG_MICRORTPS_BRIDGE is not set +# CONFIG_MUORB is not set +# CONFIG_NAVIGATOR is not set +# CONFIG_PX4IOFIRMWARE is not set +# CONFIG_RC_UPDATE is not set +# CONFIG_REPLAY is not set +# CONFIG_ROVER_POS_CONTROL is not set +# CONFIG_SENSORS is not set +# CONFIG_SIH is not set +# CONFIG_SIMULATOR is not set +# CONFIG_TEMPERATURE_COMPENSATION is not set +# CONFIG_UUV_ATT_CONTROL is not set +# CONFIG_UUV_POS_CONTROL is not set +# CONFIG_VMOUNT is not set +# CONFIG_VTOL_ATT_CONTROL is not set + +# +# systemcmds +# +# CONFIG_BL_UPDATE is not set +# CONFIG_DMESG is not set +# CONFIG_DUMPFILE is not set +# CONFIG_DYN is not set +# CONFIG_ESC_CALIB is not set +# CONFIG_FAILURE is not set +# CONFIG_GPIO is not set +# CONFIG_HARDFAULT_LOG is not set +# CONFIG_I2CDETECT is not set +# CONFIG_LED_CONTROL is not set +# CONFIG_MFT is not set +# CONFIG_MIXER is not set +# CONFIG_MOTOR_RAMP is not set +# CONFIG_MOTOR_TEST is not set +# CONFIG_MTD is not set +# CONFIG_NETMAN is not set +# CONFIG_NSHTERM is not set +# CONFIG_PARAM is not set +# CONFIG_PERF is not set +# CONFIG_PWM is not set +# CONFIG_REBOOT is not set +# CONFIG_REFLECT is not set +# CONFIG_SD_BENCH is not set +# CONFIG_SERIAL_TEST is not set +# CONFIG_SHUTDOWN is not set +# CONFIG_SYSTEM_TIME is not set +# CONFIG_TESTS is not set +# CONFIG_TOP is not set +# CONFIG_TOPIC_LISTENER is not set +# CONFIG_TUNE_CONTROL is not set +# CONFIG_UORB is not set +# CONFIG_USB_CONNECTED is not set +# CONFIG_VER is not set +# CONFIG_WORK_QUEUE is not set diff --git a/cmake/kconfig.cmake b/cmake/kconfig.cmake new file mode 100644 index 0000000000..62789996d5 --- /dev/null +++ b/cmake/kconfig.cmake @@ -0,0 +1,82 @@ +set(BOARD_DEFCONFIG ${PX4_BOARD_DIR}/${PX4_BOARD_LABEL}-boardconfig CACHE FILEPATH "path to defconfig" FORCE) + +set(COMMON_KCONFIG_ENV_SETTINGS + PYTHON_EXECUTABLE=${PYTHON_EXECUTABLE} + KCONFIG_CONFIG=${BOARD_DEFCONFIG} + # Set environment variables so that Kconfig can prune Kconfig source + # files for other architectures + PLATFORM=${PX4_PLATFORM} + VENDOR=${PX4_BOARD_VENDOR} + MODEL=${PX4_BOARD_MODEL} + LABEL=${PX4_BOARD_LABEL} + TOOLCHAIN=${CMAKE_TOOLCHAIN_FILE} + ARCHITECTURE=${CMAKE_SYSTEM_PROCESSOR} + ROMFSROOT=${config_romfs_root} +) + +add_custom_target(boardconfig + ${CMAKE_COMMAND} -E env + ${COMMON_KCONFIG_ENV_SETTINGS} + ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/tools/menuconfig.py Kconfig + WORKING_DIRECTORY ${PX4_SOURCE_DIR} + USES_TERMINAL + COMMAND_EXPAND_LISTS +) + +# parse board config options for cmake +file(STRINGS ${BOARD_DEFCONFIG} ConfigContents) +foreach(NameAndValue ${ConfigContents}) + # Strip leading spaces + string(REGEX REPLACE "^[ ]+" "" NameAndValue ${NameAndValue}) + + # Find variable name + string(REGEX MATCH "^CONFIG[^=]+" Name ${NameAndValue}) + + if(Name) + # Find the value + string(REPLACE "${Name}=" "" Value ${NameAndValue}) + + if(Value) + # remove extra quotes + string(REPLACE "\"" "" Value ${Value}) + + # Set the variable + #message(STATUS "${Name} ${Value}") + set(${Name} ${Value} CACHE INTERNAL "BOARD DEFCONFIG: ${Name}" FORCE) + endif() + endif() + + # Find variable name + string(REGEX MATCH "^CONFIG_DRIVERS[^=]+" Drivers ${NameAndValue}) + + if(Drivers) + # Find the value + string(REPLACE "${Name}=" "" Value ${NameAndValue}) + string(REPLACE "CONFIG_DRIVERS_" "" driver ${Name}) + string(TOLOWER ${driver} driver) + + string(REPLACE "_" "/" driver_path ${driver}) + + # Pattern 1 XXX / XXX_XXX + string(REGEX REPLACE "(^[a-z]+)_([a-z]+_[a-z0-9]+).*$" "\\1" driver_p1_folder ${driver}) + string(REGEX REPLACE "(^[a-z]+)_([a-z]+_[a-z0-9]+).*$" "\\2" driver_p1_subfolder ${driver}) + + # Pattern 2 XXX_XXX / XXXXXX + string(REGEX REPLACE "(^[a-z]+_[a-z]+)_([a-z0-9]+).*$" "\\1" driver_p2_folder ${driver}) + string(REGEX REPLACE "(^[a-z]+_[a-z]+)_([a-z0-9]+).*$" "\\2" driver_p2_subfolder ${driver}) + + # Trick circumvent PX4 src naming problem with underscores and slashes + if(EXISTS ${PX4_SOURCE_DIR}/src/drivers/${driver}) + list(APPEND config_module_list drivers/${driver}) + elseif(EXISTS ${PX4_SOURCE_DIR}/src/drivers/${driver_path}) + list(APPEND config_module_list drivers/${driver_path}) + elseif(EXISTS ${PX4_SOURCE_DIR}/src/drivers/${driver_p1_folder}/${driver_p1_subfolder}) + list(APPEND config_module_list drivers/${driver_p1_folder}/${driver_p1_subfolder}) + elseif(EXISTS ${PX4_SOURCE_DIR}/src/drivers/${driver_p2_folder}/${driver_p2_subfolder}) + list(APPEND config_module_list drivers/${driver_p2_folder}/${driver_p2_subfolder}) + else() + message(FATAL_ERROR "Couldn't find path for ${driver}") + endif() + + endif() +endforeach() diff --git a/src/drivers/Kconfig b/src/drivers/Kconfig index 3a85b43734..6b3489d5fa 100644 --- a/src/drivers/Kconfig +++ b/src/drivers/Kconfig @@ -1,86 +1,231 @@ -menuconfig ADC - bool "ADC Support" +menu "ADC" +source src/drivers/adc/Kconfig +endmenu + +menuconfig DRIVERS_BAROMETER + bool "Barometer" default n ---help--- - Enable support for ADC + Enable support for Barometers -menuconfig BAROMETER - bool "Barometer Support" +if DRIVERS_BAROMETER +source src/drivers/barometer/Kconfig +endif #DRIVERS_BAROMETER + +menuconfig DRIVERS_BATT_SMBUS + bool "batt smbus" default n ---help--- - Enable support for all available barometer drivers - -menuconfig BOOTLOADERS - bool "BOOTLOADERS Support" + Enable support for batt smbus + +menuconfig DRIVERS_BOOTLOADERS + bool "BOOTLOADERS" default n ---help--- Enable support for bootloaders -menuconfig DIFFERENTIAL_PRESSURE - bool "Differential pressure Support" +menuconfig DRIVERS_CAMERA_CAPTURE + bool "camera capture" + default n + ---help--- + Enable support for camera capture + +menuconfig DRIVERS_CAMERA_TRIGGER + bool "camera trigger" + default n + ---help--- + Enable support for camera trigger + +menuconfig DRIVERS_DIFFERENTIAL_PRESSURE + bool "Differential pressure" default n ---help--- Enable support for all available differential pressure drivers -menuconfig GPS - bool "GPS Support" +menuconfig DRIVERS_DISTANCE_SENSOR + bool "distance sensor" + default n + ---help--- + Enable support for distance sensor + +menuconfig DRIVERS_DSHOT + bool "dshot" + default n + ---help--- + Enable support for dshot + +menuconfig DRIVERS_GPS + bool "GPS" default n ---help--- Enable support for all available GPS drivers -menuconfig IMU - bool "IMU Support" +menuconfig DRIVERS_HEATER + bool "heater" default n ---help--- - Enable support for all available IMU drivers + Enable support for heater -menuconfig LIGHTS - bool "Lights Support" - default n - ---help--- - Enable support for lights - -if LIGHTS -#source src/drivers/lights/Kconfig -endif #LIGHTS +menu "IMU" +source src/drivers/imu/Kconfig +endmenu -menuconfig MAGNETOMETER - bool "Magnetometer Support" +menuconfig DRIVERS_IRLOCK + bool "irlock" + default n + ---help--- + Enable support for irlock + +menu "Lights" +source src/drivers/lights/Kconfig +endmenu + +menuconfig DRIVERS_LINUX_PWM_OUT + bool "linux pwm out" + default n + ---help--- + Enable support for linux pwm out + +menuconfig DRIVERS_MAGNETOMETER + bool "Magnetometer" default n ---help--- Enable support for all available magnetometer drivers -menuconfig OPTICAL_FLOW - bool "Optical flow Support" +menuconfig DRIVERS_OPTICAL_FLOW + bool "Optical flow" default n ---help--- Enable support for all available optical flow drivers -menuconfig PWM_OUT - bool "PWM Out Support" + +menuconfig DRIVERS_OSD + bool "osd" default n ---help--- - Enable support for PWM Out + Enable support for osd -menuconfig SAFETY_BUTTON - bool "Safety button Support" +menuconfig DRIVERS_PCA9685 + bool "pca9685" default n ---help--- - Enable support for Safety button + Enable support for pca9685 -menuconfig TONE_ALARM - bool "Tone alarm Support" +menuconfig DRIVERS_PCA9685_PWM_OUT + bool "pca9685 pwm out" + default n + ---help--- + Enable support for pca9685 pwm out + +menuconfig DRIVERS_POWER_MONITOR + bool "power monitor" + default n + ---help--- + Enable support for power monitor + +menuconfig DRIVERS_PROTOCOL_SPLITTER + bool "protocol splitter" + default n + ---help--- + Enable support for protocol splitter + +menuconfig DRIVERS_PWM_INPUT + bool "pwm input" + default n + ---help--- + Enable support for pwm input + +menuconfig DRIVERS_PWM_OUT + bool "pwm out" + default n + ---help--- + Enable support for pwm out + +menuconfig DRIVERS_PWM_OUT_SIM + bool "pwm out sim" + default n + ---help--- + Enable support for pwm out sim + +menuconfig DRIVERS_PX4IO + bool "px4io" + default n + ---help--- + Enable support for px4io + +menuconfig DRIVERS_QSHELL + bool "qshell" + default n + ---help--- + Enable support for qshell + +menuconfig DRIVERS_RC_INPUT + bool "rc input" + default n + ---help--- + Enable support for rc input + +menuconfig DRIVERS_ROBOCLAW + bool "roboclaw" + default n + ---help--- + Enable support for roboclaw + +menuconfig DRIVERS_RPI_RC_IN + bool "rpi rc in" + default n + ---help--- + Enable support for rpi rc in + +menuconfig DRIVERS_RPM + bool "rpm" + default n + ---help--- + Enable support for rpm + +menuconfig DRIVERS_SAFETY_BUTTON + bool "safety button" + default n + ---help--- + Enable support for safety button + +menuconfig DRIVERS_SPEKTRUM_RC + bool "spektrum rc" + default n + ---help--- + Enable support for spektrum rc + +menuconfig DRIVERS_TELEMETRY + bool "telemetry" + default n + ---help--- + Enable support for telemetry + +menuconfig DRIVERS_TEST_PPM + bool "test ppm" + default n + ---help--- + Enable support for test ppm + +menuconfig DRIVERS_TONE_ALARM + bool "Tone alarm" default n ---help--- Enable support for tone alarm -menuconfig UAVCAN_V1 - bool "UAVCANv1 Support" +menuconfig DRIVERS_UAVCAN + bool "uavcan" + default n + ---help--- + Enable support for uavcan + +menuconfig DRIVERS_UAVCAN_V1 + bool "UAVCANv1" default n ---help--- Enable support for UAVCANv1 -if UAVCAN_V1 +if DRIVERS_UAVCAN_V1 source src/drivers/uavcan_v1/Kconfig -endif #UAVCAN_V1 +endif #DRIVERS_UAVCAN_V1 diff --git a/src/drivers/adc/Kconfig b/src/drivers/adc/Kconfig new file mode 100644 index 0000000000..bb9072faa7 --- /dev/null +++ b/src/drivers/adc/Kconfig @@ -0,0 +1,11 @@ +menuconfig DRIVERS_ADC_ADS1115 + bool "ADC ADS1115" + default n + ---help--- + Enable support for ADS1115 + +menuconfig DRIVERS_ADC_BOARD_ADC + bool "Board ADC" + default n + ---help--- + Enable support for Board ADC diff --git a/src/drivers/barometer/Kconfig b/src/drivers/barometer/Kconfig new file mode 100644 index 0000000000..08f6cdb551 --- /dev/null +++ b/src/drivers/barometer/Kconfig @@ -0,0 +1,53 @@ +menuconfig DRIVERS_BAROMETER_BMP280 + bool "bmp280" + default n + ---help--- + Enable support for bmp280 + +menuconfig DRIVERS_BAROMETER_BMP388 + bool "bmp388" + default n + ---help--- + Enable support for bmp388 + +menuconfig DRIVERS_BAROMETER_DPS310 + bool "dps310" + default n + ---help--- + Enable support for dps310 + +menuconfig DRIVERS_BAROMETER_LPS22HB + bool "lps22hb" + default n + ---help--- + Enable support for lps22hb + +menuconfig DRIVERS_BAROMETER_LPS25H + bool "lps25h" + default n + ---help--- + Enable support for lps25h + +menuconfig DRIVERS_BAROMETER_LPS33HW + bool "lps33hw" + default n + ---help--- + Enable support for lps33hw + +menuconfig DRIVERS_BAROMETER_MPL3115A2 + bool "mpl3115a2" + default n + ---help--- + Enable support for mpl3115a2 + +menuconfig DRIVERS_BAROMETER_MS5611 + bool "ms5611" + default n + ---help--- + Enable support for ms5611 + +menuconfig DRIVERS_BAROMETER_TCBP001TA + bool "tcbp001ta" + default n + ---help--- + Enable support for tcbp001ta diff --git a/src/drivers/imu/Kconfig b/src/drivers/imu/Kconfig new file mode 100644 index 0000000000..72d29e337d --- /dev/null +++ b/src/drivers/imu/Kconfig @@ -0,0 +1,59 @@ +menuconfig DRIVERS_IMU_ADIS16477 + bool "adis16477" + default n + ---help--- + Enable support for adis16477 + +menuconfig DRIVERS_IMU_ADIS16497 + bool "adis16497" + default n + ---help--- + Enable support for adis16497 + +menuconfig DRIVERS_IMU_ANALOG_DEVICES + bool "analog devices" + default n + ---help--- + Enable support for analog devices + +menuconfig DRIVERS_IMU_BOSCH + bool "bosch" + default n + ---help--- + Enable support for bosch + +menuconfig DRIVERS_IMU_FXAS21002C + bool "fxas21002c" + default n + ---help--- + Enable support for fxas21002c + +menuconfig DRIVERS_IMU_FXOS8701CQ + bool "fxos8701cq" + default n + ---help--- + Enable support for fxos8701cq + +menuconfig DRIVERS_IMU_INVENSENSE + bool "invensense" + default n + ---help--- + Enable support for invensense + +menuconfig DRIVERS_IMU_L3GD20 + bool "l3gd20" + default n + ---help--- + Enable support for l3gd20 + +menuconfig DRIVERS_IMU_LSM303D + bool "lsm303d" + default n + ---help--- + Enable support for lsm303d + +menuconfig DRIVERS_IMU_ST + bool "st" + default n + ---help--- + Enable support for st diff --git a/src/drivers/lights/Kconfig b/src/drivers/lights/Kconfig new file mode 100644 index 0000000000..50aa7c7a9e --- /dev/null +++ b/src/drivers/lights/Kconfig @@ -0,0 +1,26 @@ +menuconfig DRIVERS_LIGHTS_BLINKM + bool "Blinkm" + default n + ---help--- + Enable support for blinkm lights + +menuconfig DRIVERS_LIGHTS_NEOPIXEL + bool "Neopixel" + default n + ---help--- + Enable support for Neopixel lights + +menuconfig DRIVERS_LIGHTS_RGBLED + bool "RGB Led" + ---help--- + Enable support for RGB led + +menuconfig DRIVERS_LIGHTS_RGBLED_PWM + bool "RGB Led PWM" + ---help--- + Enable support for RGB PWM led + +menuconfig DRIVERS_LIGHTS_RGBLED_NCP5623C + bool "RGB Led NCP5623C" + ---help--- + Enable support for RGB NCP5623C led