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.
65 lines
895 B
65 lines
895 B
6 years ago
|
|
||
|
px4_add_board(
|
||
|
VENDOR parrot
|
||
|
MODEL bebop
|
||
|
PLATFORM posix
|
||
|
ARCH cortex-a53
|
||
|
TOOLCHAIN Toolchain-arm-linux-gnueabihf
|
||
|
|
||
|
DRIVERS
|
||
|
gps
|
||
|
linux_sbus
|
||
|
pwm_out_sim
|
||
|
|
||
|
DF_DRIVERS # NOTE: DriverFramework is migrating to intree PX4 drivers
|
||
|
ms5607
|
||
|
mpu6050
|
||
|
ak8963
|
||
|
bebop_bus
|
||
|
bebop_rangefinder
|
||
|
#bebop_flow
|
||
|
|
||
|
MODULES
|
||
|
attitude_estimator_q
|
||
|
camera_feedback
|
||
|
commander
|
||
|
dataman
|
||
|
ekf2
|
||
|
events
|
||
|
#fw_att_control
|
||
|
#fw_pos_control_l1
|
||
|
#gnd_att_control
|
||
|
#gnd_pos_control
|
||
|
#gpio_led
|
||
|
land_detector
|
||
|
landing_target_estimator
|
||
|
load_mon
|
||
|
local_position_estimator
|
||
|
logger
|
||
|
mavlink
|
||
|
mc_att_control
|
||
|
mc_pos_control
|
||
|
navigator
|
||
|
position_estimator_inav
|
||
|
sensors
|
||
|
#vtol_att_control
|
||
|
wind_estimator
|
||
|
|
||
|
SYSTEMCMDS
|
||
|
#config
|
||
|
esc_calib
|
||
|
led_control
|
||
|
mixer
|
||
|
motor_ramp
|
||
|
param
|
||
|
perf
|
||
|
pwm
|
||
|
reboot
|
||
|
sd_bench
|
||
|
#tests # tests and test runner
|
||
|
top
|
||
|
topic_listener
|
||
|
tune_control
|
||
|
ver
|
||
|
)
|