forked from Archive/PX4-Autopilot
cmake merge linux cross compile targets (cross + native) and cleanup
- consolidate cross and native variants (only a single default is needed) - beaglebone_blue_cross + beaglebone_blue_native => beaglebone_blue_default - emlid_navio2_cross + emlid_navio2_native => emlid_navio2_default - px4_raspberrypi_cross + px4_raspberrypi_native => px4_raspberrypi_default - move upload helpers to cmake/upload.cmake
This commit is contained in:
parent
aaf5670e7d
commit
7241eebd80
|
@ -16,7 +16,7 @@ pipeline {
|
|||
]
|
||||
|
||||
def armhf_builds = [
|
||||
target: ["aerotenna_ocpoc_default", "beaglebone_blue_cross", "emlid_navio2_cross", "parrot_bebop_default", "px4_raspberrypi_cross"],
|
||||
target: ["aerotenna_ocpoc_default", "beaglebone_blue_default", "emlid_navio2_default", "parrot_bebop_default", "px4_raspberrypi_default"],
|
||||
image: docker_images.armhf,
|
||||
archive: false
|
||||
]
|
||||
|
|
|
@ -13,10 +13,10 @@ pipeline {
|
|||
sh 'make distclean'
|
||||
sh 'ccache -s'
|
||||
sh 'git fetch --tags'
|
||||
sh 'CCACHE_BASEDIR=${WORKSPACE} make emlid_navio2_native'
|
||||
sh 'CCACHE_BASEDIR=${WORKSPACE} make emlid_navio2_default'
|
||||
sh 'ccache -s'
|
||||
// sanity check
|
||||
sh 'cd build/emlid_navio2_native/ && ./bin/px4 -s ../../posix-configs/rpi/px4_test.config'
|
||||
sh 'cd build/emlid_navio2_default/ && ./bin/px4 -s ../../posix-configs/rpi/px4_test.config'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
|
|
|
@ -298,8 +298,8 @@ px4_os_add_flags()
|
|||
#=============================================================================
|
||||
# board cmake init (optional)
|
||||
#
|
||||
if(EXISTS ${PX4_BOARD_DIR}/init.cmake)
|
||||
include(${PX4_BOARD_DIR}/init.cmake)
|
||||
if(EXISTS ${PX4_BOARD_DIR}/cmake/init.cmake)
|
||||
include(${PX4_BOARD_DIR}/cmake/init.cmake)
|
||||
endif()
|
||||
|
||||
#=============================================================================
|
||||
|
|
|
@ -6,7 +6,7 @@ if [ -z ${PX4_DOCKER_REPO+x} ]; then
|
|||
# nuttx-px4fmu-v{1,2,3,4,5}
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-nuttx:2019-10-24"
|
||||
elif [[ $@ =~ .*ocpoc.* ]] || [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*bebop.* ]]; then
|
||||
# aerotenna_ocpoc_default, posix_rpi_cross, posix_bebop_default
|
||||
# aerotenna_ocpoc_default, beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, parrot_bebop_default
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2019-10-24"
|
||||
elif [[ $@ =~ .*eagle.* ]] || [[ $@ =~ .*excelsior.* ]]; then
|
||||
# eagle, excelsior
|
||||
|
|
|
@ -30,44 +30,3 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
|
||||
|
||||
|
||||
############################################################################
|
||||
# Upload
|
||||
############################################################################
|
||||
|
||||
if("${PX4_PLATFORM}" MATCHES "qurt")
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/scripts/adb_upload.sh
|
||||
${PX4_BINARY_DIR}/platforms/qurt/libpx4.so ${PX4_BINARY_DIR}/platforms/qurt/libpx4muorb_skel.so ${PX4_SOURCE_DIR}/posix-configs/eagle/flight/px4.config # source
|
||||
/usr/share/data/adsp # destination
|
||||
DEPENDS px4 px4muorb_skel
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
else()
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/scripts/adb_upload.sh
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/bin ${PX4_SOURCE_DIR}/posix-configs/eagle/flight/mainapp.config # source
|
||||
/home/linaro # destination
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
add_custom_target(sanity
|
||||
COMMAND ./px4_snapflight_sanitytest.sh -i -t
|
||||
DEPENDS px4
|
||||
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/scripts
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
endif()
|
||||
|
|
|
@ -0,0 +1,64 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
if("${PX4_PLATFORM}" MATCHES "qurt")
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND ${PX4_BOARD_DIR}/scripts/adb_upload.sh
|
||||
${PX4_BINARY_DIR}/platforms/qurt/libpx4.so ${PX4_BINARY_DIR}/platforms/qurt/libpx4muorb_skel.so ${PX4_SOURCE_DIR}/posix-configs/eagle/flight/px4.config # source
|
||||
/usr/share/data/adsp # destination
|
||||
DEPENDS px4 px4muorb_skel ${PX4_BOARD_DIR}/scripts/adb_upload.sh
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
else()
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND ${PX4_BOARD_DIR}/scripts/adb_upload.sh
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/eagle/flight/mainapp.config ${PX4_SOURCE_DIR}/ROMFS # source
|
||||
/home/linaro # destination
|
||||
DEPENDS px4 ${PX4_BOARD_DIR}/scripts/adb_upload.sh
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
add_custom_target(sanity
|
||||
COMMAND ./px4_snapflight_sanitytest.sh -i -t
|
||||
DEPENDS px4
|
||||
WORKING_DIRECTORY ${PX4_BOARD_DIR}/scripts
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
endif()
|
|
@ -32,14 +32,3 @@
|
|||
############################################################################
|
||||
|
||||
add_subdirectory(bbblue_adc)
|
||||
|
||||
############################################################################
|
||||
# Upload
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND rsync -arh --progress ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/bbblue/*.config ${PX4_SOURCE_DIR}/ROMFS debian@BBBluePX4:/home/debian/px4
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4 and data files"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND rsync -arh --progress
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/bbblue/*.config ${PX4_SOURCE_DIR}/ROMFS # source
|
||||
debian@beaglebone.lan:/home/debian/px4 # destination
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
|
@ -2,7 +2,7 @@
|
|||
px4_add_board(
|
||||
VENDOR beaglebone
|
||||
MODEL blue
|
||||
LABEL cross
|
||||
LABEL default
|
||||
PLATFORM posix
|
||||
ARCHITECTURE cortex-a8
|
||||
TOOLCHAIN arm-linux-gnueabihf
|
||||
|
@ -46,6 +46,7 @@ px4_add_board(
|
|||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
|
@ -82,4 +83,5 @@ px4_add_board(
|
|||
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
|
||||
)
|
|
@ -1,83 +0,0 @@
|
|||
|
||||
px4_add_board(
|
||||
VENDOR beaglebone
|
||||
MODEL blue
|
||||
LABEL native
|
||||
PLATFORM posix
|
||||
TESTING
|
||||
DRIVERS
|
||||
#barometer # all available barometer drivers
|
||||
barometer/bmp280
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
imu/mpu9250
|
||||
linux_pwm_out
|
||||
linux_sbus
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
pwm_out_sim
|
||||
#telemetry # all available telemetry drivers
|
||||
DF_DRIVERS # NOTE: DriverFramework is migrating to intree PX4 drivers
|
||||
mpu9250
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
#simulator
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
dyn
|
||||
esc_calib
|
||||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
bottle_drop # OBC challenge
|
||||
dyn_hello # dynamically loading modules example
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
#hwtest # Hardware test
|
||||
#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
|
||||
)
|
|
@ -34,15 +34,3 @@
|
|||
add_subdirectory(navio_adc)
|
||||
add_subdirectory(navio_rgbled)
|
||||
add_subdirectory(navio_sysfs_rc_in)
|
||||
|
||||
|
||||
############################################################################
|
||||
# Upload
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND rsync -arh --progress ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/*.config ${PX4_SOURCE_DIR}/ROMFS pi@"$ENV{AUTOPILOT_HOST}":/home/pi
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
|
|
@ -0,0 +1,47 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
if($ENV{AUTOPILOT_HOST})
|
||||
set(AUTOPILOT_HOST $ENV{AUTOPILOT_HOST})
|
||||
else()
|
||||
set(AUTOPILOT_HOST "navio")
|
||||
endif()
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND rsync -arh --progress
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/*.config ${PX4_SOURCE_DIR}/ROMFS # source
|
||||
pi@${AUTOPILOT_HOST}:/home/pi/px4 # destination
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
|
@ -2,7 +2,7 @@
|
|||
px4_add_board(
|
||||
VENDOR emlid
|
||||
MODEL navio2
|
||||
LABEL cross
|
||||
LABEL default
|
||||
PLATFORM posix
|
||||
ARCHITECTURE cortex-a53
|
||||
TOOLCHAIN arm-linux-gnueabihf
|
||||
|
@ -50,6 +50,7 @@ px4_add_board(
|
|||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
|
@ -86,4 +87,5 @@ px4_add_board(
|
|||
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
|
||||
)
|
|
@ -1,87 +0,0 @@
|
|||
|
||||
px4_add_board(
|
||||
VENDOR emlid
|
||||
MODEL navio2
|
||||
LABEL native
|
||||
PLATFORM posix
|
||||
TESTING
|
||||
DRIVERS
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
imu/mpu9250
|
||||
linux_pwm_out
|
||||
linux_sbus
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
pwm_out_sim
|
||||
#telemetry # all available telemetry drivers
|
||||
DF_DRIVERS # NOTE: DriverFramework is migrating to intree PX4 drivers
|
||||
hmc5883
|
||||
isl29501
|
||||
lsm9ds1
|
||||
mpu9250
|
||||
trone
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
#simulator
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
dyn
|
||||
esc_calib
|
||||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
bottle_drop # OBC challenge
|
||||
dyn_hello # dynamically loading modules example
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
#hwtest # Hardware test
|
||||
#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
|
||||
)
|
|
@ -32,16 +32,3 @@
|
|||
############################################################################
|
||||
|
||||
add_subdirectory(aerofc_adc)
|
||||
|
||||
|
||||
|
||||
############################################################################
|
||||
# Upload
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND ${CMAKE_CURRENT_SOURCE_DIR}/scripts/aero_upload.sh $<TARGET_FILE:px4>
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
|
|
@ -0,0 +1,39 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND ${PX4_BOARD_DIR}/scripts/aero_upload.sh $<TARGET_FILE:px4>
|
||||
DEPENDS px4 ${PX4_BOARD_DIR}/scripts/aero_upload.sh
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
|
@ -32,15 +32,3 @@
|
|||
############################################################################
|
||||
|
||||
add_subdirectory(flow)
|
||||
|
||||
|
||||
############################################################################
|
||||
# Upload
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND ${CMAKE_CURRENT_SOURCE_DIR}/scripts/adb_upload_to_bebop.sh ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/bin/. /data/ftp/internal_000/px4
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND ${PX4_BOARD_DIR}/scripts/adb_upload_to_bebop.sh
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY}
|
||||
/data/ftp/internal_000/px4
|
||||
DEPENDS px4 ${PX4_BOARD_DIR}/scripts/adb_upload_to_bebop.sh
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
|
@ -1,6 +1,47 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
if($ENV{AUTOPILOT_HOST})
|
||||
set(AUTOPILOT_HOST $ENV{AUTOPILOT_HOST})
|
||||
else()
|
||||
set(AUTOPILOT_HOST "raspberrypi")
|
||||
endif()
|
||||
|
||||
add_custom_target(upload
|
||||
COMMAND rsync -arh --progress ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/*.config ${PX4_SOURCE_DIR}/ROMFS pi@"$ENV{AUTOPILOT_HOST}":/home/pi/px4
|
||||
COMMAND rsync -arh --progress
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/*.config ${PX4_SOURCE_DIR}/ROMFS # source
|
||||
pi@${AUTOPILOT_HOST}:/home/pi/px4 # destination
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
)
|
||||
)
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
px4_add_board(
|
||||
VENDOR px4
|
||||
MODEL raspberrypi
|
||||
LABEL cross
|
||||
LABEL default
|
||||
PLATFORM posix
|
||||
ARCHITECTURE cortex-a53
|
||||
TOOLCHAIN arm-linux-gnueabihf
|
||||
|
@ -45,6 +45,7 @@ px4_add_board(
|
|||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
|
@ -81,4 +82,5 @@ px4_add_board(
|
|||
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
|
||||
)
|
|
@ -1,82 +0,0 @@
|
|||
|
||||
px4_add_board(
|
||||
VENDOR px4
|
||||
MODEL raspberrypi
|
||||
LABEL native
|
||||
PLATFORM posix
|
||||
TESTING
|
||||
DRIVERS
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
imu/mpu9250
|
||||
linux_pwm_out
|
||||
linux_sbus
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
pwm_out_sim
|
||||
rpi_rc_in
|
||||
#telemetry # all available telemetry drivers
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
#simulator
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
dyn
|
||||
esc_calib
|
||||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
bottle_drop # OBC challenge
|
||||
dyn_hello # dynamically loading modules example
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
#hwtest # Hardware test
|
||||
#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
|
||||
)
|
Loading…
Reference in New Issue