forked from Archive/PX4-Autopilot
Initial boardconfig working with FMUK66
This commit is contained in:
parent
4044fbd4a0
commit
7a747b43f6
5
Kconfig
5
Kconfig
|
@ -23,3 +23,8 @@ endmenu
|
||||||
menu "systemcmds"
|
menu "systemcmds"
|
||||||
source src/systemcmds/Kconfig
|
source src/systemcmds/Kconfig
|
||||||
endmenu
|
endmenu
|
||||||
|
|
||||||
|
menu "examples"
|
||||||
|
source src/examples/Kconfig
|
||||||
|
endmenu
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
# Generated by Kconfiglib (https://github.com/ulfalizer/Kconfiglib)
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Platform: nuttx
|
# Platform: nuttx
|
||||||
|
@ -37,6 +36,8 @@
|
||||||
#
|
#
|
||||||
# CONFIG_DRIVERS_ADC_ADS1115 is not set
|
# CONFIG_DRIVERS_ADC_ADS1115 is not set
|
||||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||||
|
# end of ADC
|
||||||
|
|
||||||
CONFIG_DRIVERS_BAROMETER=y
|
CONFIG_DRIVERS_BAROMETER=y
|
||||||
# CONFIG_DRIVERS_BAROMETER_BMP280 is not set
|
# CONFIG_DRIVERS_BAROMETER_BMP280 is not set
|
||||||
# CONFIG_DRIVERS_BAROMETER_BMP388 is not set
|
# CONFIG_DRIVERS_BAROMETER_BMP388 is not set
|
||||||
|
@ -70,6 +71,8 @@ CONFIG_DRIVERS_IMU_FXOS8701CQ=y
|
||||||
# CONFIG_DRIVERS_IMU_L3GD20 is not set
|
# CONFIG_DRIVERS_IMU_L3GD20 is not set
|
||||||
# CONFIG_DRIVERS_IMU_LSM303D is not set
|
# CONFIG_DRIVERS_IMU_LSM303D is not set
|
||||||
# CONFIG_DRIVERS_IMU_ST is not set
|
# CONFIG_DRIVERS_IMU_ST is not set
|
||||||
|
# end of IMU
|
||||||
|
|
||||||
CONFIG_DRIVERS_IRLOCK=y
|
CONFIG_DRIVERS_IRLOCK=y
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -80,110 +83,159 @@ CONFIG_DRIVERS_LIGHTS_BLINKM=y
|
||||||
CONFIG_DRIVERS_LIGHTS_RGBLED=y
|
CONFIG_DRIVERS_LIGHTS_RGBLED=y
|
||||||
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
|
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
|
||||||
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
|
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
|
||||||
|
# end of Lights
|
||||||
|
|
||||||
# CONFIG_DRIVERS_LINUX_PWM_OUT is not set
|
# CONFIG_DRIVERS_LINUX_PWM_OUT is not set
|
||||||
# CONFIG_DRIVERS_MAGNETOMETER is not set
|
CONFIG_DRIVERS_MAGNETOMETER=y
|
||||||
# CONFIG_DRIVERS_OPTICAL_FLOW is not set
|
# CONFIG_DRIVERS_MAGNETOMETER_AKM is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_BOSCH is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_HMC5883 is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_ISENTEK is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_LIS2MDL is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_LSM303AGR is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_LSM9DS1_MAG is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_QMC5883L is not set
|
||||||
|
# CONFIG_DRIVERS_MAGNETOMETER_RM3100 is not set
|
||||||
|
|
||||||
|
#
|
||||||
|
# Optical flow
|
||||||
|
#
|
||||||
|
# CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902 is not set
|
||||||
|
# CONFIG_DRIVERS_OPTICAL_FLOW_PMW3901 is not set
|
||||||
|
CONFIG_DRIVERS_OPTICAL_FLOW_PX4FLOW=y
|
||||||
|
# CONFIG_DRIVERS_OPTICAL_FLOW_THONEFLOW is not set
|
||||||
|
# end of Optical flow
|
||||||
|
|
||||||
# CONFIG_DRIVERS_OSD is not set
|
# CONFIG_DRIVERS_OSD is not set
|
||||||
# CONFIG_DRIVERS_PCA9685 is not set
|
CONFIG_DRIVERS_PCA9685=y
|
||||||
# CONFIG_DRIVERS_PCA9685_PWM_OUT is not set
|
# CONFIG_DRIVERS_PCA9685_PWM_OUT is not set
|
||||||
# CONFIG_DRIVERS_POWER_MONITOR is not set
|
|
||||||
|
#
|
||||||
|
# Power monitor
|
||||||
|
#
|
||||||
|
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||||
|
# CONFIG_DRIVERS_POWER_MONITOR_VOXLPM is not set
|
||||||
|
# end of Power monitor
|
||||||
|
|
||||||
# CONFIG_DRIVERS_PROTOCOL_SPLITTER is not set
|
# CONFIG_DRIVERS_PROTOCOL_SPLITTER is not set
|
||||||
# CONFIG_DRIVERS_PWM_INPUT is not set
|
# CONFIG_DRIVERS_PWM_INPUT is not set
|
||||||
# CONFIG_DRIVERS_PWM_OUT is not set
|
CONFIG_DRIVERS_PWM_OUT=y
|
||||||
# CONFIG_DRIVERS_PWM_OUT_SIM is not set
|
CONFIG_DRIVERS_PWM_OUT_SIM=y
|
||||||
# CONFIG_DRIVERS_PX4IO is not set
|
# CONFIG_DRIVERS_PX4IO is not set
|
||||||
# CONFIG_DRIVERS_QSHELL is not set
|
# CONFIG_DRIVERS_QSHELL is not set
|
||||||
# CONFIG_DRIVERS_RC_INPUT is not set
|
CONFIG_DRIVERS_RC_INPUT=y
|
||||||
# CONFIG_DRIVERS_ROBOCLAW is not set
|
CONFIG_DRIVERS_ROBOCLAW=y
|
||||||
# CONFIG_DRIVERS_RPI_RC_IN is not set
|
# CONFIG_DRIVERS_RPI_RC_IN is not set
|
||||||
# CONFIG_DRIVERS_RPM is not set
|
# CONFIG_DRIVERS_RPM is not set
|
||||||
# CONFIG_DRIVERS_SAFETY_BUTTON is not set
|
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||||
# CONFIG_DRIVERS_SPEKTRUM_RC is not set
|
# CONFIG_DRIVERS_SPEKTRUM_RC is not set
|
||||||
# CONFIG_DRIVERS_TELEMETRY is not set
|
CONFIG_DRIVERS_TELEMETRY=y
|
||||||
# CONFIG_DRIVERS_TEST_PPM is not set
|
# CONFIG_DRIVERS_TEST_PPM is not set
|
||||||
# CONFIG_DRIVERS_TONE_ALARM is not set
|
CONFIG_DRIVERS_TONE_ALARM=y
|
||||||
# CONFIG_DRIVERS_UAVCAN is not set
|
CONFIG_DRIVERS_UAVCAN=y
|
||||||
# CONFIG_DRIVERS_UAVCAN_V1 is not set
|
# CONFIG_DRIVERS_UAVCAN_V1 is not set
|
||||||
|
# end of drivers
|
||||||
|
|
||||||
#
|
#
|
||||||
# modules
|
# modules
|
||||||
#
|
#
|
||||||
# CONFIG_AIRSHIP_ATT_CONTROL is not set
|
# CONFIG_MODULES_AIRSHIP_ATT_CONTROL is not set
|
||||||
# CONFIG_AIRSPEED_SELECTOR is not set
|
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||||
# CONFIG_ANGULAR_VELOCITY_CONTROLLER is not set
|
# CONFIG_MODULES_ANGULAR_VELOCITY_CONTROLLER is not set
|
||||||
# CONFIG_ATTITUDE_ESTIMATOR_Q is not set
|
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||||
# CONFIG_BATTERY_STATUS is not set
|
CONFIG_MODULES_BATTERY_STATUS=y
|
||||||
# CONFIG_CAMERA_FEEDBACK is not set
|
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||||
# CONFIG_COMMANDER is not set
|
CONFIG_MODULES_COMMANDER=y
|
||||||
# CONFIG_CONTROL_ALLOCATOR is not set
|
# CONFIG_MODULES_CONTROL_ALLOCATOR is not set
|
||||||
# CONFIG_DATAMAN is not set
|
CONFIG_MODULES_DATAMAN=y
|
||||||
# CONFIG_EKF2 is not set
|
CONFIG_MODULES_EKF2=y
|
||||||
# CONFIG_ESC_BATTERY is not set
|
# CONFIG_MODULES_ESC_BATTERY is not set
|
||||||
# CONFIG_EVENTS is not set
|
CONFIG_MODULES_EVENTS=y
|
||||||
# CONFIG_FLIGHT_MODE_MANAGER is not set
|
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||||
# CONFIG_FW_ATT_CONTROL is not set
|
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||||
# CONFIG_FW_POS_CONTROL_L1 is not set
|
CONFIG_MODULES_FW_POS_CONTROL_L1=y
|
||||||
# CONFIG_GYRO_FFT is not set
|
CONFIG_MODULES_GYRO_FFT=y
|
||||||
# CONFIG_LAND_DETECTOR is not set
|
CONFIG_MODULES_LAND_DETECTOR=y
|
||||||
# CONFIG_LANDING_TARGET_ESTIMATOR is not set
|
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||||
# CONFIG_LOAD_MON is not set
|
CONFIG_MODULES_LOAD_MON=y
|
||||||
# CONFIG_LOCAL_POSITION_ESTIMATOR is not set
|
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
|
||||||
# CONFIG_LOGGER is not set
|
CONFIG_MODULES_LOGGER=y
|
||||||
# CONFIG_MAVLINK is not set
|
CONFIG_MODULES_MAVLINK=y
|
||||||
# CONFIG_MC_ATT_CONTROL is not set
|
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||||
# CONFIG_MC_HOVER_THRUST_ESTIMATOR is not set
|
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||||
# CONFIG_MC_POS_CONTROL is not set
|
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||||
# CONFIG_MC_RATE_CONTROL is not set
|
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||||
# CONFIG_MICRORTPS_BRIDGE is not set
|
# CONFIG_MODULES_MICRORTPS_BRIDGE is not set
|
||||||
# CONFIG_MUORB is not set
|
# CONFIG_MODULES_MUORB is not set
|
||||||
# CONFIG_NAVIGATOR is not set
|
CONFIG_MODULES_NAVIGATOR=y
|
||||||
# CONFIG_PX4IOFIRMWARE is not set
|
# CONFIG_MODULES_PX4IOFIRMWARE is not set
|
||||||
# CONFIG_RC_UPDATE is not set
|
CONFIG_MODULES_RC_UPDATE=y
|
||||||
# CONFIG_REPLAY is not set
|
# CONFIG_MODULES_REPLAY is not set
|
||||||
# CONFIG_ROVER_POS_CONTROL is not set
|
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||||
# CONFIG_SENSORS is not set
|
CONFIG_MODULES_SENSORS=y
|
||||||
# CONFIG_SIH is not set
|
CONFIG_MODULES_SIH=y
|
||||||
# CONFIG_SIMULATOR is not set
|
# CONFIG_MODULES_SIMULATOR is not set
|
||||||
# CONFIG_TEMPERATURE_COMPENSATION is not set
|
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||||
# CONFIG_UUV_ATT_CONTROL is not set
|
# CONFIG_MODULES_UUV_ATT_CONTROL is not set
|
||||||
# CONFIG_UUV_POS_CONTROL is not set
|
# CONFIG_MODULES_UUV_POS_CONTROL is not set
|
||||||
# CONFIG_VMOUNT is not set
|
CONFIG_MODULES_VMOUNT=y
|
||||||
# CONFIG_VTOL_ATT_CONTROL is not set
|
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||||
|
# end of modules
|
||||||
|
|
||||||
#
|
#
|
||||||
# systemcmds
|
# systemcmds
|
||||||
#
|
#
|
||||||
# CONFIG_BL_UPDATE is not set
|
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||||
# CONFIG_DMESG is not set
|
# CONFIG_SYSTEMCMDS_DMESG is not set
|
||||||
# CONFIG_DUMPFILE is not set
|
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||||
# CONFIG_DYN is not set
|
# CONFIG_SYSTEMCMDS_DYN is not set
|
||||||
# CONFIG_ESC_CALIB is not set
|
CONFIG_SYSTEMCMDS_ESC_CALIB=y
|
||||||
# CONFIG_FAILURE is not set
|
# CONFIG_SYSTEMCMDS_FAILURE is not set
|
||||||
# CONFIG_GPIO is not set
|
# CONFIG_SYSTEMCMDS_GPIO is not set
|
||||||
# CONFIG_HARDFAULT_LOG is not set
|
# CONFIG_SYSTEMCMDS_HARDFAULT_LOG is not set
|
||||||
# CONFIG_I2CDETECT is not set
|
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||||
# CONFIG_LED_CONTROL is not set
|
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||||
# CONFIG_MFT is not set
|
CONFIG_SYSTEMCMDS_MFT=y
|
||||||
# CONFIG_MIXER is not set
|
CONFIG_SYSTEMCMDS_MIXER=y
|
||||||
# CONFIG_MOTOR_RAMP is not set
|
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||||
# CONFIG_MOTOR_TEST is not set
|
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||||
# CONFIG_MTD is not set
|
CONFIG_SYSTEMCMDS_MTD=y
|
||||||
# CONFIG_NETMAN is not set
|
# CONFIG_SYSTEMCMDS_NETMAN is not set
|
||||||
# CONFIG_NSHTERM is not set
|
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||||
# CONFIG_PARAM is not set
|
CONFIG_SYSTEMCMDS_PARAM=y
|
||||||
# CONFIG_PERF is not set
|
CONFIG_SYSTEMCMDS_PERF=y
|
||||||
# CONFIG_PWM is not set
|
CONFIG_SYSTEMCMDS_PWM=y
|
||||||
# CONFIG_REBOOT is not set
|
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||||
# CONFIG_REFLECT is not set
|
CONFIG_SYSTEMCMDS_REFLECT=y
|
||||||
# CONFIG_SD_BENCH is not set
|
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||||
# CONFIG_SERIAL_TEST is not set
|
# CONFIG_SYSTEMCMDS_SERIAL_TEST is not set
|
||||||
# CONFIG_SHUTDOWN is not set
|
# CONFIG_SYSTEMCMDS_SHUTDOWN is not set
|
||||||
# CONFIG_SYSTEM_TIME is not set
|
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||||
# CONFIG_TESTS is not set
|
CONFIG_SYSTEMCMDS_TESTS=y
|
||||||
# CONFIG_TOP is not set
|
CONFIG_SYSTEMCMDS_TOP=y
|
||||||
# CONFIG_TOPIC_LISTENER is not set
|
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||||
# CONFIG_TUNE_CONTROL is not set
|
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||||
# CONFIG_UORB is not set
|
CONFIG_SYSTEMCMDS_UORB=y
|
||||||
# CONFIG_USB_CONNECTED is not set
|
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||||
# CONFIG_VER is not set
|
CONFIG_SYSTEMCMDS_VER=y
|
||||||
# CONFIG_WORK_QUEUE is not set
|
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||||
|
# end of systemcmds
|
||||||
|
|
||||||
|
#
|
||||||
|
# examples
|
||||||
|
#
|
||||||
|
# CONFIG_EXAMPLES_DYN_HELLO is not set
|
||||||
|
CONFIG_EXAMPLES_FAKE_GPS=y
|
||||||
|
# CONFIG_EXAMPLES_FAKE_GYRO is not set
|
||||||
|
# CONFIG_EXAMPLES_FAKE_MAGNETOMETER is not set
|
||||||
|
CONFIG_EXAMPLES_FIXEDWING_CONTROL=y
|
||||||
|
CONFIG_EXAMPLES_HELLO=y
|
||||||
|
CONFIG_EXAMPLES_HWTEST=y
|
||||||
|
# CONFIG_EXAMPLES_MATLAB_CSV_SERIAL is not set
|
||||||
|
CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y
|
||||||
|
CONFIG_EXAMPLES_PX4_SIMPLE_APP=y
|
||||||
|
CONFIG_EXAMPLES_ROVER_STEERING_CONTROL=y
|
||||||
|
CONFIG_EXAMPLES_UUV_EXAMPLE_APP=y
|
||||||
|
CONFIG_EXAMPLES_WORK_ITEM=y
|
||||||
|
# end of examples
|
||||||
|
|
|
@ -10,121 +10,4 @@ px4_add_board(
|
||||||
GPS1:/dev/ttyS3
|
GPS1:/dev/ttyS3
|
||||||
TEL1:/dev/ttyS4
|
TEL1:/dev/ttyS4
|
||||||
TEL2:/dev/ttyS1
|
TEL2:/dev/ttyS1
|
||||||
DRIVERS
|
|
||||||
adc/ads1115
|
|
||||||
adc/board_adc
|
|
||||||
barometer # all available barometer drivers
|
|
||||||
barometer/mpl3115a2
|
|
||||||
batt_smbus
|
|
||||||
camera_capture
|
|
||||||
camera_trigger
|
|
||||||
differential_pressure # all available differential pressure drivers
|
|
||||||
distance_sensor # all available distance sensor drivers
|
|
||||||
distance_sensor/srf05 # Specific driver
|
|
||||||
gps
|
|
||||||
#imu # all available imu drivers
|
|
||||||
imu/fxas21002c
|
|
||||||
imu/fxos8701cq
|
|
||||||
imu/invensense/icm20948 # required for ak09916 mag
|
|
||||||
irlock
|
|
||||||
lights # all available light drivers
|
|
||||||
lights/rgbled_pwm
|
|
||||||
magnetometer # all available magnetometer drivers
|
|
||||||
optical_flow # all available optical flow drivers
|
|
||||||
osd
|
|
||||||
pca9685
|
|
||||||
pca9685_pwm_out
|
|
||||||
power_monitor/ina226
|
|
||||||
#protocol_splitter
|
|
||||||
pwm_out_sim
|
|
||||||
pwm_out
|
|
||||||
rc_input
|
|
||||||
roboclaw
|
|
||||||
rpm
|
|
||||||
safety_button
|
|
||||||
smart_battery/batmon
|
|
||||||
telemetry # all available telemetry drivers
|
|
||||||
tone_alarm
|
|
||||||
uavcan
|
|
||||||
MODULES
|
|
||||||
airspeed_selector
|
|
||||||
attitude_estimator_q
|
|
||||||
battery_status
|
|
||||||
camera_feedback
|
|
||||||
commander
|
|
||||||
dataman
|
|
||||||
ekf2
|
|
||||||
esc_battery
|
|
||||||
events
|
|
||||||
flight_mode_manager
|
|
||||||
fw_att_control
|
|
||||||
fw_pos_control_l1
|
|
||||||
gyro_calibration
|
|
||||||
gyro_fft
|
|
||||||
land_detector
|
|
||||||
landing_target_estimator
|
|
||||||
load_mon
|
|
||||||
local_position_estimator
|
|
||||||
logger
|
|
||||||
mag_bias_estimator
|
|
||||||
mavlink
|
|
||||||
mc_att_control
|
|
||||||
mc_autotune_attitude_control
|
|
||||||
mc_hover_thrust_estimator
|
|
||||||
mc_pos_control
|
|
||||||
mc_rate_control
|
|
||||||
#micrortps_bridge
|
|
||||||
navigator
|
|
||||||
rc_update
|
|
||||||
rover_pos_control
|
|
||||||
sensors
|
|
||||||
sih
|
|
||||||
temperature_compensation
|
|
||||||
#uuv_att_control
|
|
||||||
#uuv_pos_control
|
|
||||||
vmount
|
|
||||||
vtol_att_control
|
|
||||||
SYSTEMCMDS
|
|
||||||
#bl_update
|
|
||||||
#dmesg
|
|
||||||
dumpfile
|
|
||||||
esc_calib
|
|
||||||
#gpio
|
|
||||||
i2cdetect
|
|
||||||
led_control
|
|
||||||
mft
|
|
||||||
mixer
|
|
||||||
motor_ramp
|
|
||||||
motor_test
|
|
||||||
mtd
|
|
||||||
nshterm
|
|
||||||
param
|
|
||||||
perf
|
|
||||||
pwm
|
|
||||||
reboot
|
|
||||||
reflect
|
|
||||||
sd_bench
|
|
||||||
sd_stress
|
|
||||||
serial_test
|
|
||||||
system_time
|
|
||||||
top
|
|
||||||
topic_listener
|
|
||||||
tune_control
|
|
||||||
uorb
|
|
||||||
usb_connected
|
|
||||||
ver
|
|
||||||
work_queue
|
|
||||||
EXAMPLES
|
|
||||||
fake_gps
|
|
||||||
#fake_imu
|
|
||||||
#fake_magnetometer
|
|
||||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
|
||||||
#hello
|
|
||||||
#hwtest # Hardware test
|
|
||||||
#matlab_csv_serial
|
|
||||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
|
||||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
|
||||||
#rover_steering_control # Rover example app
|
|
||||||
#uuv_example_app
|
|
||||||
#work_item
|
|
||||||
)
|
)
|
||||||
|
|
|
@ -1,5 +1,13 @@
|
||||||
set(BOARD_DEFCONFIG ${PX4_BOARD_DIR}/${PX4_BOARD_LABEL}-boardconfig CACHE FILEPATH "path to defconfig" FORCE)
|
set(BOARD_DEFCONFIG ${PX4_BOARD_DIR}/${PX4_BOARD_LABEL}-boardconfig CACHE FILEPATH "path to defconfig" FORCE)
|
||||||
|
|
||||||
|
|
||||||
|
find_program(MENUCONFIG_PATH menuconfig)
|
||||||
|
find_program(GUICONFIG_PATH guiconfig)
|
||||||
|
if(NOT MENUCONFIG_PATH AND NOT GUICONFIG_PATH)
|
||||||
|
message(WARNING "kconfiglib is not installed\n"
|
||||||
|
"please install using \"pip3 install kconfiglib\"\n")
|
||||||
|
endif()
|
||||||
|
|
||||||
set(COMMON_KCONFIG_ENV_SETTINGS
|
set(COMMON_KCONFIG_ENV_SETTINGS
|
||||||
PYTHON_EXECUTABLE=${PYTHON_EXECUTABLE}
|
PYTHON_EXECUTABLE=${PYTHON_EXECUTABLE}
|
||||||
KCONFIG_CONFIG=${BOARD_DEFCONFIG}
|
KCONFIG_CONFIG=${BOARD_DEFCONFIG}
|
||||||
|
@ -17,7 +25,16 @@ set(COMMON_KCONFIG_ENV_SETTINGS
|
||||||
add_custom_target(boardconfig
|
add_custom_target(boardconfig
|
||||||
${CMAKE_COMMAND} -E env
|
${CMAKE_COMMAND} -E env
|
||||||
${COMMON_KCONFIG_ENV_SETTINGS}
|
${COMMON_KCONFIG_ENV_SETTINGS}
|
||||||
${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/tools/menuconfig.py Kconfig
|
${MENUCONFIG_PATH} Kconfig
|
||||||
|
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
|
||||||
|
USES_TERMINAL
|
||||||
|
COMMAND_EXPAND_LISTS
|
||||||
|
)
|
||||||
|
|
||||||
|
add_custom_target(boardguiconfig
|
||||||
|
${CMAKE_COMMAND} -E env
|
||||||
|
${COMMON_KCONFIG_ENV_SETTINGS}
|
||||||
|
${GUICONFIG_PATH} Kconfig
|
||||||
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
|
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
|
||||||
USES_TERMINAL
|
USES_TERMINAL
|
||||||
COMMAND_EXPAND_LISTS
|
COMMAND_EXPAND_LISTS
|
||||||
|
@ -79,4 +96,40 @@ foreach(NameAndValue ${ConfigContents})
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
# Find variable name
|
||||||
|
string(REGEX MATCH "^CONFIG_MODULES[^=]+" Modules ${NameAndValue})
|
||||||
|
|
||||||
|
if(Modules)
|
||||||
|
# Find the value
|
||||||
|
string(REPLACE "${Name}=" "" Value ${NameAndValue})
|
||||||
|
string(REPLACE "CONFIG_MODULES_" "" module ${Name})
|
||||||
|
string(TOLOWER ${module} module)
|
||||||
|
|
||||||
|
list(APPEND config_module_list modules/${module})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Find variable name
|
||||||
|
string(REGEX MATCH "^CONFIG_SYSTEMCMDS[^=]+" Systemcmds ${NameAndValue})
|
||||||
|
|
||||||
|
if(Systemcmds)
|
||||||
|
# Find the value
|
||||||
|
string(REPLACE "${Name}=" "" Value ${NameAndValue})
|
||||||
|
string(REPLACE "CONFIG_SYSTEMCMDS_" "" systemcmd ${Name})
|
||||||
|
string(TOLOWER ${systemcmd} systemcmd)
|
||||||
|
|
||||||
|
list(APPEND config_module_list systemcmds/${systemcmd})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# Find variable name
|
||||||
|
string(REGEX MATCH "^CONFIG_EXAMPLES[^=]+" Examples ${NameAndValue})
|
||||||
|
|
||||||
|
if(Examples)
|
||||||
|
# Find the value
|
||||||
|
string(REPLACE "${Name}=" "" Value ${NameAndValue})
|
||||||
|
string(REPLACE "CONFIG_EXAMPLES_" "" example ${Name})
|
||||||
|
string(TOLOWER ${example} example)
|
||||||
|
|
||||||
|
list(APPEND config_module_list examples/${example})
|
||||||
|
endif()
|
||||||
endforeach()
|
endforeach()
|
||||||
|
|
|
@ -93,13 +93,14 @@ menuconfig DRIVERS_MAGNETOMETER
|
||||||
---help---
|
---help---
|
||||||
Enable support for all available magnetometer drivers
|
Enable support for all available magnetometer drivers
|
||||||
|
|
||||||
menuconfig DRIVERS_OPTICAL_FLOW
|
if DRIVERS_MAGNETOMETER
|
||||||
bool "Optical flow"
|
source src/drivers/magnetometer/Kconfig
|
||||||
default n
|
endif #DRIVERS_MAGNETOMETER
|
||||||
---help---
|
|
||||||
Enable support for all available optical flow drivers
|
menu "Optical flow"
|
||||||
|
source src/drivers/optical_flow/Kconfig
|
||||||
|
endmenu
|
||||||
|
|
||||||
menuconfig DRIVERS_OSD
|
menuconfig DRIVERS_OSD
|
||||||
bool "osd"
|
bool "osd"
|
||||||
default n
|
default n
|
||||||
|
@ -117,12 +118,10 @@ menuconfig DRIVERS_PCA9685_PWM_OUT
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for pca9685 pwm out
|
Enable support for pca9685 pwm out
|
||||||
|
|
||||||
menuconfig DRIVERS_POWER_MONITOR
|
menu "Power monitor"
|
||||||
bool "power monitor"
|
source src/drivers/power_monitor/Kconfig
|
||||||
default n
|
endmenu
|
||||||
---help---
|
|
||||||
Enable support for power monitor
|
|
||||||
|
|
||||||
menuconfig DRIVERS_PROTOCOL_SPLITTER
|
menuconfig DRIVERS_PROTOCOL_SPLITTER
|
||||||
bool "protocol splitter"
|
bool "protocol splitter"
|
||||||
|
|
|
@ -0,0 +1,59 @@
|
||||||
|
menuconfig DRIVERS_MAGNETOMETER_AKM
|
||||||
|
bool "akm"
|
||||||
|
default n
|
||||||
|
---help---
|
||||||
|
Enable support for akm
|
||||||
|
|
||||||
|
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
|
|
@ -0,0 +1,23 @@
|
||||||
|
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
|
|
@ -0,0 +1,11 @@
|
||||||
|
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
|
|
@ -0,0 +1,77 @@
|
||||||
|
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
|
|
@ -1,245 +1,245 @@
|
||||||
menuconfig AIRSHIP_ATT_CONTROL
|
menuconfig MODULES_AIRSHIP_ATT_CONTROL
|
||||||
bool "airship att control Support"
|
bool "airship att control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for airship att control
|
Enable support for airship att control
|
||||||
|
|
||||||
menuconfig AIRSPEED_SELECTOR
|
menuconfig MODULES_AIRSPEED_SELECTOR
|
||||||
bool "airspeed selector Support"
|
bool "airspeed selector"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for airspeed selector
|
Enable support for airspeed selector
|
||||||
|
|
||||||
menuconfig ANGULAR_VELOCITY_CONTROLLER
|
menuconfig MODULES_ANGULAR_VELOCITY_CONTROLLER
|
||||||
bool "angular velocity controller Support"
|
bool "angular velocity controller"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for angular velocity controller
|
Enable support for angular velocity controller
|
||||||
|
|
||||||
menuconfig ATTITUDE_ESTIMATOR_Q
|
menuconfig MODULES_ATTITUDE_ESTIMATOR_Q
|
||||||
bool "attitude estimator q Support"
|
bool "attitude estimator q"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for attitude estimator q
|
Enable support for attitude estimator q
|
||||||
|
|
||||||
menuconfig BATTERY_STATUS
|
menuconfig MODULES_BATTERY_STATUS
|
||||||
bool "battery status Support"
|
bool "battery status"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for battery status
|
Enable support for battery status
|
||||||
|
|
||||||
menuconfig CAMERA_FEEDBACK
|
menuconfig MODULES_CAMERA_FEEDBACK
|
||||||
bool "camera feedback Support"
|
bool "camera feedback"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for camera feedback
|
Enable support for camera feedback
|
||||||
|
|
||||||
menuconfig COMMANDER
|
menuconfig MODULES_COMMANDER
|
||||||
bool "commander Support"
|
bool "commander"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for commander
|
Enable support for commander
|
||||||
|
|
||||||
menuconfig CONTROL_ALLOCATOR
|
menuconfig MODULES_CONTROL_ALLOCATOR
|
||||||
bool "control allocator Support"
|
bool "control allocator"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for control allocator
|
Enable support for control allocator
|
||||||
|
|
||||||
menuconfig DATAMAN
|
menuconfig MODULES_DATAMAN
|
||||||
bool "dataman Support"
|
bool "dataman"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for dataman
|
Enable support for dataman
|
||||||
|
|
||||||
menuconfig EKF2
|
menuconfig MODULES_EKF2
|
||||||
bool "ekf2 Support"
|
bool "ekf2"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for ekf2
|
Enable support for ekf2
|
||||||
|
|
||||||
menuconfig ESC_BATTERY
|
menuconfig MODULES_ESC_BATTERY
|
||||||
bool "esc battery Support"
|
bool "esc battery"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for esc battery
|
Enable support for esc battery
|
||||||
|
|
||||||
menuconfig EVENTS
|
menuconfig MODULES_EVENTS
|
||||||
bool "events Support"
|
bool "events"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for events
|
Enable support for events
|
||||||
|
|
||||||
menuconfig FLIGHT_MODE_MANAGER
|
menuconfig MODULES_FLIGHT_MODE_MANAGER
|
||||||
bool "flight mode manager Support"
|
bool "flight mode manager"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for flight mode manager
|
Enable support for flight mode manager
|
||||||
|
|
||||||
menuconfig FW_ATT_CONTROL
|
menuconfig MODULES_FW_ATT_CONTROL
|
||||||
bool "fw att control Support"
|
bool "fw att control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for fw att control
|
Enable support for fw att control
|
||||||
|
|
||||||
menuconfig FW_POS_CONTROL_L1
|
menuconfig MODULES_FW_POS_CONTROL_L1
|
||||||
bool "fw pos control l1 Support"
|
bool "fw pos control l1"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for fw pos control l1
|
Enable support for fw pos control l1
|
||||||
|
|
||||||
menuconfig GYRO_FFT
|
menuconfig MODULES_GYRO_FFT
|
||||||
bool "gyro fft Support"
|
bool "gyro fft"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for gyro fft
|
Enable support for gyro fft
|
||||||
|
|
||||||
menuconfig LAND_DETECTOR
|
menuconfig MODULES_LAND_DETECTOR
|
||||||
bool "land detector Support"
|
bool "land detector"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for land detector
|
Enable support for land detector
|
||||||
|
|
||||||
menuconfig LANDING_TARGET_ESTIMATOR
|
menuconfig MODULES_LANDING_TARGET_ESTIMATOR
|
||||||
bool "landing target estimator Support"
|
bool "landing target estimator"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for landing target estimator
|
Enable support for landing target estimator
|
||||||
|
|
||||||
menuconfig LOAD_MON
|
menuconfig MODULES_LOAD_MON
|
||||||
bool "load mon Support"
|
bool "load mon"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for load mon
|
Enable support for load mon
|
||||||
|
|
||||||
menuconfig LOCAL_POSITION_ESTIMATOR
|
menuconfig MODULES_LOCAL_POSITION_ESTIMATOR
|
||||||
bool "local position estimator Support"
|
bool "local position estimator"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for local position estimator
|
Enable support for local position estimator
|
||||||
|
|
||||||
menuconfig LOGGER
|
menuconfig MODULES_LOGGER
|
||||||
bool "logger Support"
|
bool "logger"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for logger
|
Enable support for logger
|
||||||
|
|
||||||
menuconfig MAVLINK
|
menuconfig MODULES_MAVLINK
|
||||||
bool "mavlink Support"
|
bool "mavlink"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mavlink
|
Enable support for mavlink
|
||||||
|
|
||||||
menuconfig MC_ATT_CONTROL
|
menuconfig MODULES_MC_ATT_CONTROL
|
||||||
bool "mc att control Support"
|
bool "mc att control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mc att control
|
Enable support for mc att control
|
||||||
|
|
||||||
menuconfig MC_HOVER_THRUST_ESTIMATOR
|
menuconfig MODULES_MC_HOVER_THRUST_ESTIMATOR
|
||||||
bool "mc hover thrust estimator Support"
|
bool "mc hover thrust estimator"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mc hover thrust estimator
|
Enable support for mc hover thrust estimator
|
||||||
|
|
||||||
menuconfig MC_POS_CONTROL
|
menuconfig MODULES_MC_POS_CONTROL
|
||||||
bool "mc pos control Support"
|
bool "mc pos control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mc pos control
|
Enable support for mc pos control
|
||||||
|
|
||||||
menuconfig MC_RATE_CONTROL
|
menuconfig MODULES_MC_RATE_CONTROL
|
||||||
bool "mc rate control Support"
|
bool "mc rate control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mc rate control
|
Enable support for mc rate control
|
||||||
|
|
||||||
menuconfig MICRORTPS_BRIDGE
|
menuconfig MODULES_MICRORTPS_BRIDGE
|
||||||
bool "micrortps bridge Support"
|
bool "micrortps bridge"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for micrortps bridge
|
Enable support for micrortps bridge
|
||||||
|
|
||||||
menuconfig MUORB
|
menuconfig MODULES_MUORB
|
||||||
bool "muorb Support"
|
bool "muorb"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for muorb
|
Enable support for muorb
|
||||||
|
|
||||||
menuconfig NAVIGATOR
|
menuconfig MODULES_NAVIGATOR
|
||||||
bool "navigator Support"
|
bool "navigator"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for navigator
|
Enable support for navigator
|
||||||
|
|
||||||
menuconfig PX4IOFIRMWARE
|
menuconfig MODULES_PX4IOFIRMWARE
|
||||||
bool "px4iofirmware Support"
|
bool "px4iofirmware"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for px4iofirmware
|
Enable support for px4iofirmware
|
||||||
|
|
||||||
menuconfig RC_UPDATE
|
menuconfig MODULES_RC_UPDATE
|
||||||
bool "rc update Support"
|
bool "rc update"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for rc update
|
Enable support for rc update
|
||||||
|
|
||||||
menuconfig REPLAY
|
menuconfig MODULES_REPLAY
|
||||||
bool "replay Support"
|
bool "replay"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for replay
|
Enable support for replay
|
||||||
|
|
||||||
menuconfig ROVER_POS_CONTROL
|
menuconfig MODULES_ROVER_POS_CONTROL
|
||||||
bool "rover pos control Support"
|
bool "rover pos control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for rover pos control
|
Enable support for rover pos control
|
||||||
|
|
||||||
menuconfig SENSORS
|
menuconfig MODULES_SENSORS
|
||||||
bool "sensors Support"
|
bool "sensors"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for sensors
|
Enable support for sensors
|
||||||
|
|
||||||
menuconfig SIH
|
menuconfig MODULES_SIH
|
||||||
bool "sih Support"
|
bool "sih"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for sih
|
Enable support for sih
|
||||||
|
|
||||||
menuconfig SIMULATOR
|
menuconfig MODULES_SIMULATOR
|
||||||
bool "simulator Support"
|
bool "simulator"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for simulator
|
Enable support for simulator
|
||||||
|
|
||||||
menuconfig TEMPERATURE_COMPENSATION
|
menuconfig MODULES_TEMPERATURE_COMPENSATION
|
||||||
bool "temperature compensation Support"
|
bool "temperature compensation"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for temperature compensation
|
Enable support for temperature compensation
|
||||||
|
|
||||||
menuconfig UUV_ATT_CONTROL
|
menuconfig MODULES_UUV_ATT_CONTROL
|
||||||
bool "uuv att control Support"
|
bool "uuv att control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for uuv att control
|
Enable support for uuv att control
|
||||||
|
|
||||||
menuconfig UUV_POS_CONTROL
|
menuconfig MODULES_UUV_POS_CONTROL
|
||||||
bool "uuv pos control Support"
|
bool "uuv pos control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for uuv pos control
|
Enable support for uuv pos control
|
||||||
|
|
||||||
menuconfig VMOUNT
|
menuconfig MODULES_VMOUNT
|
||||||
bool "vmount Support"
|
bool "vmount"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for vmount
|
Enable support for vmount
|
||||||
|
|
||||||
menuconfig VTOL_ATT_CONTROL
|
menuconfig MODULES_VTOL_ATT_CONTROL
|
||||||
bool "vtol att control Support"
|
bool "vtol att control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for vtol att control
|
Enable support for vtol att control
|
||||||
|
|
|
@ -1,203 +1,203 @@
|
||||||
menuconfig BL_UPDATE
|
menuconfig SYSTEMCMDS_BL_UPDATE
|
||||||
bool "bl update Support"
|
bool "bl update"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for bl update
|
Enable support for bl update
|
||||||
|
|
||||||
menuconfig DMESG
|
menuconfig SYSTEMCMDS_DMESG
|
||||||
bool "dmesg Support"
|
bool "dmesg"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for dmesg
|
Enable support for dmesg
|
||||||
|
|
||||||
menuconfig DUMPFILE
|
menuconfig SYSTEMCMDS_DUMPFILE
|
||||||
bool "dumpfile Support"
|
bool "dumpfile"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for dumpfile
|
Enable support for dumpfile
|
||||||
|
|
||||||
menuconfig DYN
|
menuconfig SYSTEMCMDS_DYN
|
||||||
bool "dyn Support"
|
bool "dyn"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for dyn
|
Enable support for dyn
|
||||||
|
|
||||||
menuconfig ESC_CALIB
|
menuconfig SYSTEMCMDS_ESC_CALIB
|
||||||
bool "esc calib Support"
|
bool "esc calib"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for esc calib
|
Enable support for esc calib
|
||||||
|
|
||||||
menuconfig FAILURE
|
menuconfig SYSTEMCMDS_FAILURE
|
||||||
bool "failure Support"
|
bool "failure"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for failure
|
Enable support for failure
|
||||||
|
|
||||||
menuconfig GPIO
|
menuconfig SYSTEMCMDS_GPIO
|
||||||
bool "gpio Support"
|
bool "gpio"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for gpio
|
Enable support for gpio
|
||||||
|
|
||||||
menuconfig HARDFAULT_LOG
|
menuconfig SYSTEMCMDS_HARDFAULT_LOG
|
||||||
bool "hardfault log Support"
|
bool "hardfault log"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for hardfault log
|
Enable support for hardfault log
|
||||||
|
|
||||||
menuconfig I2CDETECT
|
menuconfig SYSTEMCMDS_I2CDETECT
|
||||||
bool "i2cdetect Support"
|
bool "i2cdetect"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for i2cdetect
|
Enable support for i2cdetect
|
||||||
|
|
||||||
menuconfig LED_CONTROL
|
menuconfig SYSTEMCMDS_LED_CONTROL
|
||||||
bool "led control Support"
|
bool "led control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for led control
|
Enable support for led control
|
||||||
|
|
||||||
menuconfig MFT
|
menuconfig SYSTEMCMDS_MFT
|
||||||
bool "mft Support"
|
bool "mft"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mft
|
Enable support for mft
|
||||||
|
|
||||||
menuconfig MIXER
|
menuconfig SYSTEMCMDS_MIXER
|
||||||
bool "mixer Support"
|
bool "mixer"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mixer
|
Enable support for mixer
|
||||||
|
|
||||||
menuconfig MOTOR_RAMP
|
menuconfig SYSTEMCMDS_MOTOR_RAMP
|
||||||
bool "motor ramp Support"
|
bool "motor ramp"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for motor ramp
|
Enable support for motor ramp
|
||||||
|
|
||||||
menuconfig MOTOR_TEST
|
menuconfig SYSTEMCMDS_MOTOR_TEST
|
||||||
bool "motor test Support"
|
bool "motor test"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for motor test
|
Enable support for motor test
|
||||||
|
|
||||||
menuconfig MTD
|
menuconfig SYSTEMCMDS_MTD
|
||||||
bool "mtd Support"
|
bool "mtd"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for mtd
|
Enable support for mtd
|
||||||
|
|
||||||
menuconfig NETMAN
|
menuconfig SYSTEMCMDS_NETMAN
|
||||||
bool "netman Support"
|
bool "netman"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for netman
|
Enable support for netman
|
||||||
|
|
||||||
menuconfig NSHTERM
|
menuconfig SYSTEMCMDS_NSHTERM
|
||||||
bool "nshterm Support"
|
bool "nshterm"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for nshterm
|
Enable support for nshterm
|
||||||
|
|
||||||
menuconfig PARAM
|
menuconfig SYSTEMCMDS_PARAM
|
||||||
bool "param Support"
|
bool "param"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for param
|
Enable support for param
|
||||||
|
|
||||||
menuconfig PERF
|
menuconfig SYSTEMCMDS_PERF
|
||||||
bool "perf Support"
|
bool "perf"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for perf
|
Enable support for perf
|
||||||
|
|
||||||
menuconfig PWM
|
menuconfig SYSTEMCMDS_PWM
|
||||||
bool "pwm Support"
|
bool "pwm"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for pwm
|
Enable support for pwm
|
||||||
|
|
||||||
menuconfig REBOOT
|
menuconfig SYSTEMCMDS_REBOOT
|
||||||
bool "reboot Support"
|
bool "reboot"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for reboot
|
Enable support for reboot
|
||||||
|
|
||||||
menuconfig REFLECT
|
menuconfig SYSTEMCMDS_REFLECT
|
||||||
bool "reflect Support"
|
bool "reflect"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for reflect
|
Enable support for reflect
|
||||||
|
|
||||||
menuconfig SD_BENCH
|
menuconfig SYSTEMCMDS_SD_BENCH
|
||||||
bool "sd bench Support"
|
bool "sd bench"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for sd bench
|
Enable support for sd bench
|
||||||
|
|
||||||
menuconfig SERIAL_TEST
|
menuconfig SYSTEMCMDS_SERIAL_TEST
|
||||||
bool "serial test Support"
|
bool "serial test"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for serial test
|
Enable support for serial test
|
||||||
|
|
||||||
menuconfig SHUTDOWN
|
menuconfig SYSTEMCMDS_SHUTDOWN
|
||||||
bool "shutdown Support"
|
bool "shutdown"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for shutdown
|
Enable support for shutdown
|
||||||
|
|
||||||
menuconfig SYSTEM_TIME
|
menuconfig SYSTEMCMDS_SYSTEM_TIME
|
||||||
bool "system time Support"
|
bool "system time"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for system time
|
Enable support for system time
|
||||||
|
|
||||||
menuconfig TESTS
|
menuconfig SYSTEMCMDS_TESTS
|
||||||
bool "tests Support"
|
bool "tests"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for tests
|
Enable support for tests
|
||||||
|
|
||||||
menuconfig TOP
|
menuconfig SYSTEMCMDS_TOP
|
||||||
bool "top Support"
|
bool "top"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for top
|
Enable support for top
|
||||||
|
|
||||||
menuconfig TOPIC_LISTENER
|
menuconfig SYSTEMCMDS_TOPIC_LISTENER
|
||||||
bool "topic listener Support"
|
bool "topic listener"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for topic listener
|
Enable support for topic listener
|
||||||
|
|
||||||
menuconfig TUNE_CONTROL
|
menuconfig SYSTEMCMDS_TUNE_CONTROL
|
||||||
bool "tune control Support"
|
bool "tune control"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for tune control
|
Enable support for tune control
|
||||||
|
|
||||||
menuconfig UORB
|
menuconfig SYSTEMCMDS_UORB
|
||||||
bool "uorb Support"
|
bool "uorb"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for uorb
|
Enable support for uorb
|
||||||
|
|
||||||
menuconfig USB_CONNECTED
|
menuconfig SYSTEMCMDS_USB_CONNECTED
|
||||||
bool "usb connected Support"
|
bool "usb connected"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for usb connected
|
Enable support for usb connected
|
||||||
|
|
||||||
menuconfig VER
|
menuconfig SYSTEMCMDS_VER
|
||||||
bool "ver Support"
|
bool "ver"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for ver
|
Enable support for ver
|
||||||
|
|
||||||
menuconfig WORK_QUEUE
|
menuconfig SYSTEMCMDS_WORK_QUEUE
|
||||||
bool "work queue Support"
|
bool "work queue"
|
||||||
default n
|
default n
|
||||||
---help---
|
---help---
|
||||||
Enable support for work queue
|
Enable support for work queue
|
||||||
|
|
Loading…
Reference in New Issue