From 02a9e3a6e22f0b8802d5fa28bdef78ba46e302b9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 4 Mar 2024 21:48:36 +0100 Subject: [PATCH] Use Eigen CMake target (#190) --- CMakeLists.txt | 8 +++++--- package.xml | 3 ++- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7d3a2c73..9786821c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -51,12 +51,11 @@ set(CONTROL_FILTERS_INCLUDE_DEPENDS generate_parameter_library pluginlib geometry_msgs - Eigen3 ) - foreach(Dependency IN ITEMS ${CONTROL_FILTERS_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() +find_package(Eigen3 REQUIRED NO_MODULE) generate_parameter_library( low_pass_filter_parameters @@ -72,7 +71,10 @@ target_include_directories(low_pass_filter PUBLIC $ $ ) -target_link_libraries(low_pass_filter PUBLIC low_pass_filter_parameters) +target_link_libraries(low_pass_filter PUBLIC + low_pass_filter_parameters + Eigen3::Eigen +) ament_target_dependencies(low_pass_filter PUBLIC ${CONTROL_FILTERS_INCLUDE_DEPENDS}) # Install pluginlib xml diff --git a/package.xml b/package.xml index bc977f55..b47371a3 100644 --- a/package.xml +++ b/package.xml @@ -19,10 +19,11 @@ ament_cmake control_msgs + eigen filters + generate_parameter_library geometry_msgs pluginlib - generate_parameter_library rclcpp rcutils realtime_tools