Skip to content

Commit 5090e3f

Browse files
rhaschkeDLu
andauthored
Fix dependencies (#262)
* Remove deprecated ament_target_dependencies() * Cleanup dependencies: only tests depend on Boost::filesystem Co-authored-by: David V. Lu <[email protected]>
1 parent 9085661 commit 5090e3f

File tree

3 files changed

+24
-44
lines changed

3 files changed

+24
-44
lines changed

CMakeLists.txt

Lines changed: 16 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,6 @@ find_package(resource_retriever REQUIRED)
5353
find_package(shape_msgs REQUIRED)
5454
find_package(visualization_msgs REQUIRED)
5555
find_package(fcl REQUIRED)
56-
include(ConfigExtras)
5756

5857
set(THIS_PACKAGE_EXPORT_DEPENDS
5958
eigen3_cmake_module
@@ -90,15 +89,25 @@ target_compile_options(${PROJECT_NAME} PRIVATE ${PROJECT_COMPILE_OPTIONS})
9089
target_include_directories(${PROJECT_NAME}
9190
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
9291
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>)
93-
ament_target_dependencies(${PROJECT_NAME} PUBLIC
94-
${THIS_PACKAGE_EXPORT_DEPENDS}
95-
)
9692
# Private libraries that are not transitively needed by downstream projects
97-
target_link_libraries(${PROJECT_NAME} PRIVATE assimp::assimp fcl ${QHULL_LIBRARIES})
93+
target_link_libraries(${PROJECT_NAME}
94+
PRIVATE
95+
assimp::assimp
96+
fcl
97+
${QHULL_LIBRARIES}
98+
PUBLIC
99+
${geometry_msgs_TARGETS}
100+
${shape_msgs_TARGETS}
101+
${visualization_msgs_TARGETS}
102+
${console_bridge_TARGETS}
103+
eigen_stl_containers::eigen_stl_containers
104+
random_numbers::random_numbers
105+
rclcpp::rclcpp
106+
resource_retriever::resource_retriever
107+
)
98108
target_include_directories(${PROJECT_NAME} PRIVATE ${QHULL_INCLUDE_DIRS})
99109

100110
if(BUILD_TESTING)
101-
find_package(ament_cmake_gtest REQUIRED)
102111
# Unit tests
103112
add_subdirectory(test)
104113

@@ -120,4 +129,4 @@ install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})
120129
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
121130
ament_export_dependencies(${THIS_PACKAGE_EXPORT_DEPENDS})
122131

123-
ament_package(CONFIG_EXTRAS "cmake/ConfigExtras.cmake")
132+
ament_package()

cmake/ConfigExtras.cmake

Lines changed: 0 additions & 31 deletions
This file was deleted.

test/CMakeLists.txt

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,6 @@
1+
find_package(Boost REQUIRED COMPONENTS filesystem)
2+
find_package(ament_cmake_gtest REQUIRED)
3+
14
file(TO_NATIVE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/resources" TEST_RESOURCES_DIR)
25
if(WIN32)
36
# Correct directory separator for Windows
@@ -8,13 +11,12 @@ include_directories(${CMAKE_CURRENT_BINARY_DIR})
811

912
ament_add_gtest(test_basics test_basics.cpp)
1013
target_link_libraries(test_basics ${PROJECT_NAME})
11-
ament_target_dependencies(test_basics Eigen3)
1214

1315
ament_add_gtest(test_point_inclusion test_point_inclusion.cpp)
14-
target_link_libraries(test_point_inclusion ${PROJECT_NAME})
16+
target_link_libraries(test_point_inclusion ${PROJECT_NAME} Boost::filesystem)
1517

1618
ament_add_gtest(test_bounding_sphere test_bounding_sphere.cpp)
17-
target_link_libraries(test_bounding_sphere ${PROJECT_NAME})
19+
target_link_libraries(test_bounding_sphere ${PROJECT_NAME} Boost::filesystem)
1820

1921
ament_add_gtest(test_bounding_box test_bounding_box.cpp)
2022
target_link_libraries(test_bounding_box ${PROJECT_NAME})
@@ -26,13 +28,13 @@ ament_add_gtest(test_create_mesh test_create_mesh.cpp)
2628
target_link_libraries(test_create_mesh ${PROJECT_NAME})
2729

2830
ament_add_gtest(test_loaded_meshes test_loaded_meshes.cpp)
29-
target_link_libraries(test_loaded_meshes ${PROJECT_NAME})
31+
target_link_libraries(test_loaded_meshes ${PROJECT_NAME} Boost::filesystem)
3032

3133
ament_add_gtest(test_shapes test_shapes.cpp)
3234
target_link_libraries(test_shapes ${PROJECT_NAME})
3335

3436
ament_add_gtest(test_ray_intersection test_ray_intersection.cpp)
35-
target_link_libraries(test_ray_intersection ${PROJECT_NAME})
37+
target_link_libraries(test_ray_intersection ${PROJECT_NAME} Boost::filesystem)
3638

3739
ament_add_gtest(test_body_operations test_body_operations.cpp)
38-
target_link_libraries(test_body_operations ${PROJECT_NAME})
40+
target_link_libraries(test_body_operations ${PROJECT_NAME} Boost::filesystem)

0 commit comments

Comments
 (0)