diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 72a76777b5..ce91c28518 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -16,7 +16,7 @@ pipeline { ] def armhf_builds = [ - target: ["aerotenna_ocpoc_default", "emlid_navio2_cross", "parrot_bebop_default", "px4_raspberrypi_cross"], + target: ["aerotenna_ocpoc_default", "beaglebone_blue_cross", "emlid_navio2_cross", "parrot_bebop_default", "px4_raspberrypi_cross"], image: docker_images.armhf, archive: false ] diff --git a/CMakeLists.txt b/CMakeLists.txt index cee32f30bd..9f101a6050 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -295,6 +295,13 @@ include(px4_add_common_flags) px4_add_common_flags() px4_os_add_flags() +#============================================================================= +# board cmake init (optional) +# +if(EXISTS ${PX4_BOARD_DIR}/init.cmake) + include(${PX4_BOARD_DIR}/init.cmake) +endif() + #============================================================================= # message, and airframe generation # diff --git a/Tools/docker_run.sh b/Tools/docker_run.sh index bb5ac6c9bf..1283499212 100755 --- a/Tools/docker_run.sh +++ b/Tools/docker_run.sh @@ -5,12 +5,12 @@ if [ -z ${PX4_DOCKER_REPO+x} ]; then if [[ $@ =~ .*px4_fmu.* ]]; 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 + PX4_DOCKER_REPO="px4io/px4-dev-armhf:2019-10-24" elif [[ $@ =~ .*eagle.* ]] || [[ $@ =~ .*excelsior.* ]]; then # eagle, excelsior PX4_DOCKER_REPO="lorenzmeier/px4-dev-snapdragon:2018-09-12" - elif [[ $@ =~ .*ocpoc.* ]] || [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*bebop.* ]]; then - # aerotenna_ocpoc_default, posix_rpi_cross, posix_bebop_default - PX4_DOCKER_REPO="px4io/px4-dev-armhf:2019-10-24" elif [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then # clang tools PX4_DOCKER_REPO="px4io/px4-dev-clang:2019-10-24" diff --git a/boards/beaglebone/blue/CMakeLists.txt b/boards/beaglebone/blue/CMakeLists.txt index 479f6d55c4..af45ca77f5 100644 --- a/boards/beaglebone/blue/CMakeLists.txt +++ b/boards/beaglebone/blue/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2018 PX4 Development Team. All rights reserved. +# Copyright (c) 2018-2019 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 @@ -33,7 +33,6 @@ add_subdirectory(bbblue_adc) - ############################################################################ # Upload ############################################################################ diff --git a/boards/beaglebone/blue/bbblue_adc/CMakeLists.txt b/boards/beaglebone/blue/bbblue_adc/CMakeLists.txt index f7c6fec3de..a4e43acb79 100644 --- a/boards/beaglebone/blue/bbblue_adc/CMakeLists.txt +++ b/boards/beaglebone/blue/bbblue_adc/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2018 PX4 Development Team. All rights reserved. +# Copyright (c) 2018-2019 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 @@ -35,17 +35,6 @@ px4_add_module( MODULE drivers__bbblue_adc MAIN bbblue_adc COMPILE_FLAGS - -Wno-error SRCS bbblue_adc.cpp - - # Previous board specific code is now precluded from build after - # the following was added to Frimware/CMakeLists.txt: - # - # add_subdirectory(src/drivers/boards EXCLUDE_FROM_ALL) - # - # so include bbblue board specific code here: - ../src/init.c - DEPENDS - ) diff --git a/boards/beaglebone/blue/cross.cmake b/boards/beaglebone/blue/cross.cmake index e9c6cdc7df..e503d181a7 100644 --- a/boards/beaglebone/blue/cross.cmake +++ b/boards/beaglebone/blue/cross.cmake @@ -11,6 +11,7 @@ px4_add_board( #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 diff --git a/boards/beaglebone/blue/init.cmake b/boards/beaglebone/blue/init.cmake new file mode 100644 index 0000000000..d42011bda9 --- /dev/null +++ b/boards/beaglebone/blue/init.cmake @@ -0,0 +1,56 @@ +############################################################################ +# +# Copyright (c) 2018-2019 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_compile_options(-Wno-cast-align) + +include(ExternalProject) +ExternalProject_Add(librobotcontrol + GIT_REPOSITORY https://github.com/dagar/librobotcontrol.git + GIT_TAG 1abcb0a # latest as of 2019-12-29 + CMAKE_CACHE_ARGS -DCMAKE_TOOLCHAIN_FILE:STRING=${CMAKE_TOOLCHAIN_FILE} + INSTALL_COMMAND "" + TEST_COMMAND "" + LOG_DOWNLOAD ON + LOG_CONFIGURE ON + LOG_BUILD ON +) + +ExternalProject_Get_Property(librobotcontrol install_dir) +set(ROBOTCONTROL_LIB_DIR ${install_dir}/src/librobotcontrol-build/library) +set(ROBOTCONTROL_INC_DIR ${install_dir}/src/librobotcontrol/library/include) + +include_directories(${ROBOTCONTROL_INC_DIR}) +link_directories(${ROBOTCONTROL_LIB_DIR}) + +# add to prebuild +add_dependencies(prebuild_targets librobotcontrol) diff --git a/boards/beaglebone/blue/native.cmake b/boards/beaglebone/blue/native.cmake index 1d1c12469c..074463b374 100644 --- a/boards/beaglebone/blue/native.cmake +++ b/boards/beaglebone/blue/native.cmake @@ -9,6 +9,7 @@ px4_add_board( #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 diff --git a/boards/beaglebone/blue/src/CMakeLists.txt b/boards/beaglebone/blue/src/CMakeLists.txt index 22a6c68ee6..f8245bbdf2 100644 --- a/boards/beaglebone/blue/src/CMakeLists.txt +++ b/boards/beaglebone/blue/src/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2018 PX4 Development Team. All rights reserved. +# Copyright (c) 2018-2019 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 @@ -30,10 +30,8 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ -set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-error") -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-error") -add_library(drivers_board - init.c +px4_add_library(drivers_board + init.cpp ) - +target_link_libraries(drivers_board PRIVATE robotics_cape) diff --git a/boards/beaglebone/blue/src/init.c b/boards/beaglebone/blue/src/init.cpp similarity index 100% rename from boards/beaglebone/blue/src/init.c rename to boards/beaglebone/blue/src/init.cpp diff --git a/platforms/posix/CMakeLists.txt b/platforms/posix/CMakeLists.txt index 131bbb305c..f3748094c5 100644 --- a/platforms/posix/CMakeLists.txt +++ b/platforms/posix/CMakeLists.txt @@ -108,7 +108,10 @@ endif() if ("${PX4_BOARD}" MATCHES "beaglebone_blue") - target_link_libraries(px4 PRIVATE robotcontrol) + target_link_libraries(px4 PRIVATE robotics_cape) + add_dependencies(df_driver_framework librobotcontrol) + add_dependencies(df_bmp280 librobotcontrol) + add_dependencies(df_mpu9250 librobotcontrol) elseif ("${PX4_BOARD}" MATCHES "sitl") diff --git a/platforms/posix/cmake/Toolchain-arm-linux-gnueabihf.cmake b/platforms/posix/cmake/Toolchain-arm-linux-gnueabihf.cmake index 9f68b2202c..9fc154b61a 100644 --- a/platforms/posix/cmake/Toolchain-arm-linux-gnueabihf.cmake +++ b/platforms/posix/cmake/Toolchain-arm-linux-gnueabihf.cmake @@ -1,6 +1,7 @@ # arm-linux-gnueabihf-gcc toolchain set(CMAKE_SYSTEM_NAME Linux) +set(CMAKE_SYSTEM_PROCESSOR arm) set(CMAKE_SYSTEM_VERSION 1) set(triple arm-linux-gnueabihf) @@ -13,16 +14,18 @@ set(CMAKE_C_COMPILER_TARGET ${triple}) set(CMAKE_CXX_COMPILER ${TOOLCHAIN_PREFIX}-g++) set(CMAKE_CXX_COMPILER_TARGET ${triple}) -set(CMAKE_ASM_COMPILER ${CMAKE_C_COMPILER}) +set(CMAKE_ASM_COMPILER ${TOOLCHAIN_PREFIX}-gcc) # compiler tools -foreach(tool nm ld objcopy ranlib strip) - string(TOUPPER ${tool} TOOL) - find_program(CMAKE_${TOOL} ${TOOLCHAIN_PREFIX}-${tool}) - if(CMAKE-${TOOL} MATCHES "NOTFOUND") - message(FATAL_ERROR "could not find ${TOOLCHAIN_PREFIX}-${tool}") - endif() -endforeach() +find_program(CMAKE_AR ${TOOLCHAIN_PREFIX}-gcc-ar) +find_program(CMAKE_GDB ${TOOLCHAIN_PREFIX}-gdb) +find_program(CMAKE_LD ${TOOLCHAIN_PREFIX}-ld) +find_program(CMAKE_LINKER ${TOOLCHAIN_PREFIX}-ld) +find_program(CMAKE_NM ${TOOLCHAIN_PREFIX}-gcc-nm) +find_program(CMAKE_OBJCOPY ${TOOLCHAIN_PREFIX}-objcopy) +find_program(CMAKE_OBJDUMP ${TOOLCHAIN_PREFIX}-objdump) +find_program(CMAKE_RANLIB ${TOOLCHAIN_PREFIX}-gcc-ranlib) +find_program(CMAKE_STRIP ${TOOLCHAIN_PREFIX}-strip) set(CMAKE_FIND_ROOT_PATH get_file_component(${CMAKE_C_COMPILER} PATH)) set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) @@ -37,9 +40,3 @@ foreach(tool grep make) message(FATAL_ERROR "could not find ${tool}") endif() endforeach() - -# optional compiler tools -foreach(tool gdb gdbtui) - string(TOUPPER ${tool} TOOL) - find_program(${TOOL} ${TOOLCHAIN_PREFIX}-${tool}) -endforeach() diff --git a/platforms/posix/cmake/px4_impl_os.cmake b/platforms/posix/cmake/px4_impl_os.cmake index e88a584bac..b320ef5046 100644 --- a/platforms/posix/cmake/px4_impl_os.cmake +++ b/platforms/posix/cmake/px4_impl_os.cmake @@ -309,17 +309,6 @@ function(px4_os_add_flags) -DRC_AUTOPILOT_EXT # Enable extensions in Robotics Cape Library, TODO: remove ) - set(LIBROBOTCONTROL_INSTALL_DIR $ENV{LIBROBOTCONTROL_INSTALL_DIR}) - - # On cross compile host system and native build system: - # a) select and define LIBROBOTCONTROL_INSTALL_DIR environment variable so that - # other unwanted headers will not be included - # b) install robotcontrol.h and rc/* into $LIBROBOTCONTROL_INSTALL_DIR/include - # c) install pre-built native (ARM) version of librobotcontrol.* into $LIBROBOTCONTROL_INSTALL_DIR/lib - add_compile_options(-I${LIBROBOTCONTROL_INSTALL_DIR}/include) - - set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -L${LIBROBOTCONTROL_INSTALL_DIR}/lib") - endif() endfunction() diff --git a/src/drivers/barometer/bmp280/bmp280.h b/src/drivers/barometer/bmp280/bmp280.h index 55bdcfe721..c08a596d62 100644 --- a/src/drivers/barometer/bmp280/bmp280.h +++ b/src/drivers/barometer/bmp280/bmp280.h @@ -38,6 +38,8 @@ */ #pragma once +#include + #define BMP280_ADDR_CAL 0x88 /* address of 12x 2 bytes calibration data */ #define BMP280_ADDR_DATA 0xF7 /* address of 2x 3 bytes p-t data */