From 2d84b65ca3d2fad2aee46632253e061459174927 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Mon, 3 Feb 2020 11:51:54 -0800 Subject: [PATCH] use target_include_directories Signed-off-by: Karsten Knese --- CMakeLists.txt | 21 ++++++++++----------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 46cc3615..58f958b1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,18 +17,17 @@ find_package(Eigen3 REQUIRED) # TODO(dhood): enable python support once ported to ROS 2 # catkin_python_setup() -include_directories(include - ${rclcpp_INCLUDE_DIRS} - ${sensor_msgs_INCLUDE_DIRS} - ${tf2_INCLUDE_DIRS} - ${Eigen3_INCLUDE_DIRS} -) - add_library(laser_geometry SHARED src/laser_geometry.cpp) -target_link_libraries(laser_geometry - ${rclcpp_LIBRARIES} - ${sensor_msgs_LIBRARIES} - ${tf2_LIBRARIES} +target_include_directories(laser_geometry + PUBLIC + $ + $ + ${Eigen3_INCLUDE_DIRS} +) +ament_target_dependencies(laser_geometry + "rclcpp" + "sensor_msgs" + "tf2" ) # Causes the visibility macros to use dllexport rather than dllimport,