include(nuttx/px4_impl_nuttx) px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT tap_common) set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) set(target_definitions MEMORY_CONSTRAINED_SYSTEM) set(config_module_list # # Board support modules # drivers/device drivers/stm32 drivers/stm32/adc drivers/stm32/tone_alarm drivers/led drivers/px4fmu drivers/boards/tap-v1 drivers/rgbled_pwm drivers/tap_esc drivers/mpu6000 drivers/ms5611 drivers/hmc5883 drivers/gps drivers/airspeed drivers/meas_airspeed modules/sensors drivers/vmount # # System commands # systemcmds/bl_update systemcmds/led_control systemcmds/mixer systemcmds/param systemcmds/perf systemcmds/pwm systemcmds/hardfault_log systemcmds/motor_test systemcmds/reboot systemcmds/top systemcmds/config systemcmds/nshterm systemcmds/mtd systemcmds/dumpfile systemcmds/ver systemcmds/topic_listener # # General system control # modules/commander modules/load_mon modules/navigator modules/mavlink modules/land_detector # # Estimation modules (EKF/ SO3 / other filters) # modules/ekf2 # # Vehicle Control # modules/fw_pos_control_l1 modules/fw_att_control modules/mc_att_control modules/mc_pos_control modules/vtol_att_control # # Logging # modules/logger # # Library modules # modules/param modules/systemlib modules/systemlib/mixer modules/uORB modules/dataman # # Libraries # lib/controllib lib/mathlib lib/mathlib/math/filter lib/ecl lib/external_lgpl lib/geo lib/geo_lookup lib/conversion lib/launchdetection lib/led lib/rc lib/runway_takeoff lib/tailsitter_recovery lib/terrain_estimation lib/version lib/DriverFramework/framework platforms/nuttx # had to add for cmake, not sure why wasn't in original config platforms/common platforms/nuttx/px4_layer ) set(config_extra_builtin_cmds serdis sercon ) set(config_io_board ) set(config_extra_libs ) set(config_io_extra_libs ) add_custom_target(sercon) set_target_properties(sercon PROPERTIES PRIORITY "SCHED_PRIORITY_DEFAULT" MAIN "sercon" STACK_MAIN "2048") add_custom_target(serdis) set_target_properties(serdis PROPERTIES PRIORITY "SCHED_PRIORITY_DEFAULT" MAIN "serdis" STACK_MAIN "2048")