From 4ff9bd7c380921e8089c138927642908c379d821 Mon Sep 17 00:00:00 2001 From: Michael Ferguson Date: Mon, 30 Jul 2018 19:57:14 -0400 Subject: [PATCH] fix rotate_recovery debian build * add depend on tf2_geometry_msgs (due to https://github.com/ros/geometry2/issues/275) * add other hidden depends: angles, geometry_msgs, tf2 --- rotate_recovery/CMakeLists.txt | 37 +++++++++++++++++++++------------- rotate_recovery/package.xml | 4 ++++ 2 files changed, 27 insertions(+), 14 deletions(-) diff --git a/rotate_recovery/CMakeLists.txt b/rotate_recovery/CMakeLists.txt index 0d22a902fe..e44dd4a787 100644 --- a/rotate_recovery/CMakeLists.txt +++ b/rotate_recovery/CMakeLists.txt @@ -2,15 +2,19 @@ cmake_minimum_required(VERSION 2.8.3) project(rotate_recovery) find_package(catkin REQUIRED - COMPONENTS - cmake_modules - roscpp - tf2_ros - costmap_2d - nav_core - pluginlib - base_local_planner - ) + COMPONENTS + angles + base_local_planner + cmake_modules + costmap_2d + geometry_msgs + nav_core + pluginlib + roscpp + tf2 + tf2_geometry_msgs + tf2_ros +) find_package(Eigen3 REQUIRED) include_directories( @@ -21,11 +25,16 @@ include_directories( add_definitions(${EIGEN3_DEFINITIONS}) catkin_package( - INCLUDE_DIRS include - LIBRARIES rotate_recovery - CATKIN_DEPENDS - roscpp - pluginlib + INCLUDE_DIRS include + LIBRARIES rotate_recovery + CATKIN_DEPENDS + costmap_2d + geometry_msgs + nav_core + pluginlib + roscpp + tf2 + tf2_ros ) add_library(rotate_recovery src/rotate_recovery.cpp) diff --git a/rotate_recovery/package.xml b/rotate_recovery/package.xml index 6663548c69..04fd176dd8 100644 --- a/rotate_recovery/package.xml +++ b/rotate_recovery/package.xml @@ -18,14 +18,18 @@ catkin + angles base_local_planner cmake_modules costmap_2d eigen + geometry_msgs nav_core pluginlib roscpp + tf2 + tf2_geometry_msgs tf2_ros