mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
The replay functionality was broken with lockstep. This is an interim fix for the replay functionality. In the longer term it would be nice to leverage the lockstep speedup for the replay.
106 lines
2.2 KiB
CMake
106 lines
2.2 KiB
CMake
|
|
px4_add_board(
|
|
PLATFORM posix
|
|
VENDOR px4
|
|
MODEL sitl
|
|
LABEL default
|
|
TESTING
|
|
|
|
DRIVERS
|
|
#barometer # all available barometer drivers
|
|
batt_smbus
|
|
camera_trigger
|
|
differential_pressure # all available differential pressure drivers
|
|
distance_sensor # all available distance sensor drivers
|
|
gps
|
|
#imu # all available imu drivers
|
|
#magnetometer # all available magnetometer drivers
|
|
pwm_out_sim
|
|
#telemetry # all available telemetry drivers
|
|
sim/tone_alarm
|
|
tone_alarm
|
|
#uavcan
|
|
|
|
MODULES
|
|
attitude_estimator_q
|
|
camera_feedback
|
|
commander
|
|
dataman
|
|
ekf2
|
|
events
|
|
fw_att_control
|
|
fw_pos_control_l1
|
|
gnd_att_control
|
|
gnd_pos_control
|
|
land_detector
|
|
landing_target_estimator
|
|
load_mon
|
|
local_position_estimator
|
|
logger
|
|
mavlink
|
|
mc_att_control
|
|
mc_pos_control
|
|
navigator
|
|
replay
|
|
sensors
|
|
simulator
|
|
vmount
|
|
vtol_att_control
|
|
wind_estimator
|
|
|
|
SYSTEMCMDS
|
|
#bl_update
|
|
#config
|
|
#dumpfile
|
|
dyn
|
|
esc_calib
|
|
#hardfault_log
|
|
led_control
|
|
mixer
|
|
motor_ramp
|
|
#mtd
|
|
#nshterm
|
|
param
|
|
perf
|
|
pwm
|
|
reboot
|
|
sd_bench
|
|
shutdown
|
|
tests # tests and test runner
|
|
top
|
|
topic_listener
|
|
tune_control
|
|
ver
|
|
|
|
EXAMPLES
|
|
bottle_drop # OBC challenge
|
|
dyn_hello # dynamically loading modules example
|
|
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
|
hello
|
|
#hwtest # Hardware test
|
|
position_estimator_inav
|
|
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
|
|
segway
|
|
)
|
|
|
|
set(config_sitl_viewer jmavsim CACHE STRING "viewer for sitl")
|
|
set_property(CACHE config_sitl_viewer PROPERTY STRINGS "jmavsim;none")
|
|
|
|
set(config_sitl_debugger disable CACHE STRING "debugger for sitl")
|
|
set_property(CACHE config_sitl_debugger PROPERTY STRINGS "disable;gdb;lldb")
|
|
|
|
# If the environment variable 'replay' is defined, we are building with replay
|
|
# support. In this case, we enable the orb publisher rules.
|
|
set(REPLAY_FILE "$ENV{replay}")
|
|
if(REPLAY_FILE)
|
|
message("Building with uorb publisher rules support")
|
|
add_definitions(-DORB_USE_PUBLISHER_RULES)
|
|
|
|
message("Building without lockstep for replay")
|
|
set(ENABLE_LOCKSTEP_SCHEDULER no)
|
|
else()
|
|
set(ENABLE_LOCKSTEP_SCHEDULER yes)
|
|
endif()
|