From 9926f0997b5d8a68768dfd0745585ffe27e09162 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 20 Jan 2022 09:09:01 -0800 Subject: [PATCH] Remove traces of rcutils Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 - src/DepthImageToLaserScanROS.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9cd1d75..1fbd8d4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -40,7 +40,6 @@ add_library(DepthImageToLaserScanROS target_link_libraries(DepthImageToLaserScanROS PUBLIC rclcpp::rclcpp) target_link_libraries(DepthImageToLaserScanROS PRIVATE - rcutils::rcutils rclcpp_components::component) target_link_libraries(DepthImageToLaserScanROS PUBLIC diff --git a/src/DepthImageToLaserScanROS.cpp b/src/DepthImageToLaserScanROS.cpp index 945a662..ae435b7 100644 --- a/src/DepthImageToLaserScanROS.cpp +++ b/src/DepthImageToLaserScanROS.cpp @@ -37,7 +37,6 @@ #include #include -#include #include #include #include