You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
231 lines
3.7 KiB
231 lines
3.7 KiB
include(nuttx/px4_impl_nuttx) |
|
|
|
px4_nuttx_configure(HWCLASS m7 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common) |
|
|
|
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
|
|
|
set(config_uavcan_num_ifaces 2) |
|
|
|
set(config_module_list |
|
# |
|
# Board support modules |
|
# |
|
drivers/airspeed |
|
drivers/blinkm |
|
drivers/bma180 |
|
drivers/bmi160 |
|
drivers/bmp280 |
|
drivers/boards/px4fmu-v5 |
|
drivers/bst |
|
drivers/camera_trigger |
|
drivers/device |
|
drivers/ets_airspeed |
|
drivers/frsky_telemetry |
|
drivers/gps |
|
drivers/hmc5883 |
|
drivers/hott |
|
drivers/hott/hott_sensors |
|
drivers/hott/hott_telemetry |
|
drivers/iridiumsbd |
|
drivers/led |
|
drivers/lis3mdl |
|
drivers/ll40ls |
|
drivers/mb12xx |
|
drivers/meas_airspeed |
|
drivers/mkblctrl |
|
drivers/mpu6000 |
|
drivers/mpu9250 |
|
drivers/ms5611 |
|
drivers/oreoled |
|
drivers/pwm_input |
|
drivers/pwm_out_sim |
|
drivers/px4flow |
|
drivers/px4fmu |
|
drivers/rgbled_pwm |
|
drivers/sf0x |
|
drivers/sf1xx |
|
drivers/snapdragon_rc_pwm |
|
drivers/srf02 |
|
drivers/stm32 |
|
drivers/stm32/adc |
|
drivers/stm32/tone_alarm |
|
drivers/tap_esc |
|
drivers/trone |
|
drivers/vmount |
|
modules/sensors |
|
|
|
# |
|
# System commands |
|
# |
|
systemcmds/bl_update |
|
systemcmds/config |
|
systemcmds/dumpfile |
|
systemcmds/esc_calib |
|
systemcmds/hardfault_log |
|
systemcmds/led_control |
|
systemcmds/mixer |
|
systemcmds/motor_ramp |
|
systemcmds/mtd |
|
systemcmds/nshterm |
|
systemcmds/param |
|
systemcmds/perf |
|
systemcmds/pwm |
|
systemcmds/reboot |
|
systemcmds/sd_bench |
|
systemcmds/top |
|
systemcmds/topic_listener |
|
systemcmds/ver |
|
|
|
# |
|
# Testing |
|
# |
|
drivers/sf0x/sf0x_tests |
|
drivers/test_ppm |
|
#lib/rc/rc_tests |
|
modules/commander/commander_tests |
|
modules/controllib_test |
|
modules/mavlink/mavlink_tests |
|
modules/mc_pos_control/mc_pos_control_tests |
|
modules/unit_test |
|
modules/uORB/uORB_tests |
|
systemcmds/tests |
|
|
|
# |
|
# General system control |
|
# |
|
modules/commander |
|
modules/events |
|
modules/gpio_led |
|
modules/land_detector |
|
modules/load_mon |
|
modules/mavlink |
|
modules/navigator |
|
modules/uavcan |
|
|
|
# |
|
# Estimation modules |
|
# |
|
modules/attitude_estimator_q |
|
modules/ekf2 |
|
modules/local_position_estimator |
|
modules/position_estimator_inav |
|
|
|
# |
|
# Vehicle Control |
|
# |
|
modules/fw_att_control |
|
modules/fw_pos_control_l1 |
|
modules/mc_att_control |
|
modules/mc_pos_control |
|
modules/vtol_att_control |
|
|
|
# |
|
# Logging |
|
# |
|
modules/logger |
|
modules/sdlog2 |
|
|
|
# |
|
# Library modules |
|
# |
|
modules/dataman |
|
modules/param |
|
modules/systemlib |
|
modules/systemlib/mixer |
|
modules/uORB |
|
|
|
# |
|
# Libraries |
|
# |
|
lib/controllib |
|
lib/conversion |
|
lib/DriverFramework/framework |
|
lib/ecl |
|
lib/external_lgpl |
|
lib/geo |
|
lib/geo_lookup |
|
lib/launchdetection |
|
lib/led |
|
lib/mathlib |
|
lib/mathlib/math/filter |
|
lib/rc |
|
lib/runway_takeoff |
|
lib/tailsitter_recovery |
|
lib/terrain_estimation |
|
lib/version |
|
|
|
# |
|
# Platform |
|
# |
|
platforms/common |
|
platforms/nuttx |
|
platforms/nuttx/px4_layer |
|
|
|
# |
|
# OBC challenge |
|
# |
|
#modules/bottle_drop |
|
|
|
# |
|
# Rover apps |
|
# |
|
#examples/rover_steering_control |
|
|
|
# |
|
# Segway |
|
# |
|
#examples/segway |
|
|
|
# |
|
# Demo apps |
|
# |
|
|
|
# Tutorial code from |
|
# https://px4.io/dev/px4_simple_app |
|
#examples/px4_simple_app |
|
|
|
# Tutorial code from |
|
# https://px4.io/dev/daemon |
|
#examples/px4_daemon_app |
|
|
|
# Tutorial code from |
|
# https://px4.io/dev/debug_values |
|
#examples/px4_mavlink_debug |
|
|
|
# Tutorial code from |
|
# https://px4.io/dev/example_fixedwing_control |
|
#examples/fixedwing_control |
|
|
|
# Hardware test |
|
#examples/hwtest |
|
|
|
# EKF |
|
#examples/ekf_att_pos_estimator |
|
) |
|
|
|
set(config_extra_builtin_cmds |
|
serdis |
|
sercon |
|
) |
|
|
|
set(config_extra_libs |
|
uavcan |
|
uavcan_stm32_driver |
|
) |
|
|
|
set(config_io_extra_libs |
|
) |
|
|
|
add_custom_target(sercon) |
|
set_target_properties(sercon PROPERTIES |
|
PRIORITY "SCHED_PRIORITY_DEFAULT" |
|
MAIN "sercon" |
|
STACK_MAIN "2048" |
|
COMPILE_FLAGS "-Os") |
|
|
|
add_custom_target(serdis) |
|
set_target_properties(serdis PROPERTIES |
|
PRIORITY "SCHED_PRIORITY_DEFAULT" |
|
MAIN "serdis" |
|
STACK_MAIN "2048" |
|
COMPILE_FLAGS "-Os")
|
|
|