diff --git a/.travis.yml b/.travis.yml
index 1375a0c7..ea26fd7f 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -13,15 +13,14 @@ notifications:
- 130s@2000.jukuin.keio.ac.jp
env:
global:
- - ROS_DISTRO=dashing
+ - ROS_DISTRO=foxy
- ROS_REPO=ros
- UPSTREAM_WORKSPACE=geometric_shapes.repos
- CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter"
- WARNINGS_OK=false
matrix:
- - TEST="clang-format, ament_lint"
- - ROS_DISTRO=dashing
- - ROS_DISTRO=eloquent TEST=code-coverage
+ - TEST="ament_lint" # TODO(henningkayser): re-enable clang-format
+ - ROS_DISTRO=foxy TEST=code-coverage
matrix:
include:
diff --git a/CMakeLists.txt b/CMakeLists.txt
index a940d636..acc008c4 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -13,6 +13,9 @@ if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release)
endif()
+# TODO(henningkayser): Remove policy fix when assimp 5.1 is available
+# Suppress policy warning in assimp (https://github.com/assimp/assimp/pull/2722)
+set(CMAKE_POLICY_DEFAULT_CMP0012 NEW)
find_package(ASSIMP QUIET)
if(NOT ASSIMP_FOUND)
find_package(PkgConfig REQUIRED)
@@ -29,10 +32,11 @@ set(ASSIMP_LIBRARIES "${ASSIMP_ABS_LIBRARIES}")
find_package(rclcpp REQUIRED)
find_package(Boost REQUIRED system filesystem)
+find_package(console_bridge_vendor REQUIRED)
find_package(console_bridge REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
-find_package(octomap REQUIRED)
+find_package(OCTOMAP REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(eigen_stl_containers REQUIRED)
find_package(random_numbers REQUIRED)
@@ -68,7 +72,7 @@ ament_target_dependencies(${PROJECT_NAME}
geometry_msgs
resource_retriever
console_bridge
- octomap
+ OCTOMAP
ASSIMP
QHULL
)
@@ -79,15 +83,11 @@ ament_export_dependencies(
Eigen3
eigen3_cmake_module # export Eigen3 headers
Boost
- ASSIMP
random_numbers
eigen_stl_containers
shape_msgs
visualization_msgs
-)
-target_link_libraries(${PROJECT_NAME}
-# resource_retriever doesn't support ament export hook (fixed in 2.1.1)
- resource_retriever::resource_retriever
+ OCTOMAP
)
if(BUILD_TESTING)
diff --git a/README.md b/README.md
index fbcf8a23..ecfbc2a1 100644
--- a/README.md
+++ b/README.md
@@ -21,8 +21,11 @@ Note: `bodies::ConvexMesh::MeshData` was made implementation-private and is no l
## Build Status
-Travis CI: [![Build Status](https://travis-ci.org/ros-planning/geometric_shapes.svg?branch=melodic-devel)](https://travis-ci.org/ros-planning/geometric_shapes)
+Travis CI: [![Build Status](https://travis-ci.com/ros-planning/geometric_shapes.svg?branch=ros2)](https://travis-ci.com/ros-planning/geometric_shapes)
+
diff --git a/geometric_shapes.repos b/geometric_shapes.repos
index a6f2b725..eb141c1c 100644
--- a/geometric_shapes.repos
+++ b/geometric_shapes.repos
@@ -2,7 +2,7 @@ repositories:
geometric_shapes:
type: git
url: https://github.com/ros-planning/geometric_shapes
- version: dashing-devel
+ version: ros2
random_numbers:
type: git
url: https://github.com/ros-planning/random_numbers
diff --git a/package.xml b/package.xml
index 4d7b1a8d..e0e7f0c3 100644
--- a/package.xml
+++ b/package.xml
@@ -28,7 +28,7 @@
rclcpp
boost
eigen_stl_containers
- libconsole-bridge-dev
+ console_bridge_vendor
libqhull
octomap
random_numbers