2021-08-18 04:45:58 -03:00
|
|
|
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
|
|
|
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
|
2021-08-17 13:41:59 -03:00
|
|
|
CONFIG_BOARD_CONSTRAINED_FLASH=y
|
|
|
|
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
2021-08-17 14:18:29 -03:00
|
|
|
CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing"
|
2021-08-17 13:41:59 -03:00
|
|
|
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
2021-08-18 11:49:25 -03:00
|
|
|
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y
|
2021-08-17 13:41:59 -03:00
|
|
|
CONFIG_DRIVERS_GPS=y
|
2021-08-20 07:54:04 -03:00
|
|
|
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
|
|
|
CONFIG_DRIVERS_OPTICAL_FLOW_PMW3901=y
|
2021-08-17 13:41:59 -03:00
|
|
|
CONFIG_DRIVERS_PWM_OUT=y
|
|
|
|
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
|
|
|
CONFIG_MODULES_COMMANDER=y
|
|
|
|
CONFIG_MODULES_DATAMAN=y
|
|
|
|
CONFIG_MODULES_EKF2=y
|
|
|
|
CONFIG_MODULES_EVENTS=y
|
|
|
|
CONFIG_MODULES_FLIGHT_MODE_MANAGER=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_MAVLINK=y
|
|
|
|
CONFIG_MODULES_MC_ATT_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_SENSORS=y
|
|
|
|
CONFIG_SYSTEMCMDS_DMESG=y
|
|
|
|
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
|
|
|
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
|
|
|
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
|
|
|
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
|
|
|
CONFIG_SYSTEMCMDS_MIXER=y
|
|
|
|
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
|
|
|
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
|
|
|
CONFIG_SYSTEMCMDS_MTD=y
|
|
|
|
CONFIG_SYSTEMCMDS_NSHTERM=y
|
|
|
|
CONFIG_SYSTEMCMDS_PARAM=y
|
|
|
|
CONFIG_SYSTEMCMDS_PERF=y
|
|
|
|
CONFIG_SYSTEMCMDS_PWM=y
|
|
|
|
CONFIG_SYSTEMCMDS_REBOOT=y
|
|
|
|
CONFIG_SYSTEMCMDS_REFLECT=y
|
|
|
|
CONFIG_SYSTEMCMDS_SD_BENCH=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_USB_CONNECTED=y
|
|
|
|
CONFIG_SYSTEMCMDS_VER=y
|
|
|
|
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|