Skip to content

Commit

Permalink
Use CMake target for eigen
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Feb 25, 2024
1 parent 219a121 commit 7f14732
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion admittance_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
control_msgs
control_toolbox
controller_interface
Eigen3
generate_parameter_library
geometry_msgs
hardware_interface
Expand All @@ -34,6 +33,7 @@ find_package(backward_ros REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()
find_package(Eigen3 REQUIRED NO_MODULE)

generate_parameter_library(admittance_controller_parameters
src/admittance_controller_parameters.yaml
Expand All @@ -49,6 +49,7 @@ target_include_directories(admittance_controller PUBLIC
)
target_link_libraries(admittance_controller PUBLIC
admittance_controller_parameters
Eigen3::Eigen
)
ament_target_dependencies(admittance_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

Expand Down

0 comments on commit 7f14732

Please sign in to comment.