Skip to content

Commit

Permalink
Copy FCL collision detection
Browse files Browse the repository at this point in the history
Switch to hpp-fcl

explicit namespace instead of using

Drop compatibility, suffix for createCollisionGeometry

# Conflicts:
#	moveit_core/CMakeLists.txt
#	moveit_core/package.xml
  • Loading branch information
sjahr committed Mar 11, 2024
1 parent dafa36f commit a61a190
Show file tree
Hide file tree
Showing 15 changed files with 2,613 additions and 0 deletions.
4 changes: 4 additions & 0 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ find_package(fcl REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(geometric_shapes REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(hpp-fcl REQUIRED)
find_package(kdl_parser REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(OCTOMAP REQUIRED)
Expand Down Expand Up @@ -44,6 +45,7 @@ include(ConfigExtras.cmake)

add_subdirectory(collision_detection_bullet)
add_subdirectory(collision_detection_fcl)
add_subdirectory(collision_detection_hpp_fcl)
add_subdirectory(collision_detection)
add_subdirectory(collision_distance_field)
add_subdirectory(constraint_samplers)
Expand Down Expand Up @@ -76,6 +78,7 @@ install(
moveit_collision_detection
moveit_collision_detection_bullet
moveit_collision_detection_fcl
moveit_collision_detection_hpp_fcl
moveit_collision_distance_field
moveit_constraint_samplers
moveit_distance_field
Expand Down Expand Up @@ -109,6 +112,7 @@ ament_export_dependencies(
Eigen3
eigen3_cmake_module
fcl
hpp-fcl
generate_parameter_library
geometric_shapes
geometry_msgs
Expand Down
40 changes: 40 additions & 0 deletions moveit_core/collision_detection_hpp_fcl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
set(MOVEIT_LIB_NAME moveit_collision_detection_hpp_fcl)

add_library(${MOVEIT_LIB_NAME}
src/collision_common.cpp
src/collision_env_hpp_fcl.cpp
)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

target_link_libraries(${MOVEIT_LIB_NAME} moveit_collision_detection ${catkin_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} hpp-fcl::hpp-fcl ${Boost_LIBRARIES})
add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS})

add_library(collision_detector_hpp_fcl_plugin src/collision_detector_hpp_fcl_plugin_loader.cpp)
set_target_properties(collision_detector_hpp_fcl_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
target_link_libraries(collision_detector_hpp_fcl_plugin ${catkin_LIBRARIES} ${MOVEIT_LIB_NAME} moveit_planning_scene)


install(TARGETS ${MOVEIT_LIB_NAME} collision_detector_hpp_fcl_plugin
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})

install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})

install(FILES ../collision_detector_hpp_fcl_description.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

if(CATKIN_ENABLE_TESTING)
catkin_add_gtest(test_hpp_fcl_collision_detection test/test_fcl_collision_detection_pr2.cpp)
target_link_libraries(test_hpp_fcl_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME} ${Boost_LIBRARIES})
if(NOT CMAKE_CXX_COMPILER_ID STREQUAL "MSVC")
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
target_compile_options(test_hpp_fcl_collision_detection PRIVATE -Wno-deprecated-declarations)
endif()

catkin_add_gtest(test_hpp_fcl_collision_detection_panda test/test_fcl_collision_detection_panda.cpp)
target_link_libraries(test_hpp_fcl_collision_detection_panda moveit_test_utils ${MOVEIT_LIB_NAME} ${Boost_LIBRARIES})
if(NOT CMAKE_CXX_COMPILER_ID STREQUAL "MSVC")
# TODO: remove if transition to gtest's new API TYPED_TEST_SUITE_P is finished
target_compile_options(test_hpp_fcl_collision_detection_panda PRIVATE -Wno-deprecated-declarations)
endif()
endif()
Loading

0 comments on commit a61a190

Please sign in to comment.