From 43048336c34a01156dc216e8534ffb2788675ddf Mon Sep 17 00:00:00 2001 From: Jose Luis Rivero Date: Fri, 17 Nov 2017 14:11:24 +0100 Subject: [PATCH] C++ visibility support (take II) (#233) --- CMakeLists.txt | 9 ++- include/fcl/CMakeLists.txt | 10 +++ include/fcl/broadphase/broadphase_SSaP-inl.h | 4 +- include/fcl/broadphase/broadphase_SSaP.h | 2 +- include/fcl/broadphase/broadphase_SaP-inl.h | 2 +- include/fcl/broadphase/broadphase_SaP.h | 10 +-- .../broadphase/broadphase_bruteforce-inl.h | 2 +- .../fcl/broadphase/broadphase_bruteforce.h | 2 +- .../broadphase_collision_manager-inl.h | 2 +- .../broadphase/broadphase_collision_manager.h | 2 +- ...adphase_continuous_collision_manager-inl.h | 2 +- .../broadphase_continuous_collision_manager.h | 2 +- .../broadphase_dynamic_AABB_tree-inl.h | 34 +++++++- .../broadphase/broadphase_dynamic_AABB_tree.h | 2 +- .../broadphase_dynamic_AABB_tree_array-inl.h | 34 +++++++- .../broadphase_dynamic_AABB_tree_array.h | 2 +- .../broadphase/broadphase_interval_tree-inl.h | 2 +- .../fcl/broadphase/broadphase_interval_tree.h | 6 +- .../broadphase/broadphase_spatialhash-inl.h | 2 +- .../fcl/broadphase/broadphase_spatialhash.h | 2 +- .../fcl/broadphase/detail/hierarchy_tree.h | 2 +- .../broadphase/detail/hierarchy_tree_array.h | 2 +- include/fcl/broadphase/detail/interval_tree.h | 4 +- .../detail/interval_tree_node-inl.h | 2 +- .../broadphase/detail/interval_tree_node.h | 5 +- include/fcl/broadphase/detail/morton.h | 11 ++- .../fcl/broadphase/detail/simple_hash_table.h | 2 +- .../fcl/broadphase/detail/simple_interval.h | 4 +- .../fcl/broadphase/detail/sparse_hash_table.h | 4 +- include/fcl/broadphase/detail/spatial_hash.h | 2 +- include/fcl/common/deprecated.h | 67 --------------- include/fcl/common/detail/profiler.h | 11 +-- include/fcl/common/exception.h | 4 +- include/fcl/common/time.h | 4 + include/fcl/common/types.h | 4 +- include/fcl/geometry/bvh/BVH_model.h | 2 +- include/fcl/geometry/bvh/BVH_utility-inl.h | 3 + include/fcl/geometry/bvh/BVH_utility.h | 3 + include/fcl/geometry/bvh/BV_node.h | 2 +- include/fcl/geometry/bvh/BV_node_base.h | 2 +- include/fcl/geometry/bvh/detail/BVH_front.h | 4 +- include/fcl/geometry/bvh/detail/BV_fitter.h | 2 +- .../fcl/geometry/bvh/detail/BV_fitter_base.h | 2 +- include/fcl/geometry/bvh/detail/BV_splitter.h | 2 +- .../geometry/bvh/detail/BV_splitter_base.h | 2 +- include/fcl/geometry/collision_geometry-inl.h | 2 +- include/fcl/geometry/collision_geometry.h | 3 +- include/fcl/geometry/octree/octree-inl.h | 2 +- include/fcl/geometry/octree/octree.h | 3 +- include/fcl/geometry/shape/box-inl.h | 2 +- include/fcl/geometry/shape/box.h | 2 +- include/fcl/geometry/shape/capsule-inl.h | 2 +- include/fcl/geometry/shape/capsule.h | 2 +- include/fcl/geometry/shape/cone-inl.h | 2 +- include/fcl/geometry/shape/cone.h | 2 +- include/fcl/geometry/shape/convex-inl.h | 2 +- include/fcl/geometry/shape/convex.h | 2 +- include/fcl/geometry/shape/cylinder-inl.h | 2 +- include/fcl/geometry/shape/cylinder.h | 2 +- include/fcl/geometry/shape/ellipsoid-inl.h | 2 +- include/fcl/geometry/shape/ellipsoid.h | 2 +- include/fcl/geometry/shape/halfspace-inl.h | 2 +- include/fcl/geometry/shape/halfspace.h | 3 +- include/fcl/geometry/shape/plane-inl.h | 2 +- include/fcl/geometry/shape/plane.h | 3 +- include/fcl/geometry/shape/shape_base-inl.h | 2 +- include/fcl/geometry/shape/shape_base.h | 2 +- include/fcl/geometry/shape/sphere-inl.h | 2 +- include/fcl/geometry/shape/sphere.h | 2 +- include/fcl/geometry/shape/triangle_p-inl.h | 2 +- include/fcl/geometry/shape/triangle_p.h | 2 +- include/fcl/geometry/shape/utility-inl.h | 65 +++++++-------- include/fcl/geometry/shape/utility.h | 19 ++++- include/fcl/math/bv/AABB-inl.h | 2 +- include/fcl/math/bv/AABB.h | 2 +- include/fcl/math/bv/OBB-inl.h | 2 +- include/fcl/math/bv/OBB.h | 9 ++- include/fcl/math/bv/OBBRSS-inl.h | 2 +- include/fcl/math/bv/OBBRSS.h | 7 +- include/fcl/math/bv/RSS-inl.h | 2 +- include/fcl/math/bv/RSS.h | 10 ++- include/fcl/math/bv/kDOP-inl.h | 33 ++++++-- include/fcl/math/bv/kDOP.h | 6 +- include/fcl/math/bv/kIOS-inl.h | 2 +- include/fcl/math/bv/kIOS.h | 7 +- include/fcl/math/bv/utility-inl.h | 81 +++++++++++++------ include/fcl/math/bv/utility.h | 2 + include/fcl/math/constants.h | 2 +- include/fcl/math/detail/polysolver-inl.h | 2 +- include/fcl/math/detail/polysolver.h | 4 +- include/fcl/math/detail/project-inl.h | 2 +- include/fcl/math/detail/project.h | 2 +- include/fcl/math/detail/seed.h | 3 +- include/fcl/math/geometry-inl.h | 23 ++++++ include/fcl/math/geometry.h | 20 +++++ .../fcl/math/motion/bv_motion_bound_visitor.h | 2 +- include/fcl/math/motion/interp_motion-inl.h | 2 +- include/fcl/math/motion/interp_motion.h | 2 +- include/fcl/math/motion/motion_base-inl.h | 2 +- include/fcl/math/motion/screw_motion-inl.h | 2 +- include/fcl/math/motion/screw_motion.h | 2 +- include/fcl/math/motion/spline_motion-inl.h | 2 +- include/fcl/math/motion/spline_motion.h | 2 +- .../fcl/math/motion/taylor_model/interval.h | 4 +- .../motion/taylor_model/interval_matrix.h | 3 +- .../motion/taylor_model/interval_vector.h | 4 +- .../motion/taylor_model/taylor_matrix-inl.h | 2 +- .../math/motion/taylor_model/taylor_matrix.h | 9 ++- .../motion/taylor_model/taylor_model-inl.h | 2 +- .../math/motion/taylor_model/taylor_model.h | 8 +- .../motion/taylor_model/taylor_vector-inl.h | 2 +- .../math/motion/taylor_model/taylor_vector.h | 6 +- .../math/motion/taylor_model/time_interval.h | 2 +- .../math/motion/tbv_motion_bound_visitor.h | 2 +- .../fcl/math/motion/translation_motion-inl.h | 2 +- include/fcl/math/motion/translation_motion.h | 2 +- .../triangle_motion_bound_visitor-inl.h | 2 +- .../motion/triangle_motion_bound_visitor.h | 2 +- include/fcl/math/rng-inl.h | 2 +- include/fcl/math/rng.h | 2 +- include/fcl/math/sampler/sampler_base.h | 4 +- include/fcl/math/sampler/sampler_r.h | 2 +- include/fcl/math/sampler/sampler_se2-inl.h | 2 +- include/fcl/math/sampler/sampler_se2.h | 2 +- .../fcl/math/sampler/sampler_se2_disk-inl.h | 2 +- include/fcl/math/sampler/sampler_se2_disk.h | 2 +- .../fcl/math/sampler/sampler_se3_euler-inl.h | 2 +- include/fcl/math/sampler/sampler_se3_euler.h | 2 +- .../math/sampler/sampler_se3_euler_ball-inl.h | 2 +- .../fcl/math/sampler/sampler_se3_euler_ball.h | 2 +- .../fcl/math/sampler/sampler_se3_quat-inl.h | 2 +- include/fcl/math/sampler/sampler_se3_quat.h | 2 +- .../math/sampler/sampler_se3_quat_ball-inl.h | 2 +- .../fcl/math/sampler/sampler_se3_quat_ball.h | 2 +- include/fcl/math/triangle.h | 3 +- include/fcl/math/variance3-inl.h | 2 +- include/fcl/math/variance3.h | 2 +- include/fcl/narrowphase/collision-inl.h | 6 ++ include/fcl/narrowphase/collision.h | 2 + .../fcl/narrowphase/collision_object-inl.h | 2 +- include/fcl/narrowphase/collision_object.h | 2 +- include/fcl/narrowphase/collision_request.h | 2 +- include/fcl/narrowphase/collision_result.h | 2 +- include/fcl/narrowphase/contact.h | 2 +- include/fcl/narrowphase/contact_point.h | 4 +- .../narrowphase/continuous_collision-inl.h | 10 +++ .../fcl/narrowphase/continuous_collision.h | 4 + .../continuous_collision_object-inl.h | 2 +- .../narrowphase/continuous_collision_object.h | 2 +- .../continuous_collision_request.h | 3 +- .../narrowphase/continuous_collision_result.h | 2 +- include/fcl/narrowphase/cost_source.h | 2 +- .../detail/convexity_based_algorithm/epa.h | 2 +- .../detail/convexity_based_algorithm/gjk.h | 2 +- .../gjk_libccd-inl.h | 14 ++-- .../convexity_based_algorithm/gjk_libccd.h | 24 ++++-- .../minkowski_diff-inl.h | 1 + .../minkowski_diff.h | 2 +- .../fcl/narrowphase/detail/gjk_solver_indep.h | 3 +- .../narrowphase/detail/gjk_solver_libccd.h | 3 +- .../primitive_shape_algorithm/box_box.h | 6 ++ .../capsule_capsule.h | 3 + .../primitive_shape_algorithm/halfspace.h | 15 ++++ .../detail/primitive_shape_algorithm/plane.h | 14 ++++ .../sphere_capsule.h | 3 + .../sphere_sphere-inl.h | 4 + .../sphere_triangle.h | 6 ++ .../triangle_distance-inl.h | 2 +- .../triangle_distance.h | 2 +- .../collision/bvh_collision_traversal_node.h | 2 +- .../bvh_shape_collision_traversal_node.h | 2 +- .../collision_traversal_node_base-inl.h | 2 +- .../collision/collision_traversal_node_base.h | 2 +- .../traversal/collision/intersect-inl.h | 2 +- .../detail/traversal/collision/intersect.h | 2 +- .../mesh_collision_traversal_node-inl.h | 8 +- .../collision/mesh_collision_traversal_node.h | 17 ++-- ...mesh_continuous_collision_traversal_node.h | 5 +- .../mesh_shape_collision_traversal_node.h | 16 ++-- .../shape_bvh_collision_traversal_node.h | 2 +- .../shape_collision_traversal_node.h | 2 +- .../shape_mesh_collision_traversal_node-inl.h | 20 +++++ .../shape_mesh_collision_traversal_node.h | 15 ++-- .../detail/traversal/collision_node.h | 5 ++ .../distance/bvh_distance_traversal_node.h | 2 +- .../bvh_shape_distance_traversal_node.h | 2 +- .../conservative_advancement_stack_data.h | 2 +- .../distance_traversal_node_base-inl.h | 2 +- .../distance/distance_traversal_node_base.h | 2 +- ...servative_advancement_traversal_node-inl.h | 4 +- ..._conservative_advancement_traversal_node.h | 13 ++- .../mesh_distance_traversal_node-inl.h | 6 +- .../distance/mesh_distance_traversal_node.h | 18 +++-- ..._conservative_advancement_traversal_node.h | 6 +- .../mesh_shape_distance_traversal_node.h | 8 +- .../shape_bvh_distance_traversal_node.h | 2 +- ..._conservative_advancement_traversal_node.h | 2 +- .../distance/shape_distance_traversal_node.h | 2 +- ..._conservative_advancement_traversal_node.h | 6 +- .../shape_mesh_distance_traversal_node-inl.h | 4 + .../shape_mesh_distance_traversal_node.h | 8 +- .../mesh_octree_collision_traversal_node.h | 2 +- .../octree_collision_traversal_node.h | 2 +- .../octree_mesh_collision_traversal_node.h | 2 +- .../octree_shape_collision_traversal_node.h | 2 +- .../shape_octree_collision_traversal_node.h | 2 +- .../mesh_octree_distance_traversal_node.h | 2 +- .../distance/octree_distance_traversal_node.h | 2 +- .../octree_mesh_distance_traversal_node.h | 2 +- .../octree_shape_distance_traversal_node.h | 2 +- .../shape_octree_distance_traversal_node.h | 2 +- .../detail/traversal/octree/octree_solver.h | 2 +- .../traversal/traversal_node_base-inl.h | 2 +- .../detail/traversal/traversal_node_base.h | 2 +- .../detail/traversal/traversal_recurse-inl.h | 13 ++- .../detail/traversal/traversal_recurse.h | 7 ++ include/fcl/narrowphase/distance.h | 2 + include/fcl/narrowphase/distance_request.h | 2 +- include/fcl/narrowphase/distance_result-inl.h | 5 ++ include/fcl/narrowphase/distance_result.h | 2 +- src/CMakeLists.txt | 21 +++++ src/common/detail/profiler.cpp | 8 +- 222 files changed, 789 insertions(+), 400 deletions(-) delete mode 100644 include/fcl/common/deprecated.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 599d398e6..4f20b4e31 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -24,6 +24,9 @@ project(fcl CXX C) option(FCL_ENABLE_PROFILING "Enable profiling" OFF) option(FCL_TREAT_WARNINGS_AS_ERRORS "Treat warnings as errors" OFF) +# Option for some bundle-like build system in order not to expose +# any FCL binary symbols in their public ABI +option(FCL_HIDE_ALL_SYMBOLS "Hide all binary symbols" OFF) # set the default build type if (NOT MSVC AND NOT CMAKE_BUILD_TYPE) @@ -42,6 +45,7 @@ include(FCLMacros) include(CompilerSettings) include(FCLVersion) include(GNUInstallDirs) +include(GenerateExportHeader) if(MSVC OR IS_ICPC) option(FCL_STATIC_LIBRARY "Whether the FCL library should be static rather than shared" ON) @@ -229,13 +233,12 @@ else() message(STATUS "FCL does not use OctoMap (as requested)") endif() - # FCL's own include dir should be at the front of the include path include_directories(BEFORE "include") include_directories(BEFORE "${CMAKE_CURRENT_BINARY_DIR}/include") -add_subdirectory(include/fcl) add_subdirectory(src) +add_subdirectory(include/fcl) set(pkg_conf_file_in "${CMAKE_CURRENT_SOURCE_DIR}/fcl.pc.in") set(pkg_conf_file_out "${CMAKE_CURRENT_BINARY_DIR}/fcl.pc") @@ -261,7 +264,7 @@ add_custom_target(uninstall "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/CMakeModules/cmake_uninstall.cmake") option(FCL_BUILD_TESTS "Build FCL tests" ON) -if(FCL_BUILD_TESTS) +if(FCL_BUILD_TESTS AND NOT FCL_HIDE_ALL_SYMBOLS) enable_testing() add_subdirectory(test) endif() diff --git a/include/fcl/CMakeLists.txt b/include/fcl/CMakeLists.txt index 4fabdd95b..b07b0dff3 100644 --- a/include/fcl/CMakeLists.txt +++ b/include/fcl/CMakeLists.txt @@ -2,6 +2,16 @@ file(GLOB_RECURSE HEADERS ${CMAKE_CURRENT_SOURCE_DIR}/*.h) file(GLOB_RECURSE CONFIGURED_HEADERS ${CMAKE_CURRENT_BINARY_DIR}/*.h) set(FCL_HEADERS ${HEADERS} ${CONFIGURED_HEADERS} PARENT_SCOPE) +# Generate export header. There is no way of generating a file name +# called just export.h. Workaround using configure and remove +generate_export_header(${PROJECT_NAME}) +configure_file(${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}_export.h + ${CMAKE_CURRENT_BINARY_DIR}/export.h + COPYONLY) +file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}_export.h) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/fcl) + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config.h.in ${CMAKE_CURRENT_BINARY_DIR}/config.h) install(FILES ${CMAKE_CURRENT_BINARY_DIR}/config.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/fcl) diff --git a/include/fcl/broadphase/broadphase_SSaP-inl.h b/include/fcl/broadphase/broadphase_SSaP-inl.h index 7943dd7df..ad859ea86 100644 --- a/include/fcl/broadphase/broadphase_SSaP-inl.h +++ b/include/fcl/broadphase/broadphase_SSaP-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SSaPCollisionManager; +class FCL_EXPORT SSaPCollisionManager; /** @brief Functor sorting objects according to the AABB lower x bound */ template @@ -85,7 +85,7 @@ struct SortByZLow /** @brief Dummy collision object with a point AABB */ template -class DummyCollisionObject : public CollisionObject +class FCL_EXPORT DummyCollisionObject : public CollisionObject { public: DummyCollisionObject(const AABB& aabb_) : CollisionObject(std::shared_ptr>()) diff --git a/include/fcl/broadphase/broadphase_SSaP.h b/include/fcl/broadphase/broadphase_SSaP.h index 185b9a0c2..b0cc0a9df 100644 --- a/include/fcl/broadphase/broadphase_SSaP.h +++ b/include/fcl/broadphase/broadphase_SSaP.h @@ -46,7 +46,7 @@ namespace fcl /// @brief Simple SAP collision manager template -class SSaPCollisionManager : public BroadPhaseCollisionManager +class FCL_EXPORT SSaPCollisionManager : public BroadPhaseCollisionManager { public: SSaPCollisionManager(); diff --git a/include/fcl/broadphase/broadphase_SaP-inl.h b/include/fcl/broadphase/broadphase_SaP-inl.h index e64747222..7d201c7d3 100644 --- a/include/fcl/broadphase/broadphase_SaP-inl.h +++ b/include/fcl/broadphase/broadphase_SaP-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SaPCollisionManager; +class FCL_EXPORT SaPCollisionManager; //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_SaP.h b/include/fcl/broadphase/broadphase_SaP.h index 869e6a26b..8a6b611ab 100644 --- a/include/fcl/broadphase/broadphase_SaP.h +++ b/include/fcl/broadphase/broadphase_SaP.h @@ -48,7 +48,7 @@ namespace fcl /// @brief Rigorous SAP collision manager template -class SaPCollisionManager : public BroadPhaseCollisionManager +class FCL_EXPORT SaPCollisionManager : public BroadPhaseCollisionManager { public: @@ -119,10 +119,10 @@ class SaPCollisionManager : public BroadPhaseCollisionManager struct SaPPair; /// @brief Functor to help unregister one object - class isUnregistered; + class FCL_EXPORT isUnregistered; /// @brief Functor to help remove collision pairs no longer valid (i.e., should be culled away) - class isNotValidPair; + class FCL_EXPORT isNotValidPair; void update_(SaPAABB* updated_aabb); @@ -215,7 +215,7 @@ struct SaPCollisionManager::SaPPair /// @brief Functor to help unregister one object template -class SaPCollisionManager::isUnregistered +class FCL_EXPORT SaPCollisionManager::isUnregistered { CollisionObject* obj; @@ -227,7 +227,7 @@ class SaPCollisionManager::isUnregistered /// @brief Functor to help remove collision pairs no longer valid (i.e., should be culled away) template -class SaPCollisionManager::isNotValidPair +class FCL_EXPORT SaPCollisionManager::isNotValidPair { CollisionObject* obj1; CollisionObject* obj2; diff --git a/include/fcl/broadphase/broadphase_bruteforce-inl.h b/include/fcl/broadphase/broadphase_bruteforce-inl.h index a0765a2a3..0c92ace3f 100644 --- a/include/fcl/broadphase/broadphase_bruteforce-inl.h +++ b/include/fcl/broadphase/broadphase_bruteforce-inl.h @@ -46,7 +46,7 @@ namespace fcl { //============================================================================== extern template -class NaiveCollisionManager; +class FCL_EXPORT NaiveCollisionManager; //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_bruteforce.h b/include/fcl/broadphase/broadphase_bruteforce.h index 2f9179dea..f8ce6c52c 100644 --- a/include/fcl/broadphase/broadphase_bruteforce.h +++ b/include/fcl/broadphase/broadphase_bruteforce.h @@ -46,7 +46,7 @@ namespace fcl /// @brief Brute force N-body collision manager template -class NaiveCollisionManager : public BroadPhaseCollisionManager +class FCL_EXPORT NaiveCollisionManager : public BroadPhaseCollisionManager { public: NaiveCollisionManager(); diff --git a/include/fcl/broadphase/broadphase_collision_manager-inl.h b/include/fcl/broadphase/broadphase_collision_manager-inl.h index 1b5204bcf..e69f86c4f 100644 --- a/include/fcl/broadphase/broadphase_collision_manager-inl.h +++ b/include/fcl/broadphase/broadphase_collision_manager-inl.h @@ -46,7 +46,7 @@ namespace fcl { //============================================================================== extern template -class BroadPhaseCollisionManager; +class FCL_EXPORT BroadPhaseCollisionManager; //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_collision_manager.h b/include/fcl/broadphase/broadphase_collision_manager.h index c60c21569..c372c7a43 100644 --- a/include/fcl/broadphase/broadphase_collision_manager.h +++ b/include/fcl/broadphase/broadphase_collision_manager.h @@ -63,7 +63,7 @@ using DistanceCallBack = bool (*)( /// collision/distance between N objects. Also support self collision, self /// distance and collision/distance with another M objects. template -class BroadPhaseCollisionManager +class FCL_EXPORT BroadPhaseCollisionManager { public: BroadPhaseCollisionManager(); diff --git a/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h b/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h index c5dee1140..05ff0f804 100644 --- a/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h +++ b/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h @@ -46,7 +46,7 @@ namespace fcl { //============================================================================== extern template -class BroadPhaseContinuousCollisionManager; +class FCL_EXPORT BroadPhaseContinuousCollisionManager; //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_continuous_collision_manager.h b/include/fcl/broadphase/broadphase_continuous_collision_manager.h index 7cfa2156c..d0a043572 100644 --- a/include/fcl/broadphase/broadphase_continuous_collision_manager.h +++ b/include/fcl/broadphase/broadphase_continuous_collision_manager.h @@ -63,7 +63,7 @@ using ContinuousDistanceCallBack = bool (*)( /// accelerate the continuous collision/distance between N objects. Also support /// self collision, self distance and collision/distance with another M objects. template -class BroadPhaseContinuousCollisionManager +class FCL_EXPORT BroadPhaseContinuousCollisionManager { public: BroadPhaseContinuousCollisionManager(); diff --git a/include/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h b/include/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h index d48f85443..1a7341b5c 100644 --- a/include/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h +++ b/include/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h @@ -50,7 +50,7 @@ namespace fcl { //============================================================================== extern template -class DynamicAABBTreeCollisionManager; +class FCL_EXPORT DynamicAABBTreeCollisionManager; namespace detail { @@ -59,6 +59,7 @@ namespace dynamic_AABB_tree { #if FCL_HAVE_OCTOMAP //============================================================================== template +FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -170,6 +171,7 @@ bool collisionRecurse_( //============================================================================== template +FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -276,6 +278,7 @@ bool collisionRecurse_( //============================================================================== template +FCL_EXPORT bool distanceRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -366,6 +369,7 @@ bool distanceRecurse_( //============================================================================== template +FCL_EXPORT bool collisionRecurse( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -383,6 +387,7 @@ bool collisionRecurse( //============================================================================== template +FCL_EXPORT bool distanceRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -472,6 +477,7 @@ bool distanceRecurse_( //============================================================================== template +FCL_EXPORT bool distanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, const typename OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3& tf2, void* cdata, DistanceCallBack callback, S& min_dist) { if(tf2.linear().isIdentity()) @@ -484,6 +490,7 @@ bool distanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNod //============================================================================== template +FCL_EXPORT bool collisionRecurse( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root2, @@ -517,6 +524,7 @@ bool collisionRecurse( //============================================================================== template +FCL_EXPORT bool collisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, CollisionObject* query, void* cdata, CollisionCallBack callback) { if(root->isLeaf()) @@ -540,6 +548,7 @@ bool collisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNo //============================================================================== template +FCL_EXPORT bool selfCollisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, void* cdata, CollisionCallBack callback) { if(root->isLeaf()) return false; @@ -558,6 +567,7 @@ bool selfCollisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAA //============================================================================== template +FCL_EXPORT bool distanceRecurse( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root2, @@ -646,6 +656,7 @@ bool distanceRecurse( //============================================================================== template +FCL_EXPORT bool distanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, CollisionObject* query, void* cdata, DistanceCallBack callback, S& min_dist) { if(root->isLeaf()) @@ -691,6 +702,7 @@ bool distanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNod //============================================================================== template +FCL_EXPORT bool selfDistanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, void* cdata, DistanceCallBack callback, S& min_dist) { if(root->isLeaf()) return false; @@ -713,6 +725,7 @@ bool selfDistanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAAB //============================================================================== template +FCL_EXPORT DynamicAABBTreeCollisionManager::DynamicAABBTreeCollisionManager() : tree_topdown_balance_threshold(dtree.bu_threshold), tree_topdown_level(dtree.topdown_level) @@ -731,6 +744,7 @@ DynamicAABBTreeCollisionManager::DynamicAABBTreeCollisionManager() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::registerObjects( const std::vector*>& other_objs) { @@ -763,6 +777,7 @@ void DynamicAABBTreeCollisionManager::registerObjects( //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::registerObject(CollisionObject* obj) { DynamicAABBNode* node = dtree.insert(obj->getAABB(), obj); @@ -771,6 +786,7 @@ void DynamicAABBTreeCollisionManager::registerObject(CollisionObject* obj) //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::unregisterObject(CollisionObject* obj) { DynamicAABBNode* node = table[obj]; @@ -780,6 +796,7 @@ void DynamicAABBTreeCollisionManager::unregisterObject(CollisionObject* ob //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::setup() { if(!setup_) @@ -805,6 +822,7 @@ void DynamicAABBTreeCollisionManager::setup() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::update() { for(auto it = table.cbegin(); it != table.cend(); ++it) @@ -822,6 +840,7 @@ void DynamicAABBTreeCollisionManager::update() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::update_(CollisionObject* updated_obj) { const auto it = table.find(updated_obj); @@ -836,6 +855,7 @@ void DynamicAABBTreeCollisionManager::update_(CollisionObject* updated_obj //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::update(CollisionObject* updated_obj) { update_(updated_obj); @@ -844,6 +864,7 @@ void DynamicAABBTreeCollisionManager::update(CollisionObject* updated_obj) //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::update(const std::vector*>& updated_objs) { for(size_t i = 0, size = updated_objs.size(); i < size; ++i) @@ -853,6 +874,7 @@ void DynamicAABBTreeCollisionManager::update(const std::vector +FCL_EXPORT void DynamicAABBTreeCollisionManager::clear() { dtree.clear(); @@ -861,6 +883,7 @@ void DynamicAABBTreeCollisionManager::clear() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::getObjects(std::vector*>& objs) const { objs.resize(this->size()); @@ -869,6 +892,7 @@ void DynamicAABBTreeCollisionManager::getObjects(std::vector +FCL_EXPORT void DynamicAABBTreeCollisionManager::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -894,6 +918,7 @@ void DynamicAABBTreeCollisionManager::collide(CollisionObject* obj, void* //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::distance(CollisionObject* obj, void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -920,6 +945,7 @@ void DynamicAABBTreeCollisionManager::distance(CollisionObject* obj, void* //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::collide(void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -928,6 +954,7 @@ void DynamicAABBTreeCollisionManager::collide(void* cdata, CollisionCallBack< //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::distance(void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -937,6 +964,7 @@ void DynamicAABBTreeCollisionManager::distance(void* cdata, DistanceCallBack< //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::collide(BroadPhaseCollisionManager* other_manager_, void* cdata, CollisionCallBack callback) const { DynamicAABBTreeCollisionManager* other_manager = static_cast(other_manager_); @@ -946,6 +974,7 @@ void DynamicAABBTreeCollisionManager::collide(BroadPhaseCollisionManager* //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager::distance(BroadPhaseCollisionManager* other_manager_, void* cdata, DistanceCallBack callback) const { DynamicAABBTreeCollisionManager* other_manager = static_cast(other_manager_); @@ -956,6 +985,7 @@ void DynamicAABBTreeCollisionManager::distance(BroadPhaseCollisionManager* //============================================================================== template +FCL_EXPORT bool DynamicAABBTreeCollisionManager::empty() const { return dtree.empty(); @@ -963,6 +993,7 @@ bool DynamicAABBTreeCollisionManager::empty() const //============================================================================== template +FCL_EXPORT size_t DynamicAABBTreeCollisionManager::size() const { return dtree.size(); @@ -970,6 +1001,7 @@ size_t DynamicAABBTreeCollisionManager::size() const //============================================================================== template +FCL_EXPORT const detail::HierarchyTree>& DynamicAABBTreeCollisionManager::getTree() const { diff --git a/include/fcl/broadphase/broadphase_dynamic_AABB_tree.h b/include/fcl/broadphase/broadphase_dynamic_AABB_tree.h index bfe0ef6db..7ee6a333f 100644 --- a/include/fcl/broadphase/broadphase_dynamic_AABB_tree.h +++ b/include/fcl/broadphase/broadphase_dynamic_AABB_tree.h @@ -51,7 +51,7 @@ namespace fcl { template -class DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager +class FCL_EXPORT DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager { public: diff --git a/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h b/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h index e844a02bd..3cec23cbc 100644 --- a/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h +++ b/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h @@ -49,7 +49,7 @@ namespace fcl //============================================================================== extern template -class DynamicAABBTreeCollisionManager_Array; +class FCL_EXPORT DynamicAABBTreeCollisionManager_Array; namespace detail { @@ -61,6 +61,7 @@ namespace dynamic_AABB_tree_array //============================================================================== template +FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, @@ -174,6 +175,7 @@ bool collisionRecurse_( //============================================================================== template +FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, @@ -282,6 +284,7 @@ bool collisionRecurse_( //============================================================================== template +FCL_EXPORT bool distanceRecurse_(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, const OcTree* tree2, const typename OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3& tf2, void* cdata, DistanceCallBack callback, S& min_dist) { typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* root1 = nodes1 + root1_id; @@ -365,6 +368,7 @@ bool distanceRecurse_(typename DynamicAABBTreeCollisionManager_Array::Dynamic //============================================================================== template +FCL_EXPORT bool distanceRecurse_( typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, @@ -460,6 +464,7 @@ bool distanceRecurse_( //============================================================================== template +FCL_EXPORT bool collisionRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes2, size_t root2_id, void* cdata, CollisionCallBack callback) @@ -493,6 +498,7 @@ bool collisionRecurse(typename DynamicAABBTreeCollisionManager_Array::Dynamic //============================================================================== template +FCL_EXPORT bool collisionRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes, size_t root_id, CollisionObject* query, void* cdata, CollisionCallBack callback) { typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* root = nodes + root_id; @@ -517,6 +523,7 @@ bool collisionRecurse(typename DynamicAABBTreeCollisionManager_Array::Dynamic //============================================================================== template +FCL_EXPORT bool selfCollisionRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes, size_t root_id, void* cdata, CollisionCallBack callback) { typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* root = nodes + root_id; @@ -536,6 +543,7 @@ bool selfCollisionRecurse(typename DynamicAABBTreeCollisionManager_Array::Dyn //============================================================================== template +FCL_EXPORT bool distanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes2, size_t root2_id, void* cdata, DistanceCallBack callback, S& min_dist) @@ -623,6 +631,7 @@ bool distanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicA //============================================================================== template +FCL_EXPORT bool distanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes, size_t root_id, CollisionObject* query, void* cdata, DistanceCallBack callback, S& min_dist) { typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* root = nodes + root_id; @@ -669,6 +678,7 @@ bool distanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicA //============================================================================== template +FCL_EXPORT bool selfDistanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes, size_t root_id, void* cdata, DistanceCallBack callback, S& min_dist) { typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* root = nodes + root_id; @@ -691,6 +701,7 @@ bool selfDistanceRecurse(typename DynamicAABBTreeCollisionManager_Array::Dyna //============================================================================== template +FCL_EXPORT bool collisionRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, const OcTree* tree2, const typename OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3& tf2, void* cdata, CollisionCallBack callback) { if(tf2.linear().isIdentity()) @@ -701,6 +712,7 @@ bool collisionRecurse(typename DynamicAABBTreeCollisionManager_Array::Dynamic //============================================================================== template +FCL_EXPORT bool distanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, const OcTree* tree2, const typename OcTree::OcTreeNode* root2, const AABB& root2_bv, const Transform3& tf2, void* cdata, DistanceCallBack callback, S& min_dist) { if(tf2.linear().isIdentity()) @@ -717,6 +729,7 @@ bool distanceRecurse(typename DynamicAABBTreeCollisionManager_Array::DynamicA //============================================================================== template +FCL_EXPORT DynamicAABBTreeCollisionManager_Array::DynamicAABBTreeCollisionManager_Array() : tree_topdown_balance_threshold(dtree.bu_threshold), tree_topdown_level(dtree.topdown_level) @@ -735,6 +748,7 @@ DynamicAABBTreeCollisionManager_Array::DynamicAABBTreeCollisionManager_Array( //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::registerObjects( const std::vector*>& other_objs) { @@ -767,6 +781,7 @@ void DynamicAABBTreeCollisionManager_Array::registerObjects( //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::registerObject(CollisionObject* obj) { size_t node = dtree.insert(obj->getAABB(), obj); @@ -775,6 +790,7 @@ void DynamicAABBTreeCollisionManager_Array::registerObject(CollisionObject //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::unregisterObject(CollisionObject* obj) { size_t node = table[obj]; @@ -784,6 +800,7 @@ void DynamicAABBTreeCollisionManager_Array::unregisterObject(CollisionObject< //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::setup() { if(!setup_) @@ -809,6 +826,7 @@ void DynamicAABBTreeCollisionManager_Array::setup() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update() { for(auto it = table.cbegin(), end = table.cend(); it != end; ++it) @@ -826,6 +844,7 @@ void DynamicAABBTreeCollisionManager_Array::update() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update_(CollisionObject* updated_obj) { const auto it = table.find(updated_obj); @@ -840,6 +859,7 @@ void DynamicAABBTreeCollisionManager_Array::update_(CollisionObject* updat //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update(CollisionObject* updated_obj) { update_(updated_obj); @@ -848,6 +868,7 @@ void DynamicAABBTreeCollisionManager_Array::update(CollisionObject* update //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update(const std::vector*>& updated_objs) { for(size_t i = 0, size = updated_objs.size(); i < size; ++i) @@ -857,6 +878,7 @@ void DynamicAABBTreeCollisionManager_Array::update(const std::vector +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::clear() { dtree.clear(); @@ -865,6 +887,7 @@ void DynamicAABBTreeCollisionManager_Array::clear() //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::getObjects(std::vector*>& objs) const { objs.resize(this->size()); @@ -873,6 +896,7 @@ void DynamicAABBTreeCollisionManager_Array::getObjects(std::vector +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -898,6 +922,7 @@ void DynamicAABBTreeCollisionManager_Array::collide(CollisionObject* obj, //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::distance(CollisionObject* obj, void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -924,6 +949,7 @@ void DynamicAABBTreeCollisionManager_Array::distance(CollisionObject* obj, //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::collide(void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -932,6 +958,7 @@ void DynamicAABBTreeCollisionManager_Array::collide(void* cdata, CollisionCal //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::distance(void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -941,6 +968,7 @@ void DynamicAABBTreeCollisionManager_Array::distance(void* cdata, DistanceCal //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::collide(BroadPhaseCollisionManager* other_manager_, void* cdata, CollisionCallBack callback) const { DynamicAABBTreeCollisionManager_Array* other_manager = static_cast(other_manager_); @@ -950,6 +978,7 @@ void DynamicAABBTreeCollisionManager_Array::collide(BroadPhaseCollisionManage //============================================================================== template +FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::distance(BroadPhaseCollisionManager* other_manager_, void* cdata, DistanceCallBack callback) const { DynamicAABBTreeCollisionManager_Array* other_manager = static_cast(other_manager_); @@ -960,6 +989,7 @@ void DynamicAABBTreeCollisionManager_Array::distance(BroadPhaseCollisionManag //============================================================================== template +FCL_EXPORT bool DynamicAABBTreeCollisionManager_Array::empty() const { return dtree.empty(); @@ -967,6 +997,7 @@ bool DynamicAABBTreeCollisionManager_Array::empty() const //============================================================================== template +FCL_EXPORT size_t DynamicAABBTreeCollisionManager_Array::size() const { return dtree.size(); @@ -974,6 +1005,7 @@ size_t DynamicAABBTreeCollisionManager_Array::size() const //============================================================================== template +FCL_EXPORT const detail::implementation_array::HierarchyTree>& DynamicAABBTreeCollisionManager_Array::getTree() const { diff --git a/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h b/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h index df4421edb..3d535f822 100644 --- a/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h +++ b/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h @@ -52,7 +52,7 @@ namespace fcl { template -class DynamicAABBTreeCollisionManager_Array : public BroadPhaseCollisionManager +class FCL_EXPORT DynamicAABBTreeCollisionManager_Array : public BroadPhaseCollisionManager { public: diff --git a/include/fcl/broadphase/broadphase_interval_tree-inl.h b/include/fcl/broadphase/broadphase_interval_tree-inl.h index 6f978b3a6..dcc4f6d79 100644 --- a/include/fcl/broadphase/broadphase_interval_tree-inl.h +++ b/include/fcl/broadphase/broadphase_interval_tree-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class IntervalTreeCollisionManager; +class FCL_EXPORT IntervalTreeCollisionManager; //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_interval_tree.h b/include/fcl/broadphase/broadphase_interval_tree.h index 8d28f2143..79c5467c0 100644 --- a/include/fcl/broadphase/broadphase_interval_tree.h +++ b/include/fcl/broadphase/broadphase_interval_tree.h @@ -48,7 +48,7 @@ namespace fcl /// @brief Collision manager based on interval tree template -class IntervalTreeCollisionManager : public BroadPhaseCollisionManager +class FCL_EXPORT IntervalTreeCollisionManager : public BroadPhaseCollisionManager { public: IntervalTreeCollisionManager(); @@ -147,7 +147,7 @@ using IntervalTreeCollisionManagerd = IntervalTreeCollisionManager; /// @brief SAP end point template -struct IntervalTreeCollisionManager::EndPoint +struct FCL_EXPORT IntervalTreeCollisionManager::EndPoint { /// @brief object related with the end point CollisionObject* obj; @@ -163,7 +163,7 @@ struct IntervalTreeCollisionManager::EndPoint /// @brief Extention interval tree's interval to SAP interval, adding more information template -struct IntervalTreeCollisionManager::SAPInterval : public detail::SimpleInterval +struct FCL_EXPORT IntervalTreeCollisionManager::SAPInterval : public detail::SimpleInterval { CollisionObject* obj; diff --git a/include/fcl/broadphase/broadphase_spatialhash-inl.h b/include/fcl/broadphase/broadphase_spatialhash-inl.h index 725d48977..12551ce08 100644 --- a/include/fcl/broadphase/broadphase_spatialhash-inl.h +++ b/include/fcl/broadphase/broadphase_spatialhash-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SpatialHashingCollisionManager< +class FCL_EXPORT SpatialHashingCollisionManager< double, detail::SimpleHashTable< AABB, CollisionObject*, detail::SpatialHash>>; diff --git a/include/fcl/broadphase/broadphase_spatialhash.h b/include/fcl/broadphase/broadphase_spatialhash.h index 96529b2f4..a21d0417f 100644 --- a/include/fcl/broadphase/broadphase_spatialhash.h +++ b/include/fcl/broadphase/broadphase_spatialhash.h @@ -53,7 +53,7 @@ namespace fcl template, CollisionObject*, detail::SpatialHash> > -class SpatialHashingCollisionManager : public BroadPhaseCollisionManager +class FCL_EXPORT SpatialHashingCollisionManager : public BroadPhaseCollisionManager { public: SpatialHashingCollisionManager( diff --git a/include/fcl/broadphase/detail/hierarchy_tree.h b/include/fcl/broadphase/detail/hierarchy_tree.h index 4833413c3..ae9d3c637 100644 --- a/include/fcl/broadphase/detail/hierarchy_tree.h +++ b/include/fcl/broadphase/detail/hierarchy_tree.h @@ -55,7 +55,7 @@ namespace detail /// @brief Class for hierarchy tree structure template -class HierarchyTree +class FCL_EXPORT HierarchyTree { public: diff --git a/include/fcl/broadphase/detail/hierarchy_tree_array.h b/include/fcl/broadphase/detail/hierarchy_tree_array.h index e0d84acdf..b55f1e85e 100644 --- a/include/fcl/broadphase/detail/hierarchy_tree_array.h +++ b/include/fcl/broadphase/detail/hierarchy_tree_array.h @@ -58,7 +58,7 @@ namespace implementation_array /// @brief Class for hierarchy tree structure template -class HierarchyTree +class FCL_EXPORT HierarchyTree { using S = typename BV::S; typedef NodeBase NodeType; diff --git a/include/fcl/broadphase/detail/interval_tree.h b/include/fcl/broadphase/detail/interval_tree.h index cc4a714aa..6573520c9 100644 --- a/include/fcl/broadphase/detail/interval_tree.h +++ b/include/fcl/broadphase/detail/interval_tree.h @@ -51,7 +51,7 @@ namespace detail { /// right branch in searching for intervals but possibly come back /// and check the left branch as well. template -struct it_recursion_node +struct FCL_EXPORT it_recursion_node { public: IntervalTreeNode* start_node; @@ -69,7 +69,7 @@ struct it_recursion_node; /// @brief Interval tree template -class IntervalTree +class FCL_EXPORT IntervalTree { public: diff --git a/include/fcl/broadphase/detail/interval_tree_node-inl.h b/include/fcl/broadphase/detail/interval_tree_node-inl.h index 6e2e48734..2badc0469 100644 --- a/include/fcl/broadphase/detail/interval_tree_node-inl.h +++ b/include/fcl/broadphase/detail/interval_tree_node-inl.h @@ -47,7 +47,7 @@ namespace detail { //============================================================================== extern template -class IntervalTreeNode; +class FCL_EXPORT IntervalTreeNode; //============================================================================== template diff --git a/include/fcl/broadphase/detail/interval_tree_node.h b/include/fcl/broadphase/detail/interval_tree_node.h index 069a0008a..537adab03 100644 --- a/include/fcl/broadphase/detail/interval_tree_node.h +++ b/include/fcl/broadphase/detail/interval_tree_node.h @@ -39,6 +39,7 @@ #define FCL_BROADPHASE_DETAIL_INTERVALTREENODE_H #include "fcl/broadphase/detail/simple_interval.h" +#include "fcl/export.h" namespace fcl { @@ -47,11 +48,11 @@ namespace detail { template -class IntervalTree; +class FCL_EXPORT IntervalTree; /// @brief The node for interval tree template -class IntervalTreeNode +class FCL_EXPORT IntervalTreeNode { public: diff --git a/include/fcl/broadphase/detail/morton.h b/include/fcl/broadphase/detail/morton.h index a144b8bdb..6b430c434 100644 --- a/include/fcl/broadphase/detail/morton.h +++ b/include/fcl/broadphase/detail/morton.h @@ -52,12 +52,15 @@ namespace detail { template +FCL_EXPORT uint32 quantize(S x, uint32 n); /// @brief compute 30 bit morton code +FCL_EXPORT uint32 morton_code(uint32 x, uint32 y, uint32 z); /// @brief compute 60 bit morton code +FCL_EXPORT uint64 morton_code60(uint32 x, uint32 y, uint32 z); /// @brief Functor to compute the morton code for a given AABB @@ -65,11 +68,11 @@ uint64 morton_code60(uint32 x, uint32 y, uint32 z); /// a 30- or 60-bit code, respectively, and for `std::bitset` where /// N is the length of the code and must be a multiple of 3. template -struct morton_functor {}; +struct FCL_EXPORT morton_functor {}; /// @brief Functor to compute 30 bit morton code for a given AABB template -struct morton_functor +struct FCL_EXPORT morton_functor { morton_functor(const AABB& bbox); @@ -86,7 +89,7 @@ using morton_functoru32d = morton_functor; /// @brief Functor to compute 60 bit morton code for a given AABB template -struct morton_functor +struct FCL_EXPORT morton_functor { morton_functor(const AABB& bbox); @@ -104,7 +107,7 @@ using morton_functoru64d = morton_functor; /// @brief Functor to compute N bit morton code for a given AABB /// N must be a multiple of 3. template -struct morton_functor> +struct FCL_EXPORT morton_functor> { static_assert(N%3==0, "Number of bits must be a multiple of 3"); diff --git a/include/fcl/broadphase/detail/simple_hash_table.h b/include/fcl/broadphase/detail/simple_hash_table.h index d45d3c98a..2708d02a9 100644 --- a/include/fcl/broadphase/detail/simple_hash_table.h +++ b/include/fcl/broadphase/detail/simple_hash_table.h @@ -52,7 +52,7 @@ namespace detail /// @brief A simple hash table implemented as multiple buckets. HashFnc is any /// extended hash function: HashFnc(key) = {index1, index2, ..., } template -class SimpleHashTable +class FCL_EXPORT SimpleHashTable { protected: typedef std::list Bin; diff --git a/include/fcl/broadphase/detail/simple_interval.h b/include/fcl/broadphase/detail/simple_interval.h index 10ba5015e..ee8cbcadb 100644 --- a/include/fcl/broadphase/detail/simple_interval.h +++ b/include/fcl/broadphase/detail/simple_interval.h @@ -38,6 +38,8 @@ #ifndef FCL_BROADPHASE_DETAIL_SIMPLEINTERVAL_H #define FCL_BROADPHASE_DETAIL_SIMPLEINTERVAL_H +#include "fcl/export.h" + namespace fcl { @@ -47,7 +49,7 @@ namespace detail /// @brief Interval trees implemented using red-black-trees as described in /// the book Introduction_To_Algorithms_ by Cormen, Leisserson, and Rivest. template -struct SimpleInterval +struct FCL_EXPORT SimpleInterval { public: virtual ~SimpleInterval(); diff --git a/include/fcl/broadphase/detail/sparse_hash_table.h b/include/fcl/broadphase/detail/sparse_hash_table.h index f2d4f0f4f..8f1a133e5 100644 --- a/include/fcl/broadphase/detail/sparse_hash_table.h +++ b/include/fcl/broadphase/detail/sparse_hash_table.h @@ -51,12 +51,12 @@ namespace detail { template -class unordered_map_hash_table : public std::unordered_map {}; +class FCL_EXPORT unordered_map_hash_table : public std::unordered_map {}; /// @brief A hash table implemented using unordered_map template class TableT = unordered_map_hash_table> -class SparseHashTable +class FCL_EXPORT SparseHashTable { protected: HashFnc h_; diff --git a/include/fcl/broadphase/detail/spatial_hash.h b/include/fcl/broadphase/detail/spatial_hash.h index ebb25a57b..b3f1cdd88 100644 --- a/include/fcl/broadphase/detail/spatial_hash.h +++ b/include/fcl/broadphase/detail/spatial_hash.h @@ -48,7 +48,7 @@ namespace detail /// @brief Spatial hash function: hash an AABB to a set of integer values template -struct SpatialHash +struct FCL_EXPORT SpatialHash { using S = S_; diff --git a/include/fcl/common/deprecated.h b/include/fcl/common/deprecated.h deleted file mode 100644 index 0362e15b8..000000000 --- a/include/fcl/common/deprecated.h +++ /dev/null @@ -1,67 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2013-2016, CNRS-LAAS and AIST - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of CNRS-LAAS and AIST nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -/// @author Florent Lamiraux - -#ifndef FCL_DEPRECATED_HH -# define FCL_DEPRECATED_HH - -// Define a suffix which can be used to tag a type, a function or a a -// variable as deprecated (i.e. it will emit a warning when using it). -// -// Tagging a function as deprecated: -// FCL_DEPRECATED void foo (); -// -// Tagging a type as deprecated: -// FCL_DEPRECATED class Foo {}; -// -// Tagging a variable as deprecated: -// FCL_DEPRECATED int a = 0; -// -// The use of a macro is required as this is /not/ a standardized -// feature of C++ language or preprocessor, even if most of the -// compilers support it. -# ifdef __GNUC__ -# define FCL_DEPRECATED __attribute__ ((deprecated)) -# elif defined _MSC_VER -# define FCL_DEPRECATED __declspec (deprecated) -# elif defined(clang) -# define FL_DEPRECATED \ - attribute((deprecated("FCL: Use of this method is deprecated"))) -# else -// If the compiler is not recognized, drop the feature. -# define FCL_DEPRECATED /* nothing */ -# endif - -#endif //! FCL_DEPRECATED_HH diff --git a/include/fcl/common/detail/profiler.h b/include/fcl/common/detail/profiler.h index 4fabbc555..76e3675b6 100644 --- a/include/fcl/common/detail/profiler.h +++ b/include/fcl/common/detail/profiler.h @@ -49,6 +49,7 @@ #include #include #include "fcl/common/time.h" +#include "fcl/export.h" namespace fcl { namespace detail { @@ -58,7 +59,7 @@ namespace detail { /// external profiling tools in that it allows the user to count /// time spent in various bits of code (sub-function granularity) /// or count how many times certain pieces of code are executed. -class Profiler +class FCL_EXPORT Profiler { public: // non-copyable @@ -67,13 +68,13 @@ class Profiler /// @brief This instance will call Profiler::begin() when constructed and /// Profiler::end() when it goes out of scope. - class ScopedBlock; + class FCL_EXPORT ScopedBlock; /// @brief This instance will call Profiler::start() when constructed and /// Profiler::stop() when it goes out of scope. /// If the profiler was already started, this block's constructor and /// destructor take no action - class ScopedStart; + class FCL_EXPORT ScopedStart; /// @brief Return an instance of the class static Profiler& Instance(void); @@ -210,7 +211,7 @@ class Profiler /// @brief This instance will call Profiler::begin() when constructed and /// Profiler::end() when it goes out of scope. -class Profiler::ScopedBlock +class FCL_EXPORT Profiler::ScopedBlock { public: /// @brief Start counting time for the block named \e name of the profiler @@ -229,7 +230,7 @@ class Profiler::ScopedBlock /// Profiler::stop() when it goes out of scope. /// If the profiler was already started, this block's constructor and /// destructor take no action -class Profiler::ScopedStart +class FCL_EXPORT Profiler::ScopedStart { public: diff --git a/include/fcl/common/exception.h b/include/fcl/common/exception.h index 801777d16..00da2ccfa 100644 --- a/include/fcl/common/exception.h +++ b/include/fcl/common/exception.h @@ -41,10 +41,12 @@ #include #include +#include "fcl/export.h" + namespace fcl { -class Exception : public std::runtime_error +class FCL_EXPORT Exception : public std::runtime_error { public: diff --git a/include/fcl/common/time.h b/include/fcl/common/time.h index f23949b72..7b040c518 100644 --- a/include/fcl/common/time.h +++ b/include/fcl/common/time.h @@ -39,6 +39,7 @@ #define FCL_COMMON_TIME_H #include +#include "fcl/export.h" namespace fcl { @@ -54,12 +55,15 @@ using point = std::chrono::system_clock::time_point; using duration = std::chrono::system_clock::duration; /// @brief Get the current time point +FCL_EXPORT point now(void); /// @brief Return the time duration representing a given number of seconds +FCL_EXPORT duration seconds(double sec); /// @brief Return the number of seconds that a time duration represents +FCL_EXPORT double seconds(const duration &d); } // namespace time diff --git a/include/fcl/common/types.h b/include/fcl/common/types.h index c426af348..b5187fa62 100644 --- a/include/fcl/common/types.h +++ b/include/fcl/common/types.h @@ -45,7 +45,7 @@ #include #include #include -#include "fcl/common/deprecated.h" +#include "fcl/export.h" namespace fcl { @@ -140,7 +140,7 @@ inline std::shared_ptr<_Tp> make_aligned_shared(_Args&&... __args) // C++11 compatible version is available since Eigen 3.2.9 so we use this copy // for Eigen (< 3.2.9). template -class aligned_allocator_cpp11 : public std::allocator +class FCL_EXPORT aligned_allocator_cpp11 : public std::allocator { public: typedef std::size_t size_type; diff --git a/include/fcl/geometry/bvh/BVH_model.h b/include/fcl/geometry/bvh/BVH_model.h index bab7304f5..294d521e4 100644 --- a/include/fcl/geometry/bvh/BVH_model.h +++ b/include/fcl/geometry/bvh/BVH_model.h @@ -54,7 +54,7 @@ namespace fcl /// @brief A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) template -class BVHModel : public CollisionGeometry +class FCL_EXPORT BVHModel : public CollisionGeometry { public: diff --git a/include/fcl/geometry/bvh/BVH_utility-inl.h b/include/fcl/geometry/bvh/BVH_utility-inl.h index a20a0f2b3..2196ca486 100644 --- a/include/fcl/geometry/bvh/BVH_utility-inl.h +++ b/include/fcl/geometry/bvh/BVH_utility-inl.h @@ -57,6 +57,7 @@ void BVHExpand( //============================================================================== template +FCL_EXPORT void BVHExpand(BVHModel& model, const Variance3* ucs, S r) { for(int i = 0; i < model.num_bvs; ++i) @@ -84,6 +85,7 @@ void BVHExpand(BVHModel& model, const Variance3* ucs, S r) //============================================================================== template +FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, @@ -127,6 +129,7 @@ void BVHExpand( //============================================================================== template +FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, diff --git a/include/fcl/geometry/bvh/BVH_utility.h b/include/fcl/geometry/bvh/BVH_utility.h index a0862228c..68e3974b6 100644 --- a/include/fcl/geometry/bvh/BVH_utility.h +++ b/include/fcl/geometry/bvh/BVH_utility.h @@ -47,17 +47,20 @@ namespace fcl /// @brief Expand the BVH bounding boxes according to the variance matrix /// corresponding to the data stored within each BV node template +FCL_EXPORT void BVHExpand(BVHModel& model, const Variance3* ucs, S r); /// @brief Expand the BVH bounding boxes according to the corresponding variance /// information, for OBB template +FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, S r = 1.0); /// @brief Expand the BVH bounding boxes according to the corresponding variance /// information, for RSS template +FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, S r = 1.0); diff --git a/include/fcl/geometry/bvh/BV_node.h b/include/fcl/geometry/bvh/BV_node.h index b87b9fd58..08dabbc0d 100644 --- a/include/fcl/geometry/bvh/BV_node.h +++ b/include/fcl/geometry/bvh/BV_node.h @@ -49,7 +49,7 @@ namespace fcl /// @brief A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and also the geometry data provided in BV template parameter. template -struct BVNode : public BVNodeBase +struct FCL_EXPORT BVNode : public BVNodeBase { using S = typename BV::S; diff --git a/include/fcl/geometry/bvh/BV_node_base.h b/include/fcl/geometry/bvh/BV_node_base.h index d47bd3b83..a64e67977 100644 --- a/include/fcl/geometry/bvh/BV_node_base.h +++ b/include/fcl/geometry/bvh/BV_node_base.h @@ -47,7 +47,7 @@ namespace fcl { /// @brief BVNodeBase encodes the tree structure for BVH -struct BVNodeBase +struct FCL_EXPORT BVNodeBase { /// @brief An index for first child node or primitive /// If the value is positive, it is the index of the first child bv node diff --git a/include/fcl/geometry/bvh/detail/BVH_front.h b/include/fcl/geometry/bvh/detail/BVH_front.h index 732a98ac2..2415f91a9 100644 --- a/include/fcl/geometry/bvh/detail/BVH_front.h +++ b/include/fcl/geometry/bvh/detail/BVH_front.h @@ -39,6 +39,7 @@ #define FCL_BVH_FRONT_H #include +#include "fcl/export.h" namespace fcl { @@ -51,7 +52,7 @@ namespace detail /// the traversal terminates while performing a query during a given time /// instance. The front list reflects the subset of a BVTT that is traversed for /// that particular proximity query. -struct BVHFrontNode +struct FCL_EXPORT BVHFrontNode { /// @brief The nodes to start in the future, i.e. the wave front of the /// traversal tree. @@ -68,6 +69,7 @@ struct BVHFrontNode using BVHFrontList = std::list; /// @brief Add new front node into the front list +FCL_EXPORT void updateFrontList(BVHFrontList* front_list, int b1, int b2); } // namespace detail diff --git a/include/fcl/geometry/bvh/detail/BV_fitter.h b/include/fcl/geometry/bvh/detail/BV_fitter.h index c31e2b8a3..c78c52364 100644 --- a/include/fcl/geometry/bvh/detail/BV_fitter.h +++ b/include/fcl/geometry/bvh/detail/BV_fitter.h @@ -53,7 +53,7 @@ namespace detail /// @brief The class for the default algorithm fitting a bounding volume to a set of points template -class BVFitter : public BVFitterBase +class FCL_EXPORT BVFitter : public BVFitterBase { public: diff --git a/include/fcl/geometry/bvh/detail/BV_fitter_base.h b/include/fcl/geometry/bvh/detail/BV_fitter_base.h index 6bc1db156..3e10fbb33 100644 --- a/include/fcl/geometry/bvh/detail/BV_fitter_base.h +++ b/include/fcl/geometry/bvh/detail/BV_fitter_base.h @@ -52,7 +52,7 @@ namespace detail /// @brief Interface for fitting a bv given the triangles or points inside it. template -class BVFitterBase +class FCL_EXPORT BVFitterBase { public: diff --git a/include/fcl/geometry/bvh/detail/BV_splitter.h b/include/fcl/geometry/bvh/detail/BV_splitter.h index b15561026..7480f7728 100644 --- a/include/fcl/geometry/bvh/detail/BV_splitter.h +++ b/include/fcl/geometry/bvh/detail/BV_splitter.h @@ -62,7 +62,7 @@ enum SplitMethodType /// @brief A class describing the split rule that splits each BV node template -class BVSplitter : public BVSplitterBase +class FCL_EXPORT BVSplitter : public BVSplitterBase { public: diff --git a/include/fcl/geometry/bvh/detail/BV_splitter_base.h b/include/fcl/geometry/bvh/detail/BV_splitter_base.h index 595b794da..893c2bedd 100644 --- a/include/fcl/geometry/bvh/detail/BV_splitter_base.h +++ b/include/fcl/geometry/bvh/detail/BV_splitter_base.h @@ -53,7 +53,7 @@ namespace detail /// @brief Base interface for BV splitting algorithm template -class BVSplitterBase +class FCL_EXPORT BVSplitterBase { public: diff --git a/include/fcl/geometry/collision_geometry-inl.h b/include/fcl/geometry/collision_geometry-inl.h index 607f16a0f..0fbfc01f6 100644 --- a/include/fcl/geometry/collision_geometry-inl.h +++ b/include/fcl/geometry/collision_geometry-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class CollisionGeometry; +class FCL_EXPORT CollisionGeometry; //============================================================================== template diff --git a/include/fcl/geometry/collision_geometry.h b/include/fcl/geometry/collision_geometry.h index 24c217e23..21fe84992 100644 --- a/include/fcl/geometry/collision_geometry.h +++ b/include/fcl/geometry/collision_geometry.h @@ -40,7 +40,6 @@ #include -#include "fcl/common/deprecated.h" #include "fcl/math/bv/AABB.h" #include "fcl/math/motion/motion_base.h" @@ -56,7 +55,7 @@ enum NODE_TYPE {BV_UNKNOWN, BV_AABB, BV_OBB, BV_RSS, BV_kIOS, BV_OBBRSS, BV_KDOP /// @brief The geometry for the object for collision or distance computation template -class CollisionGeometry +class FCL_EXPORT CollisionGeometry { public: CollisionGeometry(); diff --git a/include/fcl/geometry/octree/octree-inl.h b/include/fcl/geometry/octree/octree-inl.h index 783285986..95d63db0e 100644 --- a/include/fcl/geometry/octree/octree-inl.h +++ b/include/fcl/geometry/octree/octree-inl.h @@ -49,7 +49,7 @@ namespace fcl //============================================================================== extern template -class OcTree; +class FCL_EXPORT OcTree; //============================================================================== extern template diff --git a/include/fcl/geometry/octree/octree.h b/include/fcl/geometry/octree/octree.h index 2596a385f..58f73645d 100644 --- a/include/fcl/geometry/octree/octree.h +++ b/include/fcl/geometry/octree/octree.h @@ -55,7 +55,7 @@ namespace fcl /// @brief Octree is one type of collision geometry which can encode uncertainty /// information in the sensor data. template -class OcTree : public CollisionGeometry +class FCL_EXPORT OcTree : public CollisionGeometry { private: std::shared_ptr tree; @@ -138,6 +138,7 @@ using OcTreed = OcTree; /// @brief compute the bounding volume of an octree node's i-th child template +FCL_EXPORT void computeChildBV(const AABB& root_bv, unsigned int i, AABB& child_bv); } // namespace fcl diff --git a/include/fcl/geometry/shape/box-inl.h b/include/fcl/geometry/shape/box-inl.h index 474f6e326..053119a0e 100644 --- a/include/fcl/geometry/shape/box-inl.h +++ b/include/fcl/geometry/shape/box-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Box; +class FCL_EXPORT Box; //============================================================================== template diff --git a/include/fcl/geometry/shape/box.h b/include/fcl/geometry/shape/box.h index f9aff7181..1ec03d90f 100644 --- a/include/fcl/geometry/shape/box.h +++ b/include/fcl/geometry/shape/box.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Center at zero point, axis aligned box template -class Box : public ShapeBase +class FCL_EXPORT Box : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/capsule-inl.h b/include/fcl/geometry/shape/capsule-inl.h index e9cf8a5a2..3a99c179a 100644 --- a/include/fcl/geometry/shape/capsule-inl.h +++ b/include/fcl/geometry/shape/capsule-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Capsule; +class FCL_EXPORT Capsule; //============================================================================== template diff --git a/include/fcl/geometry/shape/capsule.h b/include/fcl/geometry/shape/capsule.h index 94ce5bb3f..8bb3ffbea 100644 --- a/include/fcl/geometry/shape/capsule.h +++ b/include/fcl/geometry/shape/capsule.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Center at zero point capsule template -class Capsule : public ShapeBase +class FCL_EXPORT Capsule : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/cone-inl.h b/include/fcl/geometry/shape/cone-inl.h index d52771d8f..3b023fcc0 100644 --- a/include/fcl/geometry/shape/cone-inl.h +++ b/include/fcl/geometry/shape/cone-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Cone; +class FCL_EXPORT Cone; //============================================================================== template diff --git a/include/fcl/geometry/shape/cone.h b/include/fcl/geometry/shape/cone.h index 575bfdf63..f4cc617fe 100644 --- a/include/fcl/geometry/shape/cone.h +++ b/include/fcl/geometry/shape/cone.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Center at zero cone template -class Cone : public ShapeBase +class FCL_EXPORT Cone : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/convex-inl.h b/include/fcl/geometry/shape/convex-inl.h index 542f29d13..eefe94a69 100644 --- a/include/fcl/geometry/shape/convex-inl.h +++ b/include/fcl/geometry/shape/convex-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Convex; +class FCL_EXPORT Convex; //============================================================================== template diff --git a/include/fcl/geometry/shape/convex.h b/include/fcl/geometry/shape/convex.h index dc3292ab5..11d663cc5 100644 --- a/include/fcl/geometry/shape/convex.h +++ b/include/fcl/geometry/shape/convex.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Convex polytope template -class Convex : public ShapeBase +class FCL_EXPORT Convex : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/cylinder-inl.h b/include/fcl/geometry/shape/cylinder-inl.h index 7a351a176..f5a621153 100644 --- a/include/fcl/geometry/shape/cylinder-inl.h +++ b/include/fcl/geometry/shape/cylinder-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Cylinder; +class FCL_EXPORT Cylinder; //============================================================================== template diff --git a/include/fcl/geometry/shape/cylinder.h b/include/fcl/geometry/shape/cylinder.h index b079f7f71..43be1def3 100644 --- a/include/fcl/geometry/shape/cylinder.h +++ b/include/fcl/geometry/shape/cylinder.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Center at zero cylinder template -class Cylinder : public ShapeBase +class FCL_EXPORT Cylinder : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/ellipsoid-inl.h b/include/fcl/geometry/shape/ellipsoid-inl.h index ff6fea09b..5bbf946f8 100644 --- a/include/fcl/geometry/shape/ellipsoid-inl.h +++ b/include/fcl/geometry/shape/ellipsoid-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Ellipsoid; +class FCL_EXPORT Ellipsoid; //============================================================================== template diff --git a/include/fcl/geometry/shape/ellipsoid.h b/include/fcl/geometry/shape/ellipsoid.h index 21dc4ee35..c876be685 100644 --- a/include/fcl/geometry/shape/ellipsoid.h +++ b/include/fcl/geometry/shape/ellipsoid.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Center at zero point ellipsoid template -class Ellipsoid : public ShapeBase +class FCL_EXPORT Ellipsoid : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/halfspace-inl.h b/include/fcl/geometry/shape/halfspace-inl.h index fe3c0d3bd..bc58f80f1 100644 --- a/include/fcl/geometry/shape/halfspace-inl.h +++ b/include/fcl/geometry/shape/halfspace-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Halfspace; +class FCL_EXPORT Halfspace; //============================================================================== extern template diff --git a/include/fcl/geometry/shape/halfspace.h b/include/fcl/geometry/shape/halfspace.h index 1a123c87e..05f9d0881 100644 --- a/include/fcl/geometry/shape/halfspace.h +++ b/include/fcl/geometry/shape/halfspace.h @@ -52,7 +52,7 @@ namespace fcl /// Points in the negative side of the separation plane (i.e. {x | n * x < d}) are inside the half space and points /// in the positive side of the separation plane (i.e. {x | n * x > d}) are outside the half space template -class Halfspace : public ShapeBase +class FCL_EXPORT Halfspace : public ShapeBase { public: @@ -92,6 +92,7 @@ using Halfspacef = Halfspace; using Halfspaced = Halfspace; template +FCL_EXPORT Halfspace transform(const Halfspace& a, const Transform3& tf); } // namespace fcl diff --git a/include/fcl/geometry/shape/plane-inl.h b/include/fcl/geometry/shape/plane-inl.h index 853bd2f75..2e5da9c06 100644 --- a/include/fcl/geometry/shape/plane-inl.h +++ b/include/fcl/geometry/shape/plane-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Plane; +class FCL_EXPORT Plane; //============================================================================== extern template diff --git a/include/fcl/geometry/shape/plane.h b/include/fcl/geometry/shape/plane.h index 43c0f9da8..f3518b1ce 100644 --- a/include/fcl/geometry/shape/plane.h +++ b/include/fcl/geometry/shape/plane.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Infinite plane template -class Plane : public ShapeBase +class FCL_EXPORT Plane : public ShapeBase { public: @@ -85,6 +85,7 @@ using Planef = Plane; using Planed = Plane; template +FCL_EXPORT Plane transform(const Plane& a, const Transform3& tf); } // namespace fcl diff --git a/include/fcl/geometry/shape/shape_base-inl.h b/include/fcl/geometry/shape/shape_base-inl.h index ea8fa19b4..b3148c469 100644 --- a/include/fcl/geometry/shape/shape_base-inl.h +++ b/include/fcl/geometry/shape/shape_base-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class ShapeBase; +class FCL_EXPORT ShapeBase; //============================================================================== template diff --git a/include/fcl/geometry/shape/shape_base.h b/include/fcl/geometry/shape/shape_base.h index 1f68aa270..6acc6da64 100644 --- a/include/fcl/geometry/shape/shape_base.h +++ b/include/fcl/geometry/shape/shape_base.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Base class for all basic geometric shapes template -class ShapeBase : public CollisionGeometry +class FCL_EXPORT ShapeBase : public CollisionGeometry { public: diff --git a/include/fcl/geometry/shape/sphere-inl.h b/include/fcl/geometry/shape/sphere-inl.h index 6a9a2d119..0da7eeae9 100644 --- a/include/fcl/geometry/shape/sphere-inl.h +++ b/include/fcl/geometry/shape/sphere-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Sphere; +class FCL_EXPORT Sphere; //============================================================================== template diff --git a/include/fcl/geometry/shape/sphere.h b/include/fcl/geometry/shape/sphere.h index 56f7d0830..0c9082573 100644 --- a/include/fcl/geometry/shape/sphere.h +++ b/include/fcl/geometry/shape/sphere.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Center at zero point sphere template -class Sphere : public ShapeBase +class FCL_EXPORT Sphere : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/triangle_p-inl.h b/include/fcl/geometry/shape/triangle_p-inl.h index dc97e46be..f48d41bb7 100644 --- a/include/fcl/geometry/shape/triangle_p-inl.h +++ b/include/fcl/geometry/shape/triangle_p-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class TriangleP; +class FCL_EXPORT TriangleP; //============================================================================== template diff --git a/include/fcl/geometry/shape/triangle_p.h b/include/fcl/geometry/shape/triangle_p.h index 3983436ca..7c26fa67a 100644 --- a/include/fcl/geometry/shape/triangle_p.h +++ b/include/fcl/geometry/shape/triangle_p.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Triangle stores the points instead of only indices of points template -class TriangleP : public ShapeBase +class FCL_EXPORT TriangleP : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/utility-inl.h b/include/fcl/geometry/shape/utility-inl.h index fa0057a72..1fa77fc7a 100644 --- a/include/fcl/geometry/shape/utility-inl.h +++ b/include/fcl/geometry/shape/utility-inl.h @@ -122,7 +122,7 @@ namespace detail { //============================================================================== template -struct ComputeBVImpl +struct FCL_EXPORT ComputeBVImpl { static void run(const Shape& s, const Transform3& tf, BV& bv) { @@ -133,7 +133,7 @@ struct ComputeBVImpl //============================================================================== template -struct ComputeBVImpl, Box> +struct FCL_EXPORT ComputeBVImpl, Box> { static void run(const Box& s, const Transform3& tf, AABB& bv) { @@ -152,7 +152,7 @@ struct ComputeBVImpl, Box> //============================================================================== template -struct ComputeBVImpl, Box> +struct FCL_EXPORT ComputeBVImpl, Box> { static void run(const Box& s, const Transform3& tf, OBB& bv) { @@ -164,7 +164,7 @@ struct ComputeBVImpl, Box> //============================================================================== template -struct ComputeBVImpl, Capsule> +struct FCL_EXPORT ComputeBVImpl, Capsule> { static void run(const Capsule& s, const Transform3& tf, AABB& bv) { @@ -183,7 +183,7 @@ struct ComputeBVImpl, Capsule> //============================================================================== template -struct ComputeBVImpl, Capsule> +struct FCL_EXPORT ComputeBVImpl, Capsule> { static void run(const Capsule& s, const Transform3& tf, OBB& bv) { @@ -195,7 +195,7 @@ struct ComputeBVImpl, Capsule> //============================================================================== template -struct ComputeBVImpl, Cone> +struct FCL_EXPORT ComputeBVImpl, Cone> { static void run(const Cone& s, const Transform3& tf, AABB& bv) { @@ -214,7 +214,7 @@ struct ComputeBVImpl, Cone> //============================================================================== template -struct ComputeBVImpl, Cone> +struct FCL_EXPORT ComputeBVImpl, Cone> { static void run(const Cone& s, const Transform3& tf, OBB& bv) { @@ -226,7 +226,7 @@ struct ComputeBVImpl, Cone> //============================================================================== template -struct ComputeBVImpl, Convex> +struct FCL_EXPORT ComputeBVImpl, Convex> { static void run(const Convex& s, const Transform3& tf, AABB& bv) { @@ -246,7 +246,7 @@ struct ComputeBVImpl, Convex> //============================================================================== template -struct ComputeBVImpl, Convex> +struct FCL_EXPORT ComputeBVImpl, Convex> { static void run(const Convex& s, const Transform3& tf, OBB& bv) { @@ -259,7 +259,7 @@ struct ComputeBVImpl, Convex> //============================================================================== template -struct ComputeBVImpl, Cylinder> +struct FCL_EXPORT ComputeBVImpl, Cylinder> { static void run(const Cylinder& s, const Transform3& tf, AABB& bv) { @@ -278,7 +278,7 @@ struct ComputeBVImpl, Cylinder> //============================================================================== template -struct ComputeBVImpl, Cylinder> +struct FCL_EXPORT ComputeBVImpl, Cylinder> { static void run(const Cylinder& s, const Transform3& tf, OBB& bv) { @@ -290,7 +290,7 @@ struct ComputeBVImpl, Cylinder> //============================================================================== template -struct ComputeBVImpl, Ellipsoid> +struct FCL_EXPORT ComputeBVImpl, Ellipsoid> { static void run(const Ellipsoid& s, const Transform3& tf, AABB& bv) { @@ -309,7 +309,7 @@ struct ComputeBVImpl, Ellipsoid> //============================================================================== template -struct ComputeBVImpl, Ellipsoid> +struct FCL_EXPORT ComputeBVImpl, Ellipsoid> { static void run(const Ellipsoid& s, const Transform3& tf, OBB& bv) { @@ -321,7 +321,7 @@ struct ComputeBVImpl, Ellipsoid> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, AABB& bv) { @@ -357,7 +357,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, OBB& bv) { @@ -373,7 +373,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, RSS& bv) { @@ -389,7 +389,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, OBBRSS& bv) { @@ -400,7 +400,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, kIOS& bv) { @@ -413,7 +413,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, KDOP& bv) { @@ -472,7 +472,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, KDOP& bv) { @@ -537,7 +537,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Halfspace> +struct FCL_EXPORT ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, KDOP& bv) { @@ -617,7 +617,7 @@ struct ComputeBVImpl, Halfspace> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, AABB& bv) { @@ -653,7 +653,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, OBB& bv) { @@ -670,7 +670,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, RSS& bv) { @@ -691,7 +691,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, OBBRSS& bv) { @@ -702,7 +702,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, kIOS& bv) { @@ -715,7 +715,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, KDOP& bv) { @@ -770,7 +770,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, KDOP& bv) { @@ -829,7 +829,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Plane> +struct FCL_EXPORT ComputeBVImpl, Plane> { static void run(const Plane& s, const Transform3& tf, KDOP& bv) { @@ -900,7 +900,7 @@ struct ComputeBVImpl, Plane> //============================================================================== template -struct ComputeBVImpl, Sphere> +struct FCL_EXPORT ComputeBVImpl, Sphere> { static void run(const Sphere& s, const Transform3& tf, AABB& bv) { @@ -912,7 +912,7 @@ struct ComputeBVImpl, Sphere> //============================================================================== template -struct ComputeBVImpl, Sphere> +struct FCL_EXPORT ComputeBVImpl, Sphere> { static void run(const Sphere& s, const Transform3& tf, OBB& bv) { @@ -924,7 +924,7 @@ struct ComputeBVImpl, Sphere> //============================================================================== template -struct ComputeBVImpl, TriangleP> +struct FCL_EXPORT ComputeBVImpl, TriangleP> { static void run(const TriangleP& s, const Transform3& tf, AABB& bv) { @@ -1054,6 +1054,7 @@ struct ComputeBVImpl, TriangleP>; //============================================================================== template +FCL_EXPORT void computeBV(const Shape& s, const Transform3& tf, BV& bv) { using S = typename BV::S; diff --git a/include/fcl/geometry/shape/utility.h b/include/fcl/geometry/shape/utility.h index 7a9f3a32d..ec70def9a 100644 --- a/include/fcl/geometry/shape/utility.h +++ b/include/fcl/geometry/shape/utility.h @@ -38,7 +38,7 @@ #ifndef FCL_GEOMETRY_SHAPE_UTILITY_H #define FCL_GEOMETRY_SHAPE_UTILITY_H -// This header shouldn't be included by any bounding volumen classes (e.g., +// This header shouldn't be included by any bounding volumen class (e.g., // AABB and OBB) nor geometric shapes (e.g., Box and Sphere). #include "fcl/common/types.h" @@ -57,55 +57,72 @@ namespace fcl /// @brief calculate a bounding volume for a shape in a specific configuration template +FCL_EXPORT void computeBV(const Shape& s, const Transform3& tf, BV& bv); /// @brief construct a box shape (with a configuration) from a given bounding volume template +FCL_EXPORT void constructBox(const AABB& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const OBB& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const OBBRSS& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const kIOS& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const RSS& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const KDOP& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const KDOP& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const KDOP& bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const AABB& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const OBB& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const OBBRSS& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const kIOS& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const RSS& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const KDOP& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const KDOP& bv, const Transform3& tf_bv, Box& box, Transform3& tf); template +FCL_EXPORT void constructBox(const KDOP& bv, const Transform3& tf_bv, Box& box, Transform3& tf); } // namespace fcl diff --git a/include/fcl/math/bv/AABB-inl.h b/include/fcl/math/bv/AABB-inl.h index f4f738c47..67380068f 100644 --- a/include/fcl/math/bv/AABB-inl.h +++ b/include/fcl/math/bv/AABB-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class AABB; +class FCL_EXPORT AABB; //============================================================================== template diff --git a/include/fcl/math/bv/AABB.h b/include/fcl/math/bv/AABB.h index d785a6320..f84b737ee 100644 --- a/include/fcl/math/bv/AABB.h +++ b/include/fcl/math/bv/AABB.h @@ -46,7 +46,7 @@ namespace fcl /// @brief A class describing the AABB collision structure, which is a box in 3D /// space determined by two diagonal points template -class AABB +class FCL_EXPORT AABB { public: diff --git a/include/fcl/math/bv/OBB-inl.h b/include/fcl/math/bv/OBB-inl.h index 489f34962..88813229a 100644 --- a/include/fcl/math/bv/OBB-inl.h +++ b/include/fcl/math/bv/OBB-inl.h @@ -47,7 +47,7 @@ namespace fcl //============================================================================== extern template -class OBB; +class FCL_EXPORT OBB; //============================================================================== extern template diff --git a/include/fcl/math/bv/OBB.h b/include/fcl/math/bv/OBB.h index c611070ed..3d7e216ba 100644 --- a/include/fcl/math/bv/OBB.h +++ b/include/fcl/math/bv/OBB.h @@ -48,7 +48,7 @@ namespace fcl /// @brief Oriented bounding box class template -class OBB +class FCL_EXPORT OBB { public: @@ -124,24 +124,29 @@ using OBBd = OBB; /// @brief Compute the 8 vertices of a OBB template +FCL_EXPORT void computeVertices(const OBB& b, Vector3 vertices[8]); /// @brief OBB merge method when the centers of two smaller OBB are far away template +FCL_EXPORT OBB merge_largedist(const OBB& b1, const OBB& b2); /// @brief OBB merge method when the centers of two smaller OBB are close template +FCL_EXPORT OBB merge_smalldist(const OBB& b1, const OBB& b2); /// @brief Translate the OBB bv template +FCL_EXPORT OBB translate( const OBB& bv, const Eigen::MatrixBase& t); /// @brief Check collision between two obbs, b1 is in configuration (R0, T0) and /// b2 is in identity. template +FCL_EXPORT bool overlap(const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, const OBB& b1, const OBB& b2); @@ -150,6 +155,7 @@ bool overlap(const Eigen::MatrixBase& R0, /// (R, T) and its half dimension is set by a; the second box is in identity /// configuration and its half dimension is set by b. template +FCL_EXPORT bool obbDisjoint( const Matrix3& B, const Vector3& T, @@ -160,6 +166,7 @@ bool obbDisjoint( /// (R, T) and its half dimension is set by a; the second box is in identity /// configuration and its half dimension is set by b. template +FCL_EXPORT bool obbDisjoint( const Transform3& tf, const Vector3& a, diff --git a/include/fcl/math/bv/OBBRSS-inl.h b/include/fcl/math/bv/OBBRSS-inl.h index 2a749a1ce..814a66f62 100644 --- a/include/fcl/math/bv/OBBRSS-inl.h +++ b/include/fcl/math/bv/OBBRSS-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class OBBRSS; +class FCL_EXPORT OBBRSS; //============================================================================== extern template diff --git a/include/fcl/math/bv/OBBRSS.h b/include/fcl/math/bv/OBBRSS.h index 4f1d65623..9f84c1105 100644 --- a/include/fcl/math/bv/OBBRSS.h +++ b/include/fcl/math/bv/OBBRSS.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Class merging the OBB and RSS, can handle collision and distance /// simultaneously template -class OBBRSS +class FCL_EXPORT OBBRSS { public: @@ -108,11 +108,13 @@ using OBBRSSd = OBBRSS; /// @brief Translate the OBBRSS bv template +FCL_EXPORT OBBRSS translate(const OBBRSS& bv, const Vector3& t); /// @brief Check collision between two OBBRSS, b1 is in configuration (R0, T0) /// and b2 is in indentity template +FCL_EXPORT bool overlap(const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, const OBBRSS& b1, const OBBRSS& b2); @@ -120,6 +122,7 @@ bool overlap(const Eigen::MatrixBase& R0, /// @brief Check collision between two OBBRSS, b1 is in configuration (R0, T0) /// and b2 is in indentity template +FCL_EXPORT bool overlap( const Transform3& tf, const OBBRSS& b1, @@ -128,6 +131,7 @@ bool overlap( /// @brief Computate distance between two OBBRSS, b1 is in configuation (R0, T0) /// and b2 is in indentity; P and Q, is not nullptr, returns the nearest points template +FCL_EXPORT S distance( const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, @@ -137,6 +141,7 @@ S distance( /// @brief Computate distance between two OBBRSS, b1 is in configuation (R0, T0) /// and b2 is in indentity; P and Q, is not nullptr, returns the nearest points template +FCL_EXPORT S distance( const Transform3& tf, const OBBRSS& b1, diff --git a/include/fcl/math/bv/RSS-inl.h b/include/fcl/math/bv/RSS-inl.h index 600d25c15..a88d5cb20 100644 --- a/include/fcl/math/bv/RSS-inl.h +++ b/include/fcl/math/bv/RSS-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class RSS; +class FCL_EXPORT RSS; //============================================================================== extern template diff --git a/include/fcl/math/bv/RSS.h b/include/fcl/math/bv/RSS.h index bdb2d07c1..125ca3d65 100644 --- a/include/fcl/math/bv/RSS.h +++ b/include/fcl/math/bv/RSS.h @@ -46,7 +46,7 @@ namespace fcl /// @brief A class for rectangle sphere-swept bounding volume template -class RSS +class FCL_EXPORT RSS { public: @@ -123,6 +123,7 @@ using RSSd = RSS; /// @brief Clip value between a and b template +FCL_EXPORT void clipToRange(S& val, S a, S b); /// @brief Finds the parameters t & u corresponding to the two closest points on @@ -138,6 +139,7 @@ void clipToRange(S& val, S a, S b); /// Reference: "On fast computation of distance between line segments." Vladimir /// J. Lumelsky, in Information Processing Letters, no. 21, pages 55-61, 1985. template +FCL_EXPORT void segCoords(S& t, S& u, S a, S b, S A_dot_B, S A_dot_T, S B_dot_T); @@ -147,6 +149,7 @@ void segCoords(S& t, S& u, S a, S b, /// determined by the point Pa and the direction Anorm. /// A,B, and Anorm are unit vectors. T is the vector between Pa and Pb. template +FCL_EXPORT bool inVoronoi(S a, S b, S Anorm_dot_B, S Anorm_dot_T, S A_dot_B, S A_dot_T, S B_dot_T); @@ -155,6 +158,7 @@ bool inVoronoi(S a, S b, /// values) are the closest points in the rectangles, both are in the local /// frame of the first rectangle. template +FCL_EXPORT S rectDistance( const Matrix3& Rab, const Vector3& Tab, @@ -167,6 +171,7 @@ S rectDistance( /// values) are the closest points in the rectangles, both are in the local /// frame of the first rectangle. template +FCL_EXPORT S rectDistance( const Transform3& tfab, const S a[2], @@ -180,6 +185,7 @@ S rectDistance( /// points. Notice that P and Q are both in the local frame of the first RSS /// (not global frame and not even the local frame of object 1) template +FCL_EXPORT S distance( const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, @@ -191,6 +197,7 @@ S distance( /// @brief Check collision between two RSSs, b1 is in configuration (R0, T0) and /// b2 is in identity. template +FCL_EXPORT bool overlap( const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, @@ -199,6 +206,7 @@ bool overlap( /// @brief Translate the RSS bv template +FCL_EXPORT RSS translate(const RSS& bv, const Vector3& t); } // namespace fcl diff --git a/include/fcl/math/bv/kDOP-inl.h b/include/fcl/math/bv/kDOP-inl.h index fdd71d949..371fdb61a 100644 --- a/include/fcl/math/bv/kDOP-inl.h +++ b/include/fcl/math/bv/kDOP-inl.h @@ -47,15 +47,15 @@ namespace fcl //============================================================================== extern template -class KDOP; +class FCL_EXPORT KDOP; //============================================================================== extern template -class KDOP; +class FCL_EXPORT KDOP; //============================================================================== extern template -class KDOP; +class FCL_EXPORT KDOP; //============================================================================== extern template @@ -79,6 +79,7 @@ void getDistances(const Vector3& p, double* d); //============================================================================== template +FCL_EXPORT KDOP::KDOP() { static_assert(N == 16 || N == 18 || N == 24, "N should be 16, 18, or 24"); @@ -93,6 +94,7 @@ KDOP::KDOP() //============================================================================== template +FCL_EXPORT KDOP::KDOP(const Vector3& v) { for(std::size_t i = 0; i < 3; ++i) @@ -110,6 +112,7 @@ KDOP::KDOP(const Vector3& v) //============================================================================== template +FCL_EXPORT KDOP::KDOP(const Vector3& a, const Vector3& b) { for(std::size_t i = 0; i < 3; ++i) @@ -128,6 +131,7 @@ KDOP::KDOP(const Vector3& a, const Vector3& b) //============================================================================== template +FCL_EXPORT bool KDOP::overlap(const KDOP& other) const { for(std::size_t i = 0; i < N / 2; ++i) @@ -141,6 +145,7 @@ bool KDOP::overlap(const KDOP& other) const //============================================================================== template +FCL_EXPORT bool KDOP::inside(const Vector3& p) const { for(std::size_t i = 0; i < 3; ++i) @@ -162,6 +167,7 @@ bool KDOP::inside(const Vector3& p) const //============================================================================== template +FCL_EXPORT KDOP& KDOP::operator += (const Vector3& p) { for(std::size_t i = 0; i < 3; ++i) @@ -181,6 +187,7 @@ KDOP& KDOP::operator += (const Vector3& p) //============================================================================== template +FCL_EXPORT KDOP& KDOP::operator += (const KDOP& other) { for(std::size_t i = 0; i < N / 2; ++i) @@ -193,6 +200,7 @@ KDOP& KDOP::operator += (const KDOP& other) //============================================================================== template +FCL_EXPORT KDOP KDOP::operator + (const KDOP& other) const { KDOP res(*this); @@ -201,6 +209,7 @@ KDOP KDOP::operator + (const KDOP& other) const //============================================================================== template +FCL_EXPORT S KDOP::width() const { return dist_[N / 2] - dist_[0]; @@ -208,6 +217,7 @@ S KDOP::width() const //============================================================================== template +FCL_EXPORT S KDOP::height() const { return dist_[N / 2 + 1] - dist_[1]; @@ -215,6 +225,7 @@ S KDOP::height() const //============================================================================== template +FCL_EXPORT S KDOP::depth() const { return dist_[N / 2 + 2] - dist_[2]; @@ -222,6 +233,7 @@ S KDOP::depth() const //============================================================================== template +FCL_EXPORT S KDOP::volume() const { return width() * height() * depth(); @@ -229,6 +241,7 @@ S KDOP::volume() const //============================================================================== template +FCL_EXPORT S KDOP::size() const { return width() * width() + height() * height() + depth() * depth(); @@ -236,6 +249,7 @@ S KDOP::size() const //============================================================================== template +FCL_EXPORT Vector3 KDOP::center() const { return Vector3(dist_[0] + dist_[N / 2], dist_[1] + dist_[N / 2 + 1], dist_[2] + dist_[N / 2 + 2]) * 0.5; @@ -243,6 +257,7 @@ Vector3 KDOP::center() const //============================================================================== template +FCL_EXPORT S KDOP::distance(const KDOP& other, Vector3* P, Vector3* Q) const { FCL_UNUSED(other); @@ -255,6 +270,7 @@ S KDOP::distance(const KDOP& other, Vector3* P, Vector3* Q) co //============================================================================== template +FCL_EXPORT S KDOP::dist(std::size_t i) const { return dist_[i]; @@ -262,6 +278,7 @@ S KDOP::dist(std::size_t i) const //============================================================================== template +FCL_EXPORT S& KDOP::dist(std::size_t i) { return dist_[i]; @@ -269,6 +286,7 @@ S& KDOP::dist(std::size_t i) //============================================================================== template +FCL_EXPORT KDOP translate( const KDOP& bv, const Eigen::MatrixBase& t) { @@ -292,6 +310,7 @@ KDOP translate( //============================================================================== template +FCL_EXPORT void minmax(S a, S b, S& minv, S& maxv) { if(a > b) @@ -308,6 +327,7 @@ void minmax(S a, S b, S& minv, S& maxv) //============================================================================== template +FCL_EXPORT void minmax(S p, S& minv, S& maxv) { if(p > maxv) maxv = p; @@ -326,6 +346,7 @@ struct GetDistancesImpl //============================================================================== template +FCL_EXPORT void getDistances(const Vector3& p, S* d) { GetDistancesImpl::run(p, d); @@ -333,7 +354,7 @@ void getDistances(const Vector3& p, S* d) //============================================================================== template -struct GetDistancesImpl +struct FCL_EXPORT GetDistancesImpl { static void run(const Vector3& p, S* d) { @@ -347,7 +368,7 @@ struct GetDistancesImpl //============================================================================== template -struct GetDistancesImpl +struct FCL_EXPORT GetDistancesImpl { static void run(const Vector3& p, S* d) { @@ -362,7 +383,7 @@ struct GetDistancesImpl //============================================================================== template -struct GetDistancesImpl +struct FCL_EXPORT GetDistancesImpl { static void run(const Vector3& p, S* d) { diff --git a/include/fcl/math/bv/kDOP.h b/include/fcl/math/bv/kDOP.h index 8b312162c..54b7e9c12 100644 --- a/include/fcl/math/bv/kDOP.h +++ b/include/fcl/math/bv/kDOP.h @@ -81,7 +81,7 @@ namespace fcl /// (-1, 1, -1) and (1, -1, 1) --> indices 10 and 22 /// (1, -1, -1) and (-1, 1, 1) --> indices 11 and 23 template -class KDOP +class FCL_EXPORT KDOP { public: @@ -152,19 +152,23 @@ using KDOPd = KDOP; /// @brief Find the smaller and larger one of two values template +FCL_EXPORT void minmax(S a, S b, S& minv, S& maxv); /// @brief Merge the interval [minv, maxv] and value p/ template +FCL_EXPORT void minmax(S p, S& minv, S& maxv); /// @brief Compute the distances to planes with normals from KDOP vectors except /// those of AABB face planes template +FCL_EXPORT void getDistances(const Vector3& p, S* d); /// @brief translate the KDOP BV template +FCL_EXPORT KDOP translate( const KDOP& bv, const Eigen::MatrixBase& t); diff --git a/include/fcl/math/bv/kIOS-inl.h b/include/fcl/math/bv/kIOS-inl.h index 0760cdc7a..81a802a8c 100644 --- a/include/fcl/math/bv/kIOS-inl.h +++ b/include/fcl/math/bv/kIOS-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class kIOS; +class FCL_EXPORT kIOS; //============================================================================== template diff --git a/include/fcl/math/bv/kIOS.h b/include/fcl/math/bv/kIOS.h index 3cf941778..85f8933af 100644 --- a/include/fcl/math/bv/kIOS.h +++ b/include/fcl/math/bv/kIOS.h @@ -45,7 +45,7 @@ namespace fcl /// @brief A class describing the kIOS collision structure, which is a set of spheres. template -class kIOS +class FCL_EXPORT kIOS { /// @brief One sphere in kIOS struct kIOS_Sphere @@ -126,6 +126,7 @@ using kIOSd = kIOS; /// @brief Translate the kIOS BV template +FCL_EXPORT kIOS translate( const kIOS& bv, const Eigen::MatrixBase& t); @@ -133,6 +134,7 @@ kIOS translate( /// and b2 is in identity. /// @todo Not efficient template +FCL_EXPORT bool overlap( const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, @@ -142,6 +144,7 @@ bool overlap( /// and b2 is in identity. /// @todo Not efficient template +FCL_EXPORT bool overlap( const Transform3& tf, const kIOS& b1, @@ -150,6 +153,7 @@ bool overlap( /// @brief Approximate distance between two kIOS bounding volumes /// @todo P and Q is not returned, need implementation template +FCL_EXPORT S distance( const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, @@ -161,6 +165,7 @@ S distance( /// @brief Approximate distance between two kIOS bounding volumes /// @todo P and Q is not returned, need implementation template +FCL_EXPORT S distance( const Transform3& tf, const kIOS& b1, diff --git a/include/fcl/math/bv/utility-inl.h b/include/fcl/math/bv/utility-inl.h index 250626dc3..a83d37183 100644 --- a/include/fcl/math/bv/utility-inl.h +++ b/include/fcl/math/bv/utility-inl.h @@ -62,6 +62,7 @@ namespace OBB_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(Vector3* ps, OBB& bv) { bv.To = ps[0]; @@ -71,6 +72,7 @@ void fit1(Vector3* ps, OBB& bv) //============================================================================== template +FCL_EXPORT void fit2(Vector3* ps, OBB& bv) { const Vector3& p1 = ps[0]; @@ -88,6 +90,7 @@ void fit2(Vector3* ps, OBB& bv) //============================================================================== template +FCL_EXPORT void fit3(Vector3* ps, OBB& bv) { const Vector3& p1 = ps[0]; @@ -117,6 +120,7 @@ void fit3(Vector3* ps, OBB& bv) //============================================================================== template +FCL_EXPORT void fit6(Vector3* ps, OBB& bv) { OBB bv1, bv2; @@ -127,6 +131,7 @@ void fit6(Vector3* ps, OBB& bv) //============================================================================== template +FCL_EXPORT void fitn(Vector3* ps, int n, OBB& bv) { Matrix3 M; @@ -171,6 +176,7 @@ namespace RSS_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(Vector3* ps, RSS& bv) { bv.To = ps[0]; @@ -182,6 +188,7 @@ void fit1(Vector3* ps, RSS& bv) //============================================================================== template +FCL_EXPORT void fit2(Vector3* ps, RSS& bv) { const Vector3& p1 = ps[0]; @@ -201,6 +208,7 @@ void fit2(Vector3* ps, RSS& bv) //============================================================================== template +FCL_EXPORT void fit3(Vector3* ps, RSS& bv) { const Vector3& p1 = ps[0]; @@ -228,6 +236,7 @@ void fit3(Vector3* ps, RSS& bv) //============================================================================== template +FCL_EXPORT void fit6(Vector3* ps, RSS& bv) { RSS bv1, bv2; @@ -238,6 +247,7 @@ void fit6(Vector3* ps, RSS& bv) //============================================================================== template +FCL_EXPORT void fitn(Vector3* ps, int n, RSS& bv) { Matrix3 M; // row first matrix @@ -254,22 +264,27 @@ void fitn(Vector3* ps, int n, RSS& bv) //============================================================================== extern template +FCL_EXPORT void fit1(Vector3* ps, RSS& bv); //============================================================================== extern template +FCL_EXPORT void fit2(Vector3* ps, RSS& bv); //============================================================================== extern template +FCL_EXPORT void fit3(Vector3* ps, RSS& bv); //============================================================================== extern template +FCL_EXPORT void fit6(Vector3* ps, RSS& bv); //============================================================================== extern template +FCL_EXPORT void fitn(Vector3* ps, int n, RSS& bv); //============================================================================== @@ -282,6 +297,7 @@ namespace kIOS_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(Vector3* ps, kIOS& bv) { bv.num_spheres = 1; @@ -295,6 +311,7 @@ void fit1(Vector3* ps, kIOS& bv) //============================================================================== template +FCL_EXPORT void fit2(Vector3* ps, kIOS& bv) { bv.num_spheres = 5; @@ -332,6 +349,7 @@ void fit2(Vector3* ps, kIOS& bv) //============================================================================== template +FCL_EXPORT void fit3(Vector3* ps, kIOS& bv) { bv.num_spheres = 3; @@ -377,6 +395,7 @@ void fit3(Vector3* ps, kIOS& bv) //============================================================================== template +FCL_EXPORT void fitn(Vector3* ps, int n, kIOS& bv) { Matrix3 M; @@ -444,18 +463,22 @@ void fitn(Vector3* ps, int n, kIOS& bv) //============================================================================== extern template +FCL_EXPORT void fit1(Vector3* ps, kIOS& bv); //============================================================================== extern template +FCL_EXPORT void fit2(Vector3* ps, kIOS& bv); //============================================================================== extern template +FCL_EXPORT void fit3(Vector3* ps, kIOS& bv); //============================================================================== extern template +FCL_EXPORT void fitn(Vector3* ps, int n, kIOS& bv); //============================================================================== @@ -468,6 +491,7 @@ namespace OBBRSS_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(Vector3* ps, OBBRSS& bv) { OBB_fit_functions::fit1(ps, bv.obb); @@ -476,6 +500,7 @@ void fit1(Vector3* ps, OBBRSS& bv) //============================================================================== template +FCL_EXPORT void fit2(Vector3* ps, OBBRSS& bv) { OBB_fit_functions::fit2(ps, bv.obb); @@ -484,6 +509,7 @@ void fit2(Vector3* ps, OBBRSS& bv) //============================================================================== template +FCL_EXPORT void fit3(Vector3* ps, OBBRSS& bv) { OBB_fit_functions::fit3(ps, bv.obb); @@ -492,6 +518,7 @@ void fit3(Vector3* ps, OBBRSS& bv) //============================================================================== template +FCL_EXPORT void fitn(Vector3* ps, int n, OBBRSS& bv) { OBB_fit_functions::fitn(ps, n, bv.obb); @@ -520,7 +547,7 @@ void fitn(Vector3* ps, int n, OBBRSS& bv); //============================================================================== template -struct Fitter +struct FCL_EXPORT Fitter { static void fit(Vector3* ps, int n, BV& bv) { @@ -531,7 +558,7 @@ struct Fitter //============================================================================== template -struct Fitter> +struct FCL_EXPORT Fitter> { static void fit(Vector3* ps, int n, OBB& bv) { @@ -557,7 +584,7 @@ struct Fitter> //============================================================================== template -struct Fitter> +struct FCL_EXPORT Fitter> { static void fit(Vector3* ps, int n, RSS& bv) { @@ -580,7 +607,7 @@ struct Fitter> //============================================================================== template -struct Fitter> +struct FCL_EXPORT Fitter> { static void fit(Vector3* ps, int n, kIOS& bv) { @@ -603,7 +630,7 @@ struct Fitter> //============================================================================== template -struct Fitter> +struct FCL_EXPORT Fitter> { static void fit(Vector3* ps, int n, OBBRSS& bv) { @@ -646,6 +673,7 @@ struct Fitter>; //============================================================================== template +FCL_EXPORT void fit(Vector3* ps, int n, BV& bv) { detail::Fitter::fit(ps, n, bv); @@ -658,7 +686,7 @@ namespace detail { /// @brief Convert a bounding volume of type BV1 in configuration tf1 to a /// bounding volume of type BV2 in I configuration. template -class ConvertBVImpl +class FCL_EXPORT ConvertBVImpl { private: static void run(const BV1& bv1, const Transform3& tf1, BV2& bv2) @@ -674,7 +702,7 @@ class ConvertBVImpl //============================================================================== /// @brief Convert from AABB to AABB, not very tight but is fast. template -class ConvertBVImpl, AABB> +class FCL_EXPORT ConvertBVImpl, AABB> { public: static void run(const AABB& bv1, const Transform3& tf1, AABB& bv2) @@ -690,7 +718,7 @@ class ConvertBVImpl, AABB> //============================================================================== template -class ConvertBVImpl, OBB> +class FCL_EXPORT ConvertBVImpl, OBB> { public: static void run(const AABB& bv1, const Transform3& tf1, OBB& bv2) @@ -739,7 +767,7 @@ class ConvertBVImpl, OBB> //============================================================================== template -class ConvertBVImpl, OBB> +class FCL_EXPORT ConvertBVImpl, OBB> { public: static void run(const OBB& bv1, const Transform3& tf1, OBB& bv2) @@ -752,7 +780,7 @@ class ConvertBVImpl, OBB> //============================================================================== template -class ConvertBVImpl, OBB> +class FCL_EXPORT ConvertBVImpl, OBB> { public: static void run(const OBBRSS& bv1, const Transform3& tf1, OBB& bv2) @@ -763,7 +791,7 @@ class ConvertBVImpl, OBB> //============================================================================== template -class ConvertBVImpl, OBB> +class FCL_EXPORT ConvertBVImpl, OBB> { public: static void run(const RSS& bv1, const Transform3& tf1, OBB& bv2) @@ -776,7 +804,7 @@ class ConvertBVImpl, OBB> //============================================================================== template -class ConvertBVImpl> +class FCL_EXPORT ConvertBVImpl> { public: static void run(const BV1& bv1, const Transform3& tf1, AABB& bv2) @@ -792,7 +820,7 @@ class ConvertBVImpl> //============================================================================== template -class ConvertBVImpl> +class FCL_EXPORT ConvertBVImpl> { public: static void run(const BV1& bv1, const Transform3& tf1, OBB& bv2) @@ -805,7 +833,7 @@ class ConvertBVImpl> //============================================================================== template -class ConvertBVImpl, RSS> +class FCL_EXPORT ConvertBVImpl, RSS> { public: static void run(const OBB& bv1, const Transform3& tf1, RSS& bv2) @@ -821,7 +849,7 @@ class ConvertBVImpl, RSS> //============================================================================== template -class ConvertBVImpl, RSS> +class FCL_EXPORT ConvertBVImpl, RSS> { public: static void run(const RSS& bv1, const Transform3& tf1, RSS& bv2) @@ -837,7 +865,7 @@ class ConvertBVImpl, RSS> //============================================================================== template -class ConvertBVImpl, RSS> +class FCL_EXPORT ConvertBVImpl, RSS> { public: static void run(const OBBRSS& bv1, const Transform3& tf1, RSS& bv2) @@ -848,7 +876,7 @@ class ConvertBVImpl, RSS> //============================================================================== template -class ConvertBVImpl, RSS> +class FCL_EXPORT ConvertBVImpl, RSS> { public: static void run(const AABB& bv1, const Transform3& tf1, RSS& bv2) @@ -897,39 +925,39 @@ class ConvertBVImpl, RSS> //============================================================================== extern template -class ConvertBVImpl, AABB>; +class FCL_EXPORT ConvertBVImpl, AABB>; //============================================================================== extern template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== extern template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== extern template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== extern template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== extern template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== extern template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== extern template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== extern template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== } // namespace detail @@ -937,6 +965,7 @@ class ConvertBVImpl, RSS>; //============================================================================== template +FCL_EXPORT void convertBV( const BV1& bv1, const Transform3& tf1, BV2& bv2) { diff --git a/include/fcl/math/bv/utility.h b/include/fcl/math/bv/utility.h index 12b2d4f96..fa033db0a 100644 --- a/include/fcl/math/bv/utility.h +++ b/include/fcl/math/bv/utility.h @@ -46,11 +46,13 @@ namespace fcl /// @brief Compute a bounding volume that fits a set of n points. template +FCL_EXPORT void fit(Vector3* ps, int n, BV& bv); /// @brief Convert a bounding volume of type BV1 in configuration tf1 to /// bounding volume of type BV2 in identity configuration. template +FCL_EXPORT void convertBV( const BV1& bv1, const Transform3& tf1, BV2& bv2); diff --git a/include/fcl/math/constants.h b/include/fcl/math/constants.h index efb6434aa..e3ecfdfa6 100644 --- a/include/fcl/math/constants.h +++ b/include/fcl/math/constants.h @@ -43,7 +43,7 @@ namespace fcl { template -struct constants +struct FCL_EXPORT constants { /// The mathematical constant pi static constexpr S pi() { return S(3.141592653589793238462643383279502884197169399375105820974944592L); } diff --git a/include/fcl/math/detail/polysolver-inl.h b/include/fcl/math/detail/polysolver-inl.h index 2bf96e354..c2c538cce 100644 --- a/include/fcl/math/detail/polysolver-inl.h +++ b/include/fcl/math/detail/polysolver-inl.h @@ -50,7 +50,7 @@ namespace detail { //============================================================================== extern template -class PolySolver; +class FCL_EXPORT PolySolver; //============================================================================== template diff --git a/include/fcl/math/detail/polysolver.h b/include/fcl/math/detail/polysolver.h index eb52b968e..52808a9d7 100644 --- a/include/fcl/math/detail/polysolver.h +++ b/include/fcl/math/detail/polysolver.h @@ -38,6 +38,8 @@ #ifndef FCL_NARROWPHASE_DETAIL_POLYSOLVER_H #define FCL_NARROWPHASE_DETAIL_POLYSOLVER_H +#include "fcl/export.h" + namespace fcl { @@ -45,7 +47,7 @@ namespace detail { /// @brief A class solves polynomial degree (1,2,3) equations template -class PolySolver +class FCL_EXPORT PolySolver { public: /// @brief Solve a linear equation with coefficients c, return roots s and number of roots diff --git a/include/fcl/math/detail/project-inl.h b/include/fcl/math/detail/project-inl.h index b8f3d9f25..abe4df6f7 100644 --- a/include/fcl/math/detail/project-inl.h +++ b/include/fcl/math/detail/project-inl.h @@ -48,7 +48,7 @@ namespace detail //============================================================================== extern template -class Project; +class FCL_EXPORT Project; //============================================================================== template diff --git a/include/fcl/math/detail/project.h b/include/fcl/math/detail/project.h index 4b19b0dbe..39311f2b9 100644 --- a/include/fcl/math/detail/project.h +++ b/include/fcl/math/detail/project.h @@ -49,7 +49,7 @@ namespace detail /// @brief Project functions template -class Project +class FCL_EXPORT Project { public: struct ProjectResult diff --git a/include/fcl/math/detail/seed.h b/include/fcl/math/detail/seed.h index fe237ac56..3ec4eeb68 100644 --- a/include/fcl/math/detail/seed.h +++ b/include/fcl/math/detail/seed.h @@ -39,13 +39,14 @@ #define FCL_MATH_DETAIL_SEED_H #include +#include "fcl/export.h" namespace fcl { namespace detail { -class Seed +class FCL_EXPORT Seed { public: diff --git a/include/fcl/math/geometry-inl.h b/include/fcl/math/geometry-inl.h index c61596161..b66d64559 100644 --- a/include/fcl/math/geometry-inl.h +++ b/include/fcl/math/geometry-inl.h @@ -148,6 +148,7 @@ namespace detail { //============================================================================== template +FCL_EXPORT S maximumDistance_mesh( Vector3* ps, Vector3* ps2, @@ -192,6 +193,7 @@ S maximumDistance_mesh( //============================================================================== template +FCL_EXPORT S maximumDistance_pointcloud( Vector3* ps, Vector3* ps2, @@ -226,6 +228,7 @@ S maximumDistance_pointcloud( /// @brief Compute the bounding volume extent and center for a set or subset of /// points. The bounding volume axes are known. template +FCL_EXPORT void getExtentAndCenter_pointcloud( Vector3* ps, Vector3* ps2, @@ -290,6 +293,7 @@ void getExtentAndCenter_pointcloud( /// @brief Compute the bounding volume extent and center for a set or subset of /// points. The bounding volume axes are known. template +FCL_EXPORT void getExtentAndCenter_mesh( Vector3* ps, Vector3* ps2, @@ -408,6 +412,7 @@ void getExtentAndCenter_mesh( //============================================================================== template +FCL_EXPORT void normalize(Vector3& v, bool* signal) { S sqr_length = v.squaredNorm(); @@ -425,6 +430,7 @@ void normalize(Vector3& v, bool* signal) //============================================================================== template +FCL_EXPORT typename Derived::RealScalar triple(const Eigen::MatrixBase& x, const Eigen::MatrixBase& y, const Eigen::MatrixBase& z) @@ -434,6 +440,7 @@ typename Derived::RealScalar triple(const Eigen::MatrixBase& x, //============================================================================== template +FCL_EXPORT void generateCoordinateSystem( const Eigen::MatrixBase& w, Eigen::MatrixBase& u, @@ -465,6 +472,7 @@ void generateCoordinateSystem( //============================================================================== template +FCL_EXPORT VectorN combine( const VectorN& v1, const VectorN& v2) { @@ -476,6 +484,7 @@ VectorN combine( //============================================================================== template +FCL_EXPORT void hat(Matrix3& mat, const Vector3& vec) { mat << 0, -vec[2], vec[1], vec[2], 0, -vec[0], -vec[1], vec[0], 0; @@ -483,6 +492,7 @@ void hat(Matrix3& mat, const Vector3& vec) //============================================================================== template +FCL_EXPORT void eigen(const Matrix3& m, Vector3& dout, Matrix3& vout) { // We assume that m is symmetric matrix. @@ -498,6 +508,7 @@ void eigen(const Matrix3& m, Vector3& dout, Matrix3& vout) //============================================================================== template +FCL_EXPORT void eigen_old(const Matrix3& m, Vector3& dout, Matrix3& vout) { Matrix3 R(m); @@ -587,6 +598,7 @@ void eigen_old(const Matrix3& m, Vector3& dout, Matrix3& vout) //============================================================================== template +FCL_EXPORT void axisFromEigen(const Matrix3& eigenV, const Vector3& eigenS, Matrix3& axis) @@ -626,6 +638,7 @@ void axisFromEigen(const Matrix3& eigenV, //============================================================================== template +FCL_EXPORT void axisFromEigen(const Matrix3& eigenV, const Vector3& eigenS, Transform3& tf) @@ -665,6 +678,7 @@ void axisFromEigen(const Matrix3& eigenV, //============================================================================== template +FCL_EXPORT void generateCoordinateSystem(Matrix3& axis) { // Assum axis.col(0) is closest to z-axis @@ -710,6 +724,7 @@ void generateCoordinateSystem(Matrix3& axis) //============================================================================== template +FCL_EXPORT void generateCoordinateSystem(Transform3& tf) { // Assum axis.col(0) is closest to z-axis @@ -755,6 +770,7 @@ void generateCoordinateSystem(Transform3& tf) //============================================================================== template +FCL_EXPORT void relativeTransform( const Eigen::MatrixBase& R1, const Eigen::MatrixBase& t1, const Eigen::MatrixBase& R2, const Eigen::MatrixBase& t2, @@ -786,6 +802,7 @@ void relativeTransform( //============================================================================== template +FCL_EXPORT void relativeTransform( const Transform3& T1, const Transform3& T2, @@ -807,6 +824,7 @@ void relativeTransform( //============================================================================== template +FCL_EXPORT void getRadiusAndOriginAndRectangleSize( Vector3* ps, Vector3* ps2, @@ -1089,6 +1107,7 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== template +FCL_EXPORT void getRadiusAndOriginAndRectangleSize( Vector3* ps, Vector3* ps2, @@ -1370,6 +1389,7 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== template +FCL_EXPORT void circumCircleComputation( const Vector3& a, const Vector3& b, @@ -1394,6 +1414,7 @@ void circumCircleComputation( //============================================================================== template +FCL_EXPORT S maximumDistance( Vector3* ps, Vector3* ps2, @@ -1410,6 +1431,7 @@ S maximumDistance( //============================================================================== template +FCL_EXPORT void getExtentAndCenter( Vector3* ps, Vector3* ps2, @@ -1428,6 +1450,7 @@ void getExtentAndCenter( //============================================================================== template +FCL_EXPORT void getCovariance(Vector3* ps, Vector3* ps2, Triangle* ts, diff --git a/include/fcl/math/geometry.h b/include/fcl/math/geometry.h index 92dc60728..aac140851 100644 --- a/include/fcl/math/geometry.h +++ b/include/fcl/math/geometry.h @@ -49,59 +49,72 @@ namespace fcl { template +FCL_EXPORT void normalize(Vector3& v, bool* signal); template +FCL_EXPORT typename Derived::RealScalar triple(const Eigen::MatrixBase& x, const Eigen::MatrixBase& y, const Eigen::MatrixBase& z); template +FCL_EXPORT void generateCoordinateSystem( const Eigen::MatrixBase& w, Eigen::MatrixBase& u, Eigen::MatrixBase& v); template +FCL_EXPORT VectorN combine( const VectorN& v1, const VectorN& v2); template +FCL_EXPORT void hat(Matrix3& mat, const Vector3& vec); /// @brief compute the eigen vector and eigen vector of a matrix. dout is the /// eigen values, vout is the eigen vectors template +FCL_EXPORT void eigen(const Matrix3& m, Vector3& dout, Matrix3& vout); /// @brief compute the eigen vector and eigen vector of a matrix. dout is the /// eigen values, vout is the eigen vectors template +FCL_EXPORT void eigen_old(const Matrix3& m, Vector3& dout, Matrix3& vout); template +FCL_EXPORT void axisFromEigen(const Matrix3& eigenV, const Vector3& eigenS, Matrix3& axis); template +FCL_EXPORT void axisFromEigen(const Matrix3& eigenV, const Vector3& eigenS, Transform3& tf); template +FCL_EXPORT void generateCoordinateSystem(Matrix3& axis); template +FCL_EXPORT void generateCoordinateSystem(Transform3& tf); template +FCL_EXPORT void relativeTransform( const Eigen::MatrixBase& R1, const Eigen::MatrixBase& t1, const Eigen::MatrixBase& R2, const Eigen::MatrixBase& t2, Eigen::MatrixBase& R, Eigen::MatrixBase& t); template +FCL_EXPORT void relativeTransform( const Eigen::Transform& T1, const Eigen::Transform& T2, @@ -110,6 +123,7 @@ void relativeTransform( /// @brief Compute the RSS bounding volume parameters: radius, rectangle size /// and the origin, given the BV axises. template +FCL_EXPORT void getRadiusAndOriginAndRectangleSize( Vector3* ps, Vector3* ps2, @@ -124,6 +138,7 @@ void getRadiusAndOriginAndRectangleSize( /// @brief Compute the RSS bounding volume parameters: radius, rectangle size /// and the origin, given the BV axises. template +FCL_EXPORT void getRadiusAndOriginAndRectangleSize( Vector3* ps, Vector3* ps2, @@ -136,6 +151,7 @@ void getRadiusAndOriginAndRectangleSize( /// @brief Compute the center and radius for a triangle's circumcircle template +FCL_EXPORT void circumCircleComputation( const Vector3& a, const Vector3& b, @@ -145,6 +161,7 @@ void circumCircleComputation( /// @brief Compute the maximum distance from a given center point to a point cloud template +FCL_EXPORT S maximumDistance( Vector3* ps, Vector3* ps2, @@ -156,6 +173,7 @@ S maximumDistance( /// @brief Compute the bounding volume extent and center for a set or subset of /// points, given the BV axises. template +FCL_EXPORT void getExtentAndCenter( Vector3* ps, Vector3* ps2, @@ -169,6 +187,7 @@ void getExtentAndCenter( /// @brief Compute the bounding volume extent and center for a set or subset of /// points, given the BV axises. template +FCL_EXPORT void getExtentAndCenter( Vector3* ps, Vector3* ps2, @@ -182,6 +201,7 @@ void getExtentAndCenter( /// ts = null, then indices refer to points directly; otherwise refer to /// triangles template +FCL_EXPORT void getCovariance( Vector3* ps, Vector3* ps2, diff --git a/include/fcl/math/motion/bv_motion_bound_visitor.h b/include/fcl/math/motion/bv_motion_bound_visitor.h index e60d3c218..cecfe06e7 100644 --- a/include/fcl/math/motion/bv_motion_bound_visitor.h +++ b/include/fcl/math/motion/bv_motion_bound_visitor.h @@ -59,7 +59,7 @@ class TranslationMotion; /// @brief Compute the motion bound for a bounding volume, given the closest /// direction n between two query objects template -class BVMotionBoundVisitor +class FCL_EXPORT BVMotionBoundVisitor { public: virtual S visit(const MotionBase& motion) const = 0; diff --git a/include/fcl/math/motion/interp_motion-inl.h b/include/fcl/math/motion/interp_motion-inl.h index f14a051d1..384367a80 100644 --- a/include/fcl/math/motion/interp_motion-inl.h +++ b/include/fcl/math/motion/interp_motion-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class InterpMotion; +class FCL_EXPORT InterpMotion; //============================================================================== template diff --git a/include/fcl/math/motion/interp_motion.h b/include/fcl/math/motion/interp_motion.h index 69cbd8efb..a7f58eb74 100644 --- a/include/fcl/math/motion/interp_motion.h +++ b/include/fcl/math/motion/interp_motion.h @@ -55,7 +55,7 @@ namespace fcl /// T(0) = T0 + R0 p_ref - p_ref /// T(1) = T1 + R1 p_ref - p_ref template -class InterpMotion : public MotionBase +class FCL_EXPORT InterpMotion : public MotionBase { public: /// @brief Default transformations are all identities diff --git a/include/fcl/math/motion/motion_base-inl.h b/include/fcl/math/motion/motion_base-inl.h index eb36808f1..280058f73 100644 --- a/include/fcl/math/motion/motion_base-inl.h +++ b/include/fcl/math/motion/motion_base-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class MotionBase; +class FCL_EXPORT MotionBase; //============================================================================== template diff --git a/include/fcl/math/motion/screw_motion-inl.h b/include/fcl/math/motion/screw_motion-inl.h index ce5c7ae9e..53c5c5bfd 100644 --- a/include/fcl/math/motion/screw_motion-inl.h +++ b/include/fcl/math/motion/screw_motion-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class ScrewMotion; +class FCL_EXPORT ScrewMotion; //============================================================================== template diff --git a/include/fcl/math/motion/screw_motion.h b/include/fcl/math/motion/screw_motion.h index 0adb7fa95..fce33874e 100644 --- a/include/fcl/math/motion/screw_motion.h +++ b/include/fcl/math/motion/screw_motion.h @@ -49,7 +49,7 @@ namespace fcl { template -class ScrewMotion : public MotionBase +class FCL_EXPORT ScrewMotion : public MotionBase { public: /// @brief Default transformations are all identities diff --git a/include/fcl/math/motion/spline_motion-inl.h b/include/fcl/math/motion/spline_motion-inl.h index aa2c07038..9986aecb0 100644 --- a/include/fcl/math/motion/spline_motion-inl.h +++ b/include/fcl/math/motion/spline_motion-inl.h @@ -47,7 +47,7 @@ namespace fcl //============================================================================== extern template -class SplineMotion; +class FCL_EXPORT SplineMotion; //============================================================================== template diff --git a/include/fcl/math/motion/spline_motion.h b/include/fcl/math/motion/spline_motion.h index a6082ac04..96f2eba24 100644 --- a/include/fcl/math/motion/spline_motion.h +++ b/include/fcl/math/motion/spline_motion.h @@ -50,7 +50,7 @@ namespace fcl { template -class SplineMotion : public MotionBase +class FCL_EXPORT SplineMotion : public MotionBase { public: /// @brief Construct motion from 4 deBoor points diff --git a/include/fcl/math/motion/taylor_model/interval.h b/include/fcl/math/motion/taylor_model/interval.h index 5aa2dc52f..cda1aa732 100644 --- a/include/fcl/math/motion/taylor_model/interval.h +++ b/include/fcl/math/motion/taylor_model/interval.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Interval class for [a, b] template -struct Interval +struct FCL_EXPORT Interval { S i_[2]; @@ -125,9 +125,11 @@ struct Interval }; template +FCL_EXPORT Interval bound(const Interval& i, S v); template +FCL_EXPORT Interval bound(const Interval& i, const Interval& other); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/interval_matrix.h b/include/fcl/math/motion/taylor_model/interval_matrix.h index 3f16c3eca..eab03c2d4 100644 --- a/include/fcl/math/motion/taylor_model/interval_matrix.h +++ b/include/fcl/math/motion/taylor_model/interval_matrix.h @@ -45,7 +45,7 @@ namespace fcl { template -struct IMatrix3 +struct FCL_EXPORT IMatrix3 { IVector3 v_[3]; @@ -95,6 +95,7 @@ struct IMatrix3 }; template +FCL_EXPORT IMatrix3 rotationConstrain(const IMatrix3& m); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/interval_vector.h b/include/fcl/math/motion/taylor_model/interval_vector.h index c59e81af2..d5e5a9415 100644 --- a/include/fcl/math/motion/taylor_model/interval_vector.h +++ b/include/fcl/math/motion/taylor_model/interval_vector.h @@ -44,7 +44,7 @@ namespace fcl { template -struct IVector3 +struct FCL_EXPORT IVector3 { Interval i_[3]; @@ -106,9 +106,11 @@ struct IVector3 }; template +FCL_EXPORT IVector3 bound(const IVector3& i, const Vector3& v); template +FCL_EXPORT IVector3 bound(const IVector3& i, const IVector3& v); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/taylor_matrix-inl.h b/include/fcl/math/motion/taylor_model/taylor_matrix-inl.h index 52b5a80c4..f5b184375 100644 --- a/include/fcl/math/motion/taylor_model/taylor_matrix-inl.h +++ b/include/fcl/math/motion/taylor_model/taylor_matrix-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class TMatrix3; +class FCL_EXPORT TMatrix3; //============================================================================== extern template diff --git a/include/fcl/math/motion/taylor_model/taylor_matrix.h b/include/fcl/math/motion/taylor_model/taylor_matrix.h index 2c4a11126..c26f53309 100644 --- a/include/fcl/math/motion/taylor_model/taylor_matrix.h +++ b/include/fcl/math/motion/taylor_model/taylor_matrix.h @@ -45,7 +45,7 @@ namespace fcl { template -class TMatrix3 +class FCL_EXPORT TMatrix3 { TVector3 v_[3]; @@ -106,24 +106,31 @@ class TMatrix3 }; template +FCL_EXPORT TMatrix3 rotationConstrain(const TMatrix3& m); template +FCL_EXPORT TMatrix3 operator * (const Matrix3& m, const TaylorModel& a); template +FCL_EXPORT TMatrix3 operator * (const TaylorModel& a, const Matrix3& m); template +FCL_EXPORT TMatrix3 operator * (const TaylorModel& a, const TMatrix3& m); template +FCL_EXPORT TMatrix3 operator * (S d, const TMatrix3& m); template +FCL_EXPORT TMatrix3 operator + (const Matrix3& m1, const TMatrix3& m2); template +FCL_EXPORT TMatrix3 operator - (const Matrix3& m1, const TMatrix3& m2); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/taylor_model-inl.h b/include/fcl/math/motion/taylor_model/taylor_model-inl.h index 2ebb086e6..861f72d0f 100644 --- a/include/fcl/math/motion/taylor_model/taylor_model-inl.h +++ b/include/fcl/math/motion/taylor_model/taylor_model-inl.h @@ -48,7 +48,7 @@ namespace fcl //============================================================================== extern template -class TaylorModel; +class FCL_EXPORT TaylorModel; //============================================================================== extern template diff --git a/include/fcl/math/motion/taylor_model/taylor_model.h b/include/fcl/math/motion/taylor_model/taylor_model.h index e80561fd2..b8c199949 100644 --- a/include/fcl/math/motion/taylor_model/taylor_model.h +++ b/include/fcl/math/motion/taylor_model/taylor_model.h @@ -55,7 +55,7 @@ namespace fcl /// remainder. All the operations on two Taylor models assume their time /// intervals are the same. template -class TaylorModel +class FCL_EXPORT TaylorModel { /// @brief time interval std::shared_ptr> time_interval_; @@ -118,24 +118,30 @@ class TaylorModel }; template +FCL_EXPORT TaylorModel operator * (S d, const TaylorModel& a); template +FCL_EXPORT TaylorModel operator + (S d, const TaylorModel& a); template +FCL_EXPORT TaylorModel operator - (S d, const TaylorModel& a); /// @brief Generate Taylor model for cos(w t + q0) template +FCL_EXPORT void generateTaylorModelForCosFunc(TaylorModel& tm, S w, S q0); /// @brief Generate Taylor model for sin(w t + q0) template +FCL_EXPORT void generateTaylorModelForSinFunc(TaylorModel& tm, S w, S q0); /// @brief Generate Taylor model for p + v t template +FCL_EXPORT void generateTaylorModelForLinearFunc(TaylorModel& tm, S p, S v); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/taylor_vector-inl.h b/include/fcl/math/motion/taylor_model/taylor_vector-inl.h index 516f7b531..1ce2b3613 100644 --- a/include/fcl/math/motion/taylor_model/taylor_vector-inl.h +++ b/include/fcl/math/motion/taylor_model/taylor_vector-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class TVector3; +class FCL_EXPORT TVector3; //============================================================================== extern template diff --git a/include/fcl/math/motion/taylor_model/taylor_vector.h b/include/fcl/math/motion/taylor_model/taylor_vector.h index 884a3caab..7df662f70 100644 --- a/include/fcl/math/motion/taylor_model/taylor_vector.h +++ b/include/fcl/math/motion/taylor_model/taylor_vector.h @@ -45,7 +45,7 @@ namespace fcl { template -class TVector3 +class FCL_EXPORT TVector3 { TaylorModel i_[3]; @@ -104,15 +104,19 @@ class TVector3 }; template +FCL_EXPORT void generateTVector3ForLinearFunc(TVector3& v, const Vector3& position, const Vector3& velocity); template +FCL_EXPORT TVector3 operator * (const Vector3& v, const TaylorModel& a); template +FCL_EXPORT TVector3 operator + (const Vector3& v1, const TVector3& v2); template +FCL_EXPORT TVector3 operator - (const Vector3& v1, const TVector3& v2); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/time_interval.h b/include/fcl/math/motion/taylor_model/time_interval.h index 49c686a09..1320d9c63 100644 --- a/include/fcl/math/motion/taylor_model/time_interval.h +++ b/include/fcl/math/motion/taylor_model/time_interval.h @@ -47,7 +47,7 @@ namespace fcl { template -struct TimeInterval +struct FCL_EXPORT TimeInterval { /// @brief time Interval and different powers Interval t_; // [t1, t2] diff --git a/include/fcl/math/motion/tbv_motion_bound_visitor.h b/include/fcl/math/motion/tbv_motion_bound_visitor.h index 05c947c42..515fef80e 100644 --- a/include/fcl/math/motion/tbv_motion_bound_visitor.h +++ b/include/fcl/math/motion/tbv_motion_bound_visitor.h @@ -62,7 +62,7 @@ template class TranslationMotion; template -class TBVMotionBoundVisitor : public BVMotionBoundVisitor +class FCL_EXPORT TBVMotionBoundVisitor : public BVMotionBoundVisitor { public: using S = typename BV::S; diff --git a/include/fcl/math/motion/translation_motion-inl.h b/include/fcl/math/motion/translation_motion-inl.h index 7feffd1cc..a2aaf6caf 100644 --- a/include/fcl/math/motion/translation_motion-inl.h +++ b/include/fcl/math/motion/translation_motion-inl.h @@ -47,7 +47,7 @@ namespace fcl //============================================================================== extern template -class TranslationMotion; +class FCL_EXPORT TranslationMotion; //============================================================================== template diff --git a/include/fcl/math/motion/translation_motion.h b/include/fcl/math/motion/translation_motion.h index ff2a1ff19..37b77b470 100644 --- a/include/fcl/math/motion/translation_motion.h +++ b/include/fcl/math/motion/translation_motion.h @@ -46,7 +46,7 @@ namespace fcl { template -class TranslationMotion : public MotionBase +class FCL_EXPORT TranslationMotion : public MotionBase { public: /// @brief Construct motion from intial and goal transform diff --git a/include/fcl/math/motion/triangle_motion_bound_visitor-inl.h b/include/fcl/math/motion/triangle_motion_bound_visitor-inl.h index 2f7dd34b4..59f37cb03 100644 --- a/include/fcl/math/motion/triangle_motion_bound_visitor-inl.h +++ b/include/fcl/math/motion/triangle_motion_bound_visitor-inl.h @@ -51,7 +51,7 @@ namespace fcl //============================================================================== extern template -class TriangleMotionBoundVisitor; +class FCL_EXPORT TriangleMotionBoundVisitor; //============================================================================== template diff --git a/include/fcl/math/motion/triangle_motion_bound_visitor.h b/include/fcl/math/motion/triangle_motion_bound_visitor.h index c37a206a7..e6a3b7d28 100644 --- a/include/fcl/math/motion/triangle_motion_bound_visitor.h +++ b/include/fcl/math/motion/triangle_motion_bound_visitor.h @@ -71,7 +71,7 @@ template struct TriangleMotionBoundVisitorVisitImpl; template -class TriangleMotionBoundVisitor +class FCL_EXPORT TriangleMotionBoundVisitor { public: TriangleMotionBoundVisitor( diff --git a/include/fcl/math/rng-inl.h b/include/fcl/math/rng-inl.h index af6a4a410..1ba9da77b 100644 --- a/include/fcl/math/rng-inl.h +++ b/include/fcl/math/rng-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class RNG; +class FCL_EXPORT RNG; //============================================================================== template diff --git a/include/fcl/math/rng.h b/include/fcl/math/rng.h index 827c0ea6d..782cf48ce 100644 --- a/include/fcl/math/rng.h +++ b/include/fcl/math/rng.h @@ -55,7 +55,7 @@ namespace fcl /// threads. It is also guaranteed that all created instances will /// have a different random seed. template -class RNG +class FCL_EXPORT RNG { public: /// @brief Constructor. Always sets a different random seed diff --git a/include/fcl/math/sampler/sampler_base.h b/include/fcl/math/sampler/sampler_base.h index 529b6f7ac..d49d8c99f 100644 --- a/include/fcl/math/sampler/sampler_base.h +++ b/include/fcl/math/sampler/sampler_base.h @@ -44,14 +44,14 @@ namespace fcl { template -class SamplerBase +class FCL_EXPORT SamplerBase { public: mutable RNG rng; }; extern template -class SamplerBase; +class FCL_EXPORT SamplerBase; } // namespace fcl diff --git a/include/fcl/math/sampler/sampler_r.h b/include/fcl/math/sampler/sampler_r.h index 44eed4678..9b1977624 100644 --- a/include/fcl/math/sampler/sampler_r.h +++ b/include/fcl/math/sampler/sampler_r.h @@ -46,7 +46,7 @@ namespace fcl { template -class SamplerR : public SamplerBase +class FCL_EXPORT SamplerR : public SamplerBase { public: SamplerR(); diff --git a/include/fcl/math/sampler/sampler_se2-inl.h b/include/fcl/math/sampler/sampler_se2-inl.h index 27d6471e7..aa3cb9a84 100644 --- a/include/fcl/math/sampler/sampler_se2-inl.h +++ b/include/fcl/math/sampler/sampler_se2-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SamplerSE2; +class FCL_EXPORT SamplerSE2; //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se2.h b/include/fcl/math/sampler/sampler_se2.h index be626a522..ff321e71c 100644 --- a/include/fcl/math/sampler/sampler_se2.h +++ b/include/fcl/math/sampler/sampler_se2.h @@ -45,7 +45,7 @@ namespace fcl { template -class SamplerSE2 : public SamplerBase +class FCL_EXPORT SamplerSE2 : public SamplerBase { public: SamplerSE2(); diff --git a/include/fcl/math/sampler/sampler_se2_disk-inl.h b/include/fcl/math/sampler/sampler_se2_disk-inl.h index d074c773b..64aa25622 100644 --- a/include/fcl/math/sampler/sampler_se2_disk-inl.h +++ b/include/fcl/math/sampler/sampler_se2_disk-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SamplerSE2_disk; +class FCL_EXPORT SamplerSE2_disk; //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se2_disk.h b/include/fcl/math/sampler/sampler_se2_disk.h index eed432d0f..154110b7e 100644 --- a/include/fcl/math/sampler/sampler_se2_disk.h +++ b/include/fcl/math/sampler/sampler_se2_disk.h @@ -45,7 +45,7 @@ namespace fcl { template -class SamplerSE2_disk : public SamplerBase +class FCL_EXPORT SamplerSE2_disk : public SamplerBase { public: SamplerSE2_disk(); diff --git a/include/fcl/math/sampler/sampler_se3_euler-inl.h b/include/fcl/math/sampler/sampler_se3_euler-inl.h index 98d5b91f6..14ff1b884 100644 --- a/include/fcl/math/sampler/sampler_se3_euler-inl.h +++ b/include/fcl/math/sampler/sampler_se3_euler-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SamplerSE3Euler; +class FCL_EXPORT SamplerSE3Euler; //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_euler.h b/include/fcl/math/sampler/sampler_se3_euler.h index 5ec8d9228..487e22a9b 100644 --- a/include/fcl/math/sampler/sampler_se3_euler.h +++ b/include/fcl/math/sampler/sampler_se3_euler.h @@ -45,7 +45,7 @@ namespace fcl { template -class SamplerSE3Euler : public SamplerBase +class FCL_EXPORT SamplerSE3Euler : public SamplerBase { public: SamplerSE3Euler(); diff --git a/include/fcl/math/sampler/sampler_se3_euler_ball-inl.h b/include/fcl/math/sampler/sampler_se3_euler_ball-inl.h index 3a940c2fa..48dc6d972 100644 --- a/include/fcl/math/sampler/sampler_se3_euler_ball-inl.h +++ b/include/fcl/math/sampler/sampler_se3_euler_ball-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SamplerSE3Euler_ball; +class FCL_EXPORT SamplerSE3Euler_ball; //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_euler_ball.h b/include/fcl/math/sampler/sampler_se3_euler_ball.h index 137d76606..616e0b7c0 100644 --- a/include/fcl/math/sampler/sampler_se3_euler_ball.h +++ b/include/fcl/math/sampler/sampler_se3_euler_ball.h @@ -45,7 +45,7 @@ namespace fcl { template -class SamplerSE3Euler_ball : public SamplerBase +class FCL_EXPORT SamplerSE3Euler_ball : public SamplerBase { public: SamplerSE3Euler_ball(); diff --git a/include/fcl/math/sampler/sampler_se3_quat-inl.h b/include/fcl/math/sampler/sampler_se3_quat-inl.h index 725e27e77..ed961abb3 100644 --- a/include/fcl/math/sampler/sampler_se3_quat-inl.h +++ b/include/fcl/math/sampler/sampler_se3_quat-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SamplerSE3Quat; +class FCL_EXPORT SamplerSE3Quat; //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_quat.h b/include/fcl/math/sampler/sampler_se3_quat.h index 0f0a9b4f2..3c2ae989f 100644 --- a/include/fcl/math/sampler/sampler_se3_quat.h +++ b/include/fcl/math/sampler/sampler_se3_quat.h @@ -45,7 +45,7 @@ namespace fcl { template -class SamplerSE3Quat : public SamplerBase +class FCL_EXPORT SamplerSE3Quat : public SamplerBase { public: SamplerSE3Quat(); diff --git a/include/fcl/math/sampler/sampler_se3_quat_ball-inl.h b/include/fcl/math/sampler/sampler_se3_quat_ball-inl.h index 92f79be10..6a13b91ff 100644 --- a/include/fcl/math/sampler/sampler_se3_quat_ball-inl.h +++ b/include/fcl/math/sampler/sampler_se3_quat_ball-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class SamplerSE3Quat_ball; +class FCL_EXPORT SamplerSE3Quat_ball; //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_quat_ball.h b/include/fcl/math/sampler/sampler_se3_quat_ball.h index 42a527de0..9fef44c4e 100644 --- a/include/fcl/math/sampler/sampler_se3_quat_ball.h +++ b/include/fcl/math/sampler/sampler_se3_quat_ball.h @@ -45,7 +45,7 @@ namespace fcl { template -class SamplerSE3Quat_ball : public SamplerBase +class FCL_EXPORT SamplerSE3Quat_ball : public SamplerBase { public: SamplerSE3Quat_ball(); diff --git a/include/fcl/math/triangle.h b/include/fcl/math/triangle.h index 9994eb7db..f7ce26a5f 100644 --- a/include/fcl/math/triangle.h +++ b/include/fcl/math/triangle.h @@ -39,12 +39,13 @@ #define FCL_MATH_TRIANGLE_H #include +#include "fcl/export.h" namespace fcl { /// @brief Triangle with 3 indices for points -class Triangle +class FCL_EXPORT Triangle { /// @brief indices for each vertex of triangle std::size_t vids[3]; diff --git a/include/fcl/math/variance3-inl.h b/include/fcl/math/variance3-inl.h index b39c6f447..dea534005 100644 --- a/include/fcl/math/variance3-inl.h +++ b/include/fcl/math/variance3-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class Variance3; +class FCL_EXPORT Variance3; //============================================================================== template diff --git a/include/fcl/math/variance3.h b/include/fcl/math/variance3.h index 0bdb905bd..b5938206b 100644 --- a/include/fcl/math/variance3.h +++ b/include/fcl/math/variance3.h @@ -48,7 +48,7 @@ namespace fcl /// @brief Class for variance matrix in 3d template -class Variance3 +class FCL_EXPORT Variance3 { public: /// @brief Variation matrix diff --git a/include/fcl/narrowphase/collision-inl.h b/include/fcl/narrowphase/collision-inl.h index 448d41bbf..a7442835d 100644 --- a/include/fcl/narrowphase/collision-inl.h +++ b/include/fcl/narrowphase/collision-inl.h @@ -49,6 +49,7 @@ namespace fcl //============================================================================== extern template +FCL_EXPORT std::size_t collide( const CollisionObject* o1, const CollisionObject* o2, @@ -57,6 +58,7 @@ std::size_t collide( //============================================================================== extern template +FCL_EXPORT std::size_t collide( const CollisionGeometry* o1, const Transform3& tf1, @@ -75,6 +77,7 @@ detail::CollisionFunctionMatrix& getCollisionFunctionLookTable() //============================================================================== template +FCL_EXPORT std::size_t collide( const CollisionObject* o1, const CollisionObject* o2, @@ -88,6 +91,7 @@ std::size_t collide( //============================================================================== template +FCL_EXPORT std::size_t collide( const CollisionGeometry* o1, const Transform3& tf1, @@ -146,6 +150,7 @@ std::size_t collide( //============================================================================== template +FCL_EXPORT std::size_t collide(const CollisionObject* o1, const CollisionObject* o2, const CollisionRequest& request, CollisionResult& result) { @@ -168,6 +173,7 @@ std::size_t collide(const CollisionObject* o1, const CollisionObject* o2, //============================================================================== template +FCL_EXPORT std::size_t collide( const CollisionGeometry* o1, const Transform3& tf1, diff --git a/include/fcl/narrowphase/collision.h b/include/fcl/narrowphase/collision.h index 960e6246b..f6e361e19 100644 --- a/include/fcl/narrowphase/collision.h +++ b/include/fcl/narrowphase/collision.h @@ -53,11 +53,13 @@ namespace fcl /// performs the collision between them. Return value is the number of contacts /// generated between the two objects. template +FCL_EXPORT std::size_t collide(const CollisionObject* o1, const CollisionObject* o2, const CollisionRequest& request, CollisionResult& result); template +FCL_EXPORT std::size_t collide(const CollisionGeometry* o1, const Transform3& tf1, const CollisionGeometry* o2, const Transform3& tf2, const CollisionRequest& request, diff --git a/include/fcl/narrowphase/collision_object-inl.h b/include/fcl/narrowphase/collision_object-inl.h index 2f5f48173..0c50e52c8 100644 --- a/include/fcl/narrowphase/collision_object-inl.h +++ b/include/fcl/narrowphase/collision_object-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class CollisionObject; +class FCL_EXPORT CollisionObject; //============================================================================== template diff --git a/include/fcl/narrowphase/collision_object.h b/include/fcl/narrowphase/collision_object.h index 120bcbc23..bef211a49 100644 --- a/include/fcl/narrowphase/collision_object.h +++ b/include/fcl/narrowphase/collision_object.h @@ -48,7 +48,7 @@ namespace fcl /// @brief the object for collision or distance computation, contains the /// geometry and the transform information template -class CollisionObject +class FCL_EXPORT CollisionObject { public: CollisionObject(const std::shared_ptr>& cgeom); diff --git a/include/fcl/narrowphase/collision_request.h b/include/fcl/narrowphase/collision_request.h index 4fa0ee7e8..dde2aa58d 100644 --- a/include/fcl/narrowphase/collision_request.h +++ b/include/fcl/narrowphase/collision_request.h @@ -49,7 +49,7 @@ struct CollisionResult; /// @brief request to the collision algorithm template -struct CollisionRequest +struct FCL_EXPORT CollisionRequest { /// @brief The maximum number of contacts will return size_t num_max_contacts; diff --git a/include/fcl/narrowphase/collision_result.h b/include/fcl/narrowphase/collision_result.h index 8ce60cf9b..a0d367773 100644 --- a/include/fcl/narrowphase/collision_result.h +++ b/include/fcl/narrowphase/collision_result.h @@ -49,7 +49,7 @@ namespace fcl /// @brief collision result template -struct CollisionResult +struct FCL_EXPORT CollisionResult { private: /// @brief contact information diff --git a/include/fcl/narrowphase/contact.h b/include/fcl/narrowphase/contact.h index a21a2dcef..0994036e4 100644 --- a/include/fcl/narrowphase/contact.h +++ b/include/fcl/narrowphase/contact.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Contact information returned by collision template -struct Contact +struct FCL_EXPORT Contact { /// @brief collision object 1 const CollisionGeometry* o1; diff --git a/include/fcl/narrowphase/contact_point.h b/include/fcl/narrowphase/contact_point.h index c917d6987..bca98e6bf 100644 --- a/include/fcl/narrowphase/contact_point.h +++ b/include/fcl/narrowphase/contact_point.h @@ -45,7 +45,7 @@ namespace fcl /// @brief Minimal contact information returned by collision template -struct ContactPoint +struct FCL_EXPORT ContactPoint { /// @brief Contact normal, pointing from o1 to o2 Vector3 normal; @@ -68,10 +68,12 @@ using ContactPointd = ContactPoint; /// @brief Return true if _cp1's penentration depth is less than _cp2's. template +FCL_EXPORT bool comparePenDepth( const ContactPoint& _cp1, const ContactPoint& _cp2); template +FCL_EXPORT void flipNormal(std::vector>& contacts); } // namespace fcl diff --git a/include/fcl/narrowphase/continuous_collision-inl.h b/include/fcl/narrowphase/continuous_collision-inl.h index 785a7af83..1adfb6ec2 100644 --- a/include/fcl/narrowphase/continuous_collision-inl.h +++ b/include/fcl/narrowphase/continuous_collision-inl.h @@ -105,6 +105,7 @@ getConservativeAdvancementFunctionLookTable() //============================================================================== template +FCL_EXPORT MotionBasePtr getMotionBase( const Transform3& tf_beg, const Transform3& tf_end, @@ -131,6 +132,7 @@ MotionBasePtr getMotionBase( //============================================================================== template +FCL_EXPORT S continuousCollideNaive( const CollisionGeometry* o1, const MotionBase* motion1, @@ -173,6 +175,7 @@ namespace detail //============================================================================== template +FCL_EXPORT typename BV::S continuousCollideBVHPolynomial( const CollisionGeometry* o1_, const TranslationMotion* motion1, @@ -241,6 +244,7 @@ typename BV::S continuousCollideBVHPolynomial( //============================================================================== template +FCL_EXPORT S continuousCollideBVHPolynomial( const CollisionGeometry* o1, const TranslationMotion* motion1, @@ -297,6 +301,7 @@ namespace detail //============================================================================== template +FCL_EXPORT typename NarrowPhaseSolver::S continuousCollideConservativeAdvancement( const CollisionGeometry* o1, const MotionBase* motion1, @@ -350,6 +355,7 @@ typename NarrowPhaseSolver::S continuousCollideConservativeAdvancement( } // namespace detail template +FCL_EXPORT S continuousCollideConservativeAdvancement( const CollisionGeometry* o1, const MotionBase* motion1, @@ -377,6 +383,7 @@ S continuousCollideConservativeAdvancement( //============================================================================== template +FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const MotionBase* motion1, @@ -426,6 +433,7 @@ S continuousCollide( //============================================================================== template +FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const Transform3& tf1_beg, @@ -444,6 +452,7 @@ S continuousCollide( //============================================================================== template +FCL_EXPORT S continuousCollide( const CollisionObject* o1, const Transform3& tf1_end, @@ -459,6 +468,7 @@ S continuousCollide( //============================================================================== template +FCL_EXPORT S collide( const ContinuousCollisionObject* o1, const ContinuousCollisionObject* o2, diff --git a/include/fcl/narrowphase/continuous_collision.h b/include/fcl/narrowphase/continuous_collision.h index fe02b38e4..fb1cab6c3 100644 --- a/include/fcl/narrowphase/continuous_collision.h +++ b/include/fcl/narrowphase/continuous_collision.h @@ -51,6 +51,7 @@ namespace fcl /// @brief continous collision checking between two objects template +FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const MotionBase* motion1, @@ -60,6 +61,7 @@ S continuousCollide( ContinuousCollisionResult& result); template +FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const Transform3& tf1_beg, @@ -71,6 +73,7 @@ S continuousCollide( ContinuousCollisionResult& result); template +FCL_EXPORT S continuousCollide( const CollisionObject* o1, const Transform3& tf1_end, @@ -80,6 +83,7 @@ S continuousCollide( ContinuousCollisionResult& result); template +FCL_EXPORT S collide( const ContinuousCollisionObject* o1, const ContinuousCollisionObject* o2, diff --git a/include/fcl/narrowphase/continuous_collision_object-inl.h b/include/fcl/narrowphase/continuous_collision_object-inl.h index b641a6cf2..e8008e98e 100644 --- a/include/fcl/narrowphase/continuous_collision_object-inl.h +++ b/include/fcl/narrowphase/continuous_collision_object-inl.h @@ -45,7 +45,7 @@ namespace fcl //============================================================================== extern template -class ContinuousCollisionObject; +class FCL_EXPORT ContinuousCollisionObject; //============================================================================== template diff --git a/include/fcl/narrowphase/continuous_collision_object.h b/include/fcl/narrowphase/continuous_collision_object.h index 60b874186..ecb12c422 100644 --- a/include/fcl/narrowphase/continuous_collision_object.h +++ b/include/fcl/narrowphase/continuous_collision_object.h @@ -48,7 +48,7 @@ namespace fcl /// @brief the object for continuous collision or distance computation, contains /// the geometry and the motion information template -class ContinuousCollisionObject +class FCL_EXPORT ContinuousCollisionObject { public: ContinuousCollisionObject( diff --git a/include/fcl/narrowphase/continuous_collision_request.h b/include/fcl/narrowphase/continuous_collision_request.h index f5b5cb010..356be14cd 100644 --- a/include/fcl/narrowphase/continuous_collision_request.h +++ b/include/fcl/narrowphase/continuous_collision_request.h @@ -40,6 +40,7 @@ #include #include "fcl/narrowphase/gjk_solver_type.h" +#include "fcl/export.h" namespace fcl { @@ -48,7 +49,7 @@ enum CCDMotionType {CCDM_TRANS, CCDM_LINEAR, CCDM_SCREW, CCDM_SPLINE}; enum CCDSolverType {CCDC_NAIVE, CCDC_CONSERVATIVE_ADVANCEMENT, CCDC_RAY_SHOOTING, CCDC_POLYNOMIAL_SOLVER}; template -struct ContinuousCollisionRequest +struct FCL_EXPORT ContinuousCollisionRequest { /// @brief maximum num of iterations std::size_t num_max_iterations; diff --git a/include/fcl/narrowphase/continuous_collision_result.h b/include/fcl/narrowphase/continuous_collision_result.h index 8e5f8334a..e19bf6941 100644 --- a/include/fcl/narrowphase/continuous_collision_result.h +++ b/include/fcl/narrowphase/continuous_collision_result.h @@ -45,7 +45,7 @@ namespace fcl /// @brief continuous collision result template -struct ContinuousCollisionResult +struct FCL_EXPORT ContinuousCollisionResult { /// @brief collision or not bool is_collide; diff --git a/include/fcl/narrowphase/cost_source.h b/include/fcl/narrowphase/cost_source.h index 66f072a18..15bc11180 100644 --- a/include/fcl/narrowphase/cost_source.h +++ b/include/fcl/narrowphase/cost_source.h @@ -46,7 +46,7 @@ namespace fcl /// @brief Cost source describes an area with a cost. The area is described by an AABB region. template -struct CostSource +struct FCL_EXPORT CostSource { /// @brief aabb lower bound Vector3 aabb_min; diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/epa.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/epa.h index 131dc7a7f..eb7efa4b1 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/epa.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/epa.h @@ -54,7 +54,7 @@ namespace detail /// @brief class for EPA algorithm template -struct EPA +struct FCL_EXPORT EPA { private: using SimplexV = typename GJK::SimplexV; diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk.h index 7949bba28..f5bbc2107 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk.h @@ -49,7 +49,7 @@ namespace detail /// @brief class for GJK algorithm template -struct GJK +struct FCL_EXPORT GJK { struct SimplexV { diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h index 91aa44f84..f0b81d59b 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h @@ -51,31 +51,31 @@ namespace detail //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== extern template diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h index c6cbf20d8..3eb9ba5a1 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h @@ -74,7 +74,7 @@ using GJKCenterFunction = void (*)(const void* obj, ccd_vec3_t* c); /// @brief initialize GJK stuffs template -class GJKInitializer +class FCL_EXPORT GJKInitializer { public: /// @brief Get GJK support function @@ -94,7 +94,7 @@ class GJKInitializer /// @brief initialize GJK Cylinder template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -105,7 +105,7 @@ class GJKInitializer> /// @brief initialize GJK Sphere template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -116,7 +116,7 @@ class GJKInitializer> /// @brief initialize GJK Ellipsoid template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -127,7 +127,7 @@ class GJKInitializer> /// @brief initialize GJK Box template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -138,7 +138,7 @@ class GJKInitializer> /// @brief initialize GJK Capsule template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -149,7 +149,7 @@ class GJKInitializer> /// @brief initialize GJK Cone template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -160,7 +160,7 @@ class GJKInitializer> /// @brief initialize GJK Convex template -class GJKInitializer> +class FCL_EXPORT GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -170,20 +170,26 @@ class GJKInitializer> }; /// @brief initialize GJK Triangle +FCL_EXPORT GJKSupportFunction triGetSupportFunction(); +FCL_EXPORT GJKCenterFunction triGetCenterFunction(); template +FCL_EXPORT void* triCreateGJKObject(const Vector3& P1, const Vector3& P2, const Vector3& P3); template +FCL_EXPORT void* triCreateGJKObject(const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf); +FCL_EXPORT void triDeleteGJKObject(void* o); /// @brief GJK collision algorithm template +FCL_EXPORT bool GJKCollide( void* obj1, ccd_support_fn supp1, @@ -198,6 +204,7 @@ bool GJKCollide( Vector3* normal); template +FCL_EXPORT bool GJKDistance(void* obj1, ccd_support_fn supp1, void* obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, @@ -205,6 +212,7 @@ bool GJKDistance(void* obj1, ccd_support_fn supp1, template +FCL_EXPORT bool GJKSignedDistance(void* obj1, ccd_support_fn supp1, void* obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff-inl.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff-inl.h index cdcacb5d4..f639f4bc3 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff-inl.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff-inl.h @@ -63,6 +63,7 @@ struct MinkowskiDiff; //============================================================================== template +FCL_EXPORT Vector3 getSupport( const ShapeBase* shape, const Eigen::MatrixBase& dir) diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff.h index 6e073accf..a1ee9c7da 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff.h @@ -55,7 +55,7 @@ Vector3 getSupport( /// @brief Minkowski difference class of two shapes template -struct MinkowskiDiff +struct FCL_EXPORT MinkowskiDiff { /// @brief points to two shapes const ShapeBase* shapes[2]; diff --git a/include/fcl/narrowphase/detail/gjk_solver_indep.h b/include/fcl/narrowphase/detail/gjk_solver_indep.h index 3fa7a6dde..1d08e3fa7 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_indep.h +++ b/include/fcl/narrowphase/detail/gjk_solver_indep.h @@ -38,7 +38,6 @@ #ifndef FCL_NARROWPHASE_GJKSOLVERINDEP_H #define FCL_NARROWPHASE_GJKSOLVERINDEP_H -#include "fcl/common/deprecated.h" #include "fcl/common/types.h" #include "fcl/narrowphase/contact_point.h" @@ -50,7 +49,7 @@ namespace detail /// @brief collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the GJK in bullet) template -struct GJKSolver_indep +struct FCL_EXPORT GJKSolver_indep { using S = S_; diff --git a/include/fcl/narrowphase/detail/gjk_solver_libccd.h b/include/fcl/narrowphase/detail/gjk_solver_libccd.h index 496587552..2676427da 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_libccd.h +++ b/include/fcl/narrowphase/detail/gjk_solver_libccd.h @@ -38,7 +38,6 @@ #ifndef FCL_NARROWPHASE_GJKSOLVERLIBCCD_H #define FCL_NARROWPHASE_GJKSOLVERLIBCCD_H -#include "fcl/common/deprecated.h" #include "fcl/common/types.h" #include "fcl/narrowphase/contact_point.h" @@ -50,7 +49,7 @@ namespace detail /// @brief collision and distance solver based on libccd library. template -struct GJKSolver_libccd +struct FCL_EXPORT GJKSolver_libccd { using S = S_; diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box.h index d7be73443..87a60845f 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box.h @@ -49,6 +49,7 @@ namespace detail { template +FCL_EXPORT void lineClosestApproach(const Vector3& pa, const Vector3& ua, const Vector3& pb, const Vector3& ub, S* alpha, S* beta); @@ -61,6 +62,7 @@ void lineClosestApproach(const Vector3& pa, const Vector3& ua, // the number of intersection points is returned by the function (this will // be in the range 0 to 8). template +FCL_EXPORT int intersectRectQuad2(S h[2], S p[8], S ret[16]); // given n points in the plane (array p, of size 2*n), generate m points that @@ -71,9 +73,11 @@ int intersectRectQuad2(S h[2], S p[8], S ret[16]); // n must be in the range [1..8]. m must be in the range [1..n]. i0 must be // in the range [0..n-1]. template +FCL_EXPORT void cullPoints2(int n, S p[], int m, int i0, int iret[]); template +FCL_EXPORT int boxBox2( const Vector3& side1, const Eigen::MatrixBase& R1, @@ -88,6 +92,7 @@ int boxBox2( std::vector>& contacts); template +FCL_EXPORT int boxBox2( const Vector3& side1, const Transform3& tf1, @@ -100,6 +105,7 @@ int boxBox2( std::vector>& contacts); template +FCL_EXPORT bool boxBoxIntersect(const Box& s1, const Transform3& tf1, const Box& s2, const Transform3& tf2, std::vector>* contacts_); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h index e9000ca7f..4747a5dd4 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h @@ -49,12 +49,14 @@ namespace detail // Clamp n to lie within the range [min, max] template +FCL_EXPORT S clamp(S n, S min, S max); // Computes closest points C1 and C2 of S1(s)=P1+s*(Q1-P1) and // S2(t)=P2+t*(Q2-P2), returning s and t. Function result is squared // distance between between S1(s) and S2(t) template +FCL_EXPORT S closestPtSegmentSegment( Vector3 p1, Vector3 q1, Vector3 p2, Vector3 q2, S &s, S &t, Vector3 &c1, Vector3 &c2); @@ -63,6 +65,7 @@ S closestPtSegmentSegment( // S2(t)=P2+t*(Q2-P2), returning s and t. Function result is squared // distance between between S1(s) and S2(t) template +FCL_EXPORT bool capsuleCapsuleDistance(const Capsule& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, S* dist, Vector3* p1_res, Vector3* p2_res); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h index 28e777124..c8339f76b 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h @@ -56,20 +56,25 @@ namespace detail { template +FCL_EXPORT S halfspaceIntersectTolerance(); template <> +FCL_EXPORT float halfspaceIntersectTolerance(); template <> +FCL_EXPORT double halfspaceIntersectTolerance(); template +FCL_EXPORT bool sphereHalfspaceIntersect(const Sphere& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool ellipsoidHalfspaceIntersect(const Ellipsoid& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, std::vector>* contacts); @@ -80,35 +85,42 @@ bool ellipsoidHalfspaceIntersect(const Ellipsoid& s1, const Transform3& tf /// check whether d - n * T - (R^T n) (a v1 + b v2 + c v3) >= 0 for some a, b, c /// the max value of left side is d - n * T + |(R^T n) (a v1 + b v2 + c v3)|, check that is enough template +FCL_EXPORT bool boxHalfspaceIntersect(const Box& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2); template +FCL_EXPORT bool boxHalfspaceIntersect(const Box& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool capsuleHalfspaceIntersect(const Capsule& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool cylinderHalfspaceIntersect(const Cylinder& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool coneHalfspaceIntersect(const Cone& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool convexHalfspaceIntersect(const Convex& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, Vector3* contact_points, S* penetration_depth, Vector3* normal); template +FCL_EXPORT bool halfspaceTriangleIntersect(const Halfspace& s1, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, Vector3* contact_points, S* penetration_depth, Vector3* normal); @@ -121,6 +133,7 @@ bool halfspaceTriangleIntersect(const Halfspace& s1, const Transform3& tf1 /// if not parallel /// return the intersection ray, return code 3. ray origin is p and direction is d template +FCL_EXPORT bool planeHalfspaceIntersect(const Plane& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, Plane& pl, @@ -129,6 +142,7 @@ bool planeHalfspaceIntersect(const Plane& s1, const Transform3& tf1, int& ret); template +FCL_EXPORT bool halfspacePlaneIntersect(const Halfspace& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, Plane& pl, Vector3& p, Vector3& d, @@ -144,6 +158,7 @@ bool halfspacePlaneIntersect(const Halfspace& s1, const Transform3& tf1, /// if the separation planes of the two halfspaces are not parallel, return intersection ray, return code 4. ray origin is p and direction is d /// collision free return code 0 template +FCL_EXPORT bool halfspaceIntersect(const Halfspace& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, Vector3& p, Vector3& d, diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h index c7d9dd8bd..86b141f24 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h @@ -55,20 +55,25 @@ namespace detail { template +FCL_EXPORT S planeIntersectTolerance(); template <> +FCL_EXPORT double planeIntersectTolerance(); template <> +FCL_EXPORT float planeIntersectTolerance(); template +FCL_EXPORT bool spherePlaneIntersect(const Sphere& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool ellipsoidPlaneIntersect(const Ellipsoid& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); @@ -81,15 +86,18 @@ bool ellipsoidPlaneIntersect(const Ellipsoid& s1, const Transform3& tf1, /// (R^T n) (a v1 + b v2 + c v3) can get |(R^T n) (a v1 + b v2 + c v3)| for one a, b, c. /// if |d - n * T| <= |(R^T n)(a v1 + b v2 + c v3)| then can get both positive and negative value on the right side. template +FCL_EXPORT bool boxPlaneIntersect(const Box& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool capsulePlaneIntersect(const Capsule& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2); template +FCL_EXPORT bool capsulePlaneIntersect(const Capsule& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); @@ -100,30 +108,36 @@ bool capsulePlaneIntersect(const Capsule& s1, const Transform3& tf1, /// (n^T * v3) * h + n * T -d + r * (cosa * (n^T * R * v1) + sina * (n^T * R * v2)) ~ 0 /// (n^T * v3) * h + r * (cosa * (n^T * R * v1) + sina * (n^T * R * v2)) + n * T - d ~ 0 template +FCL_EXPORT bool cylinderPlaneIntersect(const Cylinder& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2); template +FCL_EXPORT bool cylinderPlaneIntersect(const Cylinder& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool conePlaneIntersect(const Cone& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool convexPlaneIntersect(const Convex& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, Vector3* contact_points, S* penetration_depth, Vector3* normal); template +FCL_EXPORT bool planeTriangleIntersect(const Plane& s1, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, Vector3* contact_points, S* penetration_depth, Vector3* normal); template +FCL_EXPORT bool planeIntersect(const Plane& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h index 81061f390..2820b32a7 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h @@ -53,6 +53,7 @@ namespace detail // given by Dan Sunday's page: // http://geomalgorithms.com/a02-_lines.html template +FCL_EXPORT void lineSegmentPointClosestToPoint( const Vector3 &p, const Vector3 &s1, @@ -60,11 +61,13 @@ void lineSegmentPointClosestToPoint( Vector3 &sp); template +FCL_EXPORT bool sphereCapsuleIntersect(const Sphere& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, std::vector>* contacts); template +FCL_EXPORT bool sphereCapsuleDistance(const Sphere& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, S* dist, Vector3* p1, Vector3* p2); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_sphere-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_sphere-inl.h index 986d5b40f..efeeca4eb 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_sphere-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_sphere-inl.h @@ -48,18 +48,21 @@ namespace detail //============================================================================== extern template +FCL_EXPORT bool sphereSphereIntersect(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT bool sphereSphereDistance(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, double* dist, Vector3* p1, Vector3* p2); //============================================================================== template +FCL_EXPORT bool sphereSphereIntersect(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, std::vector>* contacts) @@ -84,6 +87,7 @@ bool sphereSphereIntersect(const Sphere& s1, const Transform3& tf1, //============================================================================== template +FCL_EXPORT bool sphereSphereDistance(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, S* dist, Vector3* p1, Vector3* p2) diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.h index 61da0d580..15a2a70ef 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.h @@ -49,27 +49,33 @@ namespace detail /** @brief the minimum distance from a point to a line */ template +FCL_EXPORT S segmentSqrDistance(const Vector3& from, const Vector3& to,const Vector3& p, Vector3& nearest); /// @brief Whether a point's projection is in a triangle template +FCL_EXPORT bool projectInTriangle(const Vector3& p1, const Vector3& p2, const Vector3& p3, const Vector3& normal, const Vector3& p); template +FCL_EXPORT bool sphereTriangleIntersect(const Sphere& s, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, Vector3* contact_points, S* penetration_depth, Vector3* normal_); template +FCL_EXPORT bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, S* dist); template +FCL_EXPORT bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, S* dist, Vector3* p1, Vector3* p2); template +FCL_EXPORT bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, S* dist, Vector3* p1, Vector3* p2); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance-inl.h index 9cc32c6c0..33a1d4fd6 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance-inl.h @@ -48,7 +48,7 @@ namespace detail //============================================================================== extern template -class TriangleDistance; +class FCL_EXPORT TriangleDistance; //============================================================================== template diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance.h index cc800f0f1..cb4b2e693 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance.h @@ -48,7 +48,7 @@ namespace detail /// @brief Triangle distance functions template -class TriangleDistance +class FCL_EXPORT TriangleDistance { public: diff --git a/include/fcl/narrowphase/detail/traversal/collision/bvh_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/bvh_collision_traversal_node.h index 44cfe31f4..021a47823 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/bvh_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/bvh_collision_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for collision between BVH models template -class BVHCollisionTraversalNode +class FCL_EXPORT BVHCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node.h index 551223d11..9247d5622 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for collision between BVH and shape template -class BVHShapeCollisionTraversalNode +class FCL_EXPORT BVHShapeCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h b/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h index f1243c841..86743e2d7 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h @@ -50,7 +50,7 @@ namespace detail //============================================================================== extern template -class CollisionTraversalNodeBase; +class FCL_EXPORT CollisionTraversalNodeBase; //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base.h b/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base.h index 58ea12561..6f6b10ca6 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base.h +++ b/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base.h @@ -49,7 +49,7 @@ namespace detail /// @brief Node structure encoding the information required for collision traversal. template -class CollisionTraversalNodeBase : public TraversalNodeBase +class FCL_EXPORT CollisionTraversalNodeBase : public TraversalNodeBase { public: CollisionTraversalNodeBase(); diff --git a/include/fcl/narrowphase/detail/traversal/collision/intersect-inl.h b/include/fcl/narrowphase/detail/traversal/collision/intersect-inl.h index 7834b2423..4c9d6069f 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/intersect-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/intersect-inl.h @@ -48,7 +48,7 @@ namespace detail //============================================================================== extern template -class Intersect; +class FCL_EXPORT Intersect; //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/collision/intersect.h b/include/fcl/narrowphase/detail/traversal/collision/intersect.h index 355876eb6..d653b8793 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/intersect.h +++ b/include/fcl/narrowphase/detail/traversal/collision/intersect.h @@ -51,7 +51,7 @@ namespace detail /// @brief CCD intersect kernel among primitives template -class Intersect +class FCL_EXPORT Intersect { public: diff --git a/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h index 66255b631..0a2731fa1 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h @@ -52,7 +52,7 @@ namespace detail //============================================================================== extern template -class MeshCollisionTraversalNodeOBB; +class FCL_EXPORT MeshCollisionTraversalNodeOBB; //============================================================================== extern template @@ -67,7 +67,7 @@ bool initialize( //============================================================================== extern template -class MeshCollisionTraversalNodeRSS; +class FCL_EXPORT MeshCollisionTraversalNodeRSS; //============================================================================== extern template @@ -82,7 +82,7 @@ bool initialize( //============================================================================== extern template -class MeshCollisionTraversalNodekIOS; +class FCL_EXPORT MeshCollisionTraversalNodekIOS; //============================================================================== extern template @@ -97,7 +97,7 @@ bool initialize( //============================================================================== extern template -class MeshCollisionTraversalNodeOBBRSS; +class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS; //============================================================================== extern template diff --git a/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.h index b3f8d7567..7e3d99335 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.h @@ -55,7 +55,7 @@ namespace detail /// @brief Traversal node for collision between two meshes template -class MeshCollisionTraversalNode : public BVHCollisionTraversalNode +class FCL_EXPORT MeshCollisionTraversalNode : public BVHCollisionTraversalNode { public: @@ -81,6 +81,7 @@ class MeshCollisionTraversalNode : public BVHCollisionTraversalNode /// @brief Initialize traversal node for collision between two meshes, given the /// current transforms template +FCL_EXPORT bool initialize( MeshCollisionTraversalNode& node, BVHModel& model1, @@ -95,7 +96,7 @@ bool initialize( /// @brief Traversal node for collision between two meshes if their underlying /// BVH node is oriented node (OBB, RSS, OBBRSS, kIOS) template -class MeshCollisionTraversalNodeOBB : public MeshCollisionTraversalNode> +class FCL_EXPORT MeshCollisionTraversalNodeOBB : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodeOBB(); @@ -124,6 +125,7 @@ using MeshCollisionTraversalNodeOBBd = MeshCollisionTraversalNodeOBB; /// @brief Initialize traversal node for collision between two meshes, /// specialized for OBB type template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodeOBB& node, const BVHModel>& model1, @@ -134,7 +136,7 @@ bool initialize( CollisionResult& result); template -class MeshCollisionTraversalNodeRSS : public MeshCollisionTraversalNode> +class FCL_EXPORT MeshCollisionTraversalNodeRSS : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodeRSS(); @@ -165,6 +167,7 @@ using MeshCollisionTraversalNodeRSSd = MeshCollisionTraversalNodeRSS; /// @brief Initialize traversal node for collision between two meshes, /// specialized for RSS type template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodeRSS& node, const BVHModel>& model1, @@ -175,7 +178,7 @@ bool initialize( CollisionResult& result); template -class MeshCollisionTraversalNodekIOS : public MeshCollisionTraversalNode> +class FCL_EXPORT MeshCollisionTraversalNodekIOS : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodekIOS(); @@ -196,6 +199,7 @@ using MeshCollisionTraversalNodekIOSd = MeshCollisionTraversalNodekIOS; /// @brief Initialize traversal node for collision between two meshes, /// specialized for kIOS type template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodekIOS& node, const BVHModel>& model1, @@ -206,7 +210,7 @@ bool initialize( CollisionResult& result); template -class MeshCollisionTraversalNodeOBBRSS : public MeshCollisionTraversalNode> +class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodeOBBRSS(); @@ -228,6 +232,7 @@ using MeshCollisionTraversalNodeOBBRSSd = MeshCollisionTraversalNodeOBBRSS +FCL_EXPORT bool initialize( MeshCollisionTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -238,6 +243,7 @@ bool initialize( CollisionResult& result); template +FCL_EXPORT void meshCollisionOrientedNodeLeafTesting( int b1, int b2, @@ -258,6 +264,7 @@ void meshCollisionOrientedNodeLeafTesting( CollisionResult& result); template +FCL_EXPORT void meshCollisionOrientedNodeLeafTesting( int b1, int b2, diff --git a/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.h index a9e7b0130..82425a51d 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.h @@ -48,7 +48,7 @@ namespace detail /// @brief Traversal node for continuous collision between BVH models template -struct BVHContinuousCollisionPair +struct FCL_EXPORT BVHContinuousCollisionPair { BVHContinuousCollisionPair(); @@ -66,7 +66,7 @@ struct BVHContinuousCollisionPair /// @brief Traversal node for continuous collision between meshes template -class MeshContinuousCollisionTraversalNode +class FCL_EXPORT MeshContinuousCollisionTraversalNode : public BVHCollisionTraversalNode { public: @@ -101,6 +101,7 @@ class MeshContinuousCollisionTraversalNode /// @brief Initialize traversal node for continuous collision detection between /// two meshes template +FCL_EXPORT bool initialize( MeshContinuousCollisionTraversalNode& node, const BVHModel& model1, diff --git a/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node.h index 8a658cfd7..a06250a7a 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for collision between mesh and shape template -class MeshShapeCollisionTraversalNode +class FCL_EXPORT MeshShapeCollisionTraversalNode : public BVHShapeCollisionTraversalNode { public: @@ -75,6 +75,7 @@ class MeshShapeCollisionTraversalNode /// @brief Initialize traversal node for collision between one mesh and one /// shape, given current object transform template +FCL_EXPORT bool initialize( MeshShapeCollisionTraversalNode& node, BVHModel& model1, @@ -87,6 +88,7 @@ bool initialize( bool use_refit = false, bool refit_bottomup = false); template +FCL_EXPORT void meshShapeCollisionOrientedNodeLeafTesting( int b1, int b2, @@ -105,7 +107,7 @@ void meshShapeCollisionOrientedNodeLeafTesting( /// @brief Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS) template -class MeshShapeCollisionTraversalNodeOBB +class FCL_EXPORT MeshShapeCollisionTraversalNodeOBB : public MeshShapeCollisionTraversalNode< OBB, Shape, NarrowPhaseSolver> { @@ -121,6 +123,7 @@ class MeshShapeCollisionTraversalNodeOBB /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for OBB type template +FCL_EXPORT bool initialize( MeshShapeCollisionTraversalNodeOBB& node, const BVHModel>& model1, @@ -132,7 +135,7 @@ bool initialize( CollisionResult& result); template -class MeshShapeCollisionTraversalNodeRSS +class FCL_EXPORT MeshShapeCollisionTraversalNodeRSS : public MeshShapeCollisionTraversalNode< RSS, Shape, NarrowPhaseSolver> { @@ -148,6 +151,7 @@ class MeshShapeCollisionTraversalNodeRSS /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for RSS type template +FCL_EXPORT bool initialize( MeshShapeCollisionTraversalNodeRSS& node, const BVHModel>& model1, @@ -159,7 +163,7 @@ bool initialize( CollisionResult& result); template -class MeshShapeCollisionTraversalNodekIOS +class FCL_EXPORT MeshShapeCollisionTraversalNodekIOS : public MeshShapeCollisionTraversalNode< kIOS, Shape, NarrowPhaseSolver> { @@ -175,6 +179,7 @@ class MeshShapeCollisionTraversalNodekIOS /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for kIOS type template +FCL_EXPORT bool initialize( MeshShapeCollisionTraversalNodekIOS& node, const BVHModel>& model1, @@ -186,7 +191,7 @@ bool initialize( CollisionResult& result); template -class MeshShapeCollisionTraversalNodeOBBRSS +class FCL_EXPORT MeshShapeCollisionTraversalNodeOBBRSS : public MeshShapeCollisionTraversalNode< OBBRSS, Shape, NarrowPhaseSolver> { @@ -202,6 +207,7 @@ class MeshShapeCollisionTraversalNodeOBBRSS /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for OBBRSS type template +FCL_EXPORT bool initialize( MeshShapeCollisionTraversalNodeOBBRSS& node, const BVHModel>& model1, diff --git a/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node.h index fc2ca971f..d66527960 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for collision between shape and BVH template -class ShapeBVHCollisionTraversalNode +class FCL_EXPORT ShapeBVHCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/collision/shape_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/shape_collision_traversal_node.h index 575807f44..68394d1ce 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/shape_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/shape_collision_traversal_node.h @@ -50,7 +50,7 @@ namespace detail /// @brief Traversal node for collision between two shapes template -class ShapeCollisionTraversalNode +class FCL_EXPORT ShapeCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h index ed405f592..d4fbdfbe7 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h @@ -50,6 +50,7 @@ namespace detail //============================================================================== template +FCL_EXPORT ShapeMeshCollisionTraversalNode::ShapeMeshCollisionTraversalNode() : ShapeBVHCollisionTraversalNode() { @@ -61,6 +62,7 @@ ShapeMeshCollisionTraversalNode::ShapeMeshCollisio //============================================================================== template +FCL_EXPORT void ShapeMeshCollisionTraversalNode::leafTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -129,6 +131,7 @@ void ShapeMeshCollisionTraversalNode::leafTesting( //============================================================================== template +FCL_EXPORT bool ShapeMeshCollisionTraversalNode::canStop() const { return this->request.isSatisfied(*(this->result)); @@ -136,6 +139,7 @@ bool ShapeMeshCollisionTraversalNode::canStop() co //============================================================================== template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNode& node, const Shape& model1, @@ -191,12 +195,14 @@ bool initialize( //============================================================================== template +FCL_EXPORT ShapeMeshCollisionTraversalNodeOBB::ShapeMeshCollisionTraversalNodeOBB() : ShapeMeshCollisionTraversalNode, NarrowPhaseSolver>() { } //============================================================================== template +FCL_EXPORT bool ShapeMeshCollisionTraversalNodeOBB::BVTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -207,6 +213,7 @@ bool ShapeMeshCollisionTraversalNodeOBB::BVTesting(int //============================================================================== template +FCL_EXPORT void ShapeMeshCollisionTraversalNodeOBB::leafTesting(int b1, int b2) const { detail::meshShapeCollisionOrientedNodeLeafTesting(b2, b1, *(this->model2), this->model1, this->vertices, this->tri_indices, @@ -217,12 +224,14 @@ void ShapeMeshCollisionTraversalNodeOBB::leafTesting(i //============================================================================== template +FCL_EXPORT ShapeMeshCollisionTraversalNodeRSS::ShapeMeshCollisionTraversalNodeRSS() : ShapeMeshCollisionTraversalNode, NarrowPhaseSolver>() { } //============================================================================== template +FCL_EXPORT bool ShapeMeshCollisionTraversalNodeRSS::BVTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -233,6 +242,7 @@ bool ShapeMeshCollisionTraversalNodeRSS::BVTesting(int //============================================================================== template +FCL_EXPORT void ShapeMeshCollisionTraversalNodeRSS::leafTesting(int b1, int b2) const { detail::meshShapeCollisionOrientedNodeLeafTesting(b2, b1, *(this->model2), this->model1, this->vertices, this->tri_indices, @@ -243,12 +253,14 @@ void ShapeMeshCollisionTraversalNodeRSS::leafTesting(i //============================================================================== template +FCL_EXPORT ShapeMeshCollisionTraversalNodekIOS::ShapeMeshCollisionTraversalNodekIOS() : ShapeMeshCollisionTraversalNode, NarrowPhaseSolver>() { } //============================================================================== template +FCL_EXPORT bool ShapeMeshCollisionTraversalNodekIOS::BVTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -259,6 +271,7 @@ bool ShapeMeshCollisionTraversalNodekIOS::BVTesting(in //============================================================================== template +FCL_EXPORT void ShapeMeshCollisionTraversalNodekIOS::leafTesting(int b1, int b2) const { detail::meshShapeCollisionOrientedNodeLeafTesting(b2, b1, *(this->model2), this->model1, this->vertices, this->tri_indices, @@ -269,12 +282,14 @@ void ShapeMeshCollisionTraversalNodekIOS::leafTesting( //============================================================================== template +FCL_EXPORT ShapeMeshCollisionTraversalNodeOBBRSS::ShapeMeshCollisionTraversalNodeOBBRSS() : ShapeMeshCollisionTraversalNode, NarrowPhaseSolver>() { } //============================================================================== template +FCL_EXPORT bool ShapeMeshCollisionTraversalNodeOBBRSS::BVTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -285,6 +300,7 @@ bool ShapeMeshCollisionTraversalNodeOBBRSS::BVTesting( //============================================================================== template +FCL_EXPORT void ShapeMeshCollisionTraversalNodeOBBRSS::leafTesting(int b1, int b2) const { detail::meshShapeCollisionOrientedNodeLeafTesting(b2, b1, *(this->model2), this->model1, this->vertices, this->tri_indices, @@ -325,6 +341,7 @@ static bool setupShapeMeshCollisionOrientedNode(OrientedNode +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeOBB& node, const Shape& model1, @@ -341,6 +358,7 @@ bool initialize( //============================================================================== template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeRSS& node, const Shape& model1, @@ -357,6 +375,7 @@ bool initialize( //============================================================================== template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodekIOS& node, const Shape& model1, @@ -373,6 +392,7 @@ bool initialize( //============================================================================== template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeOBBRSS& node, const Shape& model1, diff --git a/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node.h index 1514a5eec..5ebcc0308 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for collision between shape and mesh template -class ShapeMeshCollisionTraversalNode +class FCL_EXPORT ShapeMeshCollisionTraversalNode : public ShapeBVHCollisionTraversalNode { public: @@ -74,6 +74,7 @@ class ShapeMeshCollisionTraversalNode /// @brief Initialize traversal node for collision between one mesh and one /// shape, given current object transform template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNode& node, const Shape& model1, @@ -87,7 +88,7 @@ bool initialize( /// @brief Traversal node for shape and mesh, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS) template -class ShapeMeshCollisionTraversalNodeOBB +class FCL_EXPORT ShapeMeshCollisionTraversalNodeOBB : public ShapeMeshCollisionTraversalNode< Shape, OBB, NarrowPhaseSolver> { @@ -102,6 +103,7 @@ class ShapeMeshCollisionTraversalNodeOBB /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for OBB type template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeOBB& node, const Shape& model1, @@ -113,7 +115,7 @@ bool initialize( CollisionResult& result); template -class ShapeMeshCollisionTraversalNodeRSS +class FCL_EXPORT ShapeMeshCollisionTraversalNodeRSS : public ShapeMeshCollisionTraversalNode, NarrowPhaseSolver> { public: @@ -128,6 +130,7 @@ class ShapeMeshCollisionTraversalNodeRSS /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for RSS type template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeRSS& node, const Shape& model1, @@ -139,7 +142,7 @@ bool initialize( CollisionResult& result); template -class ShapeMeshCollisionTraversalNodekIOS +class FCL_EXPORT ShapeMeshCollisionTraversalNodekIOS : public ShapeMeshCollisionTraversalNode, NarrowPhaseSolver> { public: @@ -154,6 +157,7 @@ class ShapeMeshCollisionTraversalNodekIOS /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for kIOS type template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodekIOS& node, const Shape& model1, @@ -165,7 +169,7 @@ bool initialize( CollisionResult& result); template -class ShapeMeshCollisionTraversalNodeOBBRSS +class FCL_EXPORT ShapeMeshCollisionTraversalNodeOBBRSS : public ShapeMeshCollisionTraversalNode, NarrowPhaseSolver> { public: @@ -180,6 +184,7 @@ class ShapeMeshCollisionTraversalNodeOBBRSS /// @brief Initialize the traversal node for collision between one mesh and one /// shape, specialized for OBBRSS type template +FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeOBBRSS& node, const Shape& model1, diff --git a/include/fcl/narrowphase/detail/traversal/collision_node.h b/include/fcl/narrowphase/detail/traversal/collision_node.h index d15f4ee16..c00a1a1b6 100644 --- a/include/fcl/narrowphase/detail/traversal/collision_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision_node.h @@ -53,22 +53,27 @@ namespace detail /// @brief collision on collision traversal node; can use front list to accelerate template +FCL_EXPORT void collide(CollisionTraversalNodeBase* node, BVHFrontList* front_list = nullptr); /// @brief self collision on collision traversal node; can use front list to accelerate template +FCL_EXPORT void selfCollide(CollisionTraversalNodeBase* node, BVHFrontList* front_list = nullptr); /// @brief distance computation on distance traversal node; can use front list to accelerate template +FCL_EXPORT void distance(DistanceTraversalNodeBase* node, BVHFrontList* front_list = nullptr, int qsize = 2); /// @brief special collision on OBB traversal node template +FCL_EXPORT void collide2(MeshCollisionTraversalNodeOBB* node, BVHFrontList* front_list = nullptr); /// @brief special collision on RSS traversal node template +FCL_EXPORT void collide2(MeshCollisionTraversalNodeRSS* node, BVHFrontList* front_list = nullptr); } // namespace detail diff --git a/include/fcl/narrowphase/detail/traversal/distance/bvh_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/bvh_distance_traversal_node.h index 5310bdd6b..d56cbe2c9 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/bvh_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/bvh_distance_traversal_node.h @@ -50,7 +50,7 @@ namespace detail /// @brief Traversal node for distance computation between BVH models template -class BVHDistanceTraversalNode +class FCL_EXPORT BVHDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node.h index 8231fc94b..50f4fc21c 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for distance computation between BVH and shape template -class BVHShapeDistanceTraversalNode +class FCL_EXPORT BVHShapeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.h b/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.h index b372f8436..fb95a940d 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.h +++ b/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.h @@ -47,7 +47,7 @@ namespace detail { template -struct ConservativeAdvancementStackData +struct FCL_EXPORT ConservativeAdvancementStackData { ConservativeAdvancementStackData( const Vector3& P1_, diff --git a/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h b/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h index 763179b69..5fbeb5e0c 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h @@ -50,7 +50,7 @@ namespace detail //============================================================================== extern template -class DistanceTraversalNodeBase; +class FCL_EXPORT DistanceTraversalNodeBase; //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base.h b/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base.h index 72437edd0..e4a69a26c 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base.h +++ b/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base.h @@ -50,7 +50,7 @@ namespace detail /// @brief Node structure encoding the information required for distance traversal. template -class DistanceTraversalNodeBase : public TraversalNodeBase +class FCL_EXPORT DistanceTraversalNodeBase : public TraversalNodeBase { public: DistanceTraversalNodeBase(); diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node-inl.h index 1a2f5f2a8..6c09fe80e 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node-inl.h @@ -51,7 +51,7 @@ namespace detail //============================================================================== extern template -class MeshConservativeAdvancementTraversalNodeRSS; +class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS; //============================================================================== extern template @@ -65,7 +65,7 @@ bool initialize( //============================================================================== extern template -class MeshConservativeAdvancementTraversalNodeOBBRSS; +class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS; //============================================================================== extern template diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.h index 3f8035a6a..be72620e6 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.h @@ -50,7 +50,7 @@ namespace detail /// @brief continuous collision node using conservative advancement. when using this default version, must refit the BVH in current configuration (R_t, T_t) into default configuration template -class MeshConservativeAdvancementTraversalNode +class FCL_EXPORT MeshConservativeAdvancementTraversalNode : public MeshDistanceTraversalNode { public: @@ -97,6 +97,7 @@ class MeshConservativeAdvancementTraversalNode /// @brief Initialize traversal node for conservative advancement computation /// between two meshes, given the current transforms template +FCL_EXPORT bool initialize( MeshConservativeAdvancementTraversalNode& node, BVHModel& model1, @@ -108,7 +109,7 @@ bool initialize( bool refit_bottomup = false); template -class MeshConservativeAdvancementTraversalNodeRSS +class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS : public MeshConservativeAdvancementTraversalNode> { public: @@ -149,6 +150,7 @@ using MeshConservativeAdvancementTraversalNodeRSSd = MeshConservativeAdvancement /// @brief Initialize traversal node for conservative advancement computation /// between two meshes, given the current transforms, specialized for RSS template +FCL_EXPORT bool initialize( MeshConservativeAdvancementTraversalNodeRSS& node, const BVHModel>& model1, @@ -158,7 +160,7 @@ bool initialize( S w = 1); template -class MeshConservativeAdvancementTraversalNodeOBBRSS +class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS : public MeshConservativeAdvancementTraversalNode> { public: @@ -197,6 +199,7 @@ using MeshConservativeAdvancementTraversalNodeOBBRSSf = MeshConservativeAdvancem using MeshConservativeAdvancementTraversalNodeOBBRSSd = MeshConservativeAdvancementTraversalNodeOBBRSS; template +FCL_EXPORT bool initialize( MeshConservativeAdvancementTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -206,9 +209,11 @@ bool initialize( S w = 1); template +FCL_EXPORT const Vector3 getBVAxis(const BV& bv, int i); template +FCL_EXPORT bool meshConservativeAdvancementTraversalNodeCanStop( typename BV::S c, typename BV::S min_distance, @@ -223,6 +228,7 @@ bool meshConservativeAdvancementTraversalNodeCanStop( typename BV::S& delta_t); template +FCL_EXPORT bool meshConservativeAdvancementOrientedNodeCanStop( typename BV::S c, typename BV::S min_distance, @@ -237,6 +243,7 @@ bool meshConservativeAdvancementOrientedNodeCanStop( typename BV::S& delta_t); template +FCL_EXPORT void meshConservativeAdvancementOrientedNodeLeafTesting( int b1, int b2, diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node-inl.h index c4e00865b..558149dc9 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node-inl.h @@ -48,7 +48,7 @@ namespace detail //============================================================================== extern template -class MeshDistanceTraversalNodeRSS; +class FCL_EXPORT MeshDistanceTraversalNodeRSS; //============================================================================== extern template @@ -63,7 +63,7 @@ bool initialize( //============================================================================== extern template -class MeshDistanceTraversalNodekIOS; +class FCL_EXPORT MeshDistanceTraversalNodekIOS; //============================================================================== extern template @@ -78,7 +78,7 @@ bool initialize( //============================================================================== extern template -class MeshDistanceTraversalNodeOBBRSS; +class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS; //============================================================================== extern template diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.h index e119e2adf..92f44617e 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.h @@ -52,7 +52,7 @@ namespace detail /// @brief Traversal node for distance computation between two meshes template -class MeshDistanceTraversalNode : public BVHDistanceTraversalNode +class FCL_EXPORT MeshDistanceTraversalNode : public BVHDistanceTraversalNode { public: @@ -80,6 +80,7 @@ class MeshDistanceTraversalNode : public BVHDistanceTraversalNode /// @brief Initialize traversal node for distance computation between two /// meshes, given the current transforms template +FCL_EXPORT bool initialize( MeshDistanceTraversalNode& node, BVHModel& model1, @@ -92,7 +93,7 @@ bool initialize( /// @brief Traversal node for distance computation between two meshes if their underlying BVH node is oriented node (RSS, OBBRSS, kIOS) template -class MeshDistanceTraversalNodeRSS +class FCL_EXPORT MeshDistanceTraversalNodeRSS : public MeshDistanceTraversalNode> { public: @@ -122,6 +123,7 @@ using MeshDistanceTraversalNodeRSSd = MeshDistanceTraversalNodeRSS; /// @brief Initialize traversal node for distance computation between two /// meshes, specialized for RSS type template +FCL_EXPORT bool initialize( MeshDistanceTraversalNodeRSS& node, const BVHModel>& model1, @@ -132,7 +134,7 @@ bool initialize( DistanceResult& result); template -class MeshDistanceTraversalNodekIOS +class FCL_EXPORT MeshDistanceTraversalNodekIOS : public MeshDistanceTraversalNode> { public: @@ -162,6 +164,7 @@ using MeshDistanceTraversalNodekIOSd = MeshDistanceTraversalNodekIOS; /// @brief Initialize traversal node for distance computation between two /// meshes, specialized for kIOS type template +FCL_EXPORT bool initialize( MeshDistanceTraversalNodekIOS& node, const BVHModel>& model1, @@ -172,7 +175,7 @@ bool initialize( DistanceResult& result); template -class MeshDistanceTraversalNodeOBBRSS +class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS : public MeshDistanceTraversalNode> { public: @@ -202,6 +205,7 @@ using MeshDistanceTraversalNodeOBBRSSd = MeshDistanceTraversalNodeOBBRSS /// @brief Initialize traversal node for distance computation between two /// meshes, specialized for OBBRSS type template +FCL_EXPORT bool initialize( MeshDistanceTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -212,7 +216,7 @@ bool initialize( DistanceResult& result); template -FCL_DEPRECATED +FCL_DEPRECATED_EXPORT void meshDistanceOrientedNodeLeafTesting( int b1, int b2, @@ -230,6 +234,7 @@ void meshDistanceOrientedNodeLeafTesting( DistanceResult& result); template +FCL_EXPORT void meshDistanceOrientedNodeLeafTesting( int b1, int b2, @@ -246,6 +251,7 @@ void meshDistanceOrientedNodeLeafTesting( DistanceResult& result); template +FCL_EXPORT void distancePreprocessOrientedNode( const BVHModel* model1, const BVHModel* model2, @@ -261,6 +267,7 @@ void distancePreprocessOrientedNode( DistanceResult& result); template +FCL_EXPORT void distancePreprocessOrientedNode( const BVHModel* model1, const BVHModel* model2, @@ -275,6 +282,7 @@ void distancePreprocessOrientedNode( DistanceResult& result); template +FCL_EXPORT void distancePostprocessOrientedNode( const BVHModel* model1, const BVHModel* model2, diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node.h index 68b97ec7b..a9f8d7597 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for conservative advancement computation between BVH and shape template -class MeshShapeConservativeAdvancementTraversalNode +class FCL_EXPORT MeshShapeConservativeAdvancementTraversalNode : public MeshShapeDistanceTraversalNode { public: @@ -140,7 +140,7 @@ bool meshShapeConservativeAdvancementOrientedNodeCanStop( typename BV::S& delta_t); template -class MeshShapeConservativeAdvancementTraversalNodeRSS +class FCL_EXPORT MeshShapeConservativeAdvancementTraversalNodeRSS : public MeshShapeConservativeAdvancementTraversalNode< RSS, Shape, NarrowPhaseSolver> { @@ -168,7 +168,7 @@ bool initialize( typename Shape::S w = 1); template -class MeshShapeConservativeAdvancementTraversalNodeOBBRSS : +class FCL_EXPORT MeshShapeConservativeAdvancementTraversalNodeOBBRSS : public MeshShapeConservativeAdvancementTraversalNode< OBBRSS, Shape, NarrowPhaseSolver> { diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node.h index 058a5c8a3..0d40e2ef5 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for distance between mesh and shape template -class MeshShapeDistanceTraversalNode +class FCL_EXPORT MeshShapeDistanceTraversalNode : public BVHShapeDistanceTraversalNode { public: @@ -118,7 +118,7 @@ bool initialize( /// @brief Traversal node for distance between mesh and shape, when mesh BVH is one of the oriented node (RSS, OBBRSS, kIOS) template -class MeshShapeDistanceTraversalNodeRSS +class FCL_EXPORT MeshShapeDistanceTraversalNodeRSS : public MeshShapeDistanceTraversalNode< RSS, Shape, NarrowPhaseSolver> { @@ -148,7 +148,7 @@ bool initialize( DistanceResult& result); template -class MeshShapeDistanceTraversalNodekIOS +class FCL_EXPORT MeshShapeDistanceTraversalNodekIOS : public MeshShapeDistanceTraversalNode, Shape, NarrowPhaseSolver> { public: @@ -177,7 +177,7 @@ bool initialize( DistanceResult& result); template -class MeshShapeDistanceTraversalNodeOBBRSS +class FCL_EXPORT MeshShapeDistanceTraversalNodeOBBRSS : public MeshShapeDistanceTraversalNode, Shape, NarrowPhaseSolver> { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node.h index 3d176a089..53176cfb8 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node.h @@ -50,7 +50,7 @@ namespace detail /// @brief Traversal node for distance computation between shape and BVH template -class ShapeBVHDistanceTraversalNode +class FCL_EXPORT ShapeBVHDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_conservative_advancement_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/shape_conservative_advancement_traversal_node.h index 3e92008e2..525df7215 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_conservative_advancement_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_conservative_advancement_traversal_node.h @@ -47,7 +47,7 @@ namespace detail { template -class ShapeConservativeAdvancementTraversalNode +class FCL_EXPORT ShapeConservativeAdvancementTraversalNode : public ShapeDistanceTraversalNode { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/shape_distance_traversal_node.h index ad7499257..bfd1e1f64 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_distance_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for distance between two shapes template -class ShapeDistanceTraversalNode +class FCL_EXPORT ShapeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node.h index 069491bb7..bf54940a5 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node.h @@ -49,7 +49,7 @@ namespace detail { template -class ShapeMeshConservativeAdvancementTraversalNode +class FCL_EXPORT ShapeMeshConservativeAdvancementTraversalNode : public ShapeMeshDistanceTraversalNode { public: @@ -103,7 +103,7 @@ bool initialize( bool refit_bottomup = false); template -class ShapeMeshConservativeAdvancementTraversalNodeRSS +class FCL_EXPORT ShapeMeshConservativeAdvancementTraversalNodeRSS : public ShapeMeshConservativeAdvancementTraversalNode< Shape, RSS, NarrowPhaseSolver> { @@ -130,7 +130,7 @@ bool initialize( typename Shape::S w = 1); template -class ShapeMeshConservativeAdvancementTraversalNodeOBBRSS +class FCL_EXPORT ShapeMeshConservativeAdvancementTraversalNodeOBBRSS : public ShapeMeshConservativeAdvancementTraversalNode< Shape, OBBRSS, NarrowPhaseSolver> { diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h index c059ed10e..cdf8c8d00 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h @@ -108,6 +108,7 @@ bool ShapeMeshDistanceTraversalNode::canStop(S c) //============================================================================== template +FCL_EXPORT bool initialize( ShapeMeshDistanceTraversalNode& node, const Shape& model1, @@ -348,6 +349,7 @@ static bool setupShapeMeshDistanceOrientedNode(OrientedNode +FCL_EXPORT bool initialize(ShapeMeshDistanceTraversalNodeRSS& node, const Shape& model1, const Transform3& tf1, const BVHModel>& model2, const Transform3& tf2, @@ -360,6 +362,7 @@ bool initialize(ShapeMeshDistanceTraversalNodeRSS& nod //============================================================================== template +FCL_EXPORT bool initialize(ShapeMeshDistanceTraversalNodekIOS& node, const Shape& model1, const Transform3& tf1, const BVHModel>& model2, const Transform3& tf2, @@ -372,6 +375,7 @@ bool initialize(ShapeMeshDistanceTraversalNodekIOS& no //============================================================================== template +FCL_EXPORT bool initialize(ShapeMeshDistanceTraversalNodeOBBRSS& node, const Shape& model1, const Transform3& tf1, const BVHModel>& model2, const Transform3& tf2, diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node.h index 1777b8a8b..438f2053d 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node.h @@ -49,7 +49,7 @@ namespace detail /// @brief Traversal node for distance between shape and mesh template -class ShapeMeshDistanceTraversalNode +class FCL_EXPORT ShapeMeshDistanceTraversalNode : public ShapeBVHDistanceTraversalNode { public: @@ -89,7 +89,7 @@ bool initialize( bool refit_bottomup = false); template -class ShapeMeshDistanceTraversalNodeRSS +class FCL_EXPORT ShapeMeshDistanceTraversalNodeRSS : public ShapeMeshDistanceTraversalNode< Shape, RSS, NarrowPhaseSolver> { @@ -123,7 +123,7 @@ bool initialize( DistanceResult& result); template -class ShapeMeshDistanceTraversalNodekIOS +class FCL_EXPORT ShapeMeshDistanceTraversalNodekIOS : public ShapeMeshDistanceTraversalNode< Shape, kIOS, NarrowPhaseSolver> { @@ -157,7 +157,7 @@ bool initialize( DistanceResult& result); template -class ShapeMeshDistanceTraversalNodeOBBRSS +class FCL_EXPORT ShapeMeshDistanceTraversalNodeOBBRSS : public ShapeMeshDistanceTraversalNode< Shape, OBBRSS, NarrowPhaseSolver> { diff --git a/include/fcl/narrowphase/detail/traversal/octree/collision/mesh_octree_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/collision/mesh_octree_collision_traversal_node.h index c946fb165..c12324554 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/collision/mesh_octree_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/collision/mesh_octree_collision_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for mesh-octree collision template -class MeshOcTreeCollisionTraversalNode +class FCL_EXPORT MeshOcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/collision/octree_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/collision/octree_collision_traversal_node.h index 7692db9f8..b12245948 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/collision/octree_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/collision/octree_collision_traversal_node.h @@ -55,7 +55,7 @@ namespace detail /// @brief Traversal node for octree collision template -class OcTreeCollisionTraversalNode +class FCL_EXPORT OcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/collision/octree_mesh_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/collision/octree_mesh_collision_traversal_node.h index 7c16d8f27..304a9cb1c 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/collision/octree_mesh_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/collision/octree_mesh_collision_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for octree-mesh collision template -class OcTreeMeshCollisionTraversalNode +class FCL_EXPORT OcTreeMeshCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/collision/octree_shape_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/collision/octree_shape_collision_traversal_node.h index 36962baa8..93b53abf2 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/collision/octree_shape_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/collision/octree_shape_collision_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for octree-shape collision template -class OcTreeShapeCollisionTraversalNode +class FCL_EXPORT OcTreeShapeCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/collision/shape_octree_collision_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/collision/shape_octree_collision_traversal_node.h index 998b152aa..147de063c 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/collision/shape_octree_collision_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/collision/shape_octree_collision_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for shape-octree collision template -class ShapeOcTreeCollisionTraversalNode +class FCL_EXPORT ShapeOcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/distance/mesh_octree_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/distance/mesh_octree_distance_traversal_node.h index cb93739f1..c48554721 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/distance/mesh_octree_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/distance/mesh_octree_distance_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for mesh-octree distance template -class MeshOcTreeDistanceTraversalNode +class FCL_EXPORT MeshOcTreeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/distance/octree_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/distance/octree_distance_traversal_node.h index 3fc223ccf..2df84244e 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/distance/octree_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/distance/octree_distance_traversal_node.h @@ -55,7 +55,7 @@ namespace detail /// @brief Traversal node for octree distance template -class OcTreeDistanceTraversalNode +class FCL_EXPORT OcTreeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/distance/octree_mesh_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/distance/octree_mesh_distance_traversal_node.h index c1fbfeb82..5ac1cc28b 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/distance/octree_mesh_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/distance/octree_mesh_distance_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for octree-mesh distance template -class OcTreeMeshDistanceTraversalNode +class FCL_EXPORT OcTreeMeshDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/distance/octree_shape_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/distance/octree_shape_distance_traversal_node.h index b9bebf56e..482f5f87f 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/distance/octree_shape_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/distance/octree_shape_distance_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for octree-shape distance template -class OcTreeShapeDistanceTraversalNode +class FCL_EXPORT OcTreeShapeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/distance/shape_octree_distance_traversal_node.h b/include/fcl/narrowphase/detail/traversal/octree/distance/shape_octree_distance_traversal_node.h index 06d2da686..02b3547b0 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/distance/shape_octree_distance_traversal_node.h +++ b/include/fcl/narrowphase/detail/traversal/octree/distance/shape_octree_distance_traversal_node.h @@ -56,7 +56,7 @@ namespace detail /// @brief Traversal node for shape-octree distance template -class ShapeOcTreeDistanceTraversalNode +class FCL_EXPORT ShapeOcTreeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/octree/octree_solver.h b/include/fcl/narrowphase/detail/traversal/octree/octree_solver.h index 1446012ad..415974254 100644 --- a/include/fcl/narrowphase/detail/traversal/octree/octree_solver.h +++ b/include/fcl/narrowphase/detail/traversal/octree/octree_solver.h @@ -56,7 +56,7 @@ namespace detail /// @brief Algorithms for collision related with octree template -class OcTreeSolver +class FCL_EXPORT OcTreeSolver { private: diff --git a/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h b/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h index 9ff776e0e..96d849b98 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h @@ -50,7 +50,7 @@ namespace detail //============================================================================== extern template -class TraversalNodeBase; +class FCL_EXPORT TraversalNodeBase; //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/traversal_node_base.h b/include/fcl/narrowphase/detail/traversal/traversal_node_base.h index abcc4ebdf..2f3b1877e 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_node_base.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_node_base.h @@ -48,7 +48,7 @@ namespace detail /// @brief Node structure encoding the information required for traversal. template -class TraversalNodeBase +class FCL_EXPORT TraversalNodeBase { public: virtual ~TraversalNodeBase(); diff --git a/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h b/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h index 5d9704b34..1c46c1c41 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h @@ -80,6 +80,7 @@ void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase* n //============================================================================== template +FCL_EXPORT void collisionRecurse(CollisionTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list) { bool l1 = node->isFirstNodeLeaf(b1); @@ -129,6 +130,7 @@ void collisionRecurse(CollisionTraversalNodeBase* node, int b1, int b2, BVHFr //============================================================================== template +FCL_EXPORT void collisionRecurse(MeshCollisionTraversalNodeOBB* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list) { bool l1 = node->isFirstNodeLeaf(b1); @@ -214,6 +216,7 @@ void collisionRecurse(MeshCollisionTraversalNodeOBB* node, int b1, int b2, co //============================================================================== template +FCL_EXPORT void collisionRecurse(MeshCollisionTraversalNodeRSS* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list) { FCL_UNUSED(node); @@ -231,6 +234,7 @@ void collisionRecurse(MeshCollisionTraversalNodeRSS* node, int b1, int b2, co * Make sure node is set correctly so that the first and second tree are the same */ template +FCL_EXPORT void selfCollisionRecurse(CollisionTraversalNodeBase* node, int b, BVHFrontList* front_list) { bool l = node->isFirstNodeLeaf(b); @@ -251,6 +255,7 @@ void selfCollisionRecurse(CollisionTraversalNodeBase* node, int b, BVHFrontLi //============================================================================== template +FCL_EXPORT void distanceRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list) { bool l1 = node->isFirstNodeLeaf(b1); @@ -313,7 +318,7 @@ void distanceRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFron //============================================================================== /** @brief Bounding volume test structure */ template -struct BVT +struct FCL_EXPORT BVT { /** @brief distance between bvs */ S d; @@ -325,7 +330,7 @@ struct BVT //============================================================================== /** @brief Comparer between two BVT */ template -struct BVT_Comparer +struct FCL_EXPORT BVT_Comparer { bool operator() (const BVT& lhs, const BVT& rhs) const { @@ -335,7 +340,7 @@ struct BVT_Comparer //============================================================================== template -struct BVTQ +struct FCL_EXPORT BVTQ { BVTQ() : qsize(2) {} @@ -377,6 +382,7 @@ struct BVTQ //============================================================================== template +FCL_EXPORT void distanceQueueRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list, int qsize) { BVTQ bvtq; @@ -455,6 +461,7 @@ void distanceQueueRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BV //============================================================================== template +FCL_EXPORT void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase* node, BVHFrontList* front_list) { BVHFrontList::iterator front_iter; diff --git a/include/fcl/narrowphase/detail/traversal/traversal_recurse.h b/include/fcl/narrowphase/detail/traversal/traversal_recurse.h index cb9316f08..d586c7e8c 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_recurse.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_recurse.h @@ -52,30 +52,37 @@ namespace detail /// @brief Recurse function for collision template +FCL_EXPORT void collisionRecurse(CollisionTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list); /// @brief Recurse function for collision, specialized for OBB type template +FCL_EXPORT void collisionRecurse(MeshCollisionTraversalNodeOBB* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list); /// @brief Recurse function for collision, specialized for RSS type template +FCL_EXPORT void collisionRecurse(MeshCollisionTraversalNodeRSS* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list); /// @brief Recurse function for self collision. Make sure node is set correctly so that the first and second tree are the same template +FCL_EXPORT void selfCollisionRecurse(CollisionTraversalNodeBase* node, int b, BVHFrontList* front_list); /// @brief Recurse function for distance template +FCL_EXPORT void distanceRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list); /// @brief Recurse function for distance, using queue acceleration template +FCL_EXPORT void distanceQueueRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list, int qsize); /// @brief Recurse function for front list propagation template +FCL_EXPORT void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase* node, BVHFrontList* front_list); } // namespace detail diff --git a/include/fcl/narrowphase/distance.h b/include/fcl/narrowphase/distance.h index cda024fe5..7629d264f 100644 --- a/include/fcl/narrowphase/distance.h +++ b/include/fcl/narrowphase/distance.h @@ -49,11 +49,13 @@ namespace fcl /// @brief Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them. /// Return value is the minimum distance generated between the two objects. template +FCL_EXPORT S distance( const CollisionObject* o1, const CollisionObject* o2, const DistanceRequest& request, DistanceResult& result); template +FCL_EXPORT S distance( const CollisionGeometry* o1, const Transform3& tf1, const CollisionGeometry* o2, const Transform3& tf2, diff --git a/include/fcl/narrowphase/distance_request.h b/include/fcl/narrowphase/distance_request.h index 8dc92a15d..c157699be 100644 --- a/include/fcl/narrowphase/distance_request.h +++ b/include/fcl/narrowphase/distance_request.h @@ -49,7 +49,7 @@ struct DistanceResult; /// @brief request to the distance computation template -struct DistanceRequest +struct FCL_EXPORT DistanceRequest { /// @brief whether to return the nearest points bool enable_nearest_points; diff --git a/include/fcl/narrowphase/distance_result-inl.h b/include/fcl/narrowphase/distance_result-inl.h index 5d87377d2..424cffdf7 100644 --- a/include/fcl/narrowphase/distance_result-inl.h +++ b/include/fcl/narrowphase/distance_result-inl.h @@ -49,6 +49,7 @@ struct DistanceResult; //============================================================================== template +FCL_EXPORT DistanceResult::DistanceResult(S min_distance_) : min_distance(min_distance_), o1(nullptr), @@ -61,6 +62,7 @@ DistanceResult::DistanceResult(S min_distance_) //============================================================================== template +FCL_EXPORT void DistanceResult::update( S distance, const CollisionGeometry* o1_, @@ -80,6 +82,7 @@ void DistanceResult::update( //============================================================================== template +FCL_EXPORT void DistanceResult::update( S distance, const CollisionGeometry* o1_, @@ -103,6 +106,7 @@ void DistanceResult::update( //============================================================================== template +FCL_EXPORT void DistanceResult::update(const DistanceResult& other_result) { if(min_distance > other_result.min_distance) @@ -119,6 +123,7 @@ void DistanceResult::update(const DistanceResult& other_result) //============================================================================== template +FCL_EXPORT void DistanceResult::clear() { min_distance = std::numeric_limits::max(); diff --git a/include/fcl/narrowphase/distance_result.h b/include/fcl/narrowphase/distance_result.h index 98852d3c1..fb53b36d8 100644 --- a/include/fcl/narrowphase/distance_result.h +++ b/include/fcl/narrowphase/distance_result.h @@ -48,7 +48,7 @@ class CollisionGeometry; /// @brief distance result template -struct DistanceResult +struct FCL_EXPORT DistanceResult { public: diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index db2ef861a..2db9f377d 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -12,6 +12,27 @@ set_target_properties(${PROJECT_NAME} PROPERTIES VERSION ${FCL_VERSION} SOVERSION ${FCL_ABI_VERSION}) +# Hide symbols by default +################################################# +# Macro to check for visibility capability in compiler +# Original idea from: https://gitorious.org/ferric-cmake-stuff/ +macro (check_compiler_visibility) + include (CheckCXXCompilerFlag) + check_cxx_compiler_flag(-fvisibility=hidden COMPILER_SUPPORTS_VISIBILITY) +endmacro() + +if (UNIX) + check_compiler_visibility() + if (COMPILER_SUPPORTS_VISIBILITY) + set_target_properties(${PROJECT_NAME} + PROPERTIES COMPILE_FLAGS "-fvisibility=hidden") + endif() +endif() + +if (FCL_HIDE_ALL_SYMBOLS) + add_definitions("-DFCL_STATIC_DEFINE") +endif() + # Use the IMPORTED target from newer versions of ccd-config.cmake if available, # otherwise fall back to CCD_INCLUDE_DIRS and CCD_LIBRARIES if(TARGET ccd) diff --git a/src/common/detail/profiler.cpp b/src/common/detail/profiler.cpp index 47d4ffcdb..6d78ee0d5 100644 --- a/src/common/detail/profiler.cpp +++ b/src/common/detail/profiler.cpp @@ -238,14 +238,14 @@ bool Profiler::Running() } //============================================================================== -struct dataIntVal +struct FCL_EXPORT dataIntVal { std::string name; unsigned long int value; }; //============================================================================== -struct SortIntByValue +struct FCL_EXPORT SortIntByValue { bool operator()(const dataIntVal &a, const dataIntVal &b) const { @@ -254,14 +254,14 @@ struct SortIntByValue }; //============================================================================== -struct dataDoubleVal +struct FCL_EXPORT dataDoubleVal { std::string name; double value; }; //============================================================================== -struct SortDoubleByValue +struct FCL_EXPORT SortDoubleByValue { bool operator()(const dataDoubleVal &a, const dataDoubleVal &b) const {