Skip to content

Commit

Permalink
Use find_package for fcl (moveit#2399)
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw authored and m-elwin committed Dec 4, 2023
1 parent cd84de7 commit f02d8b7
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 11 deletions.
12 changes: 2 additions & 10 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,14 @@ project(moveit_core LANGUAGES CXX)
find_package(moveit_common REQUIRED)
moveit_package()

find_package(PkgConfig REQUIRED)
pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0")
# replace LIBFCL_LIBRARIES with full paths to the libraries
set(LIBFCL_LIBRARIES_FULL "")
foreach(LIBFCL_LIBRARY ${LIBFCL_LIBRARIES})
find_library(${LIBFCL_LIBRARY}_LIB ${LIBFCL_LIBRARY} ${LIBFCL_LIBRARY_DIRS})
list(APPEND LIBFCL_LIBRARIES_FULL ${${LIBFCL_LIBRARY}_LIB})
endforeach()
set(LIBFCL_LIBRARIES "${LIBFCL_LIBRARIES_FULL}")

find_package(ament_cmake REQUIRED)
find_package(angles REQUIRED)
find_package(Bullet 2.87 REQUIRED)
find_package(common_interfaces REQUIRED)
find_package(eigen_stl_containers REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(fcl REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(geometric_shapes REQUIRED)
find_package(geometry_msgs REQUIRED)
Expand Down Expand Up @@ -148,6 +139,7 @@ ament_export_dependencies(
eigen_stl_containers
Eigen3
eigen3_cmake_module
fcl
generate_parameter_library
geometric_shapes
geometry_msgs
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection_fcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,11 @@ ament_target_dependencies(moveit_collision_detection_fcl
urdf
urdfdom
urdfdom_headers
LIBFCL
visualization_msgs
)
target_link_libraries(moveit_collision_detection_fcl
moveit_collision_detection
fcl
)

add_library(collision_detector_fcl_plugin SHARED src/collision_detector_fcl_plugin_loader.cpp)
Expand Down

0 comments on commit f02d8b7

Please sign in to comment.