forked from Archive/PX4-Autopilot
boards: minimize unnecessary differences in default variants
This commit is contained in:
parent
fcc4153c26
commit
631d1647d3
|
@ -76,7 +76,6 @@ unset BOARD_RC_DEFAULTS
|
|||
#
|
||||
rgbled start -X -q
|
||||
rgbled_ncp5623c start -X -q
|
||||
rgbled_pwm start
|
||||
|
||||
if param greater -s LIGHT_EN_BLINKM 0
|
||||
then
|
||||
|
|
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -31,13 +32,12 @@ px4_add_board(
|
|||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu6500
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -45,6 +45,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -57,6 +58,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -73,12 +75,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -86,6 +91,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -101,6 +107,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -112,6 +119,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -26,18 +27,16 @@ px4_add_board(
|
|||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
irlock
|
||||
lights/blinkm
|
||||
#lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -45,6 +44,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
#tone_alarm
|
||||
|
@ -57,6 +57,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -73,19 +74,23 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
#bl_update
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -93,12 +98,14 @@ px4_add_board(
|
|||
motor_ramp
|
||||
motor_test
|
||||
nshterm
|
||||
netman
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -109,6 +116,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -14,12 +14,10 @@
|
|||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_ADDROUTE is not set
|
||||
# CONFIG_NSH_DISABLE_ARP is not set
|
||||
# CONFIG_NSH_DISABLE_BASENAME is not set
|
||||
# CONFIG_NSH_DISABLE_CMP is not set
|
||||
# CONFIG_NSH_DISABLE_DD is not set
|
||||
# CONFIG_NSH_DISABLE_DELROUTE is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_DIRNAME is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
|
@ -32,7 +30,6 @@
|
|||
# CONFIG_NSH_DISABLE_MKRD is not set
|
||||
# CONFIG_NSH_DISABLE_PRINTF is not set
|
||||
# CONFIG_NSH_DISABLE_PUT is not set
|
||||
# CONFIG_NSH_DISABLE_ROUTE is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_NSH_DISABLE_UNAME is not set
|
||||
|
@ -74,15 +71,13 @@ CONFIG_FAT_LCNAMES=y
|
|||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FSUTILS_IPCFG=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
|
@ -108,12 +103,18 @@ CONFIG_NETDB_DNSCLIENT=y
|
|||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DHCPC=y
|
||||
CONFIG_NETINIT_DNS=y
|
||||
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ROUTE=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_SOCKOPTS=y
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
|
@ -121,6 +122,7 @@ CONFIG_NET_TCPBACKLOG=y
|
|||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
|
@ -128,9 +130,9 @@ CONFIG_NSH_ARGCAT=y
|
|||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_LOGIN_PASSWORD="px4"
|
||||
CONFIG_NSH_LOGIN_USERNAME="px4"
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
|
@ -195,6 +197,7 @@ CONFIG_STM32F7_PHYSR_10FD=0x14
|
|||
CONFIG_STM32F7_PHYSR_10HD=0x4
|
||||
CONFIG_STM32F7_PHYSR_ALTCONFIG=y
|
||||
CONFIG_STM32F7_PHYSR_ALTMODE=0x1C
|
||||
CONFIG_STM32F7_PROGMEM=y
|
||||
CONFIG_STM32F7_PWR=y
|
||||
CONFIG_STM32F7_RTC=y
|
||||
CONFIG_STM32F7_RTC_HSECLOCK=y
|
||||
|
@ -229,6 +232,7 @@ CONFIG_STM32F7_USART_INVERT=y
|
|||
CONFIG_STM32F7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32F7_USART_SWAP=y
|
||||
CONFIG_STM32F7_WWDG=y
|
||||
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
|
|
|
@ -14,6 +14,7 @@ px4_add_board(
|
|||
TOOLCHAIN arm-linux-gnueabihf
|
||||
TESTING
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/bmp280
|
||||
|
@ -24,6 +25,7 @@ px4_add_board(
|
|||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/invensense/mpu9250
|
||||
linux_pwm_out
|
||||
#magnetometer # all available magnetometer drivers
|
||||
|
@ -39,6 +41,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -63,6 +66,8 @@ px4_add_board(
|
|||
sih
|
||||
#simulator
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -76,8 +81,9 @@ px4_add_board(
|
|||
perf
|
||||
pwm
|
||||
sd_bench
|
||||
shutdown
|
||||
#serial_test
|
||||
system_time
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
#top
|
||||
topic_listener
|
||||
|
@ -86,8 +92,10 @@ px4_add_board(
|
|||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
dyn_hello # dynamically loading modules example
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -30,24 +31,25 @@ px4_add_board(
|
|||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -61,6 +63,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -77,12 +80,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -90,6 +96,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -105,6 +112,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -116,7 +124,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific board MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -29,24 +30,26 @@ px4_add_board(
|
|||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all relevant IMU drivers
|
||||
imu/analog_devices/adis16470
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -60,6 +63,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -76,12 +80,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -89,6 +96,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -104,6 +112,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -115,8 +124,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific board MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
# CONSOLE:/dev/ttyS4
|
||||
GPS2:/dev/ttyS5
|
||||
DRIVERS
|
||||
#adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -30,20 +31,16 @@ px4_add_board(
|
|||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
#imu/analog_devices/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
#pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
|
@ -87,6 +84,8 @@ px4_add_board(
|
|||
sensors
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -110,6 +109,8 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
#serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
@ -120,7 +121,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
GPS2:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -35,13 +36,12 @@ px4_add_board(
|
|||
imu/invensense/icm20649
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
|
@ -85,6 +85,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -108,6 +110,8 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
#serial_test
|
||||
system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
@ -118,7 +122,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
# CONSOLE:/dev/ttyS4
|
||||
GPS2:/dev/ttyS5
|
||||
DRIVERS
|
||||
#adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -29,18 +30,16 @@ px4_add_board(
|
|||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
#pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
|
@ -54,7 +53,7 @@ px4_add_board(
|
|||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
#attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
|
@ -70,7 +69,7 @@ px4_add_board(
|
|||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
#local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
|
@ -80,10 +79,12 @@ px4_add_board(
|
|||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
#rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -107,6 +108,8 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
#serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
@ -117,7 +120,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
GPS2:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -34,13 +35,12 @@ px4_add_board(
|
|||
imu/invensense/icm20649
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
|
@ -49,7 +49,7 @@ px4_add_board(
|
|||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -84,6 +84,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -107,7 +109,9 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
tests # tests and test runner
|
||||
#serial_test
|
||||
system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
@ -117,7 +121,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -12,6 +12,7 @@ px4_add_board(
|
|||
TOOLCHAIN arm-linux-gnueabihf
|
||||
TESTING
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
|
@ -40,6 +41,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -64,6 +66,8 @@ px4_add_board(
|
|||
sih
|
||||
#simulator
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -77,6 +81,7 @@ px4_add_board(
|
|||
perf
|
||||
pwm
|
||||
sd_bench
|
||||
#serial_test
|
||||
system_time
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
@ -89,6 +94,8 @@ px4_add_board(
|
|||
EXAMPLES
|
||||
dyn_hello # dynamically loading modules example
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -10,7 +10,7 @@ px4_add_board(
|
|||
BUILD_BOOTLOADER
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
|
@ -18,6 +18,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -33,21 +34,19 @@ px4_add_board(
|
|||
imu/bosch/bmi088
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
|
||||
# all arch dependant code there
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -60,6 +59,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -76,12 +76,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -89,6 +92,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -104,6 +108,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -115,6 +120,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -33,14 +34,13 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -87,6 +87,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -110,6 +112,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -121,6 +124,7 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
|
|
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS4 # UART5 / J1
|
||||
TEL3:/dev/ttyS1 # USART2 / J4
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -28,13 +29,12 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
power_monitor/voxlpm
|
||||
#protocol_splitter
|
||||
|
@ -43,6 +43,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -72,12 +73,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -85,6 +89,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -100,6 +105,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -111,6 +117,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -25,7 +26,7 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
|
@ -33,13 +34,12 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -47,6 +47,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -60,6 +61,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -83,6 +85,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -90,6 +94,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -105,6 +110,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -116,6 +122,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
#CONSOLE:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -25,7 +26,7 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
|
@ -33,13 +34,12 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -47,6 +47,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -60,6 +61,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -83,6 +85,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -90,6 +94,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -105,6 +110,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -116,6 +122,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -8,7 +8,6 @@ px4_add_board(
|
|||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
TEL1:/dev/ttyS0
|
||||
|
@ -18,6 +17,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -33,24 +33,20 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
#safety_button TODO
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -85,6 +81,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -108,23 +106,27 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
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
|
||||
uuv_example_app
|
||||
work_item
|
||||
#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
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -8,7 +8,6 @@ px4_add_board(
|
|||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
TEL1:/dev/ttyS0
|
||||
|
@ -18,6 +17,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -33,24 +33,20 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
#safety_button TODO
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -85,6 +81,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -108,23 +106,27 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
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
|
||||
uuv_example_app
|
||||
work_item
|
||||
#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
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -8,7 +8,6 @@ px4_add_board(
|
|||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
#SPARE:/dev/ttyS0
|
||||
|
@ -19,6 +18,7 @@ px4_add_board(
|
|||
#CONSOLE:/dev/ttyS5
|
||||
#FRSKY:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -34,23 +34,20 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -85,6 +82,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -96,6 +95,7 @@ px4_add_board(
|
|||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
|
@ -109,7 +109,7 @@ px4_add_board(
|
|||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
@ -119,8 +119,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific sensors init
|
||||
# board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
board_adc start
|
||||
|
||||
|
|
|
@ -25,7 +25,7 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
|||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254
|
||||
CONFIG_BOARD_LATE_INITIALIZE=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
|
|
|
@ -16,9 +16,10 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
GPS1:/dev/ttyS3
|
||||
# PX4IO:/dev/ttyS4
|
||||
# CONSOLE:/dev/tty5
|
||||
# CONSOLE:/dev/ttyS5
|
||||
# OSD:/dev/tty6
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -33,13 +34,12 @@ px4_add_board(
|
|||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -84,6 +84,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -107,6 +109,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -118,6 +121,7 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
|
|
|
@ -12,10 +12,15 @@ px4_add_board(
|
|||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
# IO DEBUG:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
GPS1:/dev/ttyS3
|
||||
# PX4IO:/dev/ttyS4
|
||||
# CONSOLE:/dev/ttyS5
|
||||
# OSD:/dev/tty6
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -23,29 +28,27 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
#power_monitor/ina226
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -58,6 +61,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -81,6 +85,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -88,6 +94,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -103,6 +110,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -114,6 +122,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS4
|
||||
TEL2:/dev/ttyS1
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
barometer/mpl3115a2
|
||||
|
@ -25,29 +26,26 @@ px4_add_board(
|
|||
distance_sensor # all available distance sensor drivers
|
||||
distance_sensor/srf05 # Specific driver
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm # NOT Portable YET
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -58,6 +56,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -74,12 +73,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -87,7 +89,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#hardfault_log # Needs bbsrm
|
||||
#gpio
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
|
@ -102,6 +104,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -113,6 +116,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -34,6 +34,7 @@ CONFIG_CDCACM_RXBUFSIZE=600
|
|||
CONFIG_CDCACM_TXBUFSIZE=8000
|
||||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
|
|
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS4
|
||||
TEL2:/dev/ttyS1
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
barometer/mpl3115a2
|
||||
|
@ -25,29 +26,26 @@ px4_add_board(
|
|||
distance_sensor # all available distance sensor drivers
|
||||
distance_sensor/srf05 # Specific driver
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/fxas21002c
|
||||
imu/fxos8701cq
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm # NOT Portable YET
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -58,6 +56,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -74,12 +73,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -87,7 +89,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#hardfault_log # Needs bbsrm
|
||||
#gpio
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
|
@ -102,6 +104,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -113,6 +116,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -33,6 +33,7 @@ CONFIG_CDCACM_RXBUFSIZE=600
|
|||
CONFIG_CDCACM_TXBUFSIZE=8000
|
||||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
|
|
|
@ -14,48 +14,53 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS2
|
||||
TEL2:/dev/ttyS3
|
||||
GPS2:/dev/ttyS4
|
||||
|
||||
DRIVERS
|
||||
#adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
#differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
# dshot not ported
|
||||
#dshot # not ported
|
||||
gps
|
||||
#imu/analog_devices/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi055
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
#irlock
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
# pwm_input - not ptorable
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
#pca9685
|
||||
#pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
#roboclaw
|
||||
#rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
# uavcan
|
||||
#uavcan
|
||||
MODULES
|
||||
#airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
#esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
#fw_att_control
|
||||
#fw_pos_control_l1
|
||||
#gyro_calibration
|
||||
#gyro_fft
|
||||
land_detector
|
||||
|
@ -68,24 +73,30 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
temperature_compensation
|
||||
#vmount
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
# bl_update
|
||||
#bl_update # not ported
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#hardfault_log # Needs bbsrm
|
||||
#gpio
|
||||
#hardfault_log # not ported
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mft
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
|
@ -104,12 +115,16 @@ px4_add_board(
|
|||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
## fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
# hello
|
||||
# hwtest # Hardware test
|
||||
#fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
# 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
|
||||
# uuv_example_app
|
||||
#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
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
|
|
|
@ -3,6 +3,7 @@ px4_add_board(
|
|||
PLATFORM nuttx
|
||||
VENDOR omnibus
|
||||
MODEL f4sd
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
|
@ -24,11 +25,10 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/mpu6000
|
||||
#irlock
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
optical_flow/px4flow
|
||||
#optical_flow # all available optical flow drivers
|
||||
osd
|
||||
#pca9685
|
||||
#pwm_input
|
||||
|
@ -46,6 +46,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
#esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
#fw_att_control
|
||||
|
@ -62,12 +63,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
#vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -75,6 +79,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -90,6 +95,8 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
#serial_test
|
||||
#system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
@ -100,6 +107,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -34,24 +34,21 @@ px4_add_board(
|
|||
#heater
|
||||
#imu # all available imu drivers
|
||||
#imu/analog_devices/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
#imu/invensense/icm20608g
|
||||
#imu/invensense/icm20948
|
||||
imu/invensense/mpu6000
|
||||
#imu/invensense/mpu9250
|
||||
#iridiumsbd
|
||||
#irlock
|
||||
#lights/blinkm
|
||||
#lights # all available light drivers
|
||||
lights/rgbled
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
#optical_flow # all available optical flow drivers
|
||||
#optical_flow/px4flow
|
||||
#osd
|
||||
#pca9685
|
||||
#pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -59,6 +56,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
px4io
|
||||
#roboclaw
|
||||
#rpm
|
||||
#telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
|
@ -95,6 +93,8 @@ px4_add_board(
|
|||
sensors
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
#vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -102,6 +102,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
#dumpfile
|
||||
#esc_calib
|
||||
#gpio
|
||||
hardfault_log
|
||||
#i2cdetect
|
||||
#led_control
|
||||
|
@ -117,7 +118,8 @@ px4_add_board(
|
|||
reboot
|
||||
#reflect
|
||||
#sd_bench
|
||||
#shutdown
|
||||
#serial_test
|
||||
#system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
@ -128,6 +130,8 @@ px4_add_board(
|
|||
#work_queue
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -1,6 +1,4 @@
|
|||
|
||||
# FMUv3 is FMUv2 with access to the full 2MB flash
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
|
@ -19,8 +17,8 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -39,13 +37,10 @@ px4_add_board(
|
|||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
|
@ -55,6 +50,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -91,6 +87,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -114,6 +112,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -125,6 +124,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -15,10 +15,9 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
WIFI:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -32,24 +31,22 @@ px4_add_board(
|
|||
imu/analog_devices/adis16448
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm40609d
|
||||
imu/invensense/mpu6500
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -112,6 +109,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
|
|
@ -1,135 +0,0 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v4
|
||||
LABEL uavcanv1
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
WIFI:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm40609d
|
||||
imu/invensense/mpu6500
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
#uavcan
|
||||
uavcan_v1
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
gyro_calibration
|
||||
gyro_fft
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
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
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
|
@ -18,8 +18,8 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS0
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -30,26 +30,25 @@ px4_add_board(
|
|||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -95,6 +94,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -121,6 +121,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -16,8 +16,8 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -33,13 +33,11 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
|
@ -113,6 +111,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
|
|
@ -10,6 +10,7 @@ px4_add_board(
|
|||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
ETHERNET
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS6
|
||||
|
@ -17,6 +18,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS1
|
||||
GPS2:/dev/ttyS7
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -26,20 +28,19 @@ px4_add_board(
|
|||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -61,6 +62,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -84,6 +86,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -101,12 +105,14 @@ px4_add_board(
|
|||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
netman
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -116,9 +122,10 @@ px4_add_board(
|
|||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
serial_test
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -18,8 +18,8 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS1
|
||||
GPS2:/dev/ttyS7
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -28,20 +28,18 @@ px4_add_board(
|
|||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
#pca9685
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
|
@ -88,6 +86,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -112,6 +112,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -123,6 +124,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -65,6 +65,7 @@ CONFIG_FAT_LCNAMES=y
|
|||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FSUTILS_IPCFG=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
|
@ -82,6 +83,9 @@ CONFIG_I2C_RESET=y
|
|||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_IPCFG_BINARY=y
|
||||
CONFIG_IPCFG_CHARDEV=y
|
||||
CONFIG_IPCFG_PATH="/fs/mtd_net"
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
|
@ -101,8 +105,11 @@ CONFIG_NETDB_DNSCLIENT=y
|
|||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DHCPC=y
|
||||
CONFIG_NETINIT_DNS=y
|
||||
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_IPADDR=0XC0A8007B
|
||||
CONFIG_NETINIT_MONITOR=y
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
|
@ -118,6 +125,7 @@ CONFIG_NET_TCPBACKLOG=y
|
|||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
|
@ -190,14 +198,17 @@ CONFIG_STM32F7_I2C4=y
|
|||
CONFIG_STM32F7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32F7_OTGFS=y
|
||||
CONFIG_STM32F7_PHYSR=16
|
||||
CONFIG_STM32F7_PHYSR_100MBPS=0x0
|
||||
CONFIG_STM32F7_PHYSR_FULLDUPLEX=0x04
|
||||
CONFIG_STM32F7_PHYSR_MODE=0x04
|
||||
CONFIG_STM32F7_PHYSR_SPEED=0x2
|
||||
CONFIG_STM32F7_PHYADDR=0
|
||||
CONFIG_STM32F7_PHYSR=31
|
||||
CONFIG_STM32F7_PHYSR_100MBPS=0x8
|
||||
CONFIG_STM32F7_PHYSR_FULLDUPLEX=0x10
|
||||
CONFIG_STM32F7_PHYSR_MODE=0x10
|
||||
CONFIG_STM32F7_PHYSR_SPEED=0x8
|
||||
CONFIG_STM32F7_PHY_POLLING=y
|
||||
CONFIG_STM32F7_PROGMEM=y
|
||||
CONFIG_STM32F7_PWR=y
|
||||
CONFIG_STM32F7_RTC=y
|
||||
CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
|
||||
CONFIG_STM32F7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32F7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32F7_SDMMC2=y
|
||||
|
@ -235,6 +246,7 @@ CONFIG_STM32F7_USART_SINGLEWIRE=y
|
|||
CONFIG_STM32F7_USART_SWAP=y
|
||||
CONFIG_STM32F7_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
|
|
|
@ -32,9 +32,7 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm42605
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
|
@ -42,7 +40,6 @@ px4_add_board(
|
|||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input - Need to create arch/stm32 arch/stm32h7
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
|
@ -122,7 +119,7 @@ px4_add_board(
|
|||
EXAMPLES
|
||||
fake_gps
|
||||
#fake_gyro
|
||||
fake_magnetometer
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -10,7 +10,8 @@ px4_add_board(
|
|||
BUILD_BOOTLOADER
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
UAVCAN_INTERFACES 2
|
||||
ETHERNET
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS6
|
||||
|
@ -18,6 +19,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS1
|
||||
GPS2:/dev/ttyS7
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -29,21 +31,19 @@ px4_add_board(
|
|||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
|
||||
# all arch dependant code there
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
|
@ -86,6 +86,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -93,6 +95,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -102,12 +105,14 @@ px4_add_board(
|
|||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
netman
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -117,10 +122,10 @@ px4_add_board(
|
|||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
serial_test
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -66,6 +66,7 @@ CONFIG_FAT_LCNAMES=y
|
|||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FSUTILS_IPCFG=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
|
@ -83,6 +84,9 @@ CONFIG_I2C_RESET=y
|
|||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_IPCFG_BINARY=y
|
||||
CONFIG_IPCFG_CHARDEV=y
|
||||
CONFIG_IPCFG_PATH="/fs/mtd_net"
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
|
@ -102,8 +106,10 @@ CONFIG_NETDB_DNSCLIENT=y
|
|||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DHCPC=y
|
||||
CONFIG_NETINIT_DNS=y
|
||||
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_IPADDR=0XC0A8007B
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
|
@ -119,6 +125,7 @@ CONFIG_NET_TCPBACKLOG=y
|
|||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
|
@ -240,6 +247,7 @@ CONFIG_STM32H7_USART_INVERT=y
|
|||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
|
|
|
@ -38,6 +38,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -59,9 +60,11 @@ px4_add_board(
|
|||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
temperature_compensation
|
||||
sih
|
||||
#simulator
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -70,10 +73,12 @@ px4_add_board(
|
|||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
sd_bench
|
||||
#serial_test
|
||||
system_time
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
@ -84,8 +89,10 @@ px4_add_board(
|
|||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
dyn_hello # dynamically loading modules example
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -89,6 +89,7 @@ px4_add_board(
|
|||
EXAMPLES
|
||||
dyn_hello # dynamically loading modules example
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
|
|
|
@ -48,6 +48,7 @@ px4_add_board(
|
|||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
gyro_calibration
|
||||
gyro_fft
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
|
@ -59,6 +60,7 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
sensors
|
||||
|
@ -70,6 +72,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -85,6 +88,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
top
|
||||
topic_listener
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2018 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
|
||||
add_subdirectory(blinkm)
|
||||
#add_subdirectory(neopixel) # requires board support (BOARD_HAS_N_S_RGB_LED)
|
||||
add_subdirectory(rgbled)
|
||||
add_subdirectory(rgbled_ncp5623c)
|
||||
#add_subdirectory(rgbled_pwm) # requires board support (BOARD_HAS_LED_PWM/BOARD_HAS_UI_LED_PWM)
|
||||
|
|
Loading…
Reference in New Issue