From d0d994f5fb6377b4fcba8ad04bdd00dc81744739 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Thu, 5 Jul 2018 09:25:38 -0700 Subject: [PATCH] cartographer_ros doesnt depend on console_bridge ATM --- cartographer_ros/CMakeLists.txt | 1 - cartographer_ros/cartographer_ros/CMakeLists.txt | 1 - cartographer_ros/package.xml | 1 - 3 files changed, 3 deletions(-) diff --git a/cartographer_ros/CMakeLists.txt b/cartographer_ros/CMakeLists.txt index 8ccd6cee6..2079a8af0 100644 --- a/cartographer_ros/CMakeLists.txt +++ b/cartographer_ros/CMakeLists.txt @@ -51,7 +51,6 @@ find_package(visualization_msgs REQUIRED) include(FindPkgConfig) -find_package(console_bridge REQUIRED) find_package(LuaGoogle REQUIRED) find_package(PCL REQUIRED COMPONENTS common) find_package(Eigen3 REQUIRED) diff --git a/cartographer_ros/cartographer_ros/CMakeLists.txt b/cartographer_ros/cartographer_ros/CMakeLists.txt index 23738efa0..29aace42f 100644 --- a/cartographer_ros/cartographer_ros/CMakeLists.txt +++ b/cartographer_ros/cartographer_ros/CMakeLists.txt @@ -18,7 +18,6 @@ target_include_directories(cartographer_node SYSTEM PUBLIC ${LUA_INCLUDE_DIR}) target_link_libraries(cartographer_node ${PROJECT_NAME}) ament_target_dependencies(cartographer_node "cartographer_ros_msgs" - "console_bridge" "geometry_msgs" "nav_msgs" "pcl_conversions" diff --git a/cartographer_ros/package.xml b/cartographer_ros/package.xml index c659f586c..c60e8903b 100644 --- a/cartographer_ros/package.xml +++ b/cartographer_ros/package.xml @@ -40,7 +40,6 @@ cartographer cartographer_ros_msgs - console_bridge lua5.2-dev nav_msgs libpcl-all-dev