From 060f22892461659d04d6f8117d86f74c6840cb0f Mon Sep 17 00:00:00 2001 From: Oskar Roesler Date: Sat, 1 Jun 2019 11:56:06 +0200 Subject: [PATCH] Removed boost signals from CMakeLists.txt With boost=>1.69 there `signals` isn't available anymore. As it's not necessary, it should be removed to be compatible to all boost versions. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9af5eefd..6aff5997 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,7 +9,7 @@ set(THIS_PACKAGE_ROS_DEPS sensor_msgs roscpp tf filters message_filters laser_geometry pluginlib angles) find_package(catkin REQUIRED COMPONENTS ${THIS_PACKAGE_ROS_DEPS}) -find_package(Boost REQUIRED COMPONENTS system signals) +find_package(Boost REQUIRED COMPONENTS system) include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) ##############################################################################