Skip to content

Commit

Permalink
travis_ci: Add OSX build
Browse files Browse the repository at this point in the history
  • Loading branch information
TSC21 authored and LorenzMeier committed Jun 16, 2018
1 parent 8a3166b commit b5a9209
Show file tree
Hide file tree
Showing 2 changed files with 71 additions and 25 deletions.
83 changes: 64 additions & 19 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,26 +1,71 @@
language: cpp

services:
- docker

cache:
ccache: true

env:
global:
- CCACHE_DIR=$HOME/.ccache
- PX4_DOCKER_REPO=px4io/px4-dev-ros:2018-04-22
- BUILD_WITH_CMAKE = "mkdir Build; cd Build; cmake ..; make"
- BUILD_WITH_CATKIN = "source /opt/ros/kinetic/setup.bash; mkdir -p ~/catkin_ws/src; cd ~/catkin_ws/src; catkin_init_workspace; ln -s ${TRAVIS_BUILD_DIR} .; cd ~/catkin_ws; catkin_make"
- VALIDATE_SDF_SCHEMAS = "source ./scripts/validate_sdf.bash"

matrix:
# Cmake build
- STEP=${BUILD_WITH_CMAKE}
# Catkin build
- STEP=${BUILD_WITH_CATKIN}
# Validate SDF schemas
- STEP=${VALIDATE_SDF_SCHEMAS}
matrix:
include:
- os: linux
language: cpp
services:
- docker
cache:
ccache: true
env: # Cmake build
- BUILD="mkdir Build; cd Build; cmake ..; make -j$(nproc) -l$(nproc)"
- os: linux
language: cpp
services:
- docker
cache:
ccache: true
env: # Catkin build
- BUILD="source /opt/ros/kinetic/setup.bash; mkdir -p ~/catkin_ws/src; cd ~/catkin_ws/src; catkin_init_workspace; ln -s ${TRAVIS_BUILD_DIR} .; cd ~/catkin_ws; catkin_make -j$(nproc) -l$(nproc)"
- os: linux
language: cpp
services:
- docker
cache:
ccache: true
env: # Validate SDF schemas
- BUILD="source ./scripts/validate_sdf.bash"
- os: osx
osx_image: xcode9.3
language: cpp
cache:
ccache: true
env:
- GAZEBO_VERSION="gazebo8"
- os: osx
osx_image: xcode9.3
language: cpp
cache:
ccache: true
env:
- GAZEBO_VERSION="gazebo9"

before_install:
- if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then
brew update;
git clone --depth 1 https://github.com/mavlink/c_library_v2.git /usr/local/include/mavlink/v2.0;
rm -rf /usr/local/include/mavlink/v2.0/.git;
fi

install:
- if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then
brew tap PX4/px4;
brew install px4-dev;
brew tap osrf/simulation;
brew install opencv ${GAZEBO_VERSION};
brew link --overwrite numpy;
brew cask reinstall xquartz java;
sudo -H pip2 install --upgrade pip setuptools;
sudo -H pip2 install rospkg pyserial empy toml numpy pandas jinja2;
fi

script:
- docker run -it --rm -w ${TRAVIS_BUILD_DIR} --env=CCACHE_DIR="${CCACHE_DIR}" --env=LOCAL_USER_ID="$(id -u)" --volume=${CCACHE_DIR}:${CCACHE_DIR}:rw --volume=${TRAVIS_BUILD_DIR}:${TRAVIS_BUILD_DIR}:rw ${PX4_DOCKER_REPO} /bin/bash -e -c "${STEP}"
- if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then
mkdir Build;
cd Build && cmake .. && make -j$(sysctl -n hw.physicalcpu) -l$(sysctl -n hw.physicalcpu);
else docker run -it --rm -w ${TRAVIS_BUILD_DIR} --env=CCACHE_DIR="${CCACHE_DIR}" --env=LOCAL_USER_ID="$(id -u)" --volume=${CCACHE_DIR}:${CCACHE_DIR}:rw --volume=${TRAVIS_BUILD_DIR}:${TRAVIS_BUILD_DIR}:rw ${PX4_DOCKER_REPO} /bin/bash -e -c "${BUILD}";
fi
13 changes: 7 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8.3 FATAL_ERROR)
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
cmake_policy(SET CMP0042 NEW)
cmake_policy(SET CMP0048 NEW)
cmake_policy(SET CMP0054 NEW)
Expand All @@ -25,7 +25,7 @@ option(BUILD_GSTREAMER_PLUGIN "enable gstreamer plugin" "OFF")
option(BUILD_ROS_INTERFACE "Enable building ROS dependent plugins" "OFF")

## System dependencies are found with CMake's conventions
find_package(Boost 1.40 REQUIRED COMPONENTS system thread timer)
find_package(Boost 1.58 REQUIRED COMPONENTS system thread timer)
find_package(gazebo REQUIRED)
find_package(PkgConfig REQUIRED)
find_program(px4 REQUIRED)
Expand Down Expand Up @@ -287,10 +287,6 @@ add_library(gazebo_motor_model SHARED src/gazebo_motor_model.cpp)
add_library(gazebo_multirotor_base_plugin SHARED src/gazebo_multirotor_base_plugin.cpp)
#add_library(gazebo_wind_plugin SHARED src/gazebo_wind_plugin.cpp)

target_link_libraries(gazebo_gimbal_controller_plugin ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${Boost_SYSTEM_LIBRARY_RELEASE} ${Boost_THREAD_LIBRARY_RELEASE} ${TinyXML_LIBRARIES})
target_link_libraries(gazebo_opticalflow_plugin ${OpticalFlow_LIBS})
target_link_libraries(gazebo_mavlink_interface ${TinyXML_LIBRARIES})

set(plugins
gazebo_geotagged_images_plugin
gazebo_gps_plugin
Expand All @@ -309,6 +305,11 @@ set(plugins
#gazebo_wind_plugin
)

foreach(plugin ${plugins})
target_link_libraries(${plugin} ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${TinyXML_LIBRARIES})
endforeach()
target_link_libraries(gazebo_opticalflow_plugin ${OpticalFlow_LIBS})

# If BUILD_ROS_INTERFACE set to ON, build plugins that have ROS dependencies
# Current plugins that can be used with ROS interface: gazebo_motor_failure_plugin
if (BUILD_ROS_INTERFACE)
Expand Down

0 comments on commit b5a9209

Please sign in to comment.