forked from Archive/PX4-Autopilot
98 lines
3.0 KiB
Plaintext
98 lines
3.0 KiB
Plaintext
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
|
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
|
CONFIG_BOARD_ETHERNET=y
|
|
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS6"
|
|
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
|
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
|
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS2"
|
|
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
|
CONFIG_DRIVERS_ADC_ADS1115=y
|
|
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
|
CONFIG_COMMON_BAROMETERS=y
|
|
CONFIG_DRIVERS_BATT_SMBUS=y
|
|
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
|
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
|
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
|
CONFIG_COMMON_DISTANCE_SENSOR=y
|
|
CONFIG_DRIVERS_GPS=y
|
|
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16477=y
|
|
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16497=y
|
|
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
|
CONFIG_DRIVERS_IRLOCK=y
|
|
CONFIG_COMMON_LIGHT=y
|
|
CONFIG_COMMON_MAGNETOMETER=y
|
|
CONFIG_COMMON_OPTICAL_FLOW=y
|
|
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
|
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
|
CONFIG_DRIVERS_PWM_OUT=y
|
|
CONFIG_DRIVERS_RC_INPUT=y
|
|
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
|
CONFIG_COMMON_TELEMETRY=y
|
|
CONFIG_DRIVERS_UAVCAN=y
|
|
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
|
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
|
CONFIG_MODULES_BATTERY_STATUS=y
|
|
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
|
CONFIG_MODULES_COMMANDER=y
|
|
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
|
CONFIG_MODULES_DATAMAN=y
|
|
CONFIG_MODULES_EKF2=y
|
|
CONFIG_MODULES_ESC_BATTERY=y
|
|
CONFIG_MODULES_EVENTS=y
|
|
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
|
CONFIG_MODULES_FW_ATT_CONTROL=y
|
|
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
|
CONFIG_MODULES_FW_POS_CONTROL=y
|
|
CONFIG_MODULES_FW_RATE_CONTROL=y
|
|
CONFIG_MODULES_GIMBAL=y
|
|
CONFIG_MODULES_GYRO_CALIBRATION=y
|
|
CONFIG_MODULES_GYRO_FFT=y
|
|
CONFIG_MODULES_LAND_DETECTOR=y
|
|
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
|
CONFIG_MODULES_LOAD_MON=y
|
|
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
|
|
CONFIG_MODULES_LOGGER=y
|
|
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
|
CONFIG_MODULES_MANUAL_CONTROL=y
|
|
CONFIG_MODULES_MAVLINK=y
|
|
CONFIG_MODULES_MC_ATT_CONTROL=y
|
|
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
|
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
|
CONFIG_MODULES_MC_POS_CONTROL=y
|
|
CONFIG_MODULES_MC_RATE_CONTROL=y
|
|
CONFIG_MODULES_NAVIGATOR=y
|
|
CONFIG_MODULES_RC_UPDATE=y
|
|
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|
CONFIG_MODULES_SENSORS=y
|
|
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
|
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
|
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
|
CONFIG_MODULES_UUV_POS_CONTROL=y
|
|
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
|
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
|
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
|
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
|
CONFIG_SYSTEMCMDS_DMESG=y
|
|
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
|
CONFIG_SYSTEMCMDS_GPIO=y
|
|
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
|
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
|
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
|
CONFIG_SYSTEMCMDS_NETMAN=y
|
|
CONFIG_SYSTEMCMDS_NSHTERM=y
|
|
CONFIG_SYSTEMCMDS_PARAM=y
|
|
CONFIG_SYSTEMCMDS_PERF=y
|
|
CONFIG_SYSTEMCMDS_REBOOT=y
|
|
CONFIG_SYSTEMCMDS_REFLECT=y
|
|
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
|
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
|
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
|
|
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
|
CONFIG_SYSTEMCMDS_TOP=y
|
|
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
|
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
|
CONFIG_SYSTEMCMDS_UORB=y
|
|
CONFIG_SYSTEMCMDS_VER=y
|
|
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
|
CONFIG_EXAMPLES_FAKE_GPS=y
|