diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt index 72a8857b91..00a5a79956 100644 --- a/Tools/setup/requirements.txt +++ b/Tools/setup/requirements.txt @@ -5,6 +5,7 @@ coverage empy>=3.3 jinja2>=2.8 jsonschema +kconfiglib matplotlib>=3.0.* numpy>=1.13 nunavut>=1.1.0 diff --git a/boards/nxp/fmuk66-v3/default-boardconfig b/boards/nxp/fmuk66-v3/default-boardconfig index e833a4059f..551866eaef 100644 --- a/boards/nxp/fmuk66-v3/default-boardconfig +++ b/boards/nxp/fmuk66-v3/default-boardconfig @@ -13,14 +13,14 @@ CONFIG_DRIVERS_IMU_FXOS8701CQ=y CONFIG_DRIVERS_IRLOCK=y CONFIG_DRIVERS_LIGHTS_BLINKM=y CONFIG_DRIVERS_LIGHTS_RGBLED=y -CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y +CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y CONFIG_DRIVERS_MAGNETOMETER=y CONFIG_DRIVERS_OPTICAL_FLOW_PX4FLOW=y CONFIG_DRIVERS_PCA9685=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y -CONFIG_DRIVERS_PWM_OUT_SIM=y CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PWM_OUT_SIM=y CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_ROBOCLAW=y CONFIG_DRIVERS_SAFETY_BUTTON=y diff --git a/src/drivers/Kconfig b/src/drivers/Kconfig index 11d491e83f..6353836988 100644 --- a/src/drivers/Kconfig +++ b/src/drivers/Kconfig @@ -1,238 +1 @@ - -menu "ADC" -source "src/drivers/adc/Kconfig" -endmenu #ADC - -menuconfig DRIVERS_BAROMETER - bool "Barometer" - default n - ---help--- - Enable support for Barometers - -if DRIVERS_BAROMETER -source "src/drivers/barometer/Kconfig" -endif #DRIVERS_BAROMETER - -menuconfig DRIVERS_BATT_SMBUS - bool "batt smbus" - default n - ---help--- - Enable support for batt smbus - -menuconfig DRIVERS_BOOTLOADERS - bool "BOOTLOADERS" - default n - ---help--- - Enable support for bootloaders - -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 DRIVERS_DISTANCE_SENSOR - bool "distance sensor" - default n - ---help--- - Enable support for distance sensor - -if DRIVERS_DISTANCE_SENSOR -source "src/drivers/distance_sensor/Kconfig" -endif #DRIVERS_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 DRIVERS_HEATER - bool "heater" - default n - ---help--- - Enable support for heater - -menu "IMU" -source "src/drivers/imu/Kconfig" -endmenu - -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 - -if DRIVERS_MAGNETOMETER -source "src/drivers/magnetometer/Kconfig" -endif #DRIVERS_MAGNETOMETER - -menu "Optical flow" -source "src/drivers/optical_flow/Kconfig" -endmenu - -menuconfig DRIVERS_OSD - bool "osd" - default n - ---help--- - Enable support for osd - -menuconfig DRIVERS_PCA9685 - bool "pca9685" - default n - ---help--- - Enable support for pca9685 - -menuconfig DRIVERS_PCA9685_PWM_OUT - bool "pca9685 pwm out" - default n - ---help--- - Enable support for pca9685 pwm out - -menu "Power monitor" -source "src/drivers/power_monitor/Kconfig" -endmenu - -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_SIM - bool "pwm out sim" - default n - ---help--- - Enable support for pwm out sim - -menuconfig DRIVERS_PWM_OUT - bool "pwm out" - default n - ---help--- - Enable support for pwm out - -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 DRIVERS_UAVCAN - bool "uavcan" - default n - ---help--- - Enable support for uavcan - -if DRIVERS_UAVCAN -source "src/drivers/uavcan/Kconfig" -endif #DRIVERS_UAVCAN - -menuconfig DRIVERS_UAVCAN_V1 - bool "UAVCANv1" - default n - ---help--- - Enable support for UAVCANv1 - -if DRIVERS_UAVCAN_V1 -source "src/drivers/uavcan_v1/Kconfig" -endif #DRIVERS_UAVCAN_V1 +rsource "*/Kconfig" diff --git a/src/drivers/adc/Kconfig b/src/drivers/adc/Kconfig index bb9072faa7..9dd780b3e8 100644 --- a/src/drivers/adc/Kconfig +++ b/src/drivers/adc/Kconfig @@ -1,11 +1,3 @@ -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 +menu "ADC" +rsource "*/Kconfig" +endmenu #ADC diff --git a/src/drivers/adc/ads1115/Kconfig b/src/drivers/adc/ads1115/Kconfig new file mode 100644 index 0000000000..c9f1741d95 --- /dev/null +++ b/src/drivers/adc/ads1115/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_ADC_ADS1115 + bool "ads1115" + default n + ---help--- + Enable support for ads1115 diff --git a/src/drivers/adc/board_adc/Kconfig b/src/drivers/adc/board_adc/Kconfig new file mode 100644 index 0000000000..d42ac3a5ee --- /dev/null +++ b/src/drivers/adc/board_adc/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_ADC_BOARD_ADC + bool "board_adc" + default n + ---help--- + Enable support for board_adc \ No newline at end of file diff --git a/src/drivers/barometer/Kconfig b/src/drivers/barometer/Kconfig index 08f6cdb551..7ec3f14eaf 100644 --- a/src/drivers/barometer/Kconfig +++ b/src/drivers/barometer/Kconfig @@ -1,53 +1,9 @@ -menuconfig DRIVERS_BAROMETER_BMP280 - bool "bmp280" +menuconfig DRIVERS_BAROMETER + bool "barometer" 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 + Enable support for barometer + +if DRIVERS_BAROMETER +rsource "*/Kconfig" +endif #DRIVERS_BAROMETER diff --git a/src/drivers/barometer/bmp280/Kconfig b/src/drivers/barometer/bmp280/Kconfig new file mode 100644 index 0000000000..25b6fed476 --- /dev/null +++ b/src/drivers/barometer/bmp280/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_BMP280 + bool "bmp280" + default n + ---help--- + Enable support for bmp280 \ No newline at end of file diff --git a/src/drivers/barometer/bmp388/Kconfig b/src/drivers/barometer/bmp388/Kconfig new file mode 100644 index 0000000000..585c4e975e --- /dev/null +++ b/src/drivers/barometer/bmp388/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_BMP388 + bool "bmp388" + default n + ---help--- + Enable support for bmp388 \ No newline at end of file diff --git a/src/drivers/barometer/dps310/Kconfig b/src/drivers/barometer/dps310/Kconfig new file mode 100644 index 0000000000..efd7746b09 --- /dev/null +++ b/src/drivers/barometer/dps310/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_DPS310 + bool "dps310" + default n + ---help--- + Enable support for dps310 \ No newline at end of file diff --git a/src/drivers/barometer/lps22hb/Kconfig b/src/drivers/barometer/lps22hb/Kconfig new file mode 100644 index 0000000000..6823384732 --- /dev/null +++ b/src/drivers/barometer/lps22hb/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_LPS22HB + bool "lps22hb" + default n + ---help--- + Enable support for lps22hb \ No newline at end of file diff --git a/src/drivers/barometer/lps25h/Kconfig b/src/drivers/barometer/lps25h/Kconfig new file mode 100644 index 0000000000..fa17e99ed9 --- /dev/null +++ b/src/drivers/barometer/lps25h/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_LPS25H + bool "lps25h" + default n + ---help--- + Enable support for lps25h \ No newline at end of file diff --git a/src/drivers/barometer/lps33hw/Kconfig b/src/drivers/barometer/lps33hw/Kconfig new file mode 100644 index 0000000000..bcf7f33edd --- /dev/null +++ b/src/drivers/barometer/lps33hw/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_LPS33HW + bool "lps33hw" + default n + ---help--- + Enable support for lps33hw \ No newline at end of file diff --git a/src/drivers/barometer/mpl3115a2/Kconfig b/src/drivers/barometer/mpl3115a2/Kconfig new file mode 100644 index 0000000000..6d95e95af6 --- /dev/null +++ b/src/drivers/barometer/mpl3115a2/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_MPL3115A2 + bool "mpl3115a2" + default n + ---help--- + Enable support for mpl3115a2 \ No newline at end of file diff --git a/src/drivers/barometer/ms5611/Kconfig b/src/drivers/barometer/ms5611/Kconfig new file mode 100644 index 0000000000..849894ba27 --- /dev/null +++ b/src/drivers/barometer/ms5611/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_MS5611 + bool "ms5611" + default n + ---help--- + Enable support for ms5611 \ No newline at end of file diff --git a/src/drivers/barometer/tcbp001ta/Kconfig b/src/drivers/barometer/tcbp001ta/Kconfig new file mode 100644 index 0000000000..ea251c3736 --- /dev/null +++ b/src/drivers/barometer/tcbp001ta/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BAROMETER_TCBP001TA + bool "tcbp001ta" + default n + ---help--- + Enable support for tcbp001ta \ No newline at end of file diff --git a/src/drivers/batt_smbus/Kconfig b/src/drivers/batt_smbus/Kconfig new file mode 100644 index 0000000000..0b94c11e55 --- /dev/null +++ b/src/drivers/batt_smbus/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BATT_SMBUS + bool "batt_smbus" + default n + ---help--- + Enable support for batt_smbus \ No newline at end of file diff --git a/src/drivers/bootloaders/Kconfig b/src/drivers/bootloaders/Kconfig new file mode 100644 index 0000000000..116e375390 --- /dev/null +++ b/src/drivers/bootloaders/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_BOOTLOADERS + bool "bootloaders" + default n + ---help--- + Enable support for bootloaders \ No newline at end of file diff --git a/src/drivers/camera_capture/Kconfig b/src/drivers/camera_capture/Kconfig new file mode 100644 index 0000000000..c813348465 --- /dev/null +++ b/src/drivers/camera_capture/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_CAMERA_CAPTURE + bool "camera_capture" + default n + ---help--- + Enable support for camera_capture \ No newline at end of file diff --git a/src/drivers/camera_trigger/Kconfig b/src/drivers/camera_trigger/Kconfig new file mode 100644 index 0000000000..b07f7eec03 --- /dev/null +++ b/src/drivers/camera_trigger/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_CAMERA_TRIGGER + bool "camera_trigger" + default n + ---help--- + Enable support for camera_trigger \ No newline at end of file diff --git a/src/drivers/differential_pressure/Kconfig b/src/drivers/differential_pressure/Kconfig new file mode 100644 index 0000000000..1c3f4a9492 --- /dev/null +++ b/src/drivers/differential_pressure/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DIFFERENTIAL_PRESSURE + bool "differential_pressure" + default n + ---help--- + Enable support for differential_pressure \ No newline at end of file diff --git a/src/drivers/differential_pressure/ets/Kconfig b/src/drivers/differential_pressure/ets/Kconfig new file mode 100644 index 0000000000..e6e094eea4 --- /dev/null +++ b/src/drivers/differential_pressure/ets/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DIFFERENTIAL_PRESSURE_ETS + bool "ets" + default n + ---help--- + Enable support for ets \ No newline at end of file diff --git a/src/drivers/differential_pressure/ms4525/Kconfig b/src/drivers/differential_pressure/ms4525/Kconfig new file mode 100644 index 0000000000..7b836d360e --- /dev/null +++ b/src/drivers/differential_pressure/ms4525/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DIFFERENTIAL_PRESSURE_MS4525 + bool "ms4525" + default n + ---help--- + Enable support for ms4525 \ No newline at end of file diff --git a/src/drivers/differential_pressure/ms5525/Kconfig b/src/drivers/differential_pressure/ms5525/Kconfig new file mode 100644 index 0000000000..9e2e1057d5 --- /dev/null +++ b/src/drivers/differential_pressure/ms5525/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DIFFERENTIAL_PRESSURE_MS5525 + bool "ms5525" + default n + ---help--- + Enable support for ms5525 \ No newline at end of file diff --git a/src/drivers/differential_pressure/sdp3x/Kconfig b/src/drivers/differential_pressure/sdp3x/Kconfig new file mode 100644 index 0000000000..45314cfe6b --- /dev/null +++ b/src/drivers/differential_pressure/sdp3x/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DIFFERENTIAL_PRESSURE_SDP3X + bool "sdp3x" + default n + ---help--- + Enable support for sdp3x \ No newline at end of file diff --git a/src/drivers/distance_sensor/Kconfig b/src/drivers/distance_sensor/Kconfig index d6752a6663..8d9ca14547 100644 --- a/src/drivers/distance_sensor/Kconfig +++ b/src/drivers/distance_sensor/Kconfig @@ -1,95 +1,9 @@ -menuconfig DRIVERS_DISTANCE_SENSOR_CM8JL65 - bool "cm8jl65" +menuconfig DRIVERS_DISTANCE_SENSOR + bool "distance_sensor" default n ---help--- - Enable support for cm8jl65 + Enable support for distance_sensor -menuconfig DRIVERS_DISTANCE_SENSOR_LEDDAR_ONE - bool "leddar one" - default n - ---help--- - Enable support for leddar one - -menuconfig DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C - bool "lightware laser i2c" - default n - ---help--- - Enable support for lightware laser i2c - -menuconfig DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL - bool "lightware laser serial" - default n - ---help--- - Enable support for lightware laser serial - -menuconfig DRIVERS_DISTANCE_SENSOR_LL40LS - bool "ll40ls" - default n - ---help--- - Enable support for ll40ls - -menuconfig DRIVERS_DISTANCE_SENSOR_LL40LS_PWM - bool "ll40ls pwm" - default n - ---help--- - Enable support for ll40ls pwm - -menuconfig DRIVERS_DISTANCE_SENSOR_MAPPYDOT - bool "mappydot" - default n - ---help--- - Enable support for mappydot - -menuconfig DRIVERS_DISTANCE_SENSOR_MB12XX - bool "mb12xx" - default n - ---help--- - Enable support for mb12xx - -menuconfig DRIVERS_DISTANCE_SENSOR_PGA460 - bool "pga460" - default n - ---help--- - Enable support for pga460 - -menuconfig DRIVERS_DISTANCE_SENSOR_SRF02 - bool "srf02" - default n - ---help--- - Enable support for srf02 - -menuconfig DRIVERS_DISTANCE_SENSOR_SRF05 - bool "srf05" - default n - ---help--- - Enable support for srf05 - -menuconfig DRIVERS_DISTANCE_SENSOR_TERARANGER - bool "teraranger" - default n - ---help--- - Enable support for teraranger - -menuconfig DRIVERS_DISTANCE_SENSOR_TFMINI - bool "tfmini" - default n - ---help--- - Enable support for tfmini - -menuconfig DRIVERS_DISTANCE_SENSOR_ULANDING_RADAR - bool "ulanding radar" - default n - ---help--- - Enable support for ulanding radar - -menuconfig DRIVERS_DISTANCE_SENSOR_VL53L0X - bool "vl53l0x" - default n - ---help--- - Enable support for vl53l0x - -menuconfig DRIVERS_DISTANCE_SENSOR_VL53L1X - bool "vl53l1x" - default n - ---help--- - Enable support for vl53l1x +if DRIVERS_DISTANCE_SENSOR +rsource "*/Kconfig" +endif #DRIVERS_DISTANCE_SENSOR diff --git a/src/drivers/distance_sensor/cm8jl65/Kconfig b/src/drivers/distance_sensor/cm8jl65/Kconfig new file mode 100644 index 0000000000..2da9e8f79c --- /dev/null +++ b/src/drivers/distance_sensor/cm8jl65/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_CM8JL65 + bool "cm8jl65" + default n + ---help--- + Enable support for cm8jl65 \ No newline at end of file diff --git a/src/drivers/distance_sensor/leddar_one/Kconfig b/src/drivers/distance_sensor/leddar_one/Kconfig new file mode 100644 index 0000000000..8b8cd271cc --- /dev/null +++ b/src/drivers/distance_sensor/leddar_one/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_LEDDAR_ONE + bool "leddar_one" + default n + ---help--- + Enable support for leddar_one \ No newline at end of file diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/Kconfig b/src/drivers/distance_sensor/lightware_laser_i2c/Kconfig new file mode 100644 index 0000000000..ecbf154b0a --- /dev/null +++ b/src/drivers/distance_sensor/lightware_laser_i2c/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C + bool "lightware_laser_i2c" + default n + ---help--- + Enable support for lightware_laser_i2c \ No newline at end of file diff --git a/src/drivers/distance_sensor/lightware_laser_serial/Kconfig b/src/drivers/distance_sensor/lightware_laser_serial/Kconfig new file mode 100644 index 0000000000..aca223c828 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_laser_serial/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL + bool "lightware_laser_serial" + default n + ---help--- + Enable support for lightware_laser_serial \ No newline at end of file diff --git a/src/drivers/distance_sensor/ll40ls/Kconfig b/src/drivers/distance_sensor/ll40ls/Kconfig new file mode 100644 index 0000000000..297a86147a --- /dev/null +++ b/src/drivers/distance_sensor/ll40ls/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_LL40LS + bool "ll40ls" + default n + ---help--- + Enable support for ll40ls \ No newline at end of file diff --git a/src/drivers/distance_sensor/ll40ls_pwm/Kconfig b/src/drivers/distance_sensor/ll40ls_pwm/Kconfig new file mode 100644 index 0000000000..543d57f803 --- /dev/null +++ b/src/drivers/distance_sensor/ll40ls_pwm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_LL40LS_PWM + bool "ll40ls_pwm" + default n + ---help--- + Enable support for ll40ls_pwm \ No newline at end of file diff --git a/src/drivers/distance_sensor/mappydot/Kconfig b/src/drivers/distance_sensor/mappydot/Kconfig new file mode 100644 index 0000000000..8e13c2fc44 --- /dev/null +++ b/src/drivers/distance_sensor/mappydot/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_MAPPYDOT + bool "mappydot" + default n + ---help--- + Enable support for mappydot \ No newline at end of file diff --git a/src/drivers/distance_sensor/mb12xx/Kconfig b/src/drivers/distance_sensor/mb12xx/Kconfig new file mode 100644 index 0000000000..01eb0c2bfe --- /dev/null +++ b/src/drivers/distance_sensor/mb12xx/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_MB12XX + bool "mb12xx" + default n + ---help--- + Enable support for mb12xx \ No newline at end of file diff --git a/src/drivers/distance_sensor/pga460/Kconfig b/src/drivers/distance_sensor/pga460/Kconfig new file mode 100644 index 0000000000..de9f2ef539 --- /dev/null +++ b/src/drivers/distance_sensor/pga460/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_PGA460 + bool "pga460" + default n + ---help--- + Enable support for pga460 \ No newline at end of file diff --git a/src/drivers/distance_sensor/srf02/Kconfig b/src/drivers/distance_sensor/srf02/Kconfig new file mode 100644 index 0000000000..258dec353f --- /dev/null +++ b/src/drivers/distance_sensor/srf02/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_SRF02 + bool "srf02" + default n + ---help--- + Enable support for srf02 \ No newline at end of file diff --git a/src/drivers/distance_sensor/srf05/Kconfig b/src/drivers/distance_sensor/srf05/Kconfig new file mode 100644 index 0000000000..a425ccb9fc --- /dev/null +++ b/src/drivers/distance_sensor/srf05/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_SRF05 + bool "srf05" + default n + ---help--- + Enable support for srf05 \ No newline at end of file diff --git a/src/drivers/distance_sensor/teraranger/Kconfig b/src/drivers/distance_sensor/teraranger/Kconfig new file mode 100644 index 0000000000..cee7073c3d --- /dev/null +++ b/src/drivers/distance_sensor/teraranger/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_TERARANGER + bool "teraranger" + default n + ---help--- + Enable support for teraranger \ No newline at end of file diff --git a/src/drivers/distance_sensor/tfmini/Kconfig b/src/drivers/distance_sensor/tfmini/Kconfig new file mode 100644 index 0000000000..9157e4a216 --- /dev/null +++ b/src/drivers/distance_sensor/tfmini/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_TFMINI + bool "tfmini" + default n + ---help--- + Enable support for tfmini \ No newline at end of file diff --git a/src/drivers/distance_sensor/ulanding_radar/Kconfig b/src/drivers/distance_sensor/ulanding_radar/Kconfig new file mode 100644 index 0000000000..f2b51c843d --- /dev/null +++ b/src/drivers/distance_sensor/ulanding_radar/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_ULANDING_RADAR + bool "ulanding_radar" + default n + ---help--- + Enable support for ulanding_radar \ No newline at end of file diff --git a/src/drivers/distance_sensor/vl53l0x/Kconfig b/src/drivers/distance_sensor/vl53l0x/Kconfig new file mode 100644 index 0000000000..98dac82b00 --- /dev/null +++ b/src/drivers/distance_sensor/vl53l0x/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_VL53L0X + bool "vl53l0x" + default n + ---help--- + Enable support for vl53l0x \ No newline at end of file diff --git a/src/drivers/distance_sensor/vl53l1x/Kconfig b/src/drivers/distance_sensor/vl53l1x/Kconfig new file mode 100644 index 0000000000..cdb6c003b0 --- /dev/null +++ b/src/drivers/distance_sensor/vl53l1x/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_VL53L1X + bool "vl53l1x" + default n + ---help--- + Enable support for vl53l1x \ No newline at end of file diff --git a/src/drivers/dshot/Kconfig b/src/drivers/dshot/Kconfig new file mode 100644 index 0000000000..bed3aaf9d7 --- /dev/null +++ b/src/drivers/dshot/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DSHOT + bool "dshot" + default n + ---help--- + Enable support for dshot \ No newline at end of file diff --git a/src/drivers/gps/Kconfig b/src/drivers/gps/Kconfig new file mode 100644 index 0000000000..45a3e0dad5 --- /dev/null +++ b/src/drivers/gps/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_GPS + bool "gps" + default n + ---help--- + Enable support for gps \ No newline at end of file diff --git a/src/drivers/heater/Kconfig b/src/drivers/heater/Kconfig new file mode 100644 index 0000000000..a90575ed09 --- /dev/null +++ b/src/drivers/heater/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_HEATER + bool "heater" + default n + ---help--- + Enable support for heater \ No newline at end of file diff --git a/src/drivers/imu/Kconfig b/src/drivers/imu/Kconfig index 72d29e337d..5d59ecaf87 100644 --- a/src/drivers/imu/Kconfig +++ b/src/drivers/imu/Kconfig @@ -1,59 +1,3 @@ -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 +menu "IMU" +rsource "*/Kconfig" +endmenu diff --git a/src/drivers/imu/adis16477/Kconfig b/src/drivers/imu/adis16477/Kconfig new file mode 100644 index 0000000000..74b76d2482 --- /dev/null +++ b/src/drivers/imu/adis16477/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_ADIS16477 + bool "adis16477" + default n + ---help--- + Enable support for adis16477 \ No newline at end of file diff --git a/src/drivers/imu/adis16497/Kconfig b/src/drivers/imu/adis16497/Kconfig new file mode 100644 index 0000000000..41fa1b759b --- /dev/null +++ b/src/drivers/imu/adis16497/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_ADIS16497 + bool "adis16497" + default n + ---help--- + Enable support for adis16497 \ No newline at end of file diff --git a/src/drivers/imu/analog_devices/Kconfig b/src/drivers/imu/analog_devices/Kconfig new file mode 100644 index 0000000000..b2e0448a90 --- /dev/null +++ b/src/drivers/imu/analog_devices/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_ANALOG_DEVICES + bool "analog_devices" + default n + ---help--- + Enable support for analog_devices \ No newline at end of file diff --git a/src/drivers/imu/bosch/Kconfig b/src/drivers/imu/bosch/Kconfig new file mode 100644 index 0000000000..d05b1086ec --- /dev/null +++ b/src/drivers/imu/bosch/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_BOSCH + bool "bosch" + default n + ---help--- + Enable support for bosch \ No newline at end of file diff --git a/src/drivers/imu/fxas21002c/Kconfig b/src/drivers/imu/fxas21002c/Kconfig new file mode 100644 index 0000000000..15d7c39c81 --- /dev/null +++ b/src/drivers/imu/fxas21002c/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_FXAS21002C + bool "fxas21002c" + default n + ---help--- + Enable support for fxas21002c \ No newline at end of file diff --git a/src/drivers/imu/fxos8701cq/Kconfig b/src/drivers/imu/fxos8701cq/Kconfig new file mode 100644 index 0000000000..697de1dab1 --- /dev/null +++ b/src/drivers/imu/fxos8701cq/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_FXOS8701CQ + bool "fxos8701cq" + default n + ---help--- + Enable support for fxos8701cq \ No newline at end of file diff --git a/src/drivers/imu/invensense/Kconfig b/src/drivers/imu/invensense/Kconfig new file mode 100644 index 0000000000..8957a5f6f3 --- /dev/null +++ b/src/drivers/imu/invensense/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_INVENSENSE + bool "invensense" + default n + ---help--- + Enable support for invensense \ No newline at end of file diff --git a/src/drivers/imu/l3gd20/Kconfig b/src/drivers/imu/l3gd20/Kconfig new file mode 100644 index 0000000000..417becfc95 --- /dev/null +++ b/src/drivers/imu/l3gd20/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_L3GD20 + bool "l3gd20" + default n + ---help--- + Enable support for l3gd20 \ No newline at end of file diff --git a/src/drivers/imu/lsm303d/Kconfig b/src/drivers/imu/lsm303d/Kconfig new file mode 100644 index 0000000000..49c139db4f --- /dev/null +++ b/src/drivers/imu/lsm303d/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_LSM303D + bool "lsm303d" + default n + ---help--- + Enable support for lsm303d \ No newline at end of file diff --git a/src/drivers/imu/st/Kconfig b/src/drivers/imu/st/Kconfig new file mode 100644 index 0000000000..968e083bcd --- /dev/null +++ b/src/drivers/imu/st/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_ST + bool "st" + default n + ---help--- + Enable support for st \ No newline at end of file diff --git a/src/drivers/irlock/Kconfig b/src/drivers/irlock/Kconfig new file mode 100644 index 0000000000..ddf22968cd --- /dev/null +++ b/src/drivers/irlock/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IRLOCK + bool "irlock" + default n + ---help--- + Enable support for irlock \ No newline at end of file diff --git a/src/drivers/lights/Kconfig b/src/drivers/lights/Kconfig index 50aa7c7a9e..4622a6c5e0 100644 --- a/src/drivers/lights/Kconfig +++ b/src/drivers/lights/Kconfig @@ -1,26 +1,3 @@ -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 +menu "Lights" +rsource "*/Kconfig" +endmenu diff --git a/src/drivers/lights/blinkm/Kconfig b/src/drivers/lights/blinkm/Kconfig new file mode 100644 index 0000000000..a4a4ecb214 --- /dev/null +++ b/src/drivers/lights/blinkm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_LIGHTS_BLINKM + bool "blinkm" + default n + ---help--- + Enable support for blinkm \ No newline at end of file diff --git a/src/drivers/lights/neopixel/Kconfig b/src/drivers/lights/neopixel/Kconfig new file mode 100644 index 0000000000..a8f6831690 --- /dev/null +++ b/src/drivers/lights/neopixel/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_LIGHTS_NEOPIXEL + bool "neopixel" + default n + ---help--- + Enable support for neopixel \ No newline at end of file diff --git a/src/drivers/lights/rgbled/Kconfig b/src/drivers/lights/rgbled/Kconfig new file mode 100644 index 0000000000..52f606acd7 --- /dev/null +++ b/src/drivers/lights/rgbled/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_LIGHTS_RGBLED + bool "rgbled" + default n + ---help--- + Enable support for rgbled \ No newline at end of file diff --git a/src/drivers/lights/rgbled_ncp5623c/Kconfig b/src/drivers/lights/rgbled_ncp5623c/Kconfig new file mode 100644 index 0000000000..14964779b1 --- /dev/null +++ b/src/drivers/lights/rgbled_ncp5623c/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_LIGHTS_RGBLED_NCP5623C + bool "rgbled_ncp5623c" + default n + ---help--- + Enable support for rgbled_ncp5623c \ No newline at end of file diff --git a/src/drivers/lights/rgbled_pwm/Kconfig b/src/drivers/lights/rgbled_pwm/Kconfig new file mode 100644 index 0000000000..231b5161d1 --- /dev/null +++ b/src/drivers/lights/rgbled_pwm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_LIGHTS_RGBLED_PWM + bool "rgbled_pwm" + default n + ---help--- + Enable support for rgbled_pwm \ No newline at end of file diff --git a/src/drivers/linux_pwm_out/Kconfig b/src/drivers/linux_pwm_out/Kconfig new file mode 100644 index 0000000000..36193d1974 --- /dev/null +++ b/src/drivers/linux_pwm_out/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_LINUX_PWM_OUT + bool "linux_pwm_out" + default n + ---help--- + Enable support for linux_pwm_out \ No newline at end of file diff --git a/src/drivers/magnetometer/Kconfig b/src/drivers/magnetometer/Kconfig index e4806d3a25..003347a33f 100644 --- a/src/drivers/magnetometer/Kconfig +++ b/src/drivers/magnetometer/Kconfig @@ -1,59 +1,9 @@ -menuconfig DRIVERS_MAGNETOMETER_AKM - bool "akm" +menuconfig DRIVERS_MAGNETOMETER + bool "Magnetometer" default n ---help--- - Enable support for akm + Enable support for all available magnetometer drivers -menuconfig DRIVERS_MAGNETOMETER_BOSCH - bool "bosch" - default n - ---help--- - Enable support for bosch - -menuconfig DRIVERS_MAGNETOMETER_HMC5883 - bool "hmc5883" - default n - ---help--- - Enable support for hmc5883 - -menuconfig DRIVERS_MAGNETOMETER_ISENTEK - bool "isentek" - default n - ---help--- - Enable support for isentek - -menuconfig DRIVERS_MAGNETOMETER_LIS2MDL - bool "lis2mdl" - default n - ---help--- - Enable support for lis2mdl - -menuconfig DRIVERS_MAGNETOMETER_LIS3MDL - bool "lis3mdl" - default n - ---help--- - Enable support for lis3mdl - -menuconfig DRIVERS_MAGNETOMETER_LSM303AGR - bool "lsm303agr" - default n - ---help--- - Enable support for lsm303agr - -menuconfig DRIVERS_MAGNETOMETER_LSM9DS1_MAG - bool "lsm9ds1 mag" - default n - ---help--- - Enable support for lsm9ds1 mag - -menuconfig DRIVERS_MAGNETOMETER_QMC5883L - bool "qmc5883l" - default n - ---help--- - Enable support for qmc5883l - -menuconfig DRIVERS_MAGNETOMETER_RM3100 - bool "rm3100" - default n - ---help--- - Enable support for rm3100 +if DRIVERS_MAGNETOMETER +rsource "*/Kconfig" +endif #DRIVERS_MAGNETOMETER diff --git a/src/drivers/magnetometer/akm/Kconfig b/src/drivers/magnetometer/akm/Kconfig new file mode 100644 index 0000000000..aa1f053bf3 --- /dev/null +++ b/src/drivers/magnetometer/akm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_AKM + bool "akm" + default n + ---help--- + Enable support for akm \ No newline at end of file diff --git a/src/drivers/magnetometer/bosch/Kconfig b/src/drivers/magnetometer/bosch/Kconfig new file mode 100644 index 0000000000..155ab7f995 --- /dev/null +++ b/src/drivers/magnetometer/bosch/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_BOSCH + bool "bosch" + default n + ---help--- + Enable support for bosch \ No newline at end of file diff --git a/src/drivers/magnetometer/hmc5883/Kconfig b/src/drivers/magnetometer/hmc5883/Kconfig new file mode 100644 index 0000000000..658ab4b863 --- /dev/null +++ b/src/drivers/magnetometer/hmc5883/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_HMC5883 + bool "hmc5883" + default n + ---help--- + Enable support for hmc5883 \ No newline at end of file diff --git a/src/drivers/magnetometer/isentek/Kconfig b/src/drivers/magnetometer/isentek/Kconfig new file mode 100644 index 0000000000..d556143b40 --- /dev/null +++ b/src/drivers/magnetometer/isentek/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_ISENTEK + bool "isentek" + default n + ---help--- + Enable support for isentek \ No newline at end of file diff --git a/src/drivers/magnetometer/lis2mdl/Kconfig b/src/drivers/magnetometer/lis2mdl/Kconfig new file mode 100644 index 0000000000..2b841d2c65 --- /dev/null +++ b/src/drivers/magnetometer/lis2mdl/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_LIS2MDL + bool "lis2mdl" + default n + ---help--- + Enable support for lis2mdl \ No newline at end of file diff --git a/src/drivers/magnetometer/lis3mdl/Kconfig b/src/drivers/magnetometer/lis3mdl/Kconfig new file mode 100644 index 0000000000..64b3b5eee3 --- /dev/null +++ b/src/drivers/magnetometer/lis3mdl/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_LIS3MDL + bool "lis3mdl" + default n + ---help--- + Enable support for lis3mdl \ No newline at end of file diff --git a/src/drivers/magnetometer/lsm303agr/Kconfig b/src/drivers/magnetometer/lsm303agr/Kconfig new file mode 100644 index 0000000000..a51b500c31 --- /dev/null +++ b/src/drivers/magnetometer/lsm303agr/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_LSM303AGR + bool "lsm303agr" + default n + ---help--- + Enable support for lsm303agr \ No newline at end of file diff --git a/src/drivers/magnetometer/lsm9ds1_mag/Kconfig b/src/drivers/magnetometer/lsm9ds1_mag/Kconfig new file mode 100644 index 0000000000..45e0c72350 --- /dev/null +++ b/src/drivers/magnetometer/lsm9ds1_mag/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_LSM9DS1_MAG + bool "lsm9ds1_mag" + default n + ---help--- + Enable support for lsm9ds1_mag \ No newline at end of file diff --git a/src/drivers/magnetometer/qmc5883l/Kconfig b/src/drivers/magnetometer/qmc5883l/Kconfig new file mode 100644 index 0000000000..8b4e732ccd --- /dev/null +++ b/src/drivers/magnetometer/qmc5883l/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_QMC5883L + bool "qmc5883l" + default n + ---help--- + Enable support for qmc5883l \ No newline at end of file diff --git a/src/drivers/magnetometer/rm3100/Kconfig b/src/drivers/magnetometer/rm3100/Kconfig new file mode 100644 index 0000000000..e7cb534081 --- /dev/null +++ b/src/drivers/magnetometer/rm3100/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_MAGNETOMETER_RM3100 + bool "rm3100" + default n + ---help--- + Enable support for rm3100 \ No newline at end of file diff --git a/src/drivers/optical_flow/Kconfig b/src/drivers/optical_flow/Kconfig index 3a057cdc18..bd6320ee55 100644 --- a/src/drivers/optical_flow/Kconfig +++ b/src/drivers/optical_flow/Kconfig @@ -1,23 +1,3 @@ -menuconfig DRIVERS_OPTICAL_FLOW_PAW3902 - bool "paw3902" - default n - ---help--- - Enable support for paw3902 - -menuconfig DRIVERS_OPTICAL_FLOW_PMW3901 - bool "pmw3901" - default n - ---help--- - Enable support for pmw3901 - -menuconfig DRIVERS_OPTICAL_FLOW_PX4FLOW - bool "px4flow" - default n - ---help--- - Enable support for px4flow - -menuconfig DRIVERS_OPTICAL_FLOW_THONEFLOW - bool "thoneflow" - default n - ---help--- - Enable support for thoneflow +menu "Optical flow" +rsource "*/Kconfig" +endmenu diff --git a/src/drivers/optical_flow/paw3902/Kconfig b/src/drivers/optical_flow/paw3902/Kconfig new file mode 100644 index 0000000000..c3a8f3a82f --- /dev/null +++ b/src/drivers/optical_flow/paw3902/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_OPTICAL_FLOW_PAW3902 + bool "paw3902" + default n + ---help--- + Enable support for paw3902 \ No newline at end of file diff --git a/src/drivers/optical_flow/pmw3901/Kconfig b/src/drivers/optical_flow/pmw3901/Kconfig new file mode 100644 index 0000000000..f559f13d37 --- /dev/null +++ b/src/drivers/optical_flow/pmw3901/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_OPTICAL_FLOW_PMW3901 + bool "pmw3901" + default n + ---help--- + Enable support for pmw3901 \ No newline at end of file diff --git a/src/drivers/optical_flow/px4flow/Kconfig b/src/drivers/optical_flow/px4flow/Kconfig new file mode 100644 index 0000000000..497860f0c5 --- /dev/null +++ b/src/drivers/optical_flow/px4flow/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_OPTICAL_FLOW_PX4FLOW + bool "px4flow" + default n + ---help--- + Enable support for px4flow \ No newline at end of file diff --git a/src/drivers/optical_flow/thoneflow/Kconfig b/src/drivers/optical_flow/thoneflow/Kconfig new file mode 100644 index 0000000000..3a1ab3fa81 --- /dev/null +++ b/src/drivers/optical_flow/thoneflow/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_OPTICAL_FLOW_THONEFLOW + bool "thoneflow" + default n + ---help--- + Enable support for thoneflow \ No newline at end of file diff --git a/src/drivers/osd/Kconfig b/src/drivers/osd/Kconfig new file mode 100644 index 0000000000..ebaf4de51e --- /dev/null +++ b/src/drivers/osd/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_OSD + bool "osd" + default n + ---help--- + Enable support for osd \ No newline at end of file diff --git a/src/drivers/osd/atxxxx/Kconfig b/src/drivers/osd/atxxxx/Kconfig new file mode 100644 index 0000000000..8fa85e50f5 --- /dev/null +++ b/src/drivers/osd/atxxxx/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_OSD_ATXXXX + bool "atxxxx" + default n + ---help--- + Enable support for atxxxx \ No newline at end of file diff --git a/src/drivers/pca9685/Kconfig b/src/drivers/pca9685/Kconfig new file mode 100644 index 0000000000..81898b61a8 --- /dev/null +++ b/src/drivers/pca9685/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PCA9685 + bool "pca9685" + default n + ---help--- + Enable support for pca9685 \ No newline at end of file diff --git a/src/drivers/pca9685_pwm_out/Kconfig b/src/drivers/pca9685_pwm_out/Kconfig new file mode 100644 index 0000000000..84cc71cda7 --- /dev/null +++ b/src/drivers/pca9685_pwm_out/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PCA9685_PWM_OUT + bool "pca9685_pwm_out" + default n + ---help--- + Enable support for pca9685_pwm_out \ No newline at end of file diff --git a/src/drivers/power_monitor/Kconfig b/src/drivers/power_monitor/Kconfig index c6101f22da..ef809f80d0 100644 --- a/src/drivers/power_monitor/Kconfig +++ b/src/drivers/power_monitor/Kconfig @@ -1,11 +1,3 @@ -menuconfig DRIVERS_POWER_MONITOR_INA226 - bool "ina226" - default n - ---help--- - Enable support for ina226 - -menuconfig DRIVERS_POWER_MONITOR_VOXLPM - bool "voxlpm" - default n - ---help--- - Enable support for voxlpm +menu "Power monitor" +rsource "*/Kconfig" +endmenu diff --git a/src/drivers/power_monitor/ina226/Kconfig b/src/drivers/power_monitor/ina226/Kconfig new file mode 100644 index 0000000000..05f77beb78 --- /dev/null +++ b/src/drivers/power_monitor/ina226/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_POWER_MONITOR_INA226 + bool "ina226" + default n + ---help--- + Enable support for ina226 \ No newline at end of file diff --git a/src/drivers/power_monitor/voxlpm/Kconfig b/src/drivers/power_monitor/voxlpm/Kconfig new file mode 100644 index 0000000000..f2553b1ed0 --- /dev/null +++ b/src/drivers/power_monitor/voxlpm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_POWER_MONITOR_VOXLPM + bool "voxlpm" + default n + ---help--- + Enable support for voxlpm \ No newline at end of file diff --git a/src/drivers/protocol_splitter/Kconfig b/src/drivers/protocol_splitter/Kconfig new file mode 100644 index 0000000000..f251603986 --- /dev/null +++ b/src/drivers/protocol_splitter/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PROTOCOL_SPLITTER + bool "protocol_splitter" + default n + ---help--- + Enable support for protocol_splitter \ No newline at end of file diff --git a/src/drivers/pwm_input/Kconfig b/src/drivers/pwm_input/Kconfig new file mode 100644 index 0000000000..85481a2048 --- /dev/null +++ b/src/drivers/pwm_input/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PWM_INPUT + bool "pwm_input" + default n + ---help--- + Enable support for pwm_input \ No newline at end of file diff --git a/src/drivers/pwm_out/Kconfig b/src/drivers/pwm_out/Kconfig new file mode 100644 index 0000000000..a263be9a3e --- /dev/null +++ b/src/drivers/pwm_out/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PWM_OUT + bool "pwm_out" + default n + ---help--- + Enable support for pwm_out \ No newline at end of file diff --git a/src/drivers/pwm_out_sim/Kconfig b/src/drivers/pwm_out_sim/Kconfig new file mode 100644 index 0000000000..49d187b400 --- /dev/null +++ b/src/drivers/pwm_out_sim/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PWM_OUT_SIM + bool "pwm_out_sim" + default n + ---help--- + Enable support for pwm_out_sim \ No newline at end of file diff --git a/src/drivers/px4io/Kconfig b/src/drivers/px4io/Kconfig new file mode 100644 index 0000000000..b55e42ac32 --- /dev/null +++ b/src/drivers/px4io/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_PX4IO + bool "px4io" + default n + ---help--- + Enable support for px4io \ No newline at end of file diff --git a/src/drivers/qshell/posix/Kconfig b/src/drivers/qshell/posix/Kconfig new file mode 100644 index 0000000000..91c2ab36dd --- /dev/null +++ b/src/drivers/qshell/posix/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_QSHELL_POSIX + bool "posix" + default n + ---help--- + Enable support for posix \ No newline at end of file diff --git a/src/drivers/qshell/qurt/Kconfig b/src/drivers/qshell/qurt/Kconfig new file mode 100644 index 0000000000..73b3b81ca9 --- /dev/null +++ b/src/drivers/qshell/qurt/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_QSHELL_QURT + bool "qurt" + default n + ---help--- + Enable support for qurt \ No newline at end of file diff --git a/src/drivers/rc_input/Kconfig b/src/drivers/rc_input/Kconfig new file mode 100644 index 0000000000..1ada2e84f4 --- /dev/null +++ b/src/drivers/rc_input/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RC_INPUT + bool "rc_input" + default n + ---help--- + Enable support for rc_input \ No newline at end of file diff --git a/src/drivers/roboclaw/Kconfig b/src/drivers/roboclaw/Kconfig new file mode 100644 index 0000000000..9315e757bc --- /dev/null +++ b/src/drivers/roboclaw/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_ROBOCLAW + bool "roboclaw" + default n + ---help--- + Enable support for roboclaw \ No newline at end of file diff --git a/src/drivers/rpi_rc_in/Kconfig b/src/drivers/rpi_rc_in/Kconfig new file mode 100644 index 0000000000..c496b033c9 --- /dev/null +++ b/src/drivers/rpi_rc_in/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RPI_RC_IN + bool "rpi_rc_in" + default n + ---help--- + Enable support for rpi_rc_in \ No newline at end of file diff --git a/src/drivers/rpm/Kconfig b/src/drivers/rpm/Kconfig new file mode 100644 index 0000000000..052b0d4848 --- /dev/null +++ b/src/drivers/rpm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RPM + bool "rpm" + default n + ---help--- + Enable support for rpm \ No newline at end of file diff --git a/src/drivers/rpm/pcf8583/Kconfig b/src/drivers/rpm/pcf8583/Kconfig new file mode 100644 index 0000000000..7ceb228e73 --- /dev/null +++ b/src/drivers/rpm/pcf8583/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RPM_PCF8583 + bool "pcf8583" + default n + ---help--- + Enable support for pcf8583 \ No newline at end of file diff --git a/src/drivers/rpm/rpm_simulator/Kconfig b/src/drivers/rpm/rpm_simulator/Kconfig new file mode 100644 index 0000000000..8b96677d03 --- /dev/null +++ b/src/drivers/rpm/rpm_simulator/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_RPM_RPM_SIMULATOR + bool "rpm_simulator" + default n + ---help--- + Enable support for rpm_simulator \ No newline at end of file diff --git a/src/drivers/safety_button/Kconfig b/src/drivers/safety_button/Kconfig new file mode 100644 index 0000000000..e891c6f96c --- /dev/null +++ b/src/drivers/safety_button/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_SAFETY_BUTTON + bool "safety_button" + default n + ---help--- + Enable support for safety_button \ No newline at end of file diff --git a/src/drivers/spektrum_rc/Kconfig b/src/drivers/spektrum_rc/Kconfig new file mode 100644 index 0000000000..0d67ce18b2 --- /dev/null +++ b/src/drivers/spektrum_rc/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_SPEKTRUM_RC + bool "spektrum_rc" + default n + ---help--- + Enable support for spektrum_rc \ No newline at end of file diff --git a/src/drivers/telemetry/Kconfig b/src/drivers/telemetry/Kconfig new file mode 100644 index 0000000000..2633a89e35 --- /dev/null +++ b/src/drivers/telemetry/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TELEMETRY + bool "telemetry" + default n + ---help--- + Enable support for telemetry \ No newline at end of file diff --git a/src/drivers/telemetry/bst/Kconfig b/src/drivers/telemetry/bst/Kconfig new file mode 100644 index 0000000000..28ce52902d --- /dev/null +++ b/src/drivers/telemetry/bst/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TELEMETRY_BST + bool "bst" + default n + ---help--- + Enable support for bst \ No newline at end of file diff --git a/src/drivers/telemetry/frsky_telemetry/Kconfig b/src/drivers/telemetry/frsky_telemetry/Kconfig new file mode 100644 index 0000000000..ce7382b6c5 --- /dev/null +++ b/src/drivers/telemetry/frsky_telemetry/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TELEMETRY_FRSKY_TELEMETRY + bool "frsky_telemetry" + default n + ---help--- + Enable support for frsky_telemetry \ No newline at end of file diff --git a/src/drivers/telemetry/hott/Kconfig b/src/drivers/telemetry/hott/Kconfig new file mode 100644 index 0000000000..6f73e2013b --- /dev/null +++ b/src/drivers/telemetry/hott/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TELEMETRY_HOTT + bool "hott" + default n + ---help--- + Enable support for hott \ No newline at end of file diff --git a/src/drivers/telemetry/iridiumsbd/Kconfig b/src/drivers/telemetry/iridiumsbd/Kconfig new file mode 100644 index 0000000000..db01020c81 --- /dev/null +++ b/src/drivers/telemetry/iridiumsbd/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TELEMETRY_IRIDIUMSBD + bool "iridiumsbd" + default n + ---help--- + Enable support for iridiumsbd \ No newline at end of file diff --git a/src/drivers/test_ppm/Kconfig b/src/drivers/test_ppm/Kconfig new file mode 100644 index 0000000000..514f9fb52b --- /dev/null +++ b/src/drivers/test_ppm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TEST_PPM + bool "test_ppm" + default n + ---help--- + Enable support for test_ppm \ No newline at end of file diff --git a/src/drivers/tone_alarm/Kconfig b/src/drivers/tone_alarm/Kconfig new file mode 100644 index 0000000000..3e7444f92b --- /dev/null +++ b/src/drivers/tone_alarm/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_TONE_ALARM + bool "tone_alarm" + default n + ---help--- + Enable support for tone_alarm \ No newline at end of file diff --git a/src/drivers/uavcan/Kconfig b/src/drivers/uavcan/Kconfig index b093b244db..f46c16451e 100644 --- a/src/drivers/uavcan/Kconfig +++ b/src/drivers/uavcan/Kconfig @@ -1,5 +1,13 @@ -menuconfig UAVCAN_INTERFACES - int "UAVCANv0 interface count" - default 0 +menuconfig DRIVERS_UAVCAN + bool "uavcan" + default n ---help--- - Interface count for UAVCANv0 + Enable support for uavcan + +if DRIVERS_UAVCAN + menuconfig UAVCAN_INTERFACES + int "UAVCANv0 interface count" + default 0 + ---help--- + Interface count for UAVCANv0 +endif #DRIVERS_UAVCAN diff --git a/src/drivers/uavcan_v1/Kconfig b/src/drivers/uavcan_v1/Kconfig index 7e3616fc5f..46c7f15199 100644 --- a/src/drivers/uavcan_v1/Kconfig +++ b/src/drivers/uavcan_v1/Kconfig @@ -2,29 +2,33 @@ # For a description of the syntax of this configuration file, # see the file kconfig-language.txt in the NuttX tools repository. # - - - - -choice - prompt "UAVCANv1 Mode" - -config UAVCAN_V1_FMU - bool "Server (FMU)" - -config UAVCAN_V1_CLIENT - bool "Client (Peripheral)" - -endchoice - -config UAVCAN_V1_GETINFO_RESPONDER - bool "GetInfo1.0 responder" +menuconfig DRIVERS_UAVCAN_V1 + bool "UAVCANv1" default n + ---help--- + Enable support for UAVCANv1 -config UAVCAN_V1_EXECUTECOMMAND_RESPONDER - bool "ExecuteCommand1.0 responder" - default n +if DRIVERS_UAVCAN_V1 + choice + prompt "UAVCANv1 Mode" -config UAVCAN_V1_GNSS_PUBLISHER - bool "GNSS Publisher" - default n + config UAVCAN_V1_FMU + bool "Server (FMU)" + + config UAVCAN_V1_CLIENT + bool "Client (Peripheral)" + + endchoice + + config UAVCAN_V1_GETINFO_RESPONDER + bool "GetInfo1.0 responder" + default n + + config UAVCAN_V1_EXECUTECOMMAND_RESPONDER + bool "ExecuteCommand1.0 responder" + default n + + config UAVCAN_V1_GNSS_PUBLISHER + bool "GNSS Publisher" + default n +endif #DRIVERS_UAVCAN_V1 diff --git a/src/drivers/uavcannode/Kconfig b/src/drivers/uavcannode/Kconfig new file mode 100644 index 0000000000..eff5c446a3 --- /dev/null +++ b/src/drivers/uavcannode/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_UAVCANNODE + bool "uavcannode" + default n + ---help--- + Enable support for uavcannode \ No newline at end of file diff --git a/src/drivers/uavcannode_gps_demo/Kconfig b/src/drivers/uavcannode_gps_demo/Kconfig new file mode 100644 index 0000000000..e2a70e9f3d --- /dev/null +++ b/src/drivers/uavcannode_gps_demo/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_UAVCANNODE_GPS_DEMO + bool "uavcannode_gps_demo" + default n + ---help--- + Enable support for uavcannode_gps_demo \ No newline at end of file diff --git a/src/examples/Kconfig b/src/examples/Kconfig index fe38971fa7..6353836988 100644 --- a/src/examples/Kconfig +++ b/src/examples/Kconfig @@ -1,77 +1 @@ -menuconfig EXAMPLES_DYN_HELLO - bool "dyn hello" - default n - ---help--- - Enable support for dyn hello - -menuconfig EXAMPLES_FAKE_GPS - bool "fake gps" - default n - ---help--- - Enable support for fake gps - -menuconfig EXAMPLES_FAKE_GYRO - bool "fake gyro" - default n - ---help--- - Enable support for fake gyro - -menuconfig EXAMPLES_FAKE_MAGNETOMETER - bool "fake magnetometer" - default n - ---help--- - Enable support for fake magnetometer - -menuconfig EXAMPLES_FIXEDWING_CONTROL - bool "fixedwing control" - default n - ---help--- - Enable support for fixedwing control - -menuconfig EXAMPLES_HELLO - bool "hello" - default n - ---help--- - Enable support for hello - -menuconfig EXAMPLES_HWTEST - bool "hwtest" - default n - ---help--- - Enable support for hwtest - -menuconfig EXAMPLES_MATLAB_CSV_SERIAL - bool "matlab csv serial" - default n - ---help--- - Enable support for matlab csv serial - -menuconfig EXAMPLES_PX4_MAVLINK_DEBUG - bool "px4 mavlink debug" - default n - ---help--- - Enable support for px4 mavlink debug - -menuconfig EXAMPLES_PX4_SIMPLE_APP - bool "px4 simple app" - default n - ---help--- - Enable support for px4 simple app - -menuconfig EXAMPLES_ROVER_STEERING_CONTROL - bool "rover steering control" - default n - ---help--- - Enable support for rover steering control - -menuconfig EXAMPLES_UUV_EXAMPLE_APP - bool "uuv example app" - default n - ---help--- - Enable support for uuv example app - -menuconfig EXAMPLES_WORK_ITEM - bool "work item" - default n - ---help--- - Enable support for work item +rsource "*/Kconfig" diff --git a/src/examples/dyn_hello/Kconfig b/src/examples/dyn_hello/Kconfig new file mode 100644 index 0000000000..30a5b6898a --- /dev/null +++ b/src/examples/dyn_hello/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_DYN_HELLO + bool "dyn_hello" + default n + ---help--- + Enable support for dyn_hello \ No newline at end of file diff --git a/src/examples/fake_gps/Kconfig b/src/examples/fake_gps/Kconfig new file mode 100644 index 0000000000..419a5f55cd --- /dev/null +++ b/src/examples/fake_gps/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_FAKE_GPS + bool "fake_gps" + default n + ---help--- + Enable support for fake_gps \ No newline at end of file diff --git a/src/examples/fake_gyro/Kconfig b/src/examples/fake_gyro/Kconfig new file mode 100644 index 0000000000..fbfc20465b --- /dev/null +++ b/src/examples/fake_gyro/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_FAKE_GYRO + bool "fake_gyro" + default n + ---help--- + Enable support for fake_gyro \ No newline at end of file diff --git a/src/examples/fake_magnetometer/Kconfig b/src/examples/fake_magnetometer/Kconfig new file mode 100644 index 0000000000..c590603382 --- /dev/null +++ b/src/examples/fake_magnetometer/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_FAKE_MAGNETOMETER + bool "fake_magnetometer" + default n + ---help--- + Enable support for fake_magnetometer \ No newline at end of file diff --git a/src/examples/fixedwing_control/Kconfig b/src/examples/fixedwing_control/Kconfig new file mode 100644 index 0000000000..ec57ca4a34 --- /dev/null +++ b/src/examples/fixedwing_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_FIXEDWING_CONTROL + bool "fixedwing_control" + default n + ---help--- + Enable support for fixedwing_control \ No newline at end of file diff --git a/src/examples/hello/Kconfig b/src/examples/hello/Kconfig new file mode 100644 index 0000000000..c47ec7587a --- /dev/null +++ b/src/examples/hello/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_HELLO + bool "hello" + default n + ---help--- + Enable support for hello \ No newline at end of file diff --git a/src/examples/hwtest/Kconfig b/src/examples/hwtest/Kconfig new file mode 100644 index 0000000000..581c3296b1 --- /dev/null +++ b/src/examples/hwtest/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_HWTEST + bool "hwtest" + default n + ---help--- + Enable support for hwtest \ No newline at end of file diff --git a/src/examples/matlab_csv_serial/Kconfig b/src/examples/matlab_csv_serial/Kconfig new file mode 100644 index 0000000000..7352ebcabb --- /dev/null +++ b/src/examples/matlab_csv_serial/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_MATLAB_CSV_SERIAL + bool "matlab_csv_serial" + default n + ---help--- + Enable support for matlab_csv_serial \ No newline at end of file diff --git a/src/examples/px4_mavlink_debug/Kconfig b/src/examples/px4_mavlink_debug/Kconfig new file mode 100644 index 0000000000..5707edd736 --- /dev/null +++ b/src/examples/px4_mavlink_debug/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_PX4_MAVLINK_DEBUG + bool "px4_mavlink_debug" + default n + ---help--- + Enable support for px4_mavlink_debug \ No newline at end of file diff --git a/src/examples/px4_simple_app/Kconfig b/src/examples/px4_simple_app/Kconfig new file mode 100644 index 0000000000..64fbc1916d --- /dev/null +++ b/src/examples/px4_simple_app/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_PX4_SIMPLE_APP + bool "px4_simple_app" + default n + ---help--- + Enable support for px4_simple_app \ No newline at end of file diff --git a/src/examples/rover_steering_control/Kconfig b/src/examples/rover_steering_control/Kconfig new file mode 100644 index 0000000000..73e34d98f8 --- /dev/null +++ b/src/examples/rover_steering_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_ROVER_STEERING_CONTROL + bool "rover_steering_control" + default n + ---help--- + Enable support for rover_steering_control \ No newline at end of file diff --git a/src/examples/uuv_example_app/Kconfig b/src/examples/uuv_example_app/Kconfig new file mode 100644 index 0000000000..a24e18acd1 --- /dev/null +++ b/src/examples/uuv_example_app/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_UUV_EXAMPLE_APP + bool "uuv_example_app" + default n + ---help--- + Enable support for uuv_example_app \ No newline at end of file diff --git a/src/examples/work_item/Kconfig b/src/examples/work_item/Kconfig new file mode 100644 index 0000000000..f6a29b15d4 --- /dev/null +++ b/src/examples/work_item/Kconfig @@ -0,0 +1,5 @@ +menuconfig EXAMPLES_WORK_ITEM + bool "work_item" + default n + ---help--- + Enable support for work_item \ No newline at end of file diff --git a/src/modules/Kconfig b/src/modules/Kconfig index 3879f4e837..6353836988 100644 --- a/src/modules/Kconfig +++ b/src/modules/Kconfig @@ -1,251 +1 @@ -menuconfig MODULES_AIRSHIP_ATT_CONTROL - bool "airship att control" - default n - ---help--- - Enable support for airship att control - -menuconfig MODULES_AIRSPEED_SELECTOR - bool "airspeed selector" - default n - ---help--- - Enable support for airspeed selector - -menuconfig MODULES_ANGULAR_VELOCITY_CONTROLLER - bool "angular velocity controller" - default n - ---help--- - Enable support for angular velocity controller - -menuconfig MODULES_ATTITUDE_ESTIMATOR_Q - bool "attitude estimator q" - default n - ---help--- - Enable support for attitude estimator q - -menuconfig MODULES_BATTERY_STATUS - bool "battery status" - default n - ---help--- - Enable support for battery status - -menuconfig MODULES_CAMERA_FEEDBACK - bool "camera feedback" - default n - ---help--- - Enable support for camera feedback - -menuconfig MODULES_COMMANDER - bool "commander" - default n - ---help--- - Enable support for commander - -menuconfig MODULES_CONTROL_ALLOCATOR - bool "control allocator" - default n - ---help--- - Enable support for control allocator - -menuconfig MODULES_DATAMAN - bool "dataman" - default n - ---help--- - Enable support for dataman - -menuconfig MODULES_EKF2 - bool "ekf2" - default n - ---help--- - Enable support for ekf2 - -menuconfig MODULES_ESC_BATTERY - bool "esc battery" - default n - ---help--- - Enable support for esc battery - -menuconfig MODULES_EVENTS - bool "events" - default n - ---help--- - Enable support for events - -menuconfig MODULES_FLIGHT_MODE_MANAGER - bool "flight mode manager" - default n - ---help--- - Enable support for flight mode manager - -menuconfig MODULES_FW_ATT_CONTROL - bool "fw att control" - default n - ---help--- - Enable support for fw att control - -menuconfig MODULES_FW_POS_CONTROL_L1 - bool "fw pos control l1" - default n - ---help--- - Enable support for fw pos control l1 - -menuconfig MODULES_GYRO_CALIBRATION - bool "gyro calibration" - default n - ---help--- - Enable support for gyro calibration - -menuconfig MODULES_GYRO_FFT - bool "gyro fft" - default n - ---help--- - Enable support for gyro fft - -menuconfig MODULES_LAND_DETECTOR - bool "land detector" - default n - ---help--- - Enable support for land detector - -menuconfig MODULES_LANDING_TARGET_ESTIMATOR - bool "landing target estimator" - default n - ---help--- - Enable support for landing target estimator - -menuconfig MODULES_LOAD_MON - bool "load mon" - default n - ---help--- - Enable support for load mon - -menuconfig MODULES_LOCAL_POSITION_ESTIMATOR - bool "local position estimator" - default n - ---help--- - Enable support for local position estimator - -menuconfig MODULES_LOGGER - bool "logger" - default n - ---help--- - Enable support for logger - -menuconfig MODULES_MAVLINK - bool "mavlink" - default n - ---help--- - Enable support for mavlink - -menuconfig MODULES_MC_ATT_CONTROL - bool "mc att control" - default n - ---help--- - Enable support for mc att control - -menuconfig MODULES_MC_HOVER_THRUST_ESTIMATOR - bool "mc hover thrust estimator" - default n - ---help--- - Enable support for mc hover thrust estimator - -menuconfig MODULES_MC_POS_CONTROL - bool "mc pos control" - default n - ---help--- - Enable support for mc pos control - -menuconfig MODULES_MC_RATE_CONTROL - bool "mc rate control" - default n - ---help--- - Enable support for mc rate control - -menuconfig MODULES_MICRORTPS_BRIDGE - bool "micrortps bridge" - default n - ---help--- - Enable support for micrortps bridge - -menuconfig MODULES_MUORB - bool "muorb" - default n - ---help--- - Enable support for muorb - -menuconfig MODULES_NAVIGATOR - bool "navigator" - default n - ---help--- - Enable support for navigator - -menuconfig MODULES_PX4IOFIRMWARE - bool "px4iofirmware" - default n - ---help--- - Enable support for px4iofirmware - -menuconfig MODULES_RC_UPDATE - bool "rc update" - default n - ---help--- - Enable support for rc update - -menuconfig MODULES_REPLAY - bool "replay" - default n - ---help--- - Enable support for replay - -menuconfig MODULES_ROVER_POS_CONTROL - bool "rover pos control" - default n - ---help--- - Enable support for rover pos control - -menuconfig MODULES_SENSORS - bool "sensors" - default n - ---help--- - Enable support for sensors - -menuconfig MODULES_SIH - bool "sih" - default n - ---help--- - Enable support for sih - -menuconfig MODULES_SIMULATOR - bool "simulator" - default n - ---help--- - Enable support for simulator - -menuconfig MODULES_TEMPERATURE_COMPENSATION - bool "temperature compensation" - default n - ---help--- - Enable support for temperature compensation - -menuconfig MODULES_UUV_ATT_CONTROL - bool "uuv att control" - default n - ---help--- - Enable support for uuv att control - -menuconfig MODULES_UUV_POS_CONTROL - bool "uuv pos control" - default n - ---help--- - Enable support for uuv pos control - -menuconfig MODULES_VMOUNT - bool "vmount" - default n - ---help--- - Enable support for vmount - -menuconfig MODULES_VTOL_ATT_CONTROL - bool "vtol att control" - default n - ---help--- - Enable support for vtol att control +rsource "*/Kconfig" diff --git a/src/modules/airship_att_control/Kconfig b/src/modules/airship_att_control/Kconfig new file mode 100644 index 0000000000..e731f3f333 --- /dev/null +++ b/src/modules/airship_att_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_AIRSHIP_ATT_CONTROL + bool "airship_att_control" + default n + ---help--- + Enable support for airship_att_control \ No newline at end of file diff --git a/src/modules/airspeed_selector/Kconfig b/src/modules/airspeed_selector/Kconfig new file mode 100644 index 0000000000..6871d64c7d --- /dev/null +++ b/src/modules/airspeed_selector/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_AIRSPEED_SELECTOR + bool "airspeed_selector" + default n + ---help--- + Enable support for airspeed_selector \ No newline at end of file diff --git a/src/modules/angular_velocity_controller/Kconfig b/src/modules/angular_velocity_controller/Kconfig new file mode 100644 index 0000000000..f7f4784c01 --- /dev/null +++ b/src/modules/angular_velocity_controller/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_ANGULAR_VELOCITY_CONTROLLER + bool "angular_velocity_controller" + default n + ---help--- + Enable support for angular_velocity_controller \ No newline at end of file diff --git a/src/modules/attitude_estimator_q/Kconfig b/src/modules/attitude_estimator_q/Kconfig new file mode 100644 index 0000000000..f2734a7b77 --- /dev/null +++ b/src/modules/attitude_estimator_q/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_ATTITUDE_ESTIMATOR_Q + bool "attitude_estimator_q" + default n + ---help--- + Enable support for attitude_estimator_q \ No newline at end of file diff --git a/src/modules/battery_status/Kconfig b/src/modules/battery_status/Kconfig new file mode 100644 index 0000000000..dc8bb956b6 --- /dev/null +++ b/src/modules/battery_status/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_BATTERY_STATUS + bool "battery_status" + default n + ---help--- + Enable support for battery_status \ No newline at end of file diff --git a/src/modules/camera_feedback/Kconfig b/src/modules/camera_feedback/Kconfig new file mode 100644 index 0000000000..3b510195d4 --- /dev/null +++ b/src/modules/camera_feedback/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_CAMERA_FEEDBACK + bool "camera_feedback" + default n + ---help--- + Enable support for camera_feedback \ No newline at end of file diff --git a/src/modules/commander/Kconfig b/src/modules/commander/Kconfig new file mode 100644 index 0000000000..7882fcf876 --- /dev/null +++ b/src/modules/commander/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_COMMANDER + bool "commander" + default n + ---help--- + Enable support for commander \ No newline at end of file diff --git a/src/modules/control_allocator/Kconfig b/src/modules/control_allocator/Kconfig new file mode 100644 index 0000000000..808d64aa87 --- /dev/null +++ b/src/modules/control_allocator/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_CONTROL_ALLOCATOR + bool "control_allocator" + default n + ---help--- + Enable support for control_allocator \ No newline at end of file diff --git a/src/modules/ekf2/Kconfig b/src/modules/ekf2/Kconfig new file mode 100644 index 0000000000..cb26fca8da --- /dev/null +++ b/src/modules/ekf2/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_EKF2 + bool "ekf2" + default n + ---help--- + Enable support for ekf2 \ No newline at end of file diff --git a/src/modules/esc_battery/Kconfig b/src/modules/esc_battery/Kconfig new file mode 100644 index 0000000000..e951644577 --- /dev/null +++ b/src/modules/esc_battery/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_ESC_BATTERY + bool "esc_battery" + default n + ---help--- + Enable support for esc_battery \ No newline at end of file diff --git a/src/modules/events/Kconfig b/src/modules/events/Kconfig new file mode 100644 index 0000000000..e29b7bf74e --- /dev/null +++ b/src/modules/events/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_EVENTS + bool "events" + default n + ---help--- + Enable support for events \ No newline at end of file diff --git a/src/modules/flight_mode_manager/Kconfig b/src/modules/flight_mode_manager/Kconfig new file mode 100644 index 0000000000..02aec199d0 --- /dev/null +++ b/src/modules/flight_mode_manager/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_FLIGHT_MODE_MANAGER + bool "flight_mode_manager" + default n + ---help--- + Enable support for flight_mode_manager \ No newline at end of file diff --git a/src/modules/fw_att_control/Kconfig b/src/modules/fw_att_control/Kconfig new file mode 100644 index 0000000000..6d95bc8c35 --- /dev/null +++ b/src/modules/fw_att_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_FW_ATT_CONTROL + bool "fw_att_control" + default n + ---help--- + Enable support for fw_att_control \ No newline at end of file diff --git a/src/modules/fw_pos_control_l1/Kconfig b/src/modules/fw_pos_control_l1/Kconfig new file mode 100644 index 0000000000..807c6797db --- /dev/null +++ b/src/modules/fw_pos_control_l1/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_FW_POS_CONTROL_L1 + bool "fw_pos_control_l1" + default n + ---help--- + Enable support for fw_pos_control_l1 \ No newline at end of file diff --git a/src/modules/gyro_calibration/Kconfig b/src/modules/gyro_calibration/Kconfig new file mode 100644 index 0000000000..7c5ccd4dd0 --- /dev/null +++ b/src/modules/gyro_calibration/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_GYRO_CALIBRATION + bool "gyro_calibration" + default n + ---help--- + Enable support for gyro_calibration \ No newline at end of file diff --git a/src/modules/gyro_fft/Kconfig b/src/modules/gyro_fft/Kconfig new file mode 100644 index 0000000000..21357b3ac0 --- /dev/null +++ b/src/modules/gyro_fft/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_GYRO_FFT + bool "gyro_fft" + default n + ---help--- + Enable support for gyro_fft \ No newline at end of file diff --git a/src/modules/land_detector/Kconfig b/src/modules/land_detector/Kconfig new file mode 100644 index 0000000000..adbd8052e8 --- /dev/null +++ b/src/modules/land_detector/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_LAND_DETECTOR + bool "land_detector" + default n + ---help--- + Enable support for land_detector \ No newline at end of file diff --git a/src/modules/landing_target_estimator/Kconfig b/src/modules/landing_target_estimator/Kconfig new file mode 100644 index 0000000000..43cb312369 --- /dev/null +++ b/src/modules/landing_target_estimator/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_LANDING_TARGET_ESTIMATOR + bool "landing_target_estimator" + default n + ---help--- + Enable support for landing_target_estimator \ No newline at end of file diff --git a/src/modules/load_mon/Kconfig b/src/modules/load_mon/Kconfig new file mode 100644 index 0000000000..e1bc6b6cc9 --- /dev/null +++ b/src/modules/load_mon/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_LOAD_MON + bool "load_mon" + default n + ---help--- + Enable support for load_mon \ No newline at end of file diff --git a/src/modules/local_position_estimator/Kconfig b/src/modules/local_position_estimator/Kconfig new file mode 100644 index 0000000000..bb746cbfc8 --- /dev/null +++ b/src/modules/local_position_estimator/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_LOCAL_POSITION_ESTIMATOR + bool "local_position_estimator" + default n + ---help--- + Enable support for local_position_estimator \ No newline at end of file diff --git a/src/modules/logger/Kconfig b/src/modules/logger/Kconfig new file mode 100644 index 0000000000..e29bbf7e96 --- /dev/null +++ b/src/modules/logger/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_LOGGER + bool "logger" + default n + ---help--- + Enable support for logger \ No newline at end of file diff --git a/src/modules/mavlink/Kconfig b/src/modules/mavlink/Kconfig new file mode 100644 index 0000000000..ca00d63fa6 --- /dev/null +++ b/src/modules/mavlink/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_MAVLINK + bool "mavlink" + default n + ---help--- + Enable support for mavlink \ No newline at end of file diff --git a/src/modules/mc_att_control/Kconfig b/src/modules/mc_att_control/Kconfig new file mode 100644 index 0000000000..50b6d30251 --- /dev/null +++ b/src/modules/mc_att_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_MC_ATT_CONTROL + bool "mc_att_control" + default n + ---help--- + Enable support for mc_att_control \ No newline at end of file diff --git a/src/modules/mc_hover_thrust_estimator/Kconfig b/src/modules/mc_hover_thrust_estimator/Kconfig new file mode 100644 index 0000000000..9ef0452ac3 --- /dev/null +++ b/src/modules/mc_hover_thrust_estimator/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_MC_HOVER_THRUST_ESTIMATOR + bool "mc_hover_thrust_estimator" + default n + ---help--- + Enable support for mc_hover_thrust_estimator \ No newline at end of file diff --git a/src/modules/mc_pos_control/Kconfig b/src/modules/mc_pos_control/Kconfig new file mode 100644 index 0000000000..7e087dcb21 --- /dev/null +++ b/src/modules/mc_pos_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_MC_POS_CONTROL + bool "mc_pos_control" + default n + ---help--- + Enable support for mc_pos_control \ No newline at end of file diff --git a/src/modules/mc_rate_control/Kconfig b/src/modules/mc_rate_control/Kconfig new file mode 100644 index 0000000000..7c63dd9b87 --- /dev/null +++ b/src/modules/mc_rate_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_MC_RATE_CONTROL + bool "mc_rate_control" + default n + ---help--- + Enable support for mc_rate_control \ No newline at end of file diff --git a/src/modules/micrortps_bridge/Kconfig b/src/modules/micrortps_bridge/Kconfig new file mode 100644 index 0000000000..9a2d3b9c04 --- /dev/null +++ b/src/modules/micrortps_bridge/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_MICRORTPS_BRIDGE + bool "micrortps_bridge" + default n + ---help--- + Enable support for micrortps_bridge \ No newline at end of file diff --git a/src/modules/navigator/Kconfig b/src/modules/navigator/Kconfig new file mode 100644 index 0000000000..be3344c7ca --- /dev/null +++ b/src/modules/navigator/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_NAVIGATOR + bool "navigator" + default n + ---help--- + Enable support for navigator \ No newline at end of file diff --git a/src/modules/px4iofirmware/Kconfig b/src/modules/px4iofirmware/Kconfig new file mode 100644 index 0000000000..37f01af658 --- /dev/null +++ b/src/modules/px4iofirmware/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_PX4IOFIRMWARE + bool "px4iofirmware" + default n + ---help--- + Enable support for px4iofirmware \ No newline at end of file diff --git a/src/modules/rc_update/Kconfig b/src/modules/rc_update/Kconfig new file mode 100644 index 0000000000..9d57732726 --- /dev/null +++ b/src/modules/rc_update/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_RC_UPDATE + bool "rc_update" + default n + ---help--- + Enable support for rc_update \ No newline at end of file diff --git a/src/modules/replay/Kconfig b/src/modules/replay/Kconfig new file mode 100644 index 0000000000..a2868f08f5 --- /dev/null +++ b/src/modules/replay/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_REPLAY + bool "replay" + default n + ---help--- + Enable support for replay \ No newline at end of file diff --git a/src/modules/rover_pos_control/Kconfig b/src/modules/rover_pos_control/Kconfig new file mode 100644 index 0000000000..cd40f1cfe6 --- /dev/null +++ b/src/modules/rover_pos_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_ROVER_POS_CONTROL + bool "rover_pos_control" + default n + ---help--- + Enable support for rover_pos_control \ No newline at end of file diff --git a/src/modules/sensors/Kconfig b/src/modules/sensors/Kconfig new file mode 100644 index 0000000000..111c92c2bf --- /dev/null +++ b/src/modules/sensors/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_SENSORS + bool "sensors" + default n + ---help--- + Enable support for sensors \ No newline at end of file diff --git a/src/modules/sih/Kconfig b/src/modules/sih/Kconfig new file mode 100644 index 0000000000..aec5239494 --- /dev/null +++ b/src/modules/sih/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_SIH + bool "sih" + default n + ---help--- + Enable support for sih \ No newline at end of file diff --git a/src/modules/simulator/Kconfig b/src/modules/simulator/Kconfig new file mode 100644 index 0000000000..a2f40953b3 --- /dev/null +++ b/src/modules/simulator/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_SIMULATOR + bool "simulator" + default n + ---help--- + Enable support for simulator \ No newline at end of file diff --git a/src/modules/temperature_compensation/Kconfig b/src/modules/temperature_compensation/Kconfig new file mode 100644 index 0000000000..63ad6b88ba --- /dev/null +++ b/src/modules/temperature_compensation/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_TEMPERATURE_COMPENSATION + bool "temperature_compensation" + default n + ---help--- + Enable support for temperature_compensation \ No newline at end of file diff --git a/src/modules/uuv_att_control/Kconfig b/src/modules/uuv_att_control/Kconfig new file mode 100644 index 0000000000..f0f0be5643 --- /dev/null +++ b/src/modules/uuv_att_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_UUV_ATT_CONTROL + bool "uuv_att_control" + default n + ---help--- + Enable support for uuv_att_control \ No newline at end of file diff --git a/src/modules/uuv_pos_control/Kconfig b/src/modules/uuv_pos_control/Kconfig new file mode 100644 index 0000000000..88150e17e2 --- /dev/null +++ b/src/modules/uuv_pos_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_UUV_POS_CONTROL + bool "uuv_pos_control" + default n + ---help--- + Enable support for uuv_pos_control \ No newline at end of file diff --git a/src/modules/vmount/Kconfig b/src/modules/vmount/Kconfig new file mode 100644 index 0000000000..ba267d4b6b --- /dev/null +++ b/src/modules/vmount/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_VMOUNT + bool "vmount" + default n + ---help--- + Enable support for vmount \ No newline at end of file diff --git a/src/modules/vtol_att_control/Kconfig b/src/modules/vtol_att_control/Kconfig new file mode 100644 index 0000000000..6a71b4a6c3 --- /dev/null +++ b/src/modules/vtol_att_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig MODULES_VTOL_ATT_CONTROL + bool "vtol_att_control" + default n + ---help--- + Enable support for vtol_att_control \ No newline at end of file diff --git a/src/systemcmds/Kconfig b/src/systemcmds/Kconfig index 31d1f3e3e0..6353836988 100644 --- a/src/systemcmds/Kconfig +++ b/src/systemcmds/Kconfig @@ -1,203 +1 @@ -menuconfig SYSTEMCMDS_BL_UPDATE - bool "bl update" - default n - ---help--- - Enable support for bl update - -menuconfig SYSTEMCMDS_DMESG - bool "dmesg" - default n - ---help--- - Enable support for dmesg - -menuconfig SYSTEMCMDS_DUMPFILE - bool "dumpfile" - default n - ---help--- - Enable support for dumpfile - -menuconfig SYSTEMCMDS_DYN - bool "dyn" - default n - ---help--- - Enable support for dyn - -menuconfig SYSTEMCMDS_ESC_CALIB - bool "esc calib" - default n - ---help--- - Enable support for esc calib - -menuconfig SYSTEMCMDS_FAILURE - bool "failure" - default n - ---help--- - Enable support for failure - -menuconfig SYSTEMCMDS_GPIO - bool "gpio" - default n - ---help--- - Enable support for gpio - -menuconfig SYSTEMCMDS_HARDFAULT_LOG - bool "hardfault log" - default n - ---help--- - Enable support for hardfault log - -menuconfig SYSTEMCMDS_I2CDETECT - bool "i2cdetect" - default n - ---help--- - Enable support for i2cdetect - -menuconfig SYSTEMCMDS_LED_CONTROL - bool "led control" - default n - ---help--- - Enable support for led control - -menuconfig SYSTEMCMDS_MFT - bool "mft" - default n - ---help--- - Enable support for mft - -menuconfig SYSTEMCMDS_MIXER - bool "mixer" - default n - ---help--- - Enable support for mixer - -menuconfig SYSTEMCMDS_MOTOR_RAMP - bool "motor ramp" - default n - ---help--- - Enable support for motor ramp - -menuconfig SYSTEMCMDS_MOTOR_TEST - bool "motor test" - default n - ---help--- - Enable support for motor test - -menuconfig SYSTEMCMDS_MTD - bool "mtd" - default n - ---help--- - Enable support for mtd - -menuconfig SYSTEMCMDS_NETMAN - bool "netman" - default n - ---help--- - Enable support for netman - -menuconfig SYSTEMCMDS_NSHTERM - bool "nshterm" - default n - ---help--- - Enable support for nshterm - -menuconfig SYSTEMCMDS_PARAM - bool "param" - default n - ---help--- - Enable support for param - -menuconfig SYSTEMCMDS_PERF - bool "perf" - default n - ---help--- - Enable support for perf - -menuconfig SYSTEMCMDS_PWM - bool "pwm" - default n - ---help--- - Enable support for pwm - -menuconfig SYSTEMCMDS_REBOOT - bool "reboot" - default n - ---help--- - Enable support for reboot - -menuconfig SYSTEMCMDS_REFLECT - bool "reflect" - default n - ---help--- - Enable support for reflect - -menuconfig SYSTEMCMDS_SD_BENCH - bool "sd bench" - default n - ---help--- - Enable support for sd bench - -menuconfig SYSTEMCMDS_SERIAL_TEST - bool "serial test" - default n - ---help--- - Enable support for serial test - -menuconfig SYSTEMCMDS_SHUTDOWN - bool "shutdown" - default n - ---help--- - Enable support for shutdown - -menuconfig SYSTEMCMDS_SYSTEM_TIME - bool "system time" - default n - ---help--- - Enable support for system time - -menuconfig SYSTEMCMDS_TESTS - bool "tests" - default n - ---help--- - Enable support for tests - -menuconfig SYSTEMCMDS_TOP - bool "top" - default n - ---help--- - Enable support for top - -menuconfig SYSTEMCMDS_TOPIC_LISTENER - bool "topic listener" - default n - ---help--- - Enable support for topic listener - -menuconfig SYSTEMCMDS_TUNE_CONTROL - bool "tune control" - default n - ---help--- - Enable support for tune control - -menuconfig SYSTEMCMDS_UORB - bool "uorb" - default n - ---help--- - Enable support for uorb - -menuconfig SYSTEMCMDS_USB_CONNECTED - bool "usb connected" - default n - ---help--- - Enable support for usb connected - -menuconfig SYSTEMCMDS_VER - bool "ver" - default n - ---help--- - Enable support for ver - -menuconfig SYSTEMCMDS_WORK_QUEUE - bool "work queue" - default n - ---help--- - Enable support for work queue +rsource "*/Kconfig" diff --git a/src/systemcmds/bl_update/Kconfig b/src/systemcmds/bl_update/Kconfig new file mode 100644 index 0000000000..2cd6f01579 --- /dev/null +++ b/src/systemcmds/bl_update/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_BL_UPDATE + bool "bl_update" + default n + ---help--- + Enable support for bl_update \ No newline at end of file diff --git a/src/systemcmds/dmesg/Kconfig b/src/systemcmds/dmesg/Kconfig new file mode 100644 index 0000000000..a7712e93e5 --- /dev/null +++ b/src/systemcmds/dmesg/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_DMESG + bool "dmesg" + default n + ---help--- + Enable support for dmesg \ No newline at end of file diff --git a/src/systemcmds/dumpfile/Kconfig b/src/systemcmds/dumpfile/Kconfig new file mode 100644 index 0000000000..61b272f727 --- /dev/null +++ b/src/systemcmds/dumpfile/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_DUMPFILE + bool "dumpfile" + default n + ---help--- + Enable support for dumpfile \ No newline at end of file diff --git a/src/systemcmds/dyn/Kconfig b/src/systemcmds/dyn/Kconfig new file mode 100644 index 0000000000..60eeeb4bcf --- /dev/null +++ b/src/systemcmds/dyn/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_DYN + bool "dyn" + default n + ---help--- + Enable support for dyn \ No newline at end of file diff --git a/src/systemcmds/esc_calib/Kconfig b/src/systemcmds/esc_calib/Kconfig new file mode 100644 index 0000000000..057282652b --- /dev/null +++ b/src/systemcmds/esc_calib/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_ESC_CALIB + bool "esc_calib" + default n + ---help--- + Enable support for esc_calib \ No newline at end of file diff --git a/src/systemcmds/failure/Kconfig b/src/systemcmds/failure/Kconfig new file mode 100644 index 0000000000..d9b0bfc8a4 --- /dev/null +++ b/src/systemcmds/failure/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_FAILURE + bool "failure" + default n + ---help--- + Enable support for failure \ No newline at end of file diff --git a/src/systemcmds/gpio/Kconfig b/src/systemcmds/gpio/Kconfig new file mode 100644 index 0000000000..ba8d054787 --- /dev/null +++ b/src/systemcmds/gpio/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_GPIO + bool "gpio" + default n + ---help--- + Enable support for gpio \ No newline at end of file diff --git a/src/systemcmds/hardfault_log/Kconfig b/src/systemcmds/hardfault_log/Kconfig new file mode 100644 index 0000000000..11c8e81be2 --- /dev/null +++ b/src/systemcmds/hardfault_log/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_HARDFAULT_LOG + bool "hardfault_log" + default n + ---help--- + Enable support for hardfault_log \ No newline at end of file diff --git a/src/systemcmds/i2cdetect/Kconfig b/src/systemcmds/i2cdetect/Kconfig new file mode 100644 index 0000000000..a763581b3a --- /dev/null +++ b/src/systemcmds/i2cdetect/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_I2CDETECT + bool "i2cdetect" + default n + ---help--- + Enable support for i2cdetect \ No newline at end of file diff --git a/src/systemcmds/led_control/Kconfig b/src/systemcmds/led_control/Kconfig new file mode 100644 index 0000000000..ba931e2fe6 --- /dev/null +++ b/src/systemcmds/led_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_LED_CONTROL + bool "led_control" + default n + ---help--- + Enable support for led_control \ No newline at end of file diff --git a/src/systemcmds/mft/Kconfig b/src/systemcmds/mft/Kconfig new file mode 100644 index 0000000000..6aa740593b --- /dev/null +++ b/src/systemcmds/mft/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_MFT + bool "mft" + default n + ---help--- + Enable support for mft \ No newline at end of file diff --git a/src/systemcmds/mixer/Kconfig b/src/systemcmds/mixer/Kconfig new file mode 100644 index 0000000000..2175156c22 --- /dev/null +++ b/src/systemcmds/mixer/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_MIXER + bool "mixer" + default n + ---help--- + Enable support for mixer \ No newline at end of file diff --git a/src/systemcmds/motor_ramp/Kconfig b/src/systemcmds/motor_ramp/Kconfig new file mode 100644 index 0000000000..8445ecb29b --- /dev/null +++ b/src/systemcmds/motor_ramp/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_MOTOR_RAMP + bool "motor_ramp" + default n + ---help--- + Enable support for motor_ramp \ No newline at end of file diff --git a/src/systemcmds/motor_test/Kconfig b/src/systemcmds/motor_test/Kconfig new file mode 100644 index 0000000000..d1100d4d91 --- /dev/null +++ b/src/systemcmds/motor_test/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_MOTOR_TEST + bool "motor_test" + default n + ---help--- + Enable support for motor_test \ No newline at end of file diff --git a/src/systemcmds/mtd/Kconfig b/src/systemcmds/mtd/Kconfig new file mode 100644 index 0000000000..549994fd28 --- /dev/null +++ b/src/systemcmds/mtd/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_MTD + bool "mtd" + default n + ---help--- + Enable support for mtd \ No newline at end of file diff --git a/src/systemcmds/netman/Kconfig b/src/systemcmds/netman/Kconfig new file mode 100644 index 0000000000..48ee113b26 --- /dev/null +++ b/src/systemcmds/netman/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_NETMAN + bool "netman" + default n + ---help--- + Enable support for netman \ No newline at end of file diff --git a/src/systemcmds/nshterm/Kconfig b/src/systemcmds/nshterm/Kconfig new file mode 100644 index 0000000000..4bb8149198 --- /dev/null +++ b/src/systemcmds/nshterm/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_NSHTERM + bool "nshterm" + default n + ---help--- + Enable support for nshterm \ No newline at end of file diff --git a/src/systemcmds/param/Kconfig b/src/systemcmds/param/Kconfig new file mode 100644 index 0000000000..899da054fb --- /dev/null +++ b/src/systemcmds/param/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_PARAM + bool "param" + default n + ---help--- + Enable support for param \ No newline at end of file diff --git a/src/systemcmds/perf/Kconfig b/src/systemcmds/perf/Kconfig new file mode 100644 index 0000000000..ef68c79405 --- /dev/null +++ b/src/systemcmds/perf/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_PERF + bool "perf" + default n + ---help--- + Enable support for perf \ No newline at end of file diff --git a/src/systemcmds/pwm/Kconfig b/src/systemcmds/pwm/Kconfig new file mode 100644 index 0000000000..90a3f99a88 --- /dev/null +++ b/src/systemcmds/pwm/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_PWM + bool "pwm" + default n + ---help--- + Enable support for pwm \ No newline at end of file diff --git a/src/systemcmds/reboot/Kconfig b/src/systemcmds/reboot/Kconfig new file mode 100644 index 0000000000..d93743a4d6 --- /dev/null +++ b/src/systemcmds/reboot/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_REBOOT + bool "reboot" + default n + ---help--- + Enable support for reboot \ No newline at end of file diff --git a/src/systemcmds/reflect/Kconfig b/src/systemcmds/reflect/Kconfig new file mode 100644 index 0000000000..d317877114 --- /dev/null +++ b/src/systemcmds/reflect/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_REFLECT + bool "reflect" + default n + ---help--- + Enable support for reflect \ No newline at end of file diff --git a/src/systemcmds/sd_bench/Kconfig b/src/systemcmds/sd_bench/Kconfig new file mode 100644 index 0000000000..3f66eb209e --- /dev/null +++ b/src/systemcmds/sd_bench/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_SD_BENCH + bool "sd_bench" + default n + ---help--- + Enable support for sd_bench \ No newline at end of file diff --git a/src/systemcmds/serial_test/Kconfig b/src/systemcmds/serial_test/Kconfig new file mode 100644 index 0000000000..21eb7adcb9 --- /dev/null +++ b/src/systemcmds/serial_test/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_SERIAL_TEST + bool "serial_test" + default n + ---help--- + Enable support for serial_test \ No newline at end of file diff --git a/src/systemcmds/shutdown/Kconfig b/src/systemcmds/shutdown/Kconfig new file mode 100644 index 0000000000..8624daa63b --- /dev/null +++ b/src/systemcmds/shutdown/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_SHUTDOWN + bool "shutdown" + default n + ---help--- + Enable support for shutdown \ No newline at end of file diff --git a/src/systemcmds/system_time/Kconfig b/src/systemcmds/system_time/Kconfig new file mode 100644 index 0000000000..4f8513a2d9 --- /dev/null +++ b/src/systemcmds/system_time/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_SYSTEM_TIME + bool "system_time" + default n + ---help--- + Enable support for system_time \ No newline at end of file diff --git a/src/systemcmds/tests/Kconfig b/src/systemcmds/tests/Kconfig new file mode 100644 index 0000000000..3569d95103 --- /dev/null +++ b/src/systemcmds/tests/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_TESTS + bool "tests" + default n + ---help--- + Enable support for tests \ No newline at end of file diff --git a/src/systemcmds/top/Kconfig b/src/systemcmds/top/Kconfig new file mode 100644 index 0000000000..c7e3ff45ef --- /dev/null +++ b/src/systemcmds/top/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_TOP + bool "top" + default n + ---help--- + Enable support for top \ No newline at end of file diff --git a/src/systemcmds/topic_listener/Kconfig b/src/systemcmds/topic_listener/Kconfig new file mode 100644 index 0000000000..6b84e4741a --- /dev/null +++ b/src/systemcmds/topic_listener/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_TOPIC_LISTENER + bool "topic_listener" + default n + ---help--- + Enable support for topic_listener \ No newline at end of file diff --git a/src/systemcmds/tune_control/Kconfig b/src/systemcmds/tune_control/Kconfig new file mode 100644 index 0000000000..643e35c32b --- /dev/null +++ b/src/systemcmds/tune_control/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_TUNE_CONTROL + bool "tune_control" + default n + ---help--- + Enable support for tune_control \ No newline at end of file diff --git a/src/systemcmds/uorb/Kconfig b/src/systemcmds/uorb/Kconfig new file mode 100644 index 0000000000..6d23f560ea --- /dev/null +++ b/src/systemcmds/uorb/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_UORB + bool "uorb" + default n + ---help--- + Enable support for uorb \ No newline at end of file diff --git a/src/systemcmds/usb_connected/Kconfig b/src/systemcmds/usb_connected/Kconfig new file mode 100644 index 0000000000..5100f2f510 --- /dev/null +++ b/src/systemcmds/usb_connected/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_USB_CONNECTED + bool "usb_connected" + default n + ---help--- + Enable support for usb_connected \ No newline at end of file diff --git a/src/systemcmds/ver/Kconfig b/src/systemcmds/ver/Kconfig new file mode 100644 index 0000000000..53cee474b0 --- /dev/null +++ b/src/systemcmds/ver/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_VER + bool "ver" + default n + ---help--- + Enable support for ver \ No newline at end of file diff --git a/src/systemcmds/work_queue/Kconfig b/src/systemcmds/work_queue/Kconfig new file mode 100644 index 0000000000..89ae7ce114 --- /dev/null +++ b/src/systemcmds/work_queue/Kconfig @@ -0,0 +1,5 @@ +menuconfig SYSTEMCMDS_WORK_QUEUE + bool "work_queue" + default n + ---help--- + Enable support for work_queue \ No newline at end of file