forked from Archive/PX4-Autopilot
ROMFS:Bake in UAVCAN FW with builds that end in _uavcan
The configuration are mostly for testing now.
This commit is contained in:
parent
8c2678bca1
commit
e0e796a2b9
|
@ -187,6 +187,46 @@ foreach(board_rc_file ${OPTIONAL_BOARD_RC})
|
|||
|
||||
endforeach()
|
||||
|
||||
|
||||
if(config_uavcan_peripheral_firmware)
|
||||
|
||||
include(ExternalProject)
|
||||
|
||||
foreach(uavcan_peripheral_config ${config_uavcan_peripheral_firmware})
|
||||
# include the px4io binary in ROMFS
|
||||
message(STATUS "ROMFS: Building and including UAVCAN peripheral ${uavcan_peripheral_config}")
|
||||
ExternalProject_Add(build_${uavcan_peripheral_config}
|
||||
SOURCE_DIR ${CMAKE_SOURCE_DIR}
|
||||
DOWNLOAD_COMMAND ""
|
||||
UPDATE_COMMAND ""
|
||||
CMAKE_ARGS -DCONFIG=${uavcan_peripheral_config}
|
||||
INSTALL_COMMAND ""
|
||||
USES_TERMINAL_BUILD true
|
||||
DEPENDS git_nuttx git_nuttx_apps
|
||||
BUILD_ALWAYS 1
|
||||
)
|
||||
|
||||
ExternalProject_Get_Property(build_${uavcan_peripheral_config} BINARY_DIR)
|
||||
|
||||
add_custom_command(
|
||||
OUTPUT
|
||||
${romfs_gen_root_dir}/uavcan/fw/_${uavcan_board_id}.bin
|
||||
${uavcan_peripheral_config}.stamp
|
||||
COMMAND ${CMAKE_COMMAND} -E make_directory ${romfs_gen_root_dir}/uavcan/fw/
|
||||
COMMAND ${CMAKE_COMMAND} -E copy ${BINARY_DIR}/deploy/*.bin ${romfs_gen_root_dir}/uavcan/fw/
|
||||
COMMAND ls -lsa ${romfs_gen_root_dir}/uavcan/fw/
|
||||
COMMAND ${CMAKE_COMMAND} -E touch ${uavcan_peripheral_config}.stamp
|
||||
DEPENDS
|
||||
build_${uavcan_peripheral_config}
|
||||
COMMENT "ROMFS: copying ${uavcan_peripheral_config}"
|
||||
)
|
||||
|
||||
list(APPEND extras_dependencies
|
||||
${uavcan_peripheral_config}.stamp
|
||||
)
|
||||
endforeach()
|
||||
endif()
|
||||
|
||||
list(APPEND extras_dependencies
|
||||
${config_romfs_extra_dependencies}
|
||||
)
|
||||
|
|
|
@ -0,0 +1,53 @@
|
|||
|
||||
|
||||
# UAVCAN boot loadable Module ID
|
||||
set(uavcanblid_sw_version_major 0)
|
||||
set(uavcanblid_sw_version_minor 1)
|
||||
add_definitions(
|
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
|
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
)
|
||||
|
||||
set(uavcanblid_hw_version_major 1)
|
||||
set(uavcanblid_hw_version_minor 0)
|
||||
set(uavcanblid_name "\"org.cuav.can-gps-v1\"")
|
||||
|
||||
add_definitions(
|
||||
-DHW_UAVCAN_NAME=${uavcanblid_name}
|
||||
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
|
||||
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
|
||||
)
|
||||
add_definitions(-DUSE_S_RGB_LED_DMA)
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR cuav
|
||||
MODEL can-gps-v1
|
||||
LABEL debug
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
ROMFSROOT cannode
|
||||
UAVCAN_INTERFACES 1
|
||||
DRIVERS
|
||||
barometer/ms5611
|
||||
bootloaders
|
||||
gps
|
||||
lights/neopixel
|
||||
magnetometer/rm3100
|
||||
safety_button
|
||||
tone_alarm
|
||||
uavcannode
|
||||
MODULES
|
||||
load_mon
|
||||
SYSTEMCMDS
|
||||
i2cdetect
|
||||
led_control
|
||||
param
|
||||
perf
|
||||
reboot
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
ver
|
||||
work_queue
|
||||
)
|
|
@ -0,0 +1,128 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR cuav
|
||||
MODEL nora
|
||||
LABEL uavcan
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
#BUILD_BOOTLOADER
|
||||
#TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
UAVCAN_TIMER_OVERRIDE 2
|
||||
UAVCAN_PERIPHERALS
|
||||
cuav_can-gps-v1_default
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
GPS2:/dev/ttyS2
|
||||
TEL2:/dev/ttyS3
|
||||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
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
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
mkblctrl
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
#tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
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
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
#bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
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
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
#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
|
||||
)
|
|
@ -0,0 +1,128 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR cuav
|
||||
MODEL x7pro
|
||||
LABEL uavcan
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
#BUILD_BOOTLOADER
|
||||
#TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
UAVCAN_TIMER_OVERRIDE 2
|
||||
UAVCAN_PERIPHERALS
|
||||
cuav_can-gps-v1_default
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
GPS2:/dev/ttyS2
|
||||
TEL2:/dev/ttyS3
|
||||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
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
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
mkblctrl
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
#tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
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
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
#bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
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
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
#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
|
||||
)
|
|
@ -0,0 +1,138 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v5
|
||||
LABEL uavcan
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
UAVCAN_PERIPHERALS
|
||||
cuav_can-gps-v1_default
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
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/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
imu/bosch/bmi055
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
#imu/mpu6000 # legacy icm20602/icm20689 driver
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
mkblctrl
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
#pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
rc_input
|
||||
#roboclaw
|
||||
#rpm
|
||||
safety_button
|
||||
#tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
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
|
||||
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
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
#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
|
||||
)
|
|
@ -50,6 +50,7 @@
|
|||
# [ IO <string> ]
|
||||
# [ BOOTLOADER <string> ]
|
||||
# [ UAVCAN_INTERFACES <string> ]
|
||||
# [ UAVCAN_PERIPHERALS <list> ]
|
||||
# [ DRIVERS <list> ]
|
||||
# [ MODULES <list> ]
|
||||
# [ SYSTEMCMDS <list> ]
|
||||
|
@ -74,6 +75,7 @@
|
|||
# IO : name of IO board to be built and included in the ROMFS (requires a valid ROMFSROOT)
|
||||
# BOOTLOADER : bootloader file to include for flashing via bl_update (currently NuttX only)
|
||||
# UAVCAN_INTERFACES : number of interfaces for UAVCAN
|
||||
# UAVCAN_PERIPHERALS : list of UAVCAN peripheral firmware to build and embed
|
||||
# DRIVERS : list of drivers to build for this board (relative to src/drivers)
|
||||
# MODULES : list of modules to build for this board (relative to src/modules)
|
||||
# SYSTEMCMDS : list of system commands to build for this board (relative to src/systemcmds)
|
||||
|
@ -154,6 +156,7 @@ function(px4_add_board)
|
|||
SYSTEMCMDS
|
||||
EXAMPLES
|
||||
SERIAL_PORTS
|
||||
UAVCAN_PERIPHERALS
|
||||
EMBEDDED_METADATA
|
||||
OPTIONS
|
||||
BUILD_BOOTLOADER
|
||||
|
@ -236,6 +239,10 @@ function(px4_add_board)
|
|||
if(IO)
|
||||
set(config_io_board ${IO} CACHE INTERNAL "IO" FORCE)
|
||||
endif()
|
||||
|
||||
if(UAVCAN_PERIPHERALS)
|
||||
set(config_uavcan_peripheral_firmware ${UAVCAN_PERIPHERALS} CACHE INTERNAL "UAVCAN peripheral firmware" FORCE)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(UAVCAN_INTERFACES)
|
||||
|
|
Loading…
Reference in New Issue