diff --git a/CMakeLists.txt b/CMakeLists.txt index 6e5bbb8bb..7d2795958 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,9 +46,7 @@ configure_file(CTestCustom.cmake.in CTestCustom.cmake @ONLY) 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) +option(FCL_HIDE_ALL_SYMBOLS "Hide all binary symbols" ON) # set the default build type if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) @@ -65,7 +63,11 @@ if(MSVC OR MSVC90 OR MSVC10) set(MSVC ON) endif (MSVC OR MSVC90 OR MSVC10) -set(LIBRARY_OUTPUT_PATH ${PROJECT_BINARY_DIR}/lib) +if(WIN32) + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin) +else() + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/lib) +endif() set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/CMakeModules") include(CMakePackageConfigHelpers) include(GenerateExportHeader) @@ -378,7 +380,8 @@ if(NOT FCL_BUILD_TESTS STREQUAL "DEFAULT") unset(_BUILD_TESTING) endif() -if(BUILD_TESTING AND NOT FCL_HIDE_ALL_SYMBOLS) +if(BUILD_TESTING) + enable_testing() add_subdirectory(test) endif() diff --git a/CMakeModules/CompilerSettings.cmake b/CMakeModules/CompilerSettings.cmake index 96b9e1f73..21a526a63 100644 --- a/CMakeModules/CompilerSettings.cmake +++ b/CMakeModules/CompilerSettings.cmake @@ -64,7 +64,10 @@ if(MSVC) if(MSVC_VERSION VERSION_LESS 1900) message(FATAL_ERROR "${PROJECT_NAME} requires Visual Studio 2015 or greater.") endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /EHsc /MP /W1 /bigobj") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /EHsc /MP /bigobj") + if(CMAKE_CXX_FLAGS MATCHES "/W[0-4]") + STRING(REGEX REPLACE "/W[0-4]" "/W1" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") + endif() if(FCL_TREAT_WARNINGS_AS_ERRORS) add_definitions(/WX) endif() diff --git a/include/fcl/CMakeLists.txt b/include/fcl/CMakeLists.txt index 35c467026..f9065caa0 100644 --- a/include/fcl/CMakeLists.txt +++ b/include/fcl/CMakeLists.txt @@ -35,8 +35,18 @@ set(GENERATED_FILE_MARKER "GENERATED FILE DO NOT EDIT") configure_file(config.h.in config.h @ONLY) +set(FCL_EXPORT_MACRO_NAME "FCL_EXPORT") +set(EXPORT_INSTANTIATION_TEMPLATE_MACROS " +#if defined(${PROJECT_NAME}_EXPORTS) && defined(_MSC_VER) +# define FCL_EXPORT_EXPL_INST_DECL +#else +# define FCL_EXPORT_EXPL_INST_DECL ${FCL_EXPORT_MACRO_NAME} +#endif +") generate_export_header(${PROJECT_NAME} + EXPORT_MACRO_NAME ${FCL_EXPORT_MACRO_NAME} EXPORT_FILE_NAME export.h + CUSTOM_CONTENT_FROM_VARIABLE EXPORT_INSTANTIATION_TEMPLATE_MACROS ) get_filename_component(PARENT_BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}" diff --git a/include/fcl/broadphase/broadphase_SSaP-inl.h b/include/fcl/broadphase/broadphase_SSaP-inl.h index ad859ea86..361c3d403 100644 --- a/include/fcl/broadphase/broadphase_SSaP-inl.h +++ b/include/fcl/broadphase/broadphase_SSaP-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_SSAP_BUILDING extern template -class FCL_EXPORT SSaPCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL SSaPCollisionManager; +#endif /** @brief Functor sorting objects according to the AABB lower x bound */ template @@ -85,7 +87,7 @@ struct SortByZLow /** @brief Dummy collision object with a point AABB */ template -class FCL_EXPORT DummyCollisionObject : public CollisionObject +class 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 b0cc0a9df..185b9a0c2 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 FCL_EXPORT SSaPCollisionManager : public BroadPhaseCollisionManager +class SSaPCollisionManager : public BroadPhaseCollisionManager { public: SSaPCollisionManager(); diff --git a/include/fcl/broadphase/broadphase_SaP-inl.h b/include/fcl/broadphase/broadphase_SaP-inl.h index 7d201c7d3..2fd882d58 100644 --- a/include/fcl/broadphase/broadphase_SaP-inl.h +++ b/include/fcl/broadphase/broadphase_SaP-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_SAP_BUILDING extern template -class FCL_EXPORT SaPCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL SaPCollisionManager; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_SaP.h b/include/fcl/broadphase/broadphase_SaP.h index 8a6b611ab..869e6a26b 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 FCL_EXPORT SaPCollisionManager : public BroadPhaseCollisionManager +class SaPCollisionManager : public BroadPhaseCollisionManager { public: @@ -119,10 +119,10 @@ class FCL_EXPORT SaPCollisionManager : public BroadPhaseCollisionManager struct SaPPair; /// @brief Functor to help unregister one object - class FCL_EXPORT isUnregistered; + class isUnregistered; /// @brief Functor to help remove collision pairs no longer valid (i.e., should be culled away) - class FCL_EXPORT isNotValidPair; + class isNotValidPair; void update_(SaPAABB* updated_aabb); @@ -215,7 +215,7 @@ struct SaPCollisionManager::SaPPair /// @brief Functor to help unregister one object template -class FCL_EXPORT SaPCollisionManager::isUnregistered +class SaPCollisionManager::isUnregistered { CollisionObject* obj; @@ -227,7 +227,7 @@ class FCL_EXPORT SaPCollisionManager::isUnregistered /// @brief Functor to help remove collision pairs no longer valid (i.e., should be culled away) template -class FCL_EXPORT SaPCollisionManager::isNotValidPair +class 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 0c92ace3f..00574a3e9 100644 --- a/include/fcl/broadphase/broadphase_bruteforce-inl.h +++ b/include/fcl/broadphase/broadphase_bruteforce-inl.h @@ -45,8 +45,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_BRUTEFORCE_BUILDING extern template -class FCL_EXPORT NaiveCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL NaiveCollisionManager; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_bruteforce.h b/include/fcl/broadphase/broadphase_bruteforce.h index f8ce6c52c..2f9179dea 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 FCL_EXPORT NaiveCollisionManager : public BroadPhaseCollisionManager +class 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 e69f86c4f..a6e1be5b5 100644 --- a/include/fcl/broadphase/broadphase_collision_manager-inl.h +++ b/include/fcl/broadphase/broadphase_collision_manager-inl.h @@ -45,8 +45,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_COLLISION_MANAGER_BUILDING extern template -class FCL_EXPORT BroadPhaseCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL BroadPhaseCollisionManager; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_collision_manager.h b/include/fcl/broadphase/broadphase_collision_manager.h index c372c7a43..c60c21569 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 FCL_EXPORT BroadPhaseCollisionManager +class 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 05ff0f804..03eb21b07 100644 --- a/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h +++ b/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h @@ -45,8 +45,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_CONTINUOUS_COLLISION_MANAGER_BUILDING extern template -class FCL_EXPORT BroadPhaseContinuousCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL BroadPhaseContinuousCollisionManager; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_continuous_collision_manager.h b/include/fcl/broadphase/broadphase_continuous_collision_manager.h index d0a043572..7cfa2156c 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 FCL_EXPORT BroadPhaseContinuousCollisionManager +class 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 1a7341b5c..5d3ff7d6c 100644 --- a/include/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h +++ b/include/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h @@ -49,8 +49,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_DYNAMIC_AABB_TREE_BUILDING extern template -class FCL_EXPORT DynamicAABBTreeCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL DynamicAABBTreeCollisionManager; +#endif namespace detail { @@ -59,7 +61,6 @@ namespace dynamic_AABB_tree { #if FCL_HAVE_OCTOMAP //============================================================================== template -FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -171,7 +172,6 @@ bool collisionRecurse_( //============================================================================== template -FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -278,7 +278,6 @@ bool collisionRecurse_( //============================================================================== template -FCL_EXPORT bool distanceRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -369,7 +368,6 @@ bool distanceRecurse_( //============================================================================== template -FCL_EXPORT bool collisionRecurse( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -387,7 +385,6 @@ bool collisionRecurse( //============================================================================== template -FCL_EXPORT bool distanceRecurse_( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, const OcTree* tree2, @@ -477,7 +474,6 @@ 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()) @@ -490,7 +486,6 @@ bool distanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNod //============================================================================== template -FCL_EXPORT bool collisionRecurse( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root2, @@ -524,7 +519,6 @@ bool collisionRecurse( //============================================================================== template -FCL_EXPORT bool collisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, CollisionObject* query, void* cdata, CollisionCallBack callback) { if(root->isLeaf()) @@ -548,7 +542,6 @@ bool collisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNo //============================================================================== template -FCL_EXPORT bool selfCollisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, void* cdata, CollisionCallBack callback) { if(root->isLeaf()) return false; @@ -567,7 +560,6 @@ bool selfCollisionRecurse(typename DynamicAABBTreeCollisionManager::DynamicAA //============================================================================== template -FCL_EXPORT bool distanceRecurse( typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root1, typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root2, @@ -656,7 +648,6 @@ bool distanceRecurse( //============================================================================== template -FCL_EXPORT bool distanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAABBNode* root, CollisionObject* query, void* cdata, DistanceCallBack callback, S& min_dist) { if(root->isLeaf()) @@ -702,7 +693,6 @@ 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; @@ -725,7 +715,6 @@ bool selfDistanceRecurse(typename DynamicAABBTreeCollisionManager::DynamicAAB //============================================================================== template -FCL_EXPORT DynamicAABBTreeCollisionManager::DynamicAABBTreeCollisionManager() : tree_topdown_balance_threshold(dtree.bu_threshold), tree_topdown_level(dtree.topdown_level) @@ -744,7 +733,6 @@ DynamicAABBTreeCollisionManager::DynamicAABBTreeCollisionManager() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::registerObjects( const std::vector*>& other_objs) { @@ -777,7 +765,6 @@ void DynamicAABBTreeCollisionManager::registerObjects( //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::registerObject(CollisionObject* obj) { DynamicAABBNode* node = dtree.insert(obj->getAABB(), obj); @@ -786,7 +773,6 @@ void DynamicAABBTreeCollisionManager::registerObject(CollisionObject* obj) //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::unregisterObject(CollisionObject* obj) { DynamicAABBNode* node = table[obj]; @@ -796,7 +782,6 @@ void DynamicAABBTreeCollisionManager::unregisterObject(CollisionObject* ob //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::setup() { if(!setup_) @@ -822,7 +807,6 @@ void DynamicAABBTreeCollisionManager::setup() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::update() { for(auto it = table.cbegin(); it != table.cend(); ++it) @@ -840,7 +824,6 @@ void DynamicAABBTreeCollisionManager::update() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::update_(CollisionObject* updated_obj) { const auto it = table.find(updated_obj); @@ -855,7 +838,6 @@ void DynamicAABBTreeCollisionManager::update_(CollisionObject* updated_obj //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::update(CollisionObject* updated_obj) { update_(updated_obj); @@ -864,7 +846,6 @@ 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) @@ -874,7 +855,6 @@ void DynamicAABBTreeCollisionManager::update(const std::vector -FCL_EXPORT void DynamicAABBTreeCollisionManager::clear() { dtree.clear(); @@ -883,7 +863,6 @@ void DynamicAABBTreeCollisionManager::clear() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::getObjects(std::vector*>& objs) const { objs.resize(this->size()); @@ -892,7 +871,6 @@ void DynamicAABBTreeCollisionManager::getObjects(std::vector -FCL_EXPORT void DynamicAABBTreeCollisionManager::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -918,7 +896,6 @@ void DynamicAABBTreeCollisionManager::collide(CollisionObject* obj, void* //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::distance(CollisionObject* obj, void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -945,7 +922,6 @@ void DynamicAABBTreeCollisionManager::distance(CollisionObject* obj, void* //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::collide(void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -954,7 +930,6 @@ void DynamicAABBTreeCollisionManager::collide(void* cdata, CollisionCallBack< //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager::distance(void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -964,7 +939,6 @@ 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_); @@ -974,7 +948,6 @@ 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_); @@ -985,7 +958,6 @@ void DynamicAABBTreeCollisionManager::distance(BroadPhaseCollisionManager* //============================================================================== template -FCL_EXPORT bool DynamicAABBTreeCollisionManager::empty() const { return dtree.empty(); @@ -993,7 +965,6 @@ bool DynamicAABBTreeCollisionManager::empty() const //============================================================================== template -FCL_EXPORT size_t DynamicAABBTreeCollisionManager::size() const { return dtree.size(); @@ -1001,7 +972,6 @@ 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 7ee6a333f..bfe0ef6db 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 FCL_EXPORT DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager +class 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 3cec23cbc..b0fcb9ad9 100644 --- a/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h +++ b/include/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h @@ -48,8 +48,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_DYNAMIC_AABB_TREE_ARRAY_BUILDING extern template -class FCL_EXPORT DynamicAABBTreeCollisionManager_Array; +class FCL_EXPORT_EXPL_INST_DECL DynamicAABBTreeCollisionManager_Array; +#endif namespace detail { @@ -61,7 +63,6 @@ namespace dynamic_AABB_tree_array //============================================================================== template -FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, @@ -175,7 +176,6 @@ bool collisionRecurse_( //============================================================================== template -FCL_EXPORT bool collisionRecurse_( typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, @@ -284,7 +284,6 @@ 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; @@ -368,7 +367,6 @@ bool distanceRecurse_(typename DynamicAABBTreeCollisionManager_Array::Dynamic //============================================================================== template -FCL_EXPORT bool distanceRecurse_( typename DynamicAABBTreeCollisionManager_Array::DynamicAABBNode* nodes1, size_t root1_id, @@ -464,7 +462,6 @@ 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) @@ -498,7 +495,6 @@ 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; @@ -523,7 +519,6 @@ 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; @@ -543,7 +538,6 @@ 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) @@ -631,7 +625,6 @@ 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; @@ -678,7 +671,6 @@ 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; @@ -701,7 +693,6 @@ 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()) @@ -712,7 +703,6 @@ 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()) @@ -729,7 +719,6 @@ 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) @@ -748,7 +737,6 @@ DynamicAABBTreeCollisionManager_Array::DynamicAABBTreeCollisionManager_Array( //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::registerObjects( const std::vector*>& other_objs) { @@ -781,7 +769,6 @@ void DynamicAABBTreeCollisionManager_Array::registerObjects( //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::registerObject(CollisionObject* obj) { size_t node = dtree.insert(obj->getAABB(), obj); @@ -790,7 +777,6 @@ void DynamicAABBTreeCollisionManager_Array::registerObject(CollisionObject //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::unregisterObject(CollisionObject* obj) { size_t node = table[obj]; @@ -800,7 +786,6 @@ void DynamicAABBTreeCollisionManager_Array::unregisterObject(CollisionObject< //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::setup() { if(!setup_) @@ -826,7 +811,6 @@ void DynamicAABBTreeCollisionManager_Array::setup() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update() { for(auto it = table.cbegin(), end = table.cend(); it != end; ++it) @@ -844,7 +828,6 @@ void DynamicAABBTreeCollisionManager_Array::update() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update_(CollisionObject* updated_obj) { const auto it = table.find(updated_obj); @@ -859,7 +842,6 @@ void DynamicAABBTreeCollisionManager_Array::update_(CollisionObject* updat //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::update(CollisionObject* updated_obj) { update_(updated_obj); @@ -868,7 +850,6 @@ 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) @@ -878,7 +859,6 @@ void DynamicAABBTreeCollisionManager_Array::update(const std::vector -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::clear() { dtree.clear(); @@ -887,7 +867,6 @@ void DynamicAABBTreeCollisionManager_Array::clear() //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::getObjects(std::vector*>& objs) const { objs.resize(this->size()); @@ -896,7 +875,6 @@ void DynamicAABBTreeCollisionManager_Array::getObjects(std::vector -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -922,7 +900,6 @@ void DynamicAABBTreeCollisionManager_Array::collide(CollisionObject* obj, //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::distance(CollisionObject* obj, void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -949,7 +926,6 @@ void DynamicAABBTreeCollisionManager_Array::distance(CollisionObject* obj, //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::collide(void* cdata, CollisionCallBack callback) const { if(size() == 0) return; @@ -958,7 +934,6 @@ void DynamicAABBTreeCollisionManager_Array::collide(void* cdata, CollisionCal //============================================================================== template -FCL_EXPORT void DynamicAABBTreeCollisionManager_Array::distance(void* cdata, DistanceCallBack callback) const { if(size() == 0) return; @@ -968,7 +943,6 @@ 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_); @@ -978,7 +952,6 @@ 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_); @@ -989,7 +962,6 @@ void DynamicAABBTreeCollisionManager_Array::distance(BroadPhaseCollisionManag //============================================================================== template -FCL_EXPORT bool DynamicAABBTreeCollisionManager_Array::empty() const { return dtree.empty(); @@ -997,7 +969,6 @@ bool DynamicAABBTreeCollisionManager_Array::empty() const //============================================================================== template -FCL_EXPORT size_t DynamicAABBTreeCollisionManager_Array::size() const { return dtree.size(); @@ -1005,7 +976,6 @@ 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 3d535f822..df4421edb 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 FCL_EXPORT DynamicAABBTreeCollisionManager_Array : public BroadPhaseCollisionManager +class 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 dcc4f6d79..b51e3174b 100644 --- a/include/fcl/broadphase/broadphase_interval_tree-inl.h +++ b/include/fcl/broadphase/broadphase_interval_tree-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_INTERVAL_TREE_BUILDING extern template -class FCL_EXPORT IntervalTreeCollisionManager; +class FCL_EXPORT_EXPL_INST_DECL IntervalTreeCollisionManager; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_interval_tree.h b/include/fcl/broadphase/broadphase_interval_tree.h index 79c5467c0..8d28f2143 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 FCL_EXPORT IntervalTreeCollisionManager : public BroadPhaseCollisionManager +class IntervalTreeCollisionManager : public BroadPhaseCollisionManager { public: IntervalTreeCollisionManager(); @@ -147,7 +147,7 @@ using IntervalTreeCollisionManagerd = IntervalTreeCollisionManager; /// @brief SAP end point template -struct FCL_EXPORT IntervalTreeCollisionManager::EndPoint +struct IntervalTreeCollisionManager::EndPoint { /// @brief object related with the end point CollisionObject* obj; @@ -163,7 +163,7 @@ struct FCL_EXPORT IntervalTreeCollisionManager::EndPoint /// @brief Extention interval tree's interval to SAP interval, adding more information template -struct FCL_EXPORT IntervalTreeCollisionManager::SAPInterval : public detail::SimpleInterval +struct 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 12551ce08..a2008ba11 100644 --- a/include/fcl/broadphase/broadphase_spatialhash-inl.h +++ b/include/fcl/broadphase/broadphase_spatialhash-inl.h @@ -44,11 +44,13 @@ namespace fcl { //============================================================================== +#ifndef FCL_BROADPHASE_SPATIALHASH_BUILDING extern template -class FCL_EXPORT SpatialHashingCollisionManager< +class FCL_EXPORT_EXPL_INST_DECL SpatialHashingCollisionManager< double, detail::SimpleHashTable< AABB, CollisionObject*, detail::SpatialHash>>; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/broadphase_spatialhash.h b/include/fcl/broadphase/broadphase_spatialhash.h index a21d0417f..96529b2f4 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 FCL_EXPORT SpatialHashingCollisionManager : public BroadPhaseCollisionManager +class SpatialHashingCollisionManager : public BroadPhaseCollisionManager { public: SpatialHashingCollisionManager( diff --git a/include/fcl/broadphase/detail/hierarchy_tree.h b/include/fcl/broadphase/detail/hierarchy_tree.h index 456314a5d..bdea6c940 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 FCL_EXPORT HierarchyTree +class HierarchyTree { public: diff --git a/include/fcl/broadphase/detail/hierarchy_tree_array.h b/include/fcl/broadphase/detail/hierarchy_tree_array.h index 85e80feaf..8145a04be 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 FCL_EXPORT HierarchyTree +class HierarchyTree { using S = typename BV::S; typedef NodeBase NodeType; diff --git a/include/fcl/broadphase/detail/interval_tree-inl.h b/include/fcl/broadphase/detail/interval_tree-inl.h index 5c93cc43a..380308c98 100644 --- a/include/fcl/broadphase/detail/interval_tree-inl.h +++ b/include/fcl/broadphase/detail/interval_tree-inl.h @@ -46,8 +46,10 @@ namespace fcl { namespace detail { //============================================================================== +#ifndef FCL_BROADPHASE_DETAIL_INTERVAL_TREE_BUILDING extern template -class IntervalTree; +class FCL_EXPORT_EXPL_INST_DECL IntervalTree; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/detail/interval_tree.h b/include/fcl/broadphase/detail/interval_tree.h index 6573520c9..d7b3c9047 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 FCL_EXPORT it_recursion_node +struct it_recursion_node { public: IntervalTreeNode* start_node; @@ -64,12 +64,14 @@ struct FCL_EXPORT it_recursion_node using it_recursion_nodef = it_recursion_node; using it_recursion_noded = it_recursion_node; +#ifndef FCL_BROADPHASE_DETAIL_INTERVAL_TREE_BUILDING extern template -struct it_recursion_node; +struct FCL_EXPORT_EXPL_INST_DECL it_recursion_node; +#endif /// @brief Interval tree template -class FCL_EXPORT IntervalTree +class 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 2badc0469..069419a31 100644 --- a/include/fcl/broadphase/detail/interval_tree_node-inl.h +++ b/include/fcl/broadphase/detail/interval_tree_node-inl.h @@ -46,8 +46,10 @@ namespace fcl { namespace detail { //============================================================================== +#ifndef FCL_BROADPHASE_DETAIL_INTERVAL_TREE_NODE_BUILDING extern template -class FCL_EXPORT IntervalTreeNode; +class FCL_EXPORT_EXPL_INST_DECL IntervalTreeNode; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/detail/interval_tree_node.h b/include/fcl/broadphase/detail/interval_tree_node.h index 537adab03..8e243b3e3 100644 --- a/include/fcl/broadphase/detail/interval_tree_node.h +++ b/include/fcl/broadphase/detail/interval_tree_node.h @@ -48,11 +48,11 @@ namespace detail { template -class FCL_EXPORT IntervalTree; +class IntervalTree; /// @brief The node for interval tree template -class FCL_EXPORT IntervalTreeNode +class IntervalTreeNode { public: diff --git a/include/fcl/broadphase/detail/morton-inl.h b/include/fcl/broadphase/detail/morton-inl.h index cb23207b3..ce7bf5889 100644 --- a/include/fcl/broadphase/detail/morton-inl.h +++ b/include/fcl/broadphase/detail/morton-inl.h @@ -46,16 +46,19 @@ namespace fcl { namespace detail { //============================================================================== +#ifndef FCL_BROADPHASE_DETAIL_MORTON_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL uint32 quantize(double x, uint32 n); //============================================================================== extern template -struct morton_functor; +struct FCL_EXPORT_EXPL_INST_DECL morton_functor; //============================================================================== extern template -struct morton_functor; +struct FCL_EXPORT_EXPL_INST_DECL morton_functor; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/detail/morton.h b/include/fcl/broadphase/detail/morton.h index 6b430c434..7a840e497 100644 --- a/include/fcl/broadphase/detail/morton.h +++ b/include/fcl/broadphase/detail/morton.h @@ -52,7 +52,6 @@ namespace detail { template -FCL_EXPORT uint32 quantize(S x, uint32 n); /// @brief compute 30 bit morton code @@ -68,11 +67,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 FCL_EXPORT morton_functor {}; +struct morton_functor {}; /// @brief Functor to compute 30 bit morton code for a given AABB template -struct FCL_EXPORT morton_functor +struct morton_functor { morton_functor(const AABB& bbox); @@ -89,7 +88,7 @@ using morton_functoru32d = morton_functor; /// @brief Functor to compute 60 bit morton code for a given AABB template -struct FCL_EXPORT morton_functor +struct morton_functor { morton_functor(const AABB& bbox); @@ -107,7 +106,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 FCL_EXPORT morton_functor> +struct 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 2708d02a9..d45d3c98a 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 FCL_EXPORT SimpleHashTable +class SimpleHashTable { protected: typedef std::list Bin; diff --git a/include/fcl/broadphase/detail/simple_interval-inl.h b/include/fcl/broadphase/detail/simple_interval-inl.h index 4daafd9ac..284d92372 100644 --- a/include/fcl/broadphase/detail/simple_interval-inl.h +++ b/include/fcl/broadphase/detail/simple_interval-inl.h @@ -44,8 +44,10 @@ namespace fcl { namespace detail { //============================================================================== +#ifndef FCL_BROADPHASE_DETAIL_SIMPLE_INTERVAL_BUILDING extern template -struct SimpleInterval; +struct FCL_EXPORT_EXPL_INST_DECL SimpleInterval; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/detail/simple_interval.h b/include/fcl/broadphase/detail/simple_interval.h index ee8cbcadb..1b8516381 100644 --- a/include/fcl/broadphase/detail/simple_interval.h +++ b/include/fcl/broadphase/detail/simple_interval.h @@ -49,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 FCL_EXPORT SimpleInterval +struct 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 8f1a133e5..f2d4f0f4f 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 FCL_EXPORT unordered_map_hash_table : public std::unordered_map {}; +class unordered_map_hash_table : public std::unordered_map {}; /// @brief A hash table implemented using unordered_map template class TableT = unordered_map_hash_table> -class FCL_EXPORT SparseHashTable +class SparseHashTable { protected: HashFnc h_; diff --git a/include/fcl/broadphase/detail/spatial_hash-inl.h b/include/fcl/broadphase/detail/spatial_hash-inl.h index 1d4985f20..e5089f5ad 100644 --- a/include/fcl/broadphase/detail/spatial_hash-inl.h +++ b/include/fcl/broadphase/detail/spatial_hash-inl.h @@ -44,8 +44,10 @@ namespace fcl { namespace detail { //============================================================================== +#ifndef FCL_BROADPHASE_DETAIL_SPATIAL_HASH_BUILDING extern template -struct SpatialHash; +struct FCL_EXPORT_EXPL_INST_DECL SpatialHash; +#endif //============================================================================== template diff --git a/include/fcl/broadphase/detail/spatial_hash.h b/include/fcl/broadphase/detail/spatial_hash.h index b3f1cdd88..ebb25a57b 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 FCL_EXPORT SpatialHash +struct SpatialHash { using S = S_; diff --git a/include/fcl/common/types.h b/include/fcl/common/types.h index 892e2b07f..32af2b5cb 100644 --- a/include/fcl/common/types.h +++ b/include/fcl/common/types.h @@ -142,7 +142,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 FCL_EXPORT aligned_allocator_cpp11 : public std::allocator +class 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 294d521e4..bab7304f5 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 FCL_EXPORT BVHModel : public CollisionGeometry +class 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 2196ca486..51d81fa33 100644 --- a/include/fcl/geometry/bvh/BVH_utility-inl.h +++ b/include/fcl/geometry/bvh/BVH_utility-inl.h @@ -46,18 +46,21 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_BHV_UTILITY_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL void BVHExpand( BVHModel>& model, const Variance3* ucs, double r); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void BVHExpand( BVHModel>& model, const Variance3* ucs, double r); +#endif //============================================================================== template -FCL_EXPORT void BVHExpand(BVHModel& model, const Variance3* ucs, S r) { for(int i = 0; i < model.num_bvs; ++i) @@ -85,7 +88,6 @@ void BVHExpand(BVHModel& model, const Variance3* ucs, S r) //============================================================================== template -FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, @@ -129,7 +131,6 @@ 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 68e3974b6..a0862228c 100644 --- a/include/fcl/geometry/bvh/BVH_utility.h +++ b/include/fcl/geometry/bvh/BVH_utility.h @@ -47,20 +47,17 @@ 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 08dabbc0d..b87b9fd58 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 FCL_EXPORT BVNode : public BVNodeBase +struct BVNode : public BVNodeBase { using S = typename BV::S; diff --git a/include/fcl/geometry/bvh/detail/BV_fitter.h b/include/fcl/geometry/bvh/detail/BV_fitter.h index c78c52364..c31e2b8a3 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 FCL_EXPORT BVFitter : public BVFitterBase +class 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 3e10fbb33..6bc1db156 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 FCL_EXPORT BVFitterBase +class BVFitterBase { public: diff --git a/include/fcl/geometry/bvh/detail/BV_splitter.h b/include/fcl/geometry/bvh/detail/BV_splitter.h index 7480f7728..b15561026 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 FCL_EXPORT BVSplitter : public BVSplitterBase +class 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 893c2bedd..595b794da 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 FCL_EXPORT BVSplitterBase +class BVSplitterBase { public: diff --git a/include/fcl/geometry/collision_geometry-inl.h b/include/fcl/geometry/collision_geometry-inl.h index b5695325e..a41a41952 100644 --- a/include/fcl/geometry/collision_geometry-inl.h +++ b/include/fcl/geometry/collision_geometry-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_COLLISION_GEOMETRY_BUILDING extern template -class FCL_EXPORT CollisionGeometry; +class FCL_EXPORT_EXPL_INST_DECL CollisionGeometry; +#endif //============================================================================== template diff --git a/include/fcl/geometry/collision_geometry.h b/include/fcl/geometry/collision_geometry.h index 21fe84992..09d34b876 100644 --- a/include/fcl/geometry/collision_geometry.h +++ b/include/fcl/geometry/collision_geometry.h @@ -55,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 FCL_EXPORT CollisionGeometry +class CollisionGeometry { public: CollisionGeometry(); diff --git a/include/fcl/geometry/octree/octree-inl.h b/include/fcl/geometry/octree/octree-inl.h index f50fe819c..8d1a9b1e7 100644 --- a/include/fcl/geometry/octree/octree-inl.h +++ b/include/fcl/geometry/octree/octree-inl.h @@ -50,12 +50,15 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_OCTREE_BUILDING extern template -class FCL_EXPORT OcTree; +class FCL_EXPORT_EXPL_INST_DECL OcTree; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void computeChildBV(const AABB& root_bv, unsigned int i, AABB& child_bv); +#endif //============================================================================== template diff --git a/include/fcl/geometry/octree/octree.h b/include/fcl/geometry/octree/octree.h index 426414801..d0a6b1c22 100644 --- a/include/fcl/geometry/octree/octree.h +++ b/include/fcl/geometry/octree/octree.h @@ -61,7 +61,7 @@ namespace fcl /// fcl/config.h if and only if octomap was found. Doxygen documentation will /// be generated whether or not octomap was found. template -class FCL_EXPORT OcTree : public CollisionGeometry +class OcTree : public CollisionGeometry { private: std::shared_ptr tree; @@ -190,7 +190,6 @@ 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 053119a0e..d14ef592a 100644 --- a/include/fcl/geometry/shape/box-inl.h +++ b/include/fcl/geometry/shape/box-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_BOX_BUILDING extern template -class FCL_EXPORT Box; +class FCL_EXPORT_EXPL_INST_DECL Box; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/box.h b/include/fcl/geometry/shape/box.h index d15e9f269..5460828a1 100644 --- a/include/fcl/geometry/shape/box.h +++ b/include/fcl/geometry/shape/box.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Center at zero point, axis aligned box template -class FCL_EXPORT Box : public ShapeBase +class Box : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/capsule-inl.h b/include/fcl/geometry/shape/capsule-inl.h index b2add91fc..1721b1f22 100644 --- a/include/fcl/geometry/shape/capsule-inl.h +++ b/include/fcl/geometry/shape/capsule-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_CAPSULE_BUILDING extern template -class FCL_EXPORT Capsule; +class FCL_EXPORT_EXPL_INST_DECL Capsule; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/capsule.h b/include/fcl/geometry/shape/capsule.h index 5add95e27..831deed8c 100644 --- a/include/fcl/geometry/shape/capsule.h +++ b/include/fcl/geometry/shape/capsule.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Center at zero point capsule template -class FCL_EXPORT Capsule : public ShapeBase +class Capsule : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/cone-inl.h b/include/fcl/geometry/shape/cone-inl.h index 3b023fcc0..467e62bb4 100644 --- a/include/fcl/geometry/shape/cone-inl.h +++ b/include/fcl/geometry/shape/cone-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_CONE_BUILDING extern template -class FCL_EXPORT Cone; +class FCL_EXPORT_EXPL_INST_DECL Cone; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/cone.h b/include/fcl/geometry/shape/cone.h index ef9180c2a..528122069 100644 --- a/include/fcl/geometry/shape/cone.h +++ b/include/fcl/geometry/shape/cone.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Center at zero cone template -class FCL_EXPORT Cone : public ShapeBase +class Cone : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/convex-inl.h b/include/fcl/geometry/shape/convex-inl.h index 10adc699f..3fb8d9477 100644 --- a/include/fcl/geometry/shape/convex-inl.h +++ b/include/fcl/geometry/shape/convex-inl.h @@ -49,8 +49,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_CONVEX_BUILDING extern template -class FCL_EXPORT Convex; +class FCL_EXPORT_EXPL_INST_DECL Convex; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/convex.h b/include/fcl/geometry/shape/convex.h index d817b4c71..e911613c8 100644 --- a/include/fcl/geometry/shape/convex.h +++ b/include/fcl/geometry/shape/convex.h @@ -80,7 +80,7 @@ namespace fcl /// /// @tparam S_ The scalar type; must be a valid Eigen scalar. template -class FCL_EXPORT Convex : public ShapeBase +class Convex : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/cylinder-inl.h b/include/fcl/geometry/shape/cylinder-inl.h index f5a621153..c401ababb 100644 --- a/include/fcl/geometry/shape/cylinder-inl.h +++ b/include/fcl/geometry/shape/cylinder-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_CYLINDER_BUILDING extern template -class FCL_EXPORT Cylinder; +class FCL_EXPORT_EXPL_INST_DECL Cylinder; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/cylinder.h b/include/fcl/geometry/shape/cylinder.h index bd67d3132..5e33aecfd 100644 --- a/include/fcl/geometry/shape/cylinder.h +++ b/include/fcl/geometry/shape/cylinder.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Center at zero cylinder template -class FCL_EXPORT Cylinder : public ShapeBase +class Cylinder : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/ellipsoid-inl.h b/include/fcl/geometry/shape/ellipsoid-inl.h index 5bbf946f8..9cb3f31e5 100644 --- a/include/fcl/geometry/shape/ellipsoid-inl.h +++ b/include/fcl/geometry/shape/ellipsoid-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_ELLIPSOID_BUILDING extern template -class FCL_EXPORT Ellipsoid; +class FCL_EXPORT_EXPL_INST_DECL Ellipsoid; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/ellipsoid.h b/include/fcl/geometry/shape/ellipsoid.h index 85632a900..3dfd1c00c 100644 --- a/include/fcl/geometry/shape/ellipsoid.h +++ b/include/fcl/geometry/shape/ellipsoid.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Center at zero point ellipsoid template -class FCL_EXPORT Ellipsoid : public ShapeBase +class Ellipsoid : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/halfspace-inl.h b/include/fcl/geometry/shape/halfspace-inl.h index bc58f80f1..4ea7b2a6a 100644 --- a/include/fcl/geometry/shape/halfspace-inl.h +++ b/include/fcl/geometry/shape/halfspace-inl.h @@ -44,12 +44,15 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_HALFSPACE_BUILDING extern template -class FCL_EXPORT Halfspace; +class FCL_EXPORT_EXPL_INST_DECL Halfspace; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL Halfspace transform(const Halfspace& a, const Transform3& tf); +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/halfspace.h b/include/fcl/geometry/shape/halfspace.h index e67975980..641241cf0 100644 --- a/include/fcl/geometry/shape/halfspace.h +++ b/include/fcl/geometry/shape/halfspace.h @@ -56,7 +56,7 @@ namespace fcl /// in the positive side of the separation plane (i.e. {x | n * x > d}) are /// outside the half space. template -class FCL_EXPORT Halfspace : public ShapeBase +class Halfspace : public ShapeBase { public: @@ -103,7 +103,6 @@ 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 2e5da9c06..ed1e9fa32 100644 --- a/include/fcl/geometry/shape/plane-inl.h +++ b/include/fcl/geometry/shape/plane-inl.h @@ -44,12 +44,15 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_PLANE_BUILDING extern template -class FCL_EXPORT Plane; +class FCL_EXPORT_EXPL_INST_DECL Plane; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL Plane transform(const Plane& a, const Transform3& tf); +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/plane.h b/include/fcl/geometry/shape/plane.h index bcf34212e..6dfb07458 100644 --- a/include/fcl/geometry/shape/plane.h +++ b/include/fcl/geometry/shape/plane.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Infinite plane template -class FCL_EXPORT Plane : public ShapeBase +class Plane : public ShapeBase { public: @@ -93,7 +93,6 @@ 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 b3148c469..07f1342b0 100644 --- a/include/fcl/geometry/shape/shape_base-inl.h +++ b/include/fcl/geometry/shape/shape_base-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_BASE_BUILDING extern template -class FCL_EXPORT ShapeBase; +class FCL_EXPORT_EXPL_INST_DECL ShapeBase; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/shape_base.h b/include/fcl/geometry/shape/shape_base.h index 6acc6da64..1f68aa270 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 FCL_EXPORT ShapeBase : public CollisionGeometry +class ShapeBase : public CollisionGeometry { public: diff --git a/include/fcl/geometry/shape/sphere-inl.h b/include/fcl/geometry/shape/sphere-inl.h index 0da7eeae9..7d8715710 100644 --- a/include/fcl/geometry/shape/sphere-inl.h +++ b/include/fcl/geometry/shape/sphere-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_SPHERE_BUILDING extern template -class FCL_EXPORT Sphere; +class FCL_EXPORT_EXPL_INST_DECL Sphere; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/sphere.h b/include/fcl/geometry/shape/sphere.h index 48b67927f..d33a3f05c 100644 --- a/include/fcl/geometry/shape/sphere.h +++ b/include/fcl/geometry/shape/sphere.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Center at zero point sphere template -class FCL_EXPORT Sphere : public ShapeBase +class 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 f48d41bb7..e1fab6787 100644 --- a/include/fcl/geometry/shape/triangle_p-inl.h +++ b/include/fcl/geometry/shape/triangle_p-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_TRIANGLE_P_BUILDING extern template -class FCL_EXPORT TriangleP; +class FCL_EXPORT_EXPL_INST_DECL TriangleP; +#endif //============================================================================== template diff --git a/include/fcl/geometry/shape/triangle_p.h b/include/fcl/geometry/shape/triangle_p.h index 7cc18caa0..28e911ac0 100644 --- a/include/fcl/geometry/shape/triangle_p.h +++ b/include/fcl/geometry/shape/triangle_p.h @@ -47,7 +47,7 @@ namespace fcl /// @brief Triangle stores the points instead of only indices of points template -class FCL_EXPORT TriangleP : public ShapeBase +class TriangleP : public ShapeBase { public: diff --git a/include/fcl/geometry/shape/utility-inl.h b/include/fcl/geometry/shape/utility-inl.h index ca42a0b60..8b1c10959 100644 --- a/include/fcl/geometry/shape/utility-inl.h +++ b/include/fcl/geometry/shape/utility-inl.h @@ -57,994 +57,1115 @@ namespace fcl { //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_UTILITY_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL +void constructBox(const AABB& bv, Box& box, Transform3& tf); + +//============================================================================== +extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const OBB& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const OBBRSS& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const kIOS& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const RSS& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const KDOP& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const KDOP& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const KDOP& bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const AABB& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const OBB& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const OBBRSS& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const kIOS& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const RSS& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const KDOP& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const KDOP& bv, const Transform3& tf_bv, Box& box, Transform3& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void constructBox(const KDOP& bv, const Transform3& tf_bv, Box& box, Transform3& tf); +#endif //============================================================================== namespace detail { //============================================================================== -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl +struct ComputeBVImpl { - static void run(const Shape& s, const Transform3& tf, BV& bv) - { - std::vector> convex_bound_vertices = s.getBoundVertices(tf); - fit(convex_bound_vertices.data(), - static_cast(convex_bound_vertices.size()), bv); - } + static void run(const Shape& s, const Transform3& tf, BV& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Box> +struct ComputeBVImpl, Box> { - static void run(const Box& s, const Transform3& tf, AABB& bv) - { - const Matrix3& R = tf.linear(); - const Vector3& T = tf.translation(); - - S x_range = 0.5 * (fabs(R(0, 0) * s.side[0]) + fabs(R(0, 1) * s.side[1]) + fabs(R(0, 2) * s.side[2])); - S y_range = 0.5 * (fabs(R(1, 0) * s.side[0]) + fabs(R(1, 1) * s.side[1]) + fabs(R(1, 2) * s.side[2])); - S z_range = 0.5 * (fabs(R(2, 0) * s.side[0]) + fabs(R(2, 1) * s.side[1]) + fabs(R(2, 2) * s.side[2])); - - Vector3 v_delta(x_range, y_range, z_range); - bv.max_ = T + v_delta; - bv.min_ = T - v_delta; - } + static void run(const Box& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Box> +struct ComputeBVImpl, Box> { - static void run(const Box& s, const Transform3& tf, OBB& bv) - { - bv.axis = tf.linear(); - bv.To = tf.translation(); - bv.extent = s.side * (S)0.5; - } + static void run(const Box& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Capsule> +struct ComputeBVImpl, Capsule> { - static void run(const Capsule& s, const Transform3& tf, AABB& bv) - { - const Matrix3& R = tf.linear(); - const Vector3& T = tf.translation(); - - S x_range = 0.5 * fabs(R(0, 2) * s.lz) + s.radius; - S y_range = 0.5 * fabs(R(1, 2) * s.lz) + s.radius; - S z_range = 0.5 * fabs(R(2, 2) * s.lz) + s.radius; - - Vector3 v_delta(x_range, y_range, z_range); - bv.max_ = T + v_delta; - bv.min_ = T - v_delta; - } + static void run(const Capsule& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Capsule> +struct ComputeBVImpl, Capsule> { - static void run(const Capsule& s, const Transform3& tf, OBB& bv) - { - bv.axis = tf.linear(); - bv.To = tf.translation(); - bv.extent << s.radius, s.radius, s.lz / 2 + s.radius; - } + static void run(const Capsule& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Cone> +struct ComputeBVImpl, Cone> { - static void run(const Cone& s, const Transform3& tf, AABB& bv) - { - const Matrix3& R = tf.linear(); - const Vector3& T = tf.translation(); - - S x_range = fabs(R(0, 0) * s.radius) + fabs(R(0, 1) * s.radius) + 0.5 * fabs(R(0, 2) * s.lz); - S y_range = fabs(R(1, 0) * s.radius) + fabs(R(1, 1) * s.radius) + 0.5 * fabs(R(1, 2) * s.lz); - S z_range = fabs(R(2, 0) * s.radius) + fabs(R(2, 1) * s.radius) + 0.5 * fabs(R(2, 2) * s.lz); - - Vector3 v_delta(x_range, y_range, z_range); - bv.max_ = T + v_delta; - bv.min_ = T - v_delta; - } + static void run(const Cone& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Cone> +struct ComputeBVImpl, Cone> { - static void run(const Cone& s, const Transform3& tf, OBB& bv) - { - bv.axis = tf.linear(); - bv.To = tf.translation(); - bv.extent << s.radius, s.radius, s.lz / 2; - } + static void run(const Cone& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Convex> +struct ComputeBVImpl, Convex> { - static void run(const Convex& s, const Transform3& tf, AABB& bv) - { - const Matrix3& R = tf.linear(); - const Vector3& T = tf.translation(); - - AABB bv_; - for (const auto& vertex : s.getVertices()) - { - Vector3 new_p = R * vertex + T; - bv_ += new_p; - } - - bv = bv_; - } + static void run(const Convex& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Convex> +struct ComputeBVImpl, Convex> { - static void run(const Convex& s, const Transform3& tf, OBB& bv) - { - fit(s.getVertices().data(), static_cast(s.getVertices().size()), bv); - - bv.axis = tf.linear(); - bv.To = tf * bv.To; - } + static void run(const Convex& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Cylinder> +struct ComputeBVImpl, Cylinder> { - static void run(const Cylinder& s, const Transform3& tf, AABB& bv) - { - const Matrix3& R = tf.linear(); - const Vector3& T = tf.translation(); - - S x_range = fabs(R(0, 0) * s.radius) + fabs(R(0, 1) * s.radius) + 0.5 * fabs(R(0, 2) * s.lz); - S y_range = fabs(R(1, 0) * s.radius) + fabs(R(1, 1) * s.radius) + 0.5 * fabs(R(1, 2) * s.lz); - S z_range = fabs(R(2, 0) * s.radius) + fabs(R(2, 1) * s.radius) + 0.5 * fabs(R(2, 2) * s.lz); - - Vector3 v_delta(x_range, y_range, z_range); - bv.max_ = T + v_delta; - bv.min_ = T - v_delta; - } + static void run(const Cylinder& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Cylinder> +struct ComputeBVImpl, Cylinder> { - static void run(const Cylinder& s, const Transform3& tf, OBB& bv) - { - bv.axis = tf.linear(); - bv.To = tf.translation(); - bv.extent << s.radius, s.radius, s.lz / 2; - } + static void run(const Cylinder& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Ellipsoid> +struct ComputeBVImpl, Ellipsoid> { - static void run(const Ellipsoid& s, const Transform3& tf, AABB& bv) - { - const Matrix3& R = tf.linear(); - const Vector3& T = tf.translation(); - - S x_range = (fabs(R(0, 0) * s.radii[0]) + fabs(R(0, 1) * s.radii[1]) + fabs(R(0, 2) * s.radii[2])); - S y_range = (fabs(R(1, 0) * s.radii[0]) + fabs(R(1, 1) * s.radii[1]) + fabs(R(1, 2) * s.radii[2])); - S z_range = (fabs(R(2, 0) * s.radii[0]) + fabs(R(2, 1) * s.radii[1]) + fabs(R(2, 2) * s.radii[2])); - - Vector3 v_delta(x_range, y_range, z_range); - bv.max_ = T + v_delta; - bv.min_ = T - v_delta; - } + static void run(const Ellipsoid& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Ellipsoid> +struct ComputeBVImpl, Ellipsoid> { - static void run(const Ellipsoid& s, const Transform3& tf, OBB& bv) - { - bv.axis = tf.linear(); - bv.To = tf.translation(); - bv.extent = s.radii; - } + static void run(const Ellipsoid& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> +struct ComputeBVImpl, Halfspace> { - static void run(const Halfspace& s, const Transform3& tf, AABB& bv) - { - Halfspace new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - AABB bv_; - bv_.min_ = Vector3::Constant(-std::numeric_limits::max()); - bv_.max_ = Vector3::Constant(std::numeric_limits::max()); - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - // normal aligned with x axis - if(n[0] < 0) bv_.min_[0] = -d; - else if(n[0] > 0) bv_.max_[0] = d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - // normal aligned with y axis - if(n[1] < 0) bv_.min_[1] = -d; - else if(n[1] > 0) bv_.max_[1] = d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - // normal aligned with z axis - if(n[2] < 0) bv_.min_[2] = -d; - else if(n[2] > 0) bv_.max_[2] = d; - } - - bv = bv_; - } + static void run(const Halfspace& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> +struct ComputeBVImpl, Halfspace> { - static void run(const Halfspace& s, const Transform3& tf, OBB& bv) - { - FCL_UNUSED(s); - FCL_UNUSED(tf); - - /// Half space can only have very rough OBB - bv.axis.setIdentity(); - bv.To.setZero(); - bv.extent.setConstant(std::numeric_limits::max()); - } + static void run(const Halfspace& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> +struct ComputeBVImpl, Halfspace> { - static void run(const Halfspace& s, const Transform3& tf, RSS& bv) - { - FCL_UNUSED(s); - FCL_UNUSED(tf); - - /// Half space can only have very rough RSS - bv.axis.setIdentity(); - bv.To.setZero(); - bv.l[0] = bv.l[1] = bv.r = std::numeric_limits::max(); - } + static void run(const Halfspace& s, const Transform3& tf, RSS& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> +struct ComputeBVImpl, Halfspace> { - static void run(const Halfspace& s, const Transform3& tf, OBBRSS& bv) - { - computeBV(s, tf, bv.obb); - computeBV(s, tf, bv.rss); - } + static void run(const Halfspace& s, const Transform3& tf, OBBRSS& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> +struct ComputeBVImpl, Halfspace> { - static void run(const Halfspace& s, const Transform3& tf, kIOS& bv) - { - bv.num_spheres = 1; - computeBV(s, tf, bv.obb); - bv.spheres[0].o.setZero(); - bv.spheres[0].r = std::numeric_limits::max(); - } + static void run(const Halfspace& s, const Transform3& tf, kIOS& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> -{ - static void run(const Halfspace& s, const Transform3& tf, KDOP& bv) - { - Halfspace new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - const std::size_t D = 8; - for(std::size_t i = 0; i < D; ++i) - bv.dist(i) = -std::numeric_limits::max(); - for(std::size_t i = D; i < 2 * D; ++i) - bv.dist(i) = std::numeric_limits::max(); - - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D) = d; - else bv.dist(0) = -d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(D + 1) = d; - else bv.dist(1) = -d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - if(n[2] > 0) bv.dist(D + 2) = d; - else bv.dist(2) = -d; - } - else if(n[2] == (S)0.0 && n[0] == n[1]) - { - if(n[0] > 0) bv.dist(D + 3) = n[0] * d * 2; - else bv.dist(3) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] == n[2]) - { - if(n[1] > 0) bv.dist(D + 4) = n[0] * d * 2; - else bv.dist(4) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] == n[2]) - { - if(n[1] > 0) bv.dist(D + 5) = n[1] * d * 2; - else bv.dist(5) = n[1] * d * 2; - } - else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 6) = n[0] * d * 2; - else bv.dist(6) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 7) = n[0] * d * 2; - else bv.dist(7) = n[0] * d * 2; - } - } +struct ComputeBVImpl, Halfspace> +{ + static void run(const Halfspace& s, const Transform3& tf, KDOP& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> -{ - static void run(const Halfspace& s, const Transform3& tf, KDOP& bv) - { - Halfspace new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - const std::size_t D = 9; - - for(std::size_t i = 0; i < D; ++i) - bv.dist(i) = -std::numeric_limits::max(); - for(std::size_t i = D; i < 2 * D; ++i) - bv.dist(i) = std::numeric_limits::max(); - - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D) = d; - else bv.dist(0) = -d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(D + 1) = d; - else bv.dist(1) = -d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - if(n[2] > 0) bv.dist(D + 2) = d; - else bv.dist(2) = -d; - } - else if(n[2] == (S)0.0 && n[0] == n[1]) - { - if(n[0] > 0) bv.dist(D + 3) = n[0] * d * 2; - else bv.dist(3) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] == n[2]) - { - if(n[1] > 0) bv.dist(D + 4) = n[0] * d * 2; - else bv.dist(4) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] == n[2]) - { - if(n[1] > 0) bv.dist(D + 5) = n[1] * d * 2; - else bv.dist(5) = n[1] * d * 2; - } - else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 6) = n[0] * d * 2; - else bv.dist(6) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 7) = n[0] * d * 2; - else bv.dist(7) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(D + 8) = n[1] * d * 2; - else bv.dist(8) = n[1] * d * 2; - } - } +struct ComputeBVImpl, Halfspace> +{ + static void run(const Halfspace& s, const Transform3& tf, KDOP& bv); }; //============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Halfspace> -{ - static void run(const Halfspace& s, const Transform3& tf, KDOP& bv) - { - Halfspace new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - const std::size_t D = 12; - - for(std::size_t i = 0; i < D; ++i) - bv.dist(i) = -std::numeric_limits::max(); - for(std::size_t i = D; i < 2 * D; ++i) - bv.dist(i) = std::numeric_limits::max(); - - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D) = d; - else bv.dist(0) = -d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(D + 1) = d; - else bv.dist(1) = -d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - if(n[2] > 0) bv.dist(D + 2) = d; - else bv.dist(2) = -d; - } - else if(n[2] == (S)0.0 && n[0] == n[1]) - { - if(n[0] > 0) bv.dist(D + 3) = n[0] * d * 2; - else bv.dist(3) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] == n[2]) - { - if(n[1] > 0) bv.dist(D + 4) = n[0] * d * 2; - else bv.dist(4) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] == n[2]) - { - if(n[1] > 0) bv.dist(D + 5) = n[1] * d * 2; - else bv.dist(5) = n[1] * d * 2; - } - else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 6) = n[0] * d * 2; - else bv.dist(6) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 7) = n[0] * d * 2; - else bv.dist(7) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(D + 8) = n[1] * d * 2; - else bv.dist(8) = n[1] * d * 2; - } - else if(n[0] + n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 9) = n[0] * d * 3; - else bv.dist(9) = n[0] * d * 3; - } - else if(n[0] + n[1] == (S)0.0 && n[1] + n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(D + 10) = n[0] * d * 3; - else bv.dist(10) = n[0] * d * 3; - } - else if(n[0] + n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(D + 11) = n[1] * d * 3; - else bv.dist(11) = n[1] * d * 3; - } - } +struct ComputeBVImpl, Halfspace> +{ + static void run(const Halfspace& s, const Transform3& tf, KDOP& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> +struct ComputeBVImpl, Plane> { - static void run(const Plane& s, const Transform3& tf, AABB& bv) - { - Plane new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - AABB bv_; - bv_.min_ = Vector3::Constant(-std::numeric_limits::max()); - bv_.max_ = Vector3::Constant(std::numeric_limits::max()); - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - // normal aligned with x axis - if(n[0] < 0) { bv_.min_[0] = bv_.max_[0] = -d; } - else if(n[0] > 0) { bv_.min_[0] = bv_.max_[0] = d; } - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - // normal aligned with y axis - if(n[1] < 0) { bv_.min_[1] = bv_.max_[1] = -d; } - else if(n[1] > 0) { bv_.min_[1] = bv_.max_[1] = d; } - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - // normal aligned with z axis - if(n[2] < 0) { bv_.min_[2] = bv_.max_[2] = -d; } - else if(n[2] > 0) { bv_.min_[2] = bv_.max_[2] = d; } - } - - bv = bv_; - } + static void run(const Plane& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> +struct ComputeBVImpl, Plane> { - static void run(const Plane& s, const Transform3& tf, OBB& bv) - { - const Vector3 n = tf.linear() * s.n; - bv.axis = generateCoordinateSystem(n); - - bv.extent << 0, std::numeric_limits::max(), std::numeric_limits::max(); - - Vector3 p = s.n * s.d; - bv.To = tf * p; /// n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T - } + static void run(const Plane& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> +struct ComputeBVImpl, Plane> { - static void run(const Plane& s, const Transform3& tf, RSS& bv) - { - const Vector3 n = tf.linear() * s.n; - bv.axis = generateCoordinateSystem(n); - - bv.l[0] = std::numeric_limits::max(); - bv.l[1] = std::numeric_limits::max(); - - bv.r = 0; - - Vector3 p = s.n * s.d; - bv.To = tf * p; - } + static void run(const Plane& s, const Transform3& tf, RSS& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> +struct ComputeBVImpl, Plane> { - static void run(const Plane& s, const Transform3& tf, OBBRSS& bv) - { - computeBV(s, tf, bv.obb); - computeBV(s, tf, bv.rss); - } + static void run(const Plane& s, const Transform3& tf, OBBRSS& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> +struct ComputeBVImpl, Plane> { - static void run(const Plane& s, const Transform3& tf, kIOS& bv) - { - bv.num_spheres = 1; - computeBV(s, tf, bv.obb); - bv.spheres[0].o.setZero(); - bv.spheres[0].r = std::numeric_limits::max(); - } + static void run(const Plane& s, const Transform3& tf, kIOS& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> -{ - static void run(const Plane& s, const Transform3& tf, KDOP& bv) - { - Plane new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - const std::size_t D = 8; - - for(std::size_t i = 0; i < D; ++i) - bv.dist(i) = -std::numeric_limits::max(); - for(std::size_t i = D; i < 2 * D; ++i) - bv.dist(i) = std::numeric_limits::max(); - - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(0) = bv.dist(D) = d; - else bv.dist(0) = bv.dist(D) = -d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(1) = bv.dist(D + 1) = d; - else bv.dist(1) = bv.dist(D + 1) = -d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - if(n[2] > 0) bv.dist(2) = bv.dist(D + 2) = d; - else bv.dist(2) = bv.dist(D + 2) = -d; - } - else if(n[2] == (S)0.0 && n[0] == n[1]) - { - bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] == n[2]) - { - bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] == n[2]) - { - bv.dist(6) = bv.dist(D + 5) = n[1] * d * 2; - } - else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; - } - } +struct ComputeBVImpl, Plane> +{ + static void run(const Plane& s, const Transform3& tf, KDOP& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> -{ - static void run(const Plane& s, const Transform3& tf, KDOP& bv) - { - Plane new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - const std::size_t D = 9; - - for(std::size_t i = 0; i < D; ++i) - bv.dist(i) = -std::numeric_limits::max(); - for(std::size_t i = D; i < 2 * D; ++i) - bv.dist(i) = std::numeric_limits::max(); - - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(0) = bv.dist(D) = d; - else bv.dist(0) = bv.dist(D) = -d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(1) = bv.dist(D + 1) = d; - else bv.dist(1) = bv.dist(D + 1) = -d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - if(n[2] > 0) bv.dist(2) = bv.dist(D + 2) = d; - else bv.dist(2) = bv.dist(D + 2) = -d; - } - else if(n[2] == (S)0.0 && n[0] == n[1]) - { - bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] == n[2]) - { - bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] == n[2]) - { - bv.dist(5) = bv.dist(D + 5) = n[1] * d * 2; - } - else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) - { - bv.dist(8) = bv.dist(D + 8) = n[1] * d * 2; - } - } +struct ComputeBVImpl, Plane> +{ + static void run(const Plane& s, const Transform3& tf, KDOP& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Plane> -{ - static void run(const Plane& s, const Transform3& tf, KDOP& bv) - { - Plane new_s = transform(s, tf); - const Vector3& n = new_s.n; - const S& d = new_s.d; - - const std::size_t D = 12; - - for(std::size_t i = 0; i < D; ++i) - bv.dist(i) = -std::numeric_limits::max(); - for(std::size_t i = D; i < 2 * D; ++i) - bv.dist(i) = std::numeric_limits::max(); - - if(n[1] == (S)0.0 && n[2] == (S)0.0) - { - if(n[0] > 0) bv.dist(0) = bv.dist(D) = d; - else bv.dist(0) = bv.dist(D) = -d; - } - else if(n[0] == (S)0.0 && n[2] == (S)0.0) - { - if(n[1] > 0) bv.dist(1) = bv.dist(D + 1) = d; - else bv.dist(1) = bv.dist(D + 1) = -d; - } - else if(n[0] == (S)0.0 && n[1] == (S)0.0) - { - if(n[2] > 0) bv.dist(2) = bv.dist(D + 2) = d; - else bv.dist(2) = bv.dist(D + 2) = -d; - } - else if(n[2] == (S)0.0 && n[0] == n[1]) - { - bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] == n[2]) - { - bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] == n[2]) - { - bv.dist(5) = bv.dist(D + 5) = n[1] * d * 2; - } - else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; - } - else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; - } - else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) - { - bv.dist(8) = bv.dist(D + 8) = n[1] * d * 2; - } - else if(n[0] + n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) - { - bv.dist(9) = bv.dist(D + 9) = n[0] * d * 3; - } - else if(n[0] + n[1] == (S)0.0 && n[1] + n[2] == (S)0.0) - { - bv.dist(10) = bv.dist(D + 10) = n[0] * d * 3; - } - else if(n[0] + n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) - { - bv.dist(11) = bv.dist(D + 11) = n[1] * d * 3; - } - } +struct ComputeBVImpl, Plane> +{ + static void run(const Plane& s, const Transform3& tf, KDOP& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Sphere> +struct ComputeBVImpl, Sphere> { - static void run(const Sphere& s, const Transform3& tf, AABB& bv) - { - const Vector3 v_delta = Vector3::Constant(s.radius); - bv.max_ = tf.translation() + v_delta; - bv.min_ = tf.translation() - v_delta; - } + static void run(const Sphere& s, const Transform3& tf, AABB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, Sphere> +struct ComputeBVImpl, Sphere> { - static void run(const Sphere& s, const Transform3& tf, OBB& bv) - { - bv.To = tf.translation(); - bv.axis.setIdentity(); - bv.extent.setConstant(s.radius); - } + static void run(const Sphere& s, const Transform3& tf, OBB& bv); }; -//============================================================================== template -struct FCL_EXPORT ComputeBVImpl, TriangleP> +struct ComputeBVImpl, TriangleP> { - static void run(const TriangleP& s, const Transform3& tf, AABB& bv) - { - bv = AABB(tf * s.a, tf * s.b, tf * s.c); - } + static void run(const TriangleP& s, const Transform3& tf, AABB& bv); }; //============================================================================== +#ifndef FCL_GEOMETRY_SHAPE_UTILITY_BUILDING extern template -struct ComputeBVImpl, Box>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Box>; //============================================================================== extern template -struct ComputeBVImpl, Box>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Box>; //============================================================================== extern template -struct ComputeBVImpl, Capsule>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Capsule>; //============================================================================== extern template -struct ComputeBVImpl, Capsule>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Capsule>; //============================================================================== extern template -struct ComputeBVImpl, Cone>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Cone>; //============================================================================== extern template -struct ComputeBVImpl, Cone>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Cone>; //============================================================================== extern template -struct ComputeBVImpl, Cylinder>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Cylinder>; //============================================================================== extern template -struct ComputeBVImpl, Cylinder>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Cylinder>; //============================================================================== extern template -struct ComputeBVImpl, Ellipsoid>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Ellipsoid>; //============================================================================== extern template -struct ComputeBVImpl, Ellipsoid>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Ellipsoid>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Halfspace>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Plane>; //============================================================================== extern template -struct ComputeBVImpl, Sphere>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Sphere>; //============================================================================== extern template -struct ComputeBVImpl, Sphere>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, Sphere>; //============================================================================== extern template -struct ComputeBVImpl, TriangleP>; +struct FCL_EXPORT_EXPL_INST_DECL ComputeBVImpl, TriangleP>; +#endif + +//============================================================================== +template +void ComputeBVImpl::run(const Shape& s, const Transform3& tf, BV& bv) +{ + std::vector> convex_bound_vertices = s.getBoundVertices(tf); + fit(convex_bound_vertices.data(), + static_cast(convex_bound_vertices.size()), bv); +} + +//============================================================================== +template +void ComputeBVImpl, Box>::run(const Box& s, const Transform3& tf, AABB& bv) +{ + const Matrix3& R = tf.linear(); + const Vector3& T = tf.translation(); + + S x_range = 0.5 * (fabs(R(0, 0) * s.side[0]) + fabs(R(0, 1) * s.side[1]) + fabs(R(0, 2) * s.side[2])); + S y_range = 0.5 * (fabs(R(1, 0) * s.side[0]) + fabs(R(1, 1) * s.side[1]) + fabs(R(1, 2) * s.side[2])); + S z_range = 0.5 * (fabs(R(2, 0) * s.side[0]) + fabs(R(2, 1) * s.side[1]) + fabs(R(2, 2) * s.side[2])); + + Vector3 v_delta(x_range, y_range, z_range); + bv.max_ = T + v_delta; + bv.min_ = T - v_delta; +} + +//============================================================================== +template +void ComputeBVImpl, Box>::run(const Box& s, const Transform3& tf, OBB& bv) +{ + bv.axis = tf.linear(); + bv.To = tf.translation(); + bv.extent = s.side * (S)0.5; +} + +//============================================================================== +template +void ComputeBVImpl, Capsule>::run(const Capsule& s, const Transform3& tf, AABB& bv) +{ + const Matrix3& R = tf.linear(); + const Vector3& T = tf.translation(); + + S x_range = 0.5 * fabs(R(0, 2) * s.lz) + s.radius; + S y_range = 0.5 * fabs(R(1, 2) * s.lz) + s.radius; + S z_range = 0.5 * fabs(R(2, 2) * s.lz) + s.radius; + + Vector3 v_delta(x_range, y_range, z_range); + bv.max_ = T + v_delta; + bv.min_ = T - v_delta; +} + +//============================================================================== +template +void ComputeBVImpl, Capsule>::run(const Capsule& s, const Transform3& tf, OBB& bv) +{ + bv.axis = tf.linear(); + bv.To = tf.translation(); + bv.extent << s.radius, s.radius, s.lz / 2 + s.radius; +} + +//============================================================================== +template +void ComputeBVImpl, Cone>::run(const Cone& s, const Transform3& tf, AABB& bv) +{ + const Matrix3& R = tf.linear(); + const Vector3& T = tf.translation(); + + S x_range = fabs(R(0, 0) * s.radius) + fabs(R(0, 1) * s.radius) + 0.5 * fabs(R(0, 2) * s.lz); + S y_range = fabs(R(1, 0) * s.radius) + fabs(R(1, 1) * s.radius) + 0.5 * fabs(R(1, 2) * s.lz); + S z_range = fabs(R(2, 0) * s.radius) + fabs(R(2, 1) * s.radius) + 0.5 * fabs(R(2, 2) * s.lz); + + Vector3 v_delta(x_range, y_range, z_range); + bv.max_ = T + v_delta; + bv.min_ = T - v_delta; +} + +//============================================================================== +template +void ComputeBVImpl, Cone>::run(const Cone& s, const Transform3& tf, OBB& bv) +{ + bv.axis = tf.linear(); + bv.To = tf.translation(); + bv.extent << s.radius, s.radius, s.lz / 2; +} + +//============================================================================== +template +void ComputeBVImpl, Convex>::run(const Convex& s, const Transform3& tf, AABB& bv) +{ + const Matrix3& R = tf.linear(); + const Vector3& T = tf.translation(); + + AABB bv_; + for (const auto& vertex : s.getVertices()) + { + Vector3 new_p = R * vertex + T; + bv_ += new_p; + } + + bv = bv_; +} + +//============================================================================== +template +void ComputeBVImpl, Convex>::run(const Convex& s, const Transform3& tf, OBB& bv) +{ + fit(s.getVertices().data(), static_cast(s.getVertices().size()), bv); + + bv.axis = tf.linear(); + bv.To = tf * bv.To; +} + +//============================================================================== +template +void ComputeBVImpl, Cylinder>::run(const Cylinder& s, const Transform3& tf, AABB& bv) +{ + const Matrix3& R = tf.linear(); + const Vector3& T = tf.translation(); + + S x_range = fabs(R(0, 0) * s.radius) + fabs(R(0, 1) * s.radius) + 0.5 * fabs(R(0, 2) * s.lz); + S y_range = fabs(R(1, 0) * s.radius) + fabs(R(1, 1) * s.radius) + 0.5 * fabs(R(1, 2) * s.lz); + S z_range = fabs(R(2, 0) * s.radius) + fabs(R(2, 1) * s.radius) + 0.5 * fabs(R(2, 2) * s.lz); + + Vector3 v_delta(x_range, y_range, z_range); + bv.max_ = T + v_delta; + bv.min_ = T - v_delta; +} + +//============================================================================== +template +void ComputeBVImpl, Cylinder>::run(const Cylinder& s, const Transform3& tf, OBB& bv) +{ + bv.axis = tf.linear(); + bv.To = tf.translation(); + bv.extent << s.radius, s.radius, s.lz / 2; +} + +//============================================================================== +template +void ComputeBVImpl, Ellipsoid>::run(const Ellipsoid& s, const Transform3& tf, AABB& bv) +{ + const Matrix3& R = tf.linear(); + const Vector3& T = tf.translation(); + + S x_range = (fabs(R(0, 0) * s.radii[0]) + fabs(R(0, 1) * s.radii[1]) + fabs(R(0, 2) * s.radii[2])); + S y_range = (fabs(R(1, 0) * s.radii[0]) + fabs(R(1, 1) * s.radii[1]) + fabs(R(1, 2) * s.radii[2])); + S z_range = (fabs(R(2, 0) * s.radii[0]) + fabs(R(2, 1) * s.radii[1]) + fabs(R(2, 2) * s.radii[2])); + + Vector3 v_delta(x_range, y_range, z_range); + bv.max_ = T + v_delta; + bv.min_ = T - v_delta; +} + +//============================================================================== +template +void ComputeBVImpl, Ellipsoid>::run(const Ellipsoid& s, const Transform3& tf, OBB& bv) +{ + bv.axis = tf.linear(); + bv.To = tf.translation(); + bv.extent = s.radii; +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, AABB& bv) +{ + Halfspace new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + AABB bv_; + bv_.min_ = Vector3::Constant(-std::numeric_limits::max()); + bv_.max_ = Vector3::Constant(std::numeric_limits::max()); + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + // normal aligned with x axis + if(n[0] < 0) bv_.min_[0] = -d; + else if(n[0] > 0) bv_.max_[0] = d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + // normal aligned with y axis + if(n[1] < 0) bv_.min_[1] = -d; + else if(n[1] > 0) bv_.max_[1] = d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + // normal aligned with z axis + if(n[2] < 0) bv_.min_[2] = -d; + else if(n[2] > 0) bv_.max_[2] = d; + } + + bv = bv_; +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, OBB& bv) +{ + FCL_UNUSED(s); + FCL_UNUSED(tf); + + /// Half space can only have very rough OBB + bv.axis.setIdentity(); + bv.To.setZero(); + bv.extent.setConstant(std::numeric_limits::max()); +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, RSS& bv) +{ + FCL_UNUSED(s); + FCL_UNUSED(tf); + + /// Half space can only have very rough RSS + bv.axis.setIdentity(); + bv.To.setZero(); + bv.l[0] = bv.l[1] = bv.r = std::numeric_limits::max(); +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, OBBRSS& bv) +{ + computeBV(s, tf, bv.obb); + computeBV(s, tf, bv.rss); +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, kIOS& bv) +{ + bv.num_spheres = 1; + computeBV(s, tf, bv.obb); + bv.spheres[0].o.setZero(); + bv.spheres[0].r = std::numeric_limits::max(); +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, KDOP& bv) +{ + Halfspace new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + const std::size_t D = 8; + for(std::size_t i = 0; i < D; ++i) + bv.dist(i) = -std::numeric_limits::max(); + for(std::size_t i = D; i < 2 * D; ++i) + bv.dist(i) = std::numeric_limits::max(); + + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D) = d; + else bv.dist(0) = -d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(D + 1) = d; + else bv.dist(1) = -d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + if(n[2] > 0) bv.dist(D + 2) = d; + else bv.dist(2) = -d; + } + else if(n[2] == (S)0.0 && n[0] == n[1]) + { + if(n[0] > 0) bv.dist(D + 3) = n[0] * d * 2; + else bv.dist(3) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] == n[2]) + { + if(n[1] > 0) bv.dist(D + 4) = n[0] * d * 2; + else bv.dist(4) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] == n[2]) + { + if(n[1] > 0) bv.dist(D + 5) = n[1] * d * 2; + else bv.dist(5) = n[1] * d * 2; + } + else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 6) = n[0] * d * 2; + else bv.dist(6) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 7) = n[0] * d * 2; + else bv.dist(7) = n[0] * d * 2; + } +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, KDOP& bv) +{ + Halfspace new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + const std::size_t D = 9; + + for(std::size_t i = 0; i < D; ++i) + bv.dist(i) = -std::numeric_limits::max(); + for(std::size_t i = D; i < 2 * D; ++i) + bv.dist(i) = std::numeric_limits::max(); + + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D) = d; + else bv.dist(0) = -d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(D + 1) = d; + else bv.dist(1) = -d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + if(n[2] > 0) bv.dist(D + 2) = d; + else bv.dist(2) = -d; + } + else if(n[2] == (S)0.0 && n[0] == n[1]) + { + if(n[0] > 0) bv.dist(D + 3) = n[0] * d * 2; + else bv.dist(3) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] == n[2]) + { + if(n[1] > 0) bv.dist(D + 4) = n[0] * d * 2; + else bv.dist(4) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] == n[2]) + { + if(n[1] > 0) bv.dist(D + 5) = n[1] * d * 2; + else bv.dist(5) = n[1] * d * 2; + } + else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 6) = n[0] * d * 2; + else bv.dist(6) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 7) = n[0] * d * 2; + else bv.dist(7) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(D + 8) = n[1] * d * 2; + else bv.dist(8) = n[1] * d * 2; + } +} + +//============================================================================== +template +void ComputeBVImpl, Halfspace>::run(const Halfspace& s, const Transform3& tf, KDOP& bv) +{ + Halfspace new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + const std::size_t D = 12; + + for(std::size_t i = 0; i < D; ++i) + bv.dist(i) = -std::numeric_limits::max(); + for(std::size_t i = D; i < 2 * D; ++i) + bv.dist(i) = std::numeric_limits::max(); + + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D) = d; + else bv.dist(0) = -d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(D + 1) = d; + else bv.dist(1) = -d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + if(n[2] > 0) bv.dist(D + 2) = d; + else bv.dist(2) = -d; + } + else if(n[2] == (S)0.0 && n[0] == n[1]) + { + if(n[0] > 0) bv.dist(D + 3) = n[0] * d * 2; + else bv.dist(3) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] == n[2]) + { + if(n[1] > 0) bv.dist(D + 4) = n[0] * d * 2; + else bv.dist(4) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] == n[2]) + { + if(n[1] > 0) bv.dist(D + 5) = n[1] * d * 2; + else bv.dist(5) = n[1] * d * 2; + } + else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 6) = n[0] * d * 2; + else bv.dist(6) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 7) = n[0] * d * 2; + else bv.dist(7) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(D + 8) = n[1] * d * 2; + else bv.dist(8) = n[1] * d * 2; + } + else if(n[0] + n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 9) = n[0] * d * 3; + else bv.dist(9) = n[0] * d * 3; + } + else if(n[0] + n[1] == (S)0.0 && n[1] + n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(D + 10) = n[0] * d * 3; + else bv.dist(10) = n[0] * d * 3; + } + else if(n[0] + n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(D + 11) = n[1] * d * 3; + else bv.dist(11) = n[1] * d * 3; + } +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, AABB& bv) +{ + Plane new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + AABB bv_; + bv_.min_ = Vector3::Constant(-std::numeric_limits::max()); + bv_.max_ = Vector3::Constant(std::numeric_limits::max()); + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + // normal aligned with x axis + if(n[0] < 0) { bv_.min_[0] = bv_.max_[0] = -d; } + else if(n[0] > 0) { bv_.min_[0] = bv_.max_[0] = d; } + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + // normal aligned with y axis + if(n[1] < 0) { bv_.min_[1] = bv_.max_[1] = -d; } + else if(n[1] > 0) { bv_.min_[1] = bv_.max_[1] = d; } + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + // normal aligned with z axis + if(n[2] < 0) { bv_.min_[2] = bv_.max_[2] = -d; } + else if(n[2] > 0) { bv_.min_[2] = bv_.max_[2] = d; } + } + + bv = bv_; +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, OBB& bv) +{ + const Vector3 n = tf.linear() * s.n; + bv.axis = generateCoordinateSystem(n); + + bv.extent << 0, std::numeric_limits::max(), std::numeric_limits::max(); + + Vector3 p = s.n * s.d; + bv.To = tf * p; /// n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, RSS& bv) +{ + const Vector3 n = tf.linear() * s.n; + bv.axis = generateCoordinateSystem(n); + + bv.l[0] = std::numeric_limits::max(); + bv.l[1] = std::numeric_limits::max(); + + bv.r = 0; + + Vector3 p = s.n * s.d; + bv.To = tf * p; +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, OBBRSS& bv) +{ + computeBV(s, tf, bv.obb); + computeBV(s, tf, bv.rss); +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, kIOS& bv) +{ + bv.num_spheres = 1; + computeBV(s, tf, bv.obb); + bv.spheres[0].o.setZero(); + bv.spheres[0].r = std::numeric_limits::max(); +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, KDOP& bv) +{ + Plane new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + const std::size_t D = 8; + + for(std::size_t i = 0; i < D; ++i) + bv.dist(i) = -std::numeric_limits::max(); + for(std::size_t i = D; i < 2 * D; ++i) + bv.dist(i) = std::numeric_limits::max(); + + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(0) = bv.dist(D) = d; + else bv.dist(0) = bv.dist(D) = -d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(1) = bv.dist(D + 1) = d; + else bv.dist(1) = bv.dist(D + 1) = -d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + if(n[2] > 0) bv.dist(2) = bv.dist(D + 2) = d; + else bv.dist(2) = bv.dist(D + 2) = -d; + } + else if(n[2] == (S)0.0 && n[0] == n[1]) + { + bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] == n[2]) + { + bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] == n[2]) + { + bv.dist(6) = bv.dist(D + 5) = n[1] * d * 2; + } + else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; + } +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, KDOP& bv) +{ + Plane new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + const std::size_t D = 9; + + for(std::size_t i = 0; i < D; ++i) + bv.dist(i) = -std::numeric_limits::max(); + for(std::size_t i = D; i < 2 * D; ++i) + bv.dist(i) = std::numeric_limits::max(); + + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(0) = bv.dist(D) = d; + else bv.dist(0) = bv.dist(D) = -d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(1) = bv.dist(D + 1) = d; + else bv.dist(1) = bv.dist(D + 1) = -d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + if(n[2] > 0) bv.dist(2) = bv.dist(D + 2) = d; + else bv.dist(2) = bv.dist(D + 2) = -d; + } + else if(n[2] == (S)0.0 && n[0] == n[1]) + { + bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] == n[2]) + { + bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] == n[2]) + { + bv.dist(5) = bv.dist(D + 5) = n[1] * d * 2; + } + else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) + { + bv.dist(8) = bv.dist(D + 8) = n[1] * d * 2; + } +} + +//============================================================================== +template +void ComputeBVImpl, Plane>::run(const Plane& s, const Transform3& tf, KDOP& bv) +{ + Plane new_s = transform(s, tf); + const Vector3& n = new_s.n; + const S& d = new_s.d; + + const std::size_t D = 12; + + for(std::size_t i = 0; i < D; ++i) + bv.dist(i) = -std::numeric_limits::max(); + for(std::size_t i = D; i < 2 * D; ++i) + bv.dist(i) = std::numeric_limits::max(); + + if(n[1] == (S)0.0 && n[2] == (S)0.0) + { + if(n[0] > 0) bv.dist(0) = bv.dist(D) = d; + else bv.dist(0) = bv.dist(D) = -d; + } + else if(n[0] == (S)0.0 && n[2] == (S)0.0) + { + if(n[1] > 0) bv.dist(1) = bv.dist(D + 1) = d; + else bv.dist(1) = bv.dist(D + 1) = -d; + } + else if(n[0] == (S)0.0 && n[1] == (S)0.0) + { + if(n[2] > 0) bv.dist(2) = bv.dist(D + 2) = d; + else bv.dist(2) = bv.dist(D + 2) = -d; + } + else if(n[2] == (S)0.0 && n[0] == n[1]) + { + bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] == n[2]) + { + bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] == n[2]) + { + bv.dist(5) = bv.dist(D + 5) = n[1] * d * 2; + } + else if(n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; + } + else if(n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; + } + else if(n[0] == (S)0.0 && n[1] + n[2] == (S)0.0) + { + bv.dist(8) = bv.dist(D + 8) = n[1] * d * 2; + } + else if(n[0] + n[2] == (S)0.0 && n[0] + n[1] == (S)0.0) + { + bv.dist(9) = bv.dist(D + 9) = n[0] * d * 3; + } + else if(n[0] + n[1] == (S)0.0 && n[1] + n[2] == (S)0.0) + { + bv.dist(10) = bv.dist(D + 10) = n[0] * d * 3; + } + else if(n[0] + n[1] == (S)0.0 && n[0] + n[2] == (S)0.0) + { + bv.dist(11) = bv.dist(D + 11) = n[1] * d * 3; + } +} + +//============================================================================== +template +void ComputeBVImpl, Sphere>::run(const Sphere& s, const Transform3& tf, AABB& bv) +{ + const Vector3 v_delta = Vector3::Constant(s.radius); + bv.max_ = tf.translation() + v_delta; + bv.min_ = tf.translation() - v_delta; +} + +//============================================================================== +template +void ComputeBVImpl, Sphere>::run(const Sphere& s, const Transform3& tf, OBB& bv) +{ + bv.To = tf.translation(); + bv.axis.setIdentity(); + bv.extent.setConstant(s.radius); +} + +//============================================================================== +template +void ComputeBVImpl, TriangleP>::run(const TriangleP& s, const Transform3& tf, AABB& bv) +{ + bv = AABB(tf * s.a, tf * s.b, tf * s.c); +} //============================================================================== } // namespace detail @@ -1052,7 +1173,6 @@ 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 ec70def9a..fe0bc62fc 100644 --- a/include/fcl/geometry/shape/utility.h +++ b/include/fcl/geometry/shape/utility.h @@ -57,72 +57,55 @@ 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 67380068f..f023acef5 100644 --- a/include/fcl/math/bv/AABB-inl.h +++ b/include/fcl/math/bv/AABB-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_BV_AABB_BUILDING extern template -class FCL_EXPORT AABB; +class FCL_EXPORT_EXPL_INST_DECL AABB; +#endif //============================================================================== template diff --git a/include/fcl/math/bv/AABB.h b/include/fcl/math/bv/AABB.h index f84b737ee..d785a6320 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 FCL_EXPORT AABB +class AABB { public: diff --git a/include/fcl/math/bv/OBB-inl.h b/include/fcl/math/bv/OBB-inl.h index 4d5455f57..0d92ddd3d 100644 --- a/include/fcl/math/bv/OBB-inl.h +++ b/include/fcl/math/bv/OBB-inl.h @@ -46,23 +46,28 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_BV_OBB_BUILDING extern template -class FCL_EXPORT OBB; +class FCL_EXPORT_EXPL_INST_DECL OBB; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void computeVertices(const OBB& b, Vector3 vertices[8]); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL OBB merge_largedist(const OBB& b1, const OBB& b2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL OBB merge_smalldist(const OBB& b1, const OBB& b2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool obbDisjoint( const Matrix3& B, const Vector3& T, @@ -71,10 +76,12 @@ bool obbDisjoint( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool obbDisjoint( const Transform3& tf, const Vector3& a, const Vector3& b); +#endif //============================================================================== template diff --git a/include/fcl/math/bv/OBB.h b/include/fcl/math/bv/OBB.h index 3d7e216ba..c611070ed 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 FCL_EXPORT OBB +class OBB { public: @@ -124,29 +124,24 @@ 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); @@ -155,7 +150,6 @@ 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, @@ -166,7 +160,6 @@ 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 814a66f62..40d1b56d1 100644 --- a/include/fcl/math/bv/OBBRSS-inl.h +++ b/include/fcl/math/bv/OBBRSS-inl.h @@ -44,12 +44,15 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_BV_OBBRSS_BUILDING extern template -class FCL_EXPORT OBBRSS; +class FCL_EXPORT_EXPL_INST_DECL OBBRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL OBBRSS translate(const OBBRSS& bv, const Vector3& t); +#endif //============================================================================== template diff --git a/include/fcl/math/bv/OBBRSS.h b/include/fcl/math/bv/OBBRSS.h index 9f84c1105..4f1d65623 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 FCL_EXPORT OBBRSS +class OBBRSS { public: @@ -108,13 +108,11 @@ 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); @@ -122,7 +120,6 @@ 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, @@ -131,7 +128,6 @@ 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, @@ -141,7 +137,6 @@ 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 2cbc7dd9d..0debf38f3 100644 --- a/include/fcl/math/bv/RSS-inl.h +++ b/include/fcl/math/bv/RSS-inl.h @@ -44,15 +44,18 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_BV_RSS_BUILDING extern template -class FCL_EXPORT RSS; +class FCL_EXPORT_EXPL_INST_DECL RSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void clipToRange(double& val, double a, double b); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void segCoords( double& t, double& u, @@ -64,6 +67,7 @@ void segCoords( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool inVoronoi( double a, double b, @@ -75,6 +79,7 @@ bool inVoronoi( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double rectDistance( const Matrix3& Rab, const Vector3& Tab, @@ -85,6 +90,7 @@ double rectDistance( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double rectDistance( const Transform3& tfab, const double a[2], @@ -94,7 +100,9 @@ double rectDistance( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL RSS translate(const RSS& bv, const Vector3& t); +#endif //============================================================================== template diff --git a/include/fcl/math/bv/RSS.h b/include/fcl/math/bv/RSS.h index 514531c38..4aea7fd79 100644 --- a/include/fcl/math/bv/RSS.h +++ b/include/fcl/math/bv/RSS.h @@ -55,7 +55,7 @@ namespace fcl /// relative orientation between frame T and F and p_FoTo_F (the #To field) is /// the position of T's origin in frame F. template -class FCL_EXPORT RSS +class RSS { public: @@ -153,7 +153,6 @@ 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 @@ -169,7 +168,6 @@ 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); @@ -179,7 +177,6 @@ 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); @@ -188,7 +185,6 @@ 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, @@ -201,7 +197,6 @@ 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], @@ -215,7 +210,6 @@ 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, @@ -227,7 +221,6 @@ 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, @@ -236,7 +229,6 @@ 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 f66026601..23327cbe1 100644 --- a/include/fcl/math/bv/kDOP-inl.h +++ b/include/fcl/math/bv/kDOP-inl.h @@ -46,40 +46,46 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_BV_KDOP_BUILDING extern template -class FCL_EXPORT KDOP; +class FCL_EXPORT_EXPL_INST_DECL KDOP; //============================================================================== extern template -class FCL_EXPORT KDOP; +class FCL_EXPORT_EXPL_INST_DECL KDOP; //============================================================================== extern template -class FCL_EXPORT KDOP; +class FCL_EXPORT_EXPL_INST_DECL KDOP; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void minmax(double a, double b, double& minv, double& maxv); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void minmax(double p, double& minv, double& maxv); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getDistances(const Vector3& p, double* d); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getDistances(const Vector3& p, double* d); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getDistances(const Vector3& p, double* d); +#endif //============================================================================== template -FCL_EXPORT KDOP::KDOP() { static_assert(N == 16 || N == 18 || N == 24, "N should be 16, 18, or 24"); @@ -94,7 +100,6 @@ KDOP::KDOP() //============================================================================== template -FCL_EXPORT KDOP::KDOP(const Vector3& v) { for(std::size_t i = 0; i < 3; ++i) @@ -112,7 +117,6 @@ 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) @@ -131,7 +135,6 @@ 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) @@ -145,7 +148,6 @@ 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) @@ -167,7 +169,6 @@ 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) @@ -187,7 +188,6 @@ 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) @@ -200,7 +200,6 @@ KDOP& KDOP::operator += (const KDOP& other) //============================================================================== template -FCL_EXPORT KDOP KDOP::operator + (const KDOP& other) const { KDOP res(*this); @@ -209,7 +208,6 @@ KDOP KDOP::operator + (const KDOP& other) const //============================================================================== template -FCL_EXPORT S KDOP::width() const { return dist_[N / 2] - dist_[0]; @@ -217,7 +215,6 @@ S KDOP::width() const //============================================================================== template -FCL_EXPORT S KDOP::height() const { return dist_[N / 2 + 1] - dist_[1]; @@ -225,7 +222,6 @@ S KDOP::height() const //============================================================================== template -FCL_EXPORT S KDOP::depth() const { return dist_[N / 2 + 2] - dist_[2]; @@ -233,7 +229,6 @@ S KDOP::depth() const //============================================================================== template -FCL_EXPORT S KDOP::volume() const { return width() * height() * depth(); @@ -241,7 +236,6 @@ S KDOP::volume() const //============================================================================== template -FCL_EXPORT S KDOP::size() const { return width() * width() + height() * height() + depth() * depth(); @@ -249,7 +243,6 @@ 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; @@ -257,7 +250,6 @@ Vector3 KDOP::center() const //============================================================================== template -FCL_EXPORT S KDOP::distance(const KDOP& other, Vector3* P, Vector3* Q) const { FCL_UNUSED(other); @@ -270,7 +262,6 @@ 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]; @@ -278,7 +269,6 @@ S KDOP::dist(std::size_t i) const //============================================================================== template -FCL_EXPORT S& KDOP::dist(std::size_t i) { return dist_[i]; @@ -286,7 +276,6 @@ S& KDOP::dist(std::size_t i) //============================================================================== template -FCL_EXPORT KDOP translate( const KDOP& bv, const Eigen::MatrixBase& t) { @@ -310,7 +299,6 @@ KDOP translate( //============================================================================== template -FCL_EXPORT void minmax(S a, S b, S& minv, S& maxv) { if(a > b) @@ -327,7 +315,6 @@ 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; @@ -346,7 +333,6 @@ struct GetDistancesImpl //============================================================================== template -FCL_EXPORT void getDistances(const Vector3& p, S* d) { GetDistancesImpl::run(p, d); @@ -354,7 +340,7 @@ void getDistances(const Vector3& p, S* d) //============================================================================== template -struct FCL_EXPORT GetDistancesImpl +struct GetDistancesImpl { static void run(const Vector3& p, S* d) { @@ -368,7 +354,7 @@ struct FCL_EXPORT GetDistancesImpl //============================================================================== template -struct FCL_EXPORT GetDistancesImpl +struct GetDistancesImpl { static void run(const Vector3& p, S* d) { @@ -383,7 +369,7 @@ struct FCL_EXPORT GetDistancesImpl //============================================================================== template -struct FCL_EXPORT GetDistancesImpl +struct 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 54b7e9c12..8b312162c 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 FCL_EXPORT KDOP +class KDOP { public: @@ -152,23 +152,19 @@ 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 81a802a8c..68eae5d45 100644 --- a/include/fcl/math/bv/kIOS-inl.h +++ b/include/fcl/math/bv/kIOS-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_BV_KIOS_BUILDING extern template -class FCL_EXPORT kIOS; +class FCL_EXPORT_EXPL_INST_DECL kIOS; +#endif //============================================================================== template diff --git a/include/fcl/math/bv/kIOS.h b/include/fcl/math/bv/kIOS.h index 85f8933af..3cf941778 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 FCL_EXPORT kIOS +class kIOS { /// @brief One sphere in kIOS struct kIOS_Sphere @@ -126,7 +126,6 @@ using kIOSd = kIOS; /// @brief Translate the kIOS BV template -FCL_EXPORT kIOS translate( const kIOS& bv, const Eigen::MatrixBase& t); @@ -134,7 +133,6 @@ kIOS translate( /// and b2 is in identity. /// @todo Not efficient template -FCL_EXPORT bool overlap( const Eigen::MatrixBase& R0, const Eigen::MatrixBase& T0, @@ -144,7 +142,6 @@ bool overlap( /// and b2 is in identity. /// @todo Not efficient template -FCL_EXPORT bool overlap( const Transform3& tf, const kIOS& b1, @@ -153,7 +150,6 @@ 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, @@ -165,7 +161,6 @@ 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 333ec154b..63bf8a9a1 100644 --- a/include/fcl/math/bv/utility-inl.h +++ b/include/fcl/math/bv/utility-inl.h @@ -62,7 +62,56 @@ namespace OBB_fit_functions { //============================================================================== template -FCL_EXPORT +void fit1(const Vector3* ps, OBB& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fit1(const Vector3d* ps, OBB& bv); +#endif + +//============================================================================== +template +void fit2(const Vector3* ps, OBB& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fit2(const Vector3d* ps, OBB& bv); +#endif + +//============================================================================== +template +void fit3(const Vector3* ps, OBB& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fit3(const Vector3d* ps, OBB& bv); +#endif + +//============================================================================== +template +void fit6(const Vector3* ps, OBB& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fit6(const Vector3d* ps, OBB& bv); +#endif + +//============================================================================== +template +void fitn(const Vector3* ps, int n, OBB& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fitn(const Vector3d* ps, int n, OBB& bv); +#endif + +//============================================================================== +template void fit1(const Vector3* const ps, OBB& bv) { bv.To = ps[0]; @@ -72,7 +121,6 @@ void fit1(const Vector3* const ps, OBB& bv) //============================================================================== template -FCL_EXPORT void fit2(const Vector3* const ps, OBB& bv) { const Vector3& p1 = ps[0]; @@ -88,7 +136,6 @@ void fit2(const Vector3* const ps, OBB& bv) //============================================================================== template -FCL_EXPORT void fit3(const Vector3* const ps, OBB& bv) { const Vector3& p1 = ps[0]; @@ -118,7 +165,6 @@ void fit3(const Vector3* const ps, OBB& bv) //============================================================================== template -FCL_EXPORT void fit6(const Vector3* const ps, OBB& bv) { OBB bv1, bv2; @@ -129,7 +175,6 @@ void fit6(const Vector3* const ps, OBB& bv) //============================================================================== template -FCL_EXPORT void fitn(const Vector3* const ps, int n, OBB& bv) { Matrix3 M; @@ -145,36 +190,65 @@ void fitn(const Vector3* const ps, int n, OBB& bv) } //============================================================================== -extern template -void fit1(const Vector3d* const ps, OBB& bv); +} // namespace OBB_fit_functions +//============================================================================== //============================================================================== -extern template -void fit2(const Vector3d* const ps, OBB& bv); +namespace RSS_fit_functions { +//============================================================================== //============================================================================== +template +void fit1(const Vector3* ps, RSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -void fit3(const Vector3d* const ps, OBB& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit1(const Vector3d* ps, RSS& bv); +#endif //============================================================================== +template +void fit2(const Vector3* ps, RSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -void fit6(const Vector3d* const ps, OBB& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit2(const Vector3d* ps, RSS& bv); +#endif //============================================================================== +template +void fit3(const Vector3* ps, RSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -void fitn(const Vector3d* const ps, int n, OBB& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit3(const Vector3d* ps, RSS& bv); +#endif //============================================================================== -} // namespace OBB_fit_functions -//============================================================================== +template +void fit6(const Vector3* ps, RSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fit6(const Vector3d* ps, RSS& bv); +#endif //============================================================================== -namespace RSS_fit_functions { -//============================================================================== +template +void fitn(const Vector3* ps, int n, RSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fitn(const Vector3d* ps, int n, RSS& bv); +#endif //============================================================================== template -FCL_EXPORT void fit1(const Vector3* const ps, RSS& bv) { bv.To = ps[0]; @@ -186,7 +260,6 @@ void fit1(const Vector3* const ps, RSS& bv) //============================================================================== template -FCL_EXPORT void fit2(const Vector3* const ps, RSS& bv) { const Vector3& p1 = ps[0]; @@ -204,7 +277,6 @@ void fit2(const Vector3* const ps, RSS& bv) //============================================================================== template -FCL_EXPORT void fit3(const Vector3* const ps, RSS& bv) { const Vector3& p1 = ps[0]; @@ -232,7 +304,6 @@ void fit3(const Vector3* const ps, RSS& bv) //============================================================================== template -FCL_EXPORT void fit6(const Vector3* const ps, RSS& bv) { RSS bv1, bv2; @@ -243,7 +314,6 @@ void fit6(const Vector3* const ps, RSS& bv) //============================================================================== template -FCL_EXPORT void fitn(const Vector3* const ps, int n, RSS& bv) { Matrix3 M; // row first matrix @@ -259,41 +329,55 @@ void fitn(const Vector3* const ps, int n, RSS& bv) } //============================================================================== -extern template -FCL_EXPORT -void fit1(const Vector3d* const ps, RSS& bv); +} // namespace RSS_fit_functions +//============================================================================== //============================================================================== -extern template -FCL_EXPORT -void fit2(const Vector3d* const ps, RSS& bv); +namespace kIOS_fit_functions { +//============================================================================== //============================================================================== +template +void fit1(const Vector3* ps, kIOS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -FCL_EXPORT -void fit3(const Vector3d* const ps, RSS& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit1(const Vector3d* ps, kIOS& bv); +#endif //============================================================================== +template +void fit2(const Vector3* ps, kIOS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -FCL_EXPORT -void fit6(const Vector3d* const ps, RSS& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit2(const Vector3d* ps, kIOS& bv); +#endif //============================================================================== +template +void fit3(const Vector3* ps, kIOS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -FCL_EXPORT -void fitn(const Vector3d* const ps, int n, RSS& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit3(const Vector3d* ps, kIOS& bv); +#endif //============================================================================== -} // namespace RSS_fit_functions -//============================================================================== +template +void fitn(const Vector3* ps, int n, kIOS& bv); -//============================================================================== -namespace kIOS_fit_functions { -//============================================================================== +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fitn(const Vector3d* ps, int n, kIOS& bv); +#endif //============================================================================== template -FCL_EXPORT void fit1(const Vector3* const ps, kIOS& bv) { bv.num_spheres = 1; @@ -307,7 +391,6 @@ void fit1(const Vector3* const ps, kIOS& bv) //============================================================================== template -FCL_EXPORT void fit2(const Vector3* const ps, kIOS& bv) { bv.num_spheres = 5; @@ -343,7 +426,6 @@ void fit2(const Vector3* const ps, kIOS& bv) //============================================================================== template -FCL_EXPORT void fit3(const Vector3* const ps, kIOS& bv) { bv.num_spheres = 3; @@ -389,7 +471,6 @@ void fit3(const Vector3* const ps, kIOS& bv) //============================================================================== template -FCL_EXPORT void fitn(const Vector3* const ps, int n, kIOS& bv) { Matrix3 M; @@ -456,36 +537,55 @@ void fitn(const Vector3* const ps, int n, kIOS& bv) } //============================================================================== -extern template -FCL_EXPORT -void fit1(const Vector3d* const ps, kIOS& bv); +} // namespace kIOS_fit_functions +//============================================================================== //============================================================================== -extern template -FCL_EXPORT -void fit2(const Vector3d* const ps, kIOS& bv); +namespace OBBRSS_fit_functions { +//============================================================================== //============================================================================== +template +void fit1(const Vector3* ps, OBBRSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -FCL_EXPORT -void fit3(const Vector3d* const ps, kIOS& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit1(const Vector3d* ps, OBBRSS& bv); +#endif //============================================================================== +template +void fit2(const Vector3* ps, OBBRSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -FCL_EXPORT -void fitn(const Vector3d* const ps, int n, kIOS& bv); +FCL_EXPORT_EXPL_INST_DECL +void fit2(const Vector3d* ps, OBBRSS& bv); +#endif //============================================================================== -} // namespace kIOS_fit_functions -//============================================================================== +template +void fit3(const Vector3* ps, OBBRSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fit3(const Vector3d* ps, OBBRSS& bv); +#endif //============================================================================== -namespace OBBRSS_fit_functions { -//============================================================================== +template +void fitn(const Vector3* ps, int n, OBBRSS& bv); + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +void fitn(const Vector3d* ps, int n, OBBRSS& bv); +#endif //============================================================================== template -FCL_EXPORT void fit1(const Vector3* const ps, OBBRSS& bv) { OBB_fit_functions::fit1(ps, bv.obb); @@ -494,7 +594,6 @@ void fit1(const Vector3* const ps, OBBRSS& bv) //============================================================================== template -FCL_EXPORT void fit2(const Vector3* const ps, OBBRSS& bv) { OBB_fit_functions::fit2(ps, bv.obb); @@ -503,7 +602,6 @@ void fit2(const Vector3* const ps, OBBRSS& bv) //============================================================================== template -FCL_EXPORT void fit3(const Vector3* const ps, OBBRSS& bv) { OBB_fit_functions::fit3(ps, bv.obb); @@ -512,7 +610,6 @@ void fit3(const Vector3* const ps, OBBRSS& bv) //============================================================================== template -FCL_EXPORT void fitn(const Vector3* const ps, int n, OBBRSS& bv) { OBB_fit_functions::fitn(ps, n, bv.obb); @@ -520,146 +617,154 @@ void fitn(const Vector3* const ps, int n, OBBRSS& bv) } //============================================================================== -extern template -void fit1(const Vector3d* const ps, OBBRSS& bv); +} // namespace OBBRSS_fit_functions +//============================================================================== //============================================================================== -extern template -void fit2(const Vector3d* const ps, OBBRSS& bv); +template +struct Fitter +{ + static void fit(const Vector3* ps, int n, BV& bv); +}; //============================================================================== +template +struct Fitter> +{ + static void fit(const Vector3* ps, int n, OBB& bv); +}; + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -void fit3(const Vector3d* const ps, OBBRSS& bv); +struct FCL_EXPORT_EXPL_INST_DECL Fitter>; +#endif //============================================================================== +template +struct Fitter> +{ + static void fit(const Vector3* ps, int n, RSS& bv); +}; + +#ifndef FCL_MATH_BV_UTILITY_BUILDING extern template -void fitn(const Vector3d* const ps, int n, OBBRSS& bv); +struct FCL_EXPORT_EXPL_INST_DECL Fitter>; +#endif //============================================================================== -} // namespace OBBRSS_fit_functions +template +struct Fitter> +{ + static void fit(const Vector3* ps, int n, kIOS& bv); +}; + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +struct FCL_EXPORT_EXPL_INST_DECL Fitter>; +#endif + //============================================================================== +template +struct Fitter> +{ + static void fit(const Vector3* ps, int n, OBBRSS& bv); +}; + +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +struct FCL_EXPORT_EXPL_INST_DECL Fitter>; +#endif //============================================================================== template -struct FCL_EXPORT Fitter +void Fitter::fit(const Vector3* const ps, int n, BV& bv) { - static void fit(const Vector3* const ps, int n, BV& bv) - { - for(int i = 0; i < n; ++i) - bv += ps[i]; - } -}; + for(int i = 0; i < n; ++i) + bv += ps[i]; +} //============================================================================== template -struct FCL_EXPORT Fitter> +void Fitter>::fit(const Vector3* const ps, int n, OBB& bv) { - static void fit(const Vector3* const ps, int n, OBB& bv) + switch(n) { - switch(n) - { - case 1: - OBB_fit_functions::fit1(ps, bv); - break; - case 2: - OBB_fit_functions::fit2(ps, bv); - break; - case 3: - OBB_fit_functions::fit3(ps, bv); - break; - case 6: - OBB_fit_functions::fit6(ps, bv); - break; - default: - OBB_fit_functions::fitn(ps, n, bv); - } + case 1: + OBB_fit_functions::fit1(ps, bv); + break; + case 2: + OBB_fit_functions::fit2(ps, bv); + break; + case 3: + OBB_fit_functions::fit3(ps, bv); + break; + case 6: + OBB_fit_functions::fit6(ps, bv); + break; + default: + OBB_fit_functions::fitn(ps, n, bv); } -}; +} //============================================================================== template -struct FCL_EXPORT Fitter> +void Fitter>::fit(const Vector3* const ps, int n, RSS& bv) { - static void fit(const Vector3* const ps, int n, RSS& bv) + switch(n) { - switch(n) - { - case 1: - RSS_fit_functions::fit1(ps, bv); - break; - case 2: - RSS_fit_functions::fit2(ps, bv); - break; - case 3: - RSS_fit_functions::fit3(ps, bv); - break; - default: - RSS_fit_functions::fitn(ps, n, bv); - } + case 1: + RSS_fit_functions::fit1(ps, bv); + break; + case 2: + RSS_fit_functions::fit2(ps, bv); + break; + case 3: + RSS_fit_functions::fit3(ps, bv); + break; + default: + RSS_fit_functions::fitn(ps, n, bv); } -}; +} //============================================================================== template -struct FCL_EXPORT Fitter> +void Fitter>::fit(const Vector3* const ps, int n, kIOS& bv) { - static void fit(const Vector3* const ps, int n, kIOS& bv) + switch(n) { - switch(n) - { - case 1: - kIOS_fit_functions::fit1(ps, bv); - break; - case 2: - kIOS_fit_functions::fit2(ps, bv); - break; - case 3: - kIOS_fit_functions::fit3(ps, bv); - break; - default: - kIOS_fit_functions::fitn(ps, n, bv); - } + case 1: + kIOS_fit_functions::fit1(ps, bv); + break; + case 2: + kIOS_fit_functions::fit2(ps, bv); + break; + case 3: + kIOS_fit_functions::fit3(ps, bv); + break; + default: + kIOS_fit_functions::fitn(ps, n, bv); } -}; +} //============================================================================== template -struct FCL_EXPORT Fitter> +void Fitter>::fit(const Vector3* const ps, int n, OBBRSS& bv) { - static void fit(const Vector3* const ps, int n, OBBRSS& bv) + switch(n) { - switch(n) - { - case 1: - OBBRSS_fit_functions::fit1(ps, bv); - break; - case 2: - OBBRSS_fit_functions::fit2(ps, bv); - break; - case 3: - OBBRSS_fit_functions::fit3(ps, bv); - break; - default: - OBBRSS_fit_functions::fitn(ps, n, bv); - } + case 1: + OBBRSS_fit_functions::fit1(ps, bv); + break; + case 2: + OBBRSS_fit_functions::fit2(ps, bv); + break; + case 3: + OBBRSS_fit_functions::fit3(ps, bv); + break; + default: + OBBRSS_fit_functions::fitn(ps, n, bv); } -}; - -//============================================================================== -extern template -struct Fitter>; - -//============================================================================== -extern template -struct Fitter>; - -//============================================================================== -extern template -struct Fitter>; - -//============================================================================== -extern template -struct Fitter>; +} //============================================================================== } // namespace detail @@ -667,7 +772,6 @@ struct Fitter>; //============================================================================== template -FCL_EXPORT void fit(const Vector3* const ps, int n, BV& bv) { detail::Fitter::fit(ps, n, bv); @@ -677,215 +781,201 @@ void fit(const Vector3* const ps, int n, BV& bv) 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 FCL_EXPORT ConvertBVImpl +class ConvertBVImpl { private: - static void run(const BV1& bv1, const Transform3& tf1, BV2& bv2) - { - FCL_UNUSED(bv1); - FCL_UNUSED(tf1); - FCL_UNUSED(bv2); - - // should only use the specialized version, so it is private. - } + static void run(const BV1& bv1, const Transform3& tf1, BV2& bv2); }; //============================================================================== -/// @brief Convert from AABB to AABB, not very tight but is fast. -template -class FCL_EXPORT ConvertBVImpl, AABB> +template +class ConvertBVImpl> { public: - static void run(const AABB& bv1, const Transform3& tf1, AABB& bv2) - { - const Vector3 center = bv1.center(); - S r = (bv1.max_ - bv1.min_).norm() * 0.5; - Vector3 center2 = tf1 * center; - Vector3 delta(r, r, r); - bv2.min_ = center2 - delta; - bv2.max_ = center2 + delta; - } + static void run(const BV1& bv1, const Transform3& tf1, AABB& bv2); }; //============================================================================== +/// @brief Convert from AABB to AABB, not very tight but is fast. template -class FCL_EXPORT ConvertBVImpl, OBB> +class ConvertBVImpl, AABB> { public: - static void run(const AABB& bv1, const Transform3& tf1, OBB& bv2) - { - /* - bv2.To = tf1 * bv1.center()); - - /// Sort the AABB edges so that AABB extents are ordered. - S d[3] = {bv1.width(), bv1.height(), bv1.depth() }; - std::size_t id[3] = {0, 1, 2}; + static void run(const AABB& bv1, const Transform3& tf1, AABB& bv2); +}; - for(std::size_t i = 1; i < 3; ++i) - { - for(std::size_t j = i; j > 0; --j) - { - if(d[j] > d[j-1]) - { - { - S tmp = d[j]; - d[j] = d[j-1]; - d[j-1] = tmp; - } - { - std::size_t tmp = id[j]; - id[j] = id[j-1]; - id[j-1] = tmp; - } - } - } - } +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, AABB>; +#endif - Vector3 extent = (bv1.max_ - bv1.min_) * 0.5; - bv2.extent = Vector3(extent[id[0]], extent[id[1]], extent[id[2]]); - const Matrix3& R = tf1.linear(); - bool left_hand = (id[0] == (id[1] + 1) % 3); - bv2.axis[0] = left_hand ? -R.col(id[0]) : R.col(id[0]); - bv2.axis[1] = R.col(id[1]); - bv2.axis[2] = R.col(id[2]); - */ - - bv2.To.noalias() = tf1 * bv1.center(); - bv2.extent.noalias() = (bv1.max_ - bv1.min_) * 0.5; - bv2.axis = tf1.linear(); - } +//============================================================================== +template +class ConvertBVImpl> +{ +public: + static void run(const BV1& bv1, const Transform3& tf1, OBB& bv2); }; //============================================================================== template -class FCL_EXPORT ConvertBVImpl, OBB> +class ConvertBVImpl, OBB> { public: - static void run(const OBB& bv1, const Transform3& tf1, OBB& bv2) - { - bv2.extent = bv1.extent; - bv2.To.noalias() = tf1 * bv1.To; - bv2.axis.noalias() = tf1.linear() * bv1.axis; - } + static void run(const AABB& bv1, const Transform3& tf1, OBB& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, OBB>; +#endif + //============================================================================== template -class FCL_EXPORT ConvertBVImpl, OBB> +class ConvertBVImpl, OBB> { public: - static void run(const OBBRSS& bv1, const Transform3& tf1, OBB& bv2) - { - ConvertBVImpl, OBB>::run(bv1.obb, tf1, bv2); - } + static void run(const OBB& bv1, const Transform3& tf1, OBB& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, OBB>; +#endif + //============================================================================== template -class FCL_EXPORT ConvertBVImpl, OBB> +class ConvertBVImpl, OBB> { public: - static void run(const RSS& bv1, const Transform3& tf1, OBB& bv2) - { - bv2.extent << bv1.l[0] * 0.5 + bv1.r, bv1.l[1] * 0.5 + bv1.r, bv1.r; - bv2.To.noalias() = tf1 * bv1.center(); - bv2.axis.noalias() = tf1.linear() * bv1.axis; - } + static void run(const OBBRSS& bv1, const Transform3& tf1, OBB& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, OBB>; +#endif + //============================================================================== -template -class FCL_EXPORT ConvertBVImpl> +template +class ConvertBVImpl, OBB> { public: - static void run(const BV1& bv1, const Transform3& tf1, AABB& bv2) - { - const Vector3 center = bv1.center(); - S r = Vector3(bv1.width(), bv1.height(), bv1.depth()).norm() * 0.5; - Vector3 delta(r, r, r); - Vector3 center2 = tf1 * center; - bv2.min_ = center2 - delta; - bv2.max_ = center2 + delta; - } + static void run(const RSS& bv1, const Transform3& tf1, OBB& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, OBB>; +#endif + //============================================================================== -template -class FCL_EXPORT ConvertBVImpl> +template +class ConvertBVImpl, RSS> { public: - static void run(const BV1& bv1, const Transform3& tf1, OBB& bv2) - { - AABB bv; - ConvertBVImpl>::run(bv1, Transform3::Identity(), bv); - ConvertBVImpl, OBB>::run(bv, tf1, bv2); - } + static void run(const OBB& bv1, const Transform3& tf1, RSS& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, RSS>; +#endif + //============================================================================== template -class FCL_EXPORT ConvertBVImpl, RSS> +class ConvertBVImpl, RSS> { public: - static void run(const OBB& bv1, const Transform3& tf1, RSS& bv2) - { - // OBB's rotation matrix in axis is required to be lined up with the - // x-axis along the longest edge, the y-axis on the next longest edge - // and the z-axis on the shortest edge. RSS requires the longest edge - // of the rectangle to be the x-axis and the next longest the y-axis. - // This maps perfectly from OBB to RSS so simply transform the rotation - // axis of the OBB into the RSS. - bv2.axis.noalias() = tf1.linear() * bv1.axis; - - // Set longest rectangle side for RSS to longest dimension of OBB. - bv2.l[0] = 2 * (bv1.extent[0]); - // Set shortest rectangle side for RSS to next-longest dimension of OBB. - bv2.l[1] = 2 * (bv1.extent[1]); - // Set radius for RSS to the smallest dimension of OBB. - bv2.r = bv1.extent[2]; - - // OBB's To is at its center while RSS's To is at a corner. - bv2.setToFromCenter(tf1 * bv1.center()); - } + static void run(const RSS& bv1, const Transform3& tf1, RSS& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, RSS>; +#endif + //============================================================================== template -class FCL_EXPORT ConvertBVImpl, RSS> +class ConvertBVImpl, RSS> { public: - static void run(const RSS& bv1, const Transform3& tf1, RSS& bv2) - { - bv2.To.noalias() = tf1 * bv1.To; - bv2.axis.noalias() = tf1.linear() * bv1.axis; - - bv2.r = bv1.r; - bv2.l[0] = bv1.l[0]; - bv2.l[1] = bv1.l[1]; - } + static void run(const OBBRSS& bv1, const Transform3& tf1, RSS& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, RSS>; +#endif + //============================================================================== template -class FCL_EXPORT ConvertBVImpl, RSS> +class ConvertBVImpl, RSS> { public: - static void run(const OBBRSS& bv1, const Transform3& tf1, RSS& bv2) - { - ConvertBVImpl, RSS>::run(bv1.rss, tf1, bv2); - } + static void run(const AABB& bv1, const Transform3& tf1, RSS& bv2); }; +#ifndef FCL_MATH_BV_UTILITY_BUILDING +extern template +class FCL_EXPORT_EXPL_INST_DECL ConvertBVImpl, RSS>; +#endif + +//============================================================================== +template +void ConvertBVImpl::run(const BV1& bv1, const Transform3& tf1, BV2& bv2) +{ + FCL_UNUSED(bv1); + FCL_UNUSED(tf1); + FCL_UNUSED(bv2); + + // should only use the specialized version, so it is private. +} + +//============================================================================== +template +void ConvertBVImpl>::run(const BV1& bv1, const Transform3& tf1, AABB& bv2) +{ + const Vector3 center = bv1.center(); + S r = Vector3(bv1.width(), bv1.height(), bv1.depth()).norm() * 0.5; + Vector3 delta(r, r, r); + Vector3 center2 = tf1 * center; + bv2.min_ = center2 - delta; + bv2.max_ = center2 + delta; +} + //============================================================================== template -class FCL_EXPORT ConvertBVImpl, RSS> +void ConvertBVImpl, AABB>::run(const AABB& bv1, const Transform3& tf1, AABB& bv2) { -public: - static void run(const AABB& bv1, const Transform3& tf1, RSS& bv2) - { + const Vector3 center = bv1.center(); + S r = (bv1.max_ - bv1.min_).norm() * 0.5; + Vector3 center2 = tf1 * center; + Vector3 delta(r, r, r); + bv2.min_ = center2 - delta; + bv2.max_ = center2 + delta; +} + +//============================================================================== +template +void ConvertBVImpl>::run(const BV1& bv1, const Transform3& tf1, OBB& bv2) +{ + AABB bv; + ConvertBVImpl>::run(bv1, Transform3::Identity(), bv); + ConvertBVImpl, OBB>::run(bv, tf1, bv2); +} + +//============================================================================== +template +void ConvertBVImpl, OBB>::run(const AABB& bv1, const Transform3& tf1, OBB& bv2) +{ + /* + bv2.To = tf1 * bv1.center()); + /// Sort the AABB edges so that AABB extents are ordered. S d[3] = {bv1.width(), bv1.height(), bv1.depth() }; std::size_t id[3] = {0, 1, 2}; @@ -911,57 +1001,129 @@ class FCL_EXPORT ConvertBVImpl, RSS> } Vector3 extent = (bv1.max_ - bv1.min_) * 0.5; - bv2.r = extent[id[2]]; - bv2.l[0] = (extent[id[0]]) * 2; - bv2.l[1] = (extent[id[1]]) * 2; - + bv2.extent = Vector3(extent[id[0]], extent[id[1]], extent[id[2]]); const Matrix3& R = tf1.linear(); bool left_hand = (id[0] == (id[1] + 1) % 3); - if (left_hand) - bv2.axis.col(0) = -R.col(id[0]); - else - bv2.axis.col(0) = R.col(id[0]); - bv2.axis.col(1) = R.col(id[1]); - bv2.axis.col(2) = R.col(id[2]); - bv2.setToFromCenter(tf1 * bv1.center()); - } -}; + bv2.axis[0] = left_hand ? -R.col(id[0]) : R.col(id[0]); + bv2.axis[1] = R.col(id[1]); + bv2.axis[2] = R.col(id[2]); + */ + + bv2.To.noalias() = tf1 * bv1.center(); + bv2.extent.noalias() = (bv1.max_ - bv1.min_) * 0.5; + bv2.axis = tf1.linear(); +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, AABB>; +template +void ConvertBVImpl, OBB>::run(const OBB& bv1, const Transform3& tf1, OBB& bv2) +{ + bv2.extent = bv1.extent; + bv2.To.noalias() = tf1 * bv1.To; + bv2.axis.noalias() = tf1.linear() * bv1.axis; +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, OBB>; +template +void ConvertBVImpl, OBB>::run(const OBBRSS& bv1, const Transform3& tf1, OBB& bv2) +{ + ConvertBVImpl, OBB>::run(bv1.obb, tf1, bv2); +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, OBB>; +template +void ConvertBVImpl, OBB>::run(const RSS& bv1, const Transform3& tf1, OBB& bv2) +{ + bv2.extent << bv1.l[0] * 0.5 + bv1.r, bv1.l[1] * 0.5 + bv1.r, bv1.r; + bv2.To.noalias() = tf1 * bv1.center(); + bv2.axis.noalias() = tf1.linear() * bv1.axis; +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, OBB>; +template +void ConvertBVImpl, RSS>::run(const OBB& bv1, const Transform3& tf1, RSS& bv2) +{ + // OBB's rotation matrix in axis is required to be lined up with the + // x-axis along the longest edge, the y-axis on the next longest edge + // and the z-axis on the shortest edge. RSS requires the longest edge + // of the rectangle to be the x-axis and the next longest the y-axis. + // This maps perfectly from OBB to RSS so simply transform the rotation + // axis of the OBB into the RSS. + bv2.axis.noalias() = tf1.linear() * bv1.axis; + + // Set longest rectangle side for RSS to longest dimension of OBB. + bv2.l[0] = 2 * (bv1.extent[0]); + // Set shortest rectangle side for RSS to next-longest dimension of OBB. + bv2.l[1] = 2 * (bv1.extent[1]); + // Set radius for RSS to the smallest dimension of OBB. + bv2.r = bv1.extent[2]; + + // OBB's To is at its center while RSS's To is at a corner. + bv2.setToFromCenter(tf1 * bv1.center()); +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, OBB>; +template +void ConvertBVImpl, RSS>::run(const RSS& bv1, const Transform3& tf1, RSS& bv2) +{ + bv2.To.noalias() = tf1 * bv1.To; + bv2.axis.noalias() = tf1.linear() * bv1.axis; -//============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, RSS>; + bv2.r = bv1.r; + bv2.l[0] = bv1.l[0]; + bv2.l[1] = bv1.l[1]; +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, RSS>; +template +void ConvertBVImpl, RSS>::run(const OBBRSS& bv1, const Transform3& tf1, RSS& bv2) +{ + ConvertBVImpl, RSS>::run(bv1.rss, tf1, bv2); +} //============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, RSS>; +template +void ConvertBVImpl, RSS>::run(const AABB& bv1, const Transform3& tf1, RSS& bv2) +{ + /// Sort the AABB edges so that AABB extents are ordered. + S d[3] = {bv1.width(), bv1.height(), bv1.depth() }; + std::size_t id[3] = {0, 1, 2}; -//============================================================================== -extern template -class FCL_EXPORT ConvertBVImpl, RSS>; + for(std::size_t i = 1; i < 3; ++i) + { + for(std::size_t j = i; j > 0; --j) + { + if(d[j] > d[j-1]) + { + { + S tmp = d[j]; + d[j] = d[j-1]; + d[j-1] = tmp; + } + { + std::size_t tmp = id[j]; + id[j] = id[j-1]; + id[j-1] = tmp; + } + } + } + } + + Vector3 extent = (bv1.max_ - bv1.min_) * 0.5; + bv2.r = extent[id[2]]; + bv2.l[0] = (extent[id[0]]) * 2; + bv2.l[1] = (extent[id[1]]) * 2; + + const Matrix3& R = tf1.linear(); + bool left_hand = (id[0] == (id[1] + 1) % 3); + if (left_hand) + bv2.axis.col(0) = -R.col(id[0]); + else + bv2.axis.col(0) = R.col(id[0]); + bv2.axis.col(1) = R.col(id[1]); + bv2.axis.col(2) = R.col(id[2]); + bv2.setToFromCenter(tf1 * bv1.center()); +} //============================================================================== } // namespace detail @@ -969,7 +1131,6 @@ class FCL_EXPORT 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 2cea40cad..c10ffde76 100644 --- a/include/fcl/math/bv/utility.h +++ b/include/fcl/math/bv/utility.h @@ -46,13 +46,11 @@ namespace fcl /// @brief Compute a bounding volume that fits a set of n points. template -FCL_EXPORT void fit(const Vector3* const 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 ba24176af..d94dbc7d3 100644 --- a/include/fcl/math/constants.h +++ b/include/fcl/math/constants.h @@ -126,7 +126,7 @@ struct ScalarTrait { /// /// \tparam S The scalar type for which constant values will be retrieved. template -struct FCL_EXPORT constants +struct constants { typedef typename detail::ScalarTrait::type Real; diff --git a/include/fcl/math/detail/polysolver-inl.h b/include/fcl/math/detail/polysolver-inl.h index c2c538cce..985bb2fef 100644 --- a/include/fcl/math/detail/polysolver-inl.h +++ b/include/fcl/math/detail/polysolver-inl.h @@ -35,8 +35,8 @@ /** @author Jia Pan */ -#ifndef FCL_NARROWPHASE_DETAIL_POLYSOLVER_INL_H -#define FCL_NARROWPHASE_DETAIL_POLYSOLVER_INL_H +#ifndef FCL_MATH_DETAIL_POLYSOLVER_INL_H +#define FCL_MATH_DETAIL_POLYSOLVER_INL_H #include "fcl/math/detail/polysolver.h" @@ -49,8 +49,10 @@ namespace fcl namespace detail { //============================================================================== +#ifndef FCL_MATH_DETAIL_POLYSOLVER_BUILDING extern template -class FCL_EXPORT PolySolver; +class FCL_EXPORT_EXPL_INST_DECL PolySolver; +#endif //============================================================================== template diff --git a/include/fcl/math/detail/polysolver.h b/include/fcl/math/detail/polysolver.h index 52808a9d7..8d86b5575 100644 --- a/include/fcl/math/detail/polysolver.h +++ b/include/fcl/math/detail/polysolver.h @@ -35,8 +35,8 @@ /** @author Jia Pan */ -#ifndef FCL_NARROWPHASE_DETAIL_POLYSOLVER_H -#define FCL_NARROWPHASE_DETAIL_POLYSOLVER_H +#ifndef FCL_MATH_DETAIL_POLYSOLVER_H +#define FCL_MATH_DETAIL_POLYSOLVER_H #include "fcl/export.h" @@ -47,7 +47,7 @@ namespace detail { /// @brief A class solves polynomial degree (1,2,3) equations template -class FCL_EXPORT PolySolver +class 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 abe4df6f7..0f9ac1650 100644 --- a/include/fcl/math/detail/project-inl.h +++ b/include/fcl/math/detail/project-inl.h @@ -35,8 +35,8 @@ /** @author Jia Pan */ -#ifndef FCL_NARROWPHASE_DETAIL_PROJECT_INL_H -#define FCL_NARROWPHASE_DETAIL_PROJECT_INL_H +#ifndef FCL_MATH_DETAIL_PROJECT_INL_H +#define FCL_MATH_DETAIL_PROJECT_INL_H #include "fcl/math/detail/project.h" @@ -47,8 +47,10 @@ namespace detail { //============================================================================== +#ifndef FCL_MATH_DETAIL_PROJECT_BUILDING extern template -class FCL_EXPORT Project; +class FCL_EXPORT_EXPL_INST_DECL Project; +#endif //============================================================================== template diff --git a/include/fcl/math/detail/project.h b/include/fcl/math/detail/project.h index 39311f2b9..848a47fc9 100644 --- a/include/fcl/math/detail/project.h +++ b/include/fcl/math/detail/project.h @@ -35,8 +35,8 @@ /** @author Jia Pan */ -#ifndef FCL_NARROWPHASE_DETAIL_PROJECT_H -#define FCL_NARROWPHASE_DETAIL_PROJECT_H +#ifndef FCL_MATH_DETAIL_PROJECT_H +#define FCL_MATH_DETAIL_PROJECT_H #include "fcl/common/types.h" #include "fcl/math/geometry.h" @@ -49,7 +49,7 @@ namespace detail /// @brief Project functions template -class FCL_EXPORT Project +class Project { public: struct ProjectResult diff --git a/include/fcl/math/geometry-inl.h b/include/fcl/math/geometry-inl.h index a9d3dc851..9b605333d 100644 --- a/include/fcl/math/geometry-inl.h +++ b/include/fcl/math/geometry-inl.h @@ -35,8 +35,8 @@ /** @author Jia Pan */ -#ifndef FCL_BV_DETAIL_UTILITY_INL_H -#define FCL_BV_DETAIL_UTILITY_INL_H +#ifndef FCL_MATH_GEOMETRY_INL_H +#define FCL_MATH_GEOMETRY_INL_H #include "fcl/math/geometry.h" #include "fcl/math/constants.h" @@ -44,38 +44,47 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_GEOMETRY_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL void normalize(Vector3d& v, bool* signal); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void hat(Matrix3d& mat, const Vector3d& vec); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void eigen(const Matrix3d& m, Vector3d& dout, Matrix3d& vout); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void eigen_old(const Matrix3d& m, Vector3d& dout, Matrix3d& vout); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void axisFromEigen( const Matrix3d& eigenV, const Vector3d& eigenS, Matrix3d& axis); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void axisFromEigen(const Matrix3d& eigenV, const Vector3d& eigenS, Transform3d& tf); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL Matrix3d generateCoordinateSystem(const Vector3d& x_axis); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getRadiusAndOriginAndRectangleSize( const Vector3d* const ps, const Vector3d* const ps2, @@ -89,6 +98,7 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getRadiusAndOriginAndRectangleSize( const Vector3d* const ps, const Vector3d* const ps2, @@ -101,6 +111,7 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void circumCircleComputation( const Vector3d& a, const Vector3d& b, @@ -110,6 +121,7 @@ void circumCircleComputation( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double maximumDistance( const Vector3d* const ps, const Vector3d* const ps2, @@ -120,6 +132,7 @@ double maximumDistance( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getExtentAndCenter( const Vector3d* const ps, const Vector3d* const ps2, @@ -132,12 +145,14 @@ void getExtentAndCenter( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getCovariance( const Vector3d* const ps, const Vector3d* const ps2, Triangle* ts, unsigned int* indices, int n, Matrix3d& M); +#endif //============================================================================== namespace detail { @@ -145,7 +160,6 @@ namespace detail { //============================================================================== template -FCL_EXPORT S maximumDistance_mesh( const Vector3* const ps, const Vector3* const ps2, @@ -190,7 +204,6 @@ S maximumDistance_mesh( //============================================================================== template -FCL_EXPORT S maximumDistance_pointcloud( const Vector3* const ps, const Vector3* const ps2, @@ -225,7 +238,6 @@ 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( const Vector3* const ps, const Vector3* const ps2, @@ -290,7 +302,6 @@ 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( const Vector3* const ps, const Vector3* const ps2, @@ -362,7 +373,9 @@ void getExtentAndCenter_mesh( } //============================================================================== +#ifndef FCL_MATH_GEOMETRY_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL double maximumDistance_mesh( const Vector3d* const ps, const Vector3d* const ps2, @@ -373,6 +386,7 @@ double maximumDistance_mesh( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double maximumDistance_pointcloud( const Vector3d* const ps, const Vector3d* const ps2, @@ -382,6 +396,7 @@ double maximumDistance_pointcloud( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getExtentAndCenter_pointcloud( const Vector3d* const ps, const Vector3d* const ps2, @@ -393,6 +408,7 @@ void getExtentAndCenter_pointcloud( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void getExtentAndCenter_mesh( const Vector3d* const ps, const Vector3d* const ps2, @@ -402,6 +418,7 @@ void getExtentAndCenter_mesh( const Matrix3d& axis, Vector3d& center, Vector3d& extent); +#endif //============================================================================== } // namespace detail @@ -409,7 +426,6 @@ void getExtentAndCenter_mesh( //============================================================================== template -FCL_EXPORT void normalize(Vector3& v, bool* signal) { S sqr_length = v.squaredNorm(); @@ -427,7 +443,6 @@ 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) @@ -437,7 +452,6 @@ typename Derived::RealScalar triple(const Eigen::MatrixBase& x, //============================================================================== template -FCL_EXPORT VectorN combine( const VectorN& v1, const VectorN& v2) { @@ -449,7 +463,6 @@ 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; @@ -457,7 +470,6 @@ 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. @@ -473,7 +485,6 @@ 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); @@ -563,7 +574,6 @@ void eigen_old(const Matrix3& m, Vector3& dout, Matrix3& vout) //============================================================================== template -FCL_EXPORT void axisFromEigen(const Matrix3& eigenV, const Vector3& eigenS, Matrix3& axis) @@ -603,7 +613,6 @@ void axisFromEigen(const Matrix3& eigenV, //============================================================================== template -FCL_EXPORT void axisFromEigen(const Matrix3& eigenV, const Vector3& eigenS, Transform3& tf) @@ -643,7 +652,6 @@ void axisFromEigen(const Matrix3& eigenV, //============================================================================== template -FCL_EXPORT Matrix3 generateCoordinateSystem(const Vector3& x_axis) { Matrix3 axis; @@ -655,7 +663,6 @@ Matrix3 generateCoordinateSystem(const Vector3& x_axis) //============================================================================== template -FCL_EXPORT void relativeTransform( const Eigen::MatrixBase& R1, const Eigen::MatrixBase& t1, const Eigen::MatrixBase& R2, const Eigen::MatrixBase& t2, @@ -687,7 +694,6 @@ void relativeTransform( //============================================================================== template -FCL_EXPORT void relativeTransform( const Transform3& T1, const Transform3& T2, @@ -709,7 +715,6 @@ void relativeTransform( //============================================================================== template -FCL_EXPORT void getRadiusAndOriginAndRectangleSize( const Vector3* const ps, const Vector3* const ps2, @@ -992,7 +997,6 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== template -FCL_EXPORT void getRadiusAndOriginAndRectangleSize( const Vector3* const ps, const Vector3* const ps2, @@ -1274,7 +1278,6 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== template -FCL_EXPORT void circumCircleComputation( const Vector3& a, const Vector3& b, @@ -1299,7 +1302,6 @@ void circumCircleComputation( //============================================================================== template -FCL_EXPORT S maximumDistance( const Vector3* const ps, const Vector3* const ps2, @@ -1316,7 +1318,6 @@ S maximumDistance( //============================================================================== template -FCL_EXPORT void getExtentAndCenter( const Vector3* const ps, const Vector3* const ps2, @@ -1335,7 +1336,6 @@ void getExtentAndCenter( //============================================================================== template -FCL_EXPORT void getCovariance( const Vector3* const ps, const Vector3* const ps2, diff --git a/include/fcl/math/geometry.h b/include/fcl/math/geometry.h index 90c2a5a14..58b1bf8a0 100644 --- a/include/fcl/math/geometry.h +++ b/include/fcl/math/geometry.h @@ -49,44 +49,36 @@ 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 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); @@ -102,18 +94,15 @@ void axisFromEigen(const Matrix3& eigenV, /// orthogonal to each other. Otherwise, the orientation of the y-axis /// and z-axis to the x-axis is arbitrary. template -FCL_EXPORT Matrix3 generateCoordinateSystem(const Vector3& x_axis); 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, @@ -122,7 +111,6 @@ void relativeTransform( /// @brief Compute the RSS bounding volume parameters: radius, rectangle size /// and the origin, given the BV axises. template -FCL_EXPORT void getRadiusAndOriginAndRectangleSize( const Vector3* const ps, const Vector3* const ps2, @@ -137,7 +125,6 @@ void getRadiusAndOriginAndRectangleSize( /// @brief Compute the RSS bounding volume parameters: radius, rectangle size /// and the origin, given the BV axises. template -FCL_EXPORT void getRadiusAndOriginAndRectangleSize( const Vector3* const ps, const Vector3* const ps2, @@ -150,7 +137,6 @@ void getRadiusAndOriginAndRectangleSize( /// @brief Compute the center and radius for a triangle's circumcircle template -FCL_EXPORT void circumCircleComputation( const Vector3& a, const Vector3& b, @@ -160,7 +146,6 @@ void circumCircleComputation( /// @brief Compute the maximum distance from a given center point to a point cloud template -FCL_EXPORT S maximumDistance( const Vector3* const ps, const Vector3* const ps2, @@ -172,7 +157,6 @@ 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( const Vector3* const ps, const Vector3* const ps2, @@ -186,7 +170,6 @@ 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( const Vector3* const ps, const Vector3* const ps2, @@ -200,7 +183,6 @@ void getExtentAndCenter( /// ts = null, then indices refer to points directly; otherwise refer to /// triangles template -FCL_EXPORT void getCovariance( const Vector3* const ps, const Vector3* const ps2, diff --git a/include/fcl/math/motion/bv_motion_bound_visitor.h b/include/fcl/math/motion/bv_motion_bound_visitor.h index cecfe06e7..e60d3c218 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 FCL_EXPORT BVMotionBoundVisitor +class 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 384367a80..db77ae926 100644 --- a/include/fcl/math/motion/interp_motion-inl.h +++ b/include/fcl/math/motion/interp_motion-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_INTERP_MOTION_BUILDING extern template -class FCL_EXPORT InterpMotion; +class FCL_EXPORT_EXPL_INST_DECL InterpMotion; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/interp_motion.h b/include/fcl/math/motion/interp_motion.h index a7f58eb74..69cbd8efb 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 FCL_EXPORT InterpMotion : public MotionBase +class 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 280058f73..d021f6782 100644 --- a/include/fcl/math/motion/motion_base-inl.h +++ b/include/fcl/math/motion/motion_base-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_BASE_BUILDING extern template -class FCL_EXPORT MotionBase; +class FCL_EXPORT_EXPL_INST_DECL MotionBase; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/screw_motion-inl.h b/include/fcl/math/motion/screw_motion-inl.h index 53c5c5bfd..417629919 100644 --- a/include/fcl/math/motion/screw_motion-inl.h +++ b/include/fcl/math/motion/screw_motion-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_SCREW_MOTION_BUILDING extern template -class FCL_EXPORT ScrewMotion; +class FCL_EXPORT_EXPL_INST_DECL ScrewMotion; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/screw_motion.h b/include/fcl/math/motion/screw_motion.h index fce33874e..0adb7fa95 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 FCL_EXPORT ScrewMotion : public MotionBase +class 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 e3d992d0c..b76783e12 100644 --- a/include/fcl/math/motion/spline_motion-inl.h +++ b/include/fcl/math/motion/spline_motion-inl.h @@ -46,8 +46,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_SPLINE_MOTION_BUILDING extern template -class FCL_EXPORT SplineMotion; +class FCL_EXPORT_EXPL_INST_DECL SplineMotion; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/spline_motion.h b/include/fcl/math/motion/spline_motion.h index 96f2eba24..a6082ac04 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 FCL_EXPORT SplineMotion : public MotionBase +class SplineMotion : public MotionBase { public: /// @brief Construct motion from 4 deBoor points diff --git a/include/fcl/math/motion/taylor_model/interval-inl.h b/include/fcl/math/motion/taylor_model/interval-inl.h index 2e2dbb105..7ec251ee5 100644 --- a/include/fcl/math/motion/taylor_model/interval-inl.h +++ b/include/fcl/math/motion/taylor_model/interval-inl.h @@ -45,16 +45,20 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_INTERVAL_BUILDING extern template -struct Interval; +struct FCL_EXPORT_EXPL_INST_DECL Interval; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL Interval bound(const Interval& i, double v); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL Interval bound(const Interval& i, const Interval& other); +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/interval.h b/include/fcl/math/motion/taylor_model/interval.h index cda1aa732..5aa2dc52f 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 FCL_EXPORT Interval +struct Interval { S i_[2]; @@ -125,11 +125,9 @@ struct FCL_EXPORT 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-inl.h b/include/fcl/math/motion/taylor_model/interval_matrix-inl.h index bda8fc03e..3f11a8a65 100644 --- a/include/fcl/math/motion/taylor_model/interval_matrix-inl.h +++ b/include/fcl/math/motion/taylor_model/interval_matrix-inl.h @@ -44,12 +44,15 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_INTERVAL_MATRIX_BUILDING extern template -struct IMatrix3; +struct FCL_EXPORT_EXPL_INST_DECL IMatrix3; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL IMatrix3 rotationConstrain(const IMatrix3& m); +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/interval_matrix.h b/include/fcl/math/motion/taylor_model/interval_matrix.h index eab03c2d4..3f16c3eca 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 FCL_EXPORT IMatrix3 +struct IMatrix3 { IVector3 v_[3]; @@ -95,7 +95,6 @@ struct FCL_EXPORT IMatrix3 }; template -FCL_EXPORT IMatrix3 rotationConstrain(const IMatrix3& m); } // namespace fcl diff --git a/include/fcl/math/motion/taylor_model/interval_vector-inl.h b/include/fcl/math/motion/taylor_model/interval_vector-inl.h index 5755f763a..d05979cf8 100644 --- a/include/fcl/math/motion/taylor_model/interval_vector-inl.h +++ b/include/fcl/math/motion/taylor_model/interval_vector-inl.h @@ -44,16 +44,20 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_INTERVAL_VECTOR_BUILDING extern template -struct IVector3; +struct FCL_EXPORT_EXPL_INST_DECL IVector3; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL IVector3 bound(const IVector3& i, const Vector3& v); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL IVector3 bound(const IVector3& i, const IVector3& v); +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/interval_vector.h b/include/fcl/math/motion/taylor_model/interval_vector.h index d5e5a9415..c59e81af2 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 FCL_EXPORT IVector3 +struct IVector3 { Interval i_[3]; @@ -106,11 +106,9 @@ struct FCL_EXPORT 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 f5b184375..0dbb30b6b 100644 --- a/include/fcl/math/motion/taylor_model/taylor_matrix-inl.h +++ b/include/fcl/math/motion/taylor_model/taylor_matrix-inl.h @@ -44,36 +44,45 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_TAYLOR_MATRIX_BUILDING extern template -class FCL_EXPORT TMatrix3; +class FCL_EXPORT_EXPL_INST_DECL TMatrix3; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 rotationConstrain(const TMatrix3& m); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 operator * (const Matrix3& m, const TaylorModel& a); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 operator * (const TaylorModel& a, const Matrix3& m); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 operator * (const TaylorModel& a, const TMatrix3& m); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 operator * (double d, const TMatrix3& m); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 operator + (const Matrix3& m1, const TMatrix3& m2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TMatrix3 operator - (const Matrix3& m1, const TMatrix3& m2); +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/taylor_matrix.h b/include/fcl/math/motion/taylor_model/taylor_matrix.h index c26f53309..2c4a11126 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 FCL_EXPORT TMatrix3 +class TMatrix3 { TVector3 v_[3]; @@ -106,31 +106,24 @@ class FCL_EXPORT 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 861f72d0f..6c33f307d 100644 --- a/include/fcl/math/motion/taylor_model/taylor_model-inl.h +++ b/include/fcl/math/motion/taylor_model/taylor_model-inl.h @@ -47,32 +47,40 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_BUILDING extern template -class FCL_EXPORT TaylorModel; +class FCL_EXPORT_EXPL_INST_DECL TaylorModel; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TaylorModel operator * (double d, const TaylorModel& a); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TaylorModel operator + (double d, const TaylorModel& a); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TaylorModel operator - (double d, const TaylorModel& a); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void generateTaylorModelForCosFunc(TaylorModel& tm, double w, double q0); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void generateTaylorModelForSinFunc(TaylorModel& tm, double w, double q0); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void generateTaylorModelForLinearFunc(TaylorModel& tm, double p, double v); +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/taylor_model.h b/include/fcl/math/motion/taylor_model/taylor_model.h index b8c199949..e80561fd2 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 FCL_EXPORT TaylorModel +class TaylorModel { /// @brief time interval std::shared_ptr> time_interval_; @@ -118,30 +118,24 @@ class FCL_EXPORT 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 1ce2b3613..3d3788656 100644 --- a/include/fcl/math/motion/taylor_model/taylor_vector-inl.h +++ b/include/fcl/math/motion/taylor_model/taylor_vector-inl.h @@ -44,24 +44,30 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_TAYLOR_VECTOR_BUILDING extern template -class FCL_EXPORT TVector3; +class FCL_EXPORT_EXPL_INST_DECL TVector3; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void generateTVector3ForLinearFunc(TVector3& v, const Vector3& position, const Vector3& velocity); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TVector3 operator * (const Vector3& v, const TaylorModel& a); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TVector3 operator + (const Vector3& v1, const TVector3& v2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL TVector3 operator - (const Vector3& v1, const TVector3& v2); +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/taylor_vector.h b/include/fcl/math/motion/taylor_model/taylor_vector.h index 7df662f70..884a3caab 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 FCL_EXPORT TVector3 +class TVector3 { TaylorModel i_[3]; @@ -104,19 +104,15 @@ class FCL_EXPORT 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-inl.h b/include/fcl/math/motion/taylor_model/time_interval-inl.h index 62d83d034..71ec1284c 100644 --- a/include/fcl/math/motion/taylor_model/time_interval-inl.h +++ b/include/fcl/math/motion/taylor_model/time_interval-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TAYLOR_MODEL_TIME_INTERVAL_BUILDING extern template -struct TimeInterval; +struct FCL_EXPORT_EXPL_INST_DECL TimeInterval; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/taylor_model/time_interval.h b/include/fcl/math/motion/taylor_model/time_interval.h index 1320d9c63..49c686a09 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 FCL_EXPORT TimeInterval +struct 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 515fef80e..05c947c42 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 FCL_EXPORT TBVMotionBoundVisitor : public BVMotionBoundVisitor +class 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 a2aaf6caf..402598fe5 100644 --- a/include/fcl/math/motion/translation_motion-inl.h +++ b/include/fcl/math/motion/translation_motion-inl.h @@ -46,8 +46,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TRANSLATION_MOTION_BUILDING extern template -class FCL_EXPORT TranslationMotion; +class FCL_EXPORT_EXPL_INST_DECL TranslationMotion; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/translation_motion.h b/include/fcl/math/motion/translation_motion.h index 37b77b470..ff2a1ff19 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 FCL_EXPORT TranslationMotion : public MotionBase +class 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 59f37cb03..e4c5fc474 100644 --- a/include/fcl/math/motion/triangle_motion_bound_visitor-inl.h +++ b/include/fcl/math/motion/triangle_motion_bound_visitor-inl.h @@ -50,8 +50,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_MOTION_TRIANGLE_MOTION_BOUND_VISITOR_BUILDING extern template -class FCL_EXPORT TriangleMotionBoundVisitor; +class FCL_EXPORT_EXPL_INST_DECL TriangleMotionBoundVisitor; +#endif //============================================================================== template diff --git a/include/fcl/math/motion/triangle_motion_bound_visitor.h b/include/fcl/math/motion/triangle_motion_bound_visitor.h index e6a3b7d28..c37a206a7 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 FCL_EXPORT TriangleMotionBoundVisitor +class TriangleMotionBoundVisitor { public: TriangleMotionBoundVisitor( diff --git a/include/fcl/math/rng-inl.h b/include/fcl/math/rng-inl.h index 8877c48a3..4732f34a3 100644 --- a/include/fcl/math/rng-inl.h +++ b/include/fcl/math/rng-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_RNG_BUILDING extern template -class FCL_EXPORT RNG; +class FCL_EXPORT_EXPL_INST_DECL RNG; +#endif //============================================================================== template diff --git a/include/fcl/math/rng.h b/include/fcl/math/rng.h index 782cf48ce..827c0ea6d 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 FCL_EXPORT RNG +class 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 d49d8c99f..dbbc83a8e 100644 --- a/include/fcl/math/sampler/sampler_base.h +++ b/include/fcl/math/sampler/sampler_base.h @@ -44,14 +44,16 @@ namespace fcl { template -class FCL_EXPORT SamplerBase +class SamplerBase { public: mutable RNG rng; }; +#ifndef FCL_MATH_SAMPLER_BASE_BUILDING extern template -class FCL_EXPORT SamplerBase; +class FCL_EXPORT_EXPL_INST_DECL SamplerBase; +#endif } // namespace fcl diff --git a/include/fcl/math/sampler/sampler_r.h b/include/fcl/math/sampler/sampler_r.h index 9b1977624..44eed4678 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 FCL_EXPORT SamplerR : public SamplerBase +class 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 aa3cb9a84..6c089ac0d 100644 --- a/include/fcl/math/sampler/sampler_se2-inl.h +++ b/include/fcl/math/sampler/sampler_se2-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_SAMPLER_SE2_BUILDING extern template -class FCL_EXPORT SamplerSE2; +class FCL_EXPORT_EXPL_INST_DECL SamplerSE2; +#endif //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se2.h b/include/fcl/math/sampler/sampler_se2.h index ff321e71c..be626a522 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 FCL_EXPORT SamplerSE2 : public SamplerBase +class 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 64aa25622..8dc389244 100644 --- a/include/fcl/math/sampler/sampler_se2_disk-inl.h +++ b/include/fcl/math/sampler/sampler_se2_disk-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_SAMPLER_SE2_DISK_BUILDING extern template -class FCL_EXPORT SamplerSE2_disk; +class FCL_EXPORT_EXPL_INST_DECL SamplerSE2_disk; +#endif //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se2_disk.h b/include/fcl/math/sampler/sampler_se2_disk.h index 154110b7e..eed432d0f 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 FCL_EXPORT SamplerSE2_disk : public SamplerBase +class 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 14ff1b884..2ddc5425c 100644 --- a/include/fcl/math/sampler/sampler_se3_euler-inl.h +++ b/include/fcl/math/sampler/sampler_se3_euler-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_SAMPLER_SE3_EULER_BUILDING extern template -class FCL_EXPORT SamplerSE3Euler; +class FCL_EXPORT_EXPL_INST_DECL SamplerSE3Euler; +#endif //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_euler.h b/include/fcl/math/sampler/sampler_se3_euler.h index 487e22a9b..5ec8d9228 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 FCL_EXPORT SamplerSE3Euler : public SamplerBase +class 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 48dc6d972..2554e6b77 100644 --- a/include/fcl/math/sampler/sampler_se3_euler_ball-inl.h +++ b/include/fcl/math/sampler/sampler_se3_euler_ball-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_SAMPLER_SE3_EULER_BALL_BUILDING extern template -class FCL_EXPORT SamplerSE3Euler_ball; +class FCL_EXPORT_EXPL_INST_DECL SamplerSE3Euler_ball; +#endif //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_euler_ball.h b/include/fcl/math/sampler/sampler_se3_euler_ball.h index 616e0b7c0..137d76606 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 FCL_EXPORT SamplerSE3Euler_ball : public SamplerBase +class 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 ed961abb3..160494401 100644 --- a/include/fcl/math/sampler/sampler_se3_quat-inl.h +++ b/include/fcl/math/sampler/sampler_se3_quat-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_SAMPLER_SE3_QUAT_BUILDING extern template -class FCL_EXPORT SamplerSE3Quat; +class FCL_EXPORT_EXPL_INST_DECL SamplerSE3Quat; +#endif //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_quat.h b/include/fcl/math/sampler/sampler_se3_quat.h index 3c2ae989f..0f0a9b4f2 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 FCL_EXPORT SamplerSE3Quat : public SamplerBase +class 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 6a13b91ff..31aa0c252 100644 --- a/include/fcl/math/sampler/sampler_se3_quat_ball-inl.h +++ b/include/fcl/math/sampler/sampler_se3_quat_ball-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_SAMPLER_SE3_QUAT_BALL_BUILDING extern template -class FCL_EXPORT SamplerSE3Quat_ball; +class FCL_EXPORT_EXPL_INST_DECL SamplerSE3Quat_ball; +#endif //============================================================================== template diff --git a/include/fcl/math/sampler/sampler_se3_quat_ball.h b/include/fcl/math/sampler/sampler_se3_quat_ball.h index 9fef44c4e..42a527de0 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 FCL_EXPORT SamplerSE3Quat_ball : public SamplerBase +class SamplerSE3Quat_ball : public SamplerBase { public: SamplerSE3Quat_ball(); diff --git a/include/fcl/math/variance3-inl.h b/include/fcl/math/variance3-inl.h index dea534005..5a568af13 100644 --- a/include/fcl/math/variance3-inl.h +++ b/include/fcl/math/variance3-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_MATH_VARIANCE3_BUILDING extern template -class FCL_EXPORT Variance3; +class FCL_EXPORT_EXPL_INST_DECL Variance3; +#endif //============================================================================== template diff --git a/include/fcl/math/variance3.h b/include/fcl/math/variance3.h index b5938206b..0bdb905bd 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 FCL_EXPORT Variance3 +class Variance3 { public: /// @brief Variation matrix diff --git a/include/fcl/narrowphase/collision-inl.h b/include/fcl/narrowphase/collision-inl.h index 69f4c2c8e..2eaea8f5a 100644 --- a/include/fcl/narrowphase/collision-inl.h +++ b/include/fcl/narrowphase/collision-inl.h @@ -48,8 +48,9 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_COLLISION_BUILDING extern template -FCL_EXPORT +FCL_EXPORT_EXPL_INST_DECL std::size_t collide( const CollisionObject* o1, const CollisionObject* o2, @@ -58,7 +59,7 @@ std::size_t collide( //============================================================================== extern template -FCL_EXPORT +FCL_EXPORT_EXPL_INST_DECL std::size_t collide( const CollisionGeometry* o1, const Transform3& tf1, @@ -66,6 +67,7 @@ std::size_t collide( const Transform3& tf2, const CollisionRequest& request, CollisionResult& result); +#endif //============================================================================== template @@ -77,7 +79,6 @@ detail::CollisionFunctionMatrix& getCollisionFunctionLookTable() //============================================================================== template -FCL_EXPORT std::size_t collide( const CollisionObject* o1, const CollisionObject* o2, @@ -91,7 +92,6 @@ std::size_t collide( //============================================================================== template -FCL_EXPORT std::size_t collide( const CollisionGeometry* o1, const Transform3& tf1, @@ -150,7 +150,6 @@ std::size_t collide( //============================================================================== template -FCL_EXPORT std::size_t collide(const CollisionObject* o1, const CollisionObject* o2, const CollisionRequest& request, CollisionResult& result) { @@ -176,7 +175,6 @@ 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 f6e361e19..960e6246b 100644 --- a/include/fcl/narrowphase/collision.h +++ b/include/fcl/narrowphase/collision.h @@ -53,13 +53,11 @@ 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 0c50e52c8..82fde42b8 100644 --- a/include/fcl/narrowphase/collision_object-inl.h +++ b/include/fcl/narrowphase/collision_object-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_COLLISION_OBJECT_BUILDING extern template -class FCL_EXPORT CollisionObject; +class FCL_EXPORT_EXPL_INST_DECL CollisionObject; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/collision_object.h b/include/fcl/narrowphase/collision_object.h index bef211a49..120bcbc23 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 FCL_EXPORT CollisionObject +class CollisionObject { public: CollisionObject(const std::shared_ptr>& cgeom); diff --git a/include/fcl/narrowphase/collision_request-inl.h b/include/fcl/narrowphase/collision_request-inl.h index eb779014a..501c96012 100644 --- a/include/fcl/narrowphase/collision_request-inl.h +++ b/include/fcl/narrowphase/collision_request-inl.h @@ -46,8 +46,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_COLLISION_REQUEST_BUILDING extern template -struct CollisionRequest; +struct FCL_EXPORT_EXPL_INST_DECL CollisionRequest; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/collision_request.h b/include/fcl/narrowphase/collision_request.h index 33417141c..b1604f46c 100644 --- a/include/fcl/narrowphase/collision_request.h +++ b/include/fcl/narrowphase/collision_request.h @@ -49,7 +49,7 @@ struct CollisionResult; /// @brief Parameters for performing collision request. template -struct FCL_EXPORT CollisionRequest +struct CollisionRequest { /// The underlying numerical representation of the request's scalar (e.g., /// float or double). diff --git a/include/fcl/narrowphase/collision_result-inl.h b/include/fcl/narrowphase/collision_result-inl.h index e8829be23..a89ff06f4 100644 --- a/include/fcl/narrowphase/collision_result-inl.h +++ b/include/fcl/narrowphase/collision_result-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_COLLISION_RESULT_BUILDING extern template -struct CollisionResult; +struct FCL_EXPORT_EXPL_INST_DECL CollisionResult; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/collision_result.h b/include/fcl/narrowphase/collision_result.h index a0d367773..8ce60cf9b 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 FCL_EXPORT CollisionResult +struct CollisionResult { private: /// @brief contact information diff --git a/include/fcl/narrowphase/contact-inl.h b/include/fcl/narrowphase/contact-inl.h index 88d26e557..039b1aa82 100644 --- a/include/fcl/narrowphase/contact-inl.h +++ b/include/fcl/narrowphase/contact-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_CONTACT_BUILDING extern template -struct Contact; +struct FCL_EXPORT_EXPL_INST_DECL Contact; +#endif //============================================================================== template @@ -58,6 +60,26 @@ Contact::Contact() // Do nothing } +//============================================================================== +template +Contact::~Contact() = default; + +//============================================================================== +template +Contact::Contact(const Contact&) = default; + +//============================================================================== +template +Contact& Contact::operator=(const Contact&) = default; + +//============================================================================== +template +Contact::Contact(Contact&&) noexcept = default; + +//============================================================================== +template +Contact& Contact::operator=(Contact&&) noexcept = default; + //============================================================================== template Contact::Contact( diff --git a/include/fcl/narrowphase/contact.h b/include/fcl/narrowphase/contact.h index eaa9b2f86..686086c61 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 FCL_EXPORT Contact +struct Contact { /// @brief collision object 1 const CollisionGeometry* o1; @@ -82,6 +82,16 @@ struct FCL_EXPORT Contact Contact(); + ~Contact(); + + Contact(const Contact&); + + Contact& operator=(const Contact&); + + Contact(Contact&&) noexcept; + + Contact& operator=(Contact&&) noexcept; + Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_, int b2_); Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_, int b2_, diff --git a/include/fcl/narrowphase/contact_point-inl.h b/include/fcl/narrowphase/contact_point-inl.h index 74ab8ca0d..98c91c2d9 100644 --- a/include/fcl/narrowphase/contact_point-inl.h +++ b/include/fcl/narrowphase/contact_point-inl.h @@ -44,17 +44,21 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_CONTACT_POINT_BUILDING extern template -struct ContactPoint; +struct FCL_EXPORT_EXPL_INST_DECL ContactPoint; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool comparePenDepth( const ContactPoint& _cp1, const ContactPoint& _cp2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void flipNormal(std::vector>& contacts); +#endif //============================================================================== template @@ -66,6 +70,26 @@ ContactPoint::ContactPoint() // Do nothing } +//============================================================================== +template +ContactPoint::~ContactPoint() = default; + +//============================================================================== +template +ContactPoint::ContactPoint(const ContactPoint&) = default; + +//============================================================================== +template +ContactPoint& ContactPoint::operator=(const ContactPoint&) = default; + +//============================================================================== +template +ContactPoint::ContactPoint(ContactPoint&&) noexcept = default; + +//============================================================================== +template +ContactPoint& ContactPoint::operator=(ContactPoint&&) noexcept = default; + //============================================================================== template ContactPoint::ContactPoint( diff --git a/include/fcl/narrowphase/contact_point.h b/include/fcl/narrowphase/contact_point.h index bca98e6bf..267c9c3ef 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 FCL_EXPORT ContactPoint +struct ContactPoint { /// @brief Contact normal, pointing from o1 to o2 Vector3 normal; @@ -56,9 +56,24 @@ struct FCL_EXPORT ContactPoint /// @brief Penetration depth S penetration_depth; - /// @brief Constructor + /// @brief Default Constructor ContactPoint(); + /// @brief Destructor + ~ContactPoint(); + + /// @brief Copy Constructor + ContactPoint(const ContactPoint&); + + /// @brief Copy assignment operator + ContactPoint& operator=(const ContactPoint&); + + /// @brief Move Constructor + ContactPoint(ContactPoint&&) noexcept; + + /// @brief Move assignment operator + ContactPoint& operator=(ContactPoint&&) noexcept; + /// @brief Constructor ContactPoint(const Vector3& n_, const Vector3& p_, S d_); }; @@ -68,12 +83,10 @@ 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 b24d0b8b1..1784ecbc4 100644 --- a/include/fcl/narrowphase/continuous_collision-inl.h +++ b/include/fcl/narrowphase/continuous_collision-inl.h @@ -55,7 +55,9 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_CONTINUOUS_COLLISION_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL double continuousCollide( const CollisionGeometry* o1, const MotionBase* motion1, @@ -66,6 +68,7 @@ double continuousCollide( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double continuousCollide( const CollisionGeometry* o1, const Transform3& tf1_beg, @@ -78,6 +81,7 @@ double continuousCollide( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double continuousCollide( const CollisionObject* o1, const Transform3& tf1_end, @@ -88,11 +92,13 @@ double continuousCollide( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double collide( const ContinuousCollisionObject* o1, const ContinuousCollisionObject* o2, const ContinuousCollisionRequest& request, ContinuousCollisionResult& result); +#endif //============================================================================== template @@ -105,7 +111,6 @@ getConservativeAdvancementFunctionLookTable() //============================================================================== template -FCL_EXPORT MotionBasePtr getMotionBase( const Transform3& tf_beg, const Transform3& tf_end, @@ -132,7 +137,6 @@ MotionBasePtr getMotionBase( //============================================================================== template -FCL_EXPORT S continuousCollideNaive( const CollisionGeometry* o1, const MotionBase* motion1, @@ -175,7 +179,6 @@ namespace detail //============================================================================== template -FCL_EXPORT typename BV::S continuousCollideBVHPolynomial( const CollisionGeometry* o1_, const TranslationMotion* motion1, @@ -244,7 +247,6 @@ typename BV::S continuousCollideBVHPolynomial( //============================================================================== template -FCL_EXPORT S continuousCollideBVHPolynomial( const CollisionGeometry* o1, const TranslationMotion* motion1, @@ -301,7 +303,6 @@ namespace detail //============================================================================== template -FCL_EXPORT typename NarrowPhaseSolver::S continuousCollideConservativeAdvancement( const CollisionGeometry* o1, const MotionBase* motion1, @@ -355,7 +356,6 @@ typename NarrowPhaseSolver::S continuousCollideConservativeAdvancement( } // namespace detail template -FCL_EXPORT S continuousCollideConservativeAdvancement( const CollisionGeometry* o1, const MotionBase* motion1, @@ -383,7 +383,6 @@ S continuousCollideConservativeAdvancement( //============================================================================== template -FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const MotionBase* motion1, @@ -433,7 +432,6 @@ S continuousCollide( //============================================================================== template -FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const Transform3& tf1_beg, @@ -452,7 +450,6 @@ S continuousCollide( //============================================================================== template -FCL_EXPORT S continuousCollide( const CollisionObject* o1, const Transform3& tf1_end, @@ -468,7 +465,6 @@ 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 fb1cab6c3..fe02b38e4 100644 --- a/include/fcl/narrowphase/continuous_collision.h +++ b/include/fcl/narrowphase/continuous_collision.h @@ -51,7 +51,6 @@ namespace fcl /// @brief continous collision checking between two objects template -FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const MotionBase* motion1, @@ -61,7 +60,6 @@ S continuousCollide( ContinuousCollisionResult& result); template -FCL_EXPORT S continuousCollide( const CollisionGeometry* o1, const Transform3& tf1_beg, @@ -73,7 +71,6 @@ S continuousCollide( ContinuousCollisionResult& result); template -FCL_EXPORT S continuousCollide( const CollisionObject* o1, const Transform3& tf1_end, @@ -83,7 +80,6 @@ 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 e8008e98e..94660488e 100644 --- a/include/fcl/narrowphase/continuous_collision_object-inl.h +++ b/include/fcl/narrowphase/continuous_collision_object-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_CONTINUOUS_COLLISION_OBJECT_BUILDING extern template -class FCL_EXPORT ContinuousCollisionObject; +class FCL_EXPORT_EXPL_INST_DECL ContinuousCollisionObject; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/continuous_collision_object.h b/include/fcl/narrowphase/continuous_collision_object.h index ecb12c422..60b874186 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 FCL_EXPORT ContinuousCollisionObject +class ContinuousCollisionObject { public: ContinuousCollisionObject( diff --git a/include/fcl/narrowphase/continuous_collision_request-inl.h b/include/fcl/narrowphase/continuous_collision_request-inl.h index cd08e7fc7..a2545e700 100644 --- a/include/fcl/narrowphase/continuous_collision_request-inl.h +++ b/include/fcl/narrowphase/continuous_collision_request-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_CONTINUOUS_COLLISION_REQUEST_BUILDING extern template -struct ContinuousCollisionRequest; +struct FCL_EXPORT_EXPL_INST_DECL ContinuousCollisionRequest; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/continuous_collision_request.h b/include/fcl/narrowphase/continuous_collision_request.h index 356be14cd..518b09598 100644 --- a/include/fcl/narrowphase/continuous_collision_request.h +++ b/include/fcl/narrowphase/continuous_collision_request.h @@ -49,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 FCL_EXPORT ContinuousCollisionRequest +struct ContinuousCollisionRequest { /// @brief maximum num of iterations std::size_t num_max_iterations; diff --git a/include/fcl/narrowphase/continuous_collision_result-inl.h b/include/fcl/narrowphase/continuous_collision_result-inl.h index a34d168c0..56bd2fda1 100644 --- a/include/fcl/narrowphase/continuous_collision_result-inl.h +++ b/include/fcl/narrowphase/continuous_collision_result-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_CONTINUOUS_COLLISION_RESULT_BUILDING extern template -struct ContinuousCollisionResult; +struct FCL_EXPORT_EXPL_INST_DECL ContinuousCollisionResult; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/continuous_collision_result.h b/include/fcl/narrowphase/continuous_collision_result.h index e19bf6941..8e5f8334a 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 FCL_EXPORT ContinuousCollisionResult +struct ContinuousCollisionResult { /// @brief collision or not bool is_collide; diff --git a/include/fcl/narrowphase/cost_source-inl.h b/include/fcl/narrowphase/cost_source-inl.h index abadfc960..c83a47f8b 100644 --- a/include/fcl/narrowphase/cost_source-inl.h +++ b/include/fcl/narrowphase/cost_source-inl.h @@ -44,8 +44,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_COST_SOURCE_BUILDING extern template -struct CostSource; +struct FCL_EXPORT_EXPL_INST_DECL CostSource; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/cost_source.h b/include/fcl/narrowphase/cost_source.h index 15bc11180..66f072a18 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 FCL_EXPORT CostSource +struct CostSource { /// @brief aabb lower bound Vector3 aabb_min; diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/epa-inl.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/epa-inl.h index e9c667d6d..c25cad794 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/epa-inl.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/epa-inl.h @@ -47,8 +47,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_EPA_BUILDING extern template -struct EPA; +struct FCL_EXPORT_EXPL_INST_DECL EPA; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/epa.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/epa.h index eb7efa4b1..131dc7a7f 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 FCL_EXPORT EPA +struct EPA { private: using SimplexV = typename GJK::SimplexV; diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk-inl.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk-inl.h index fa01dc352..5333a27f3 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk-inl.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk-inl.h @@ -47,8 +47,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_GJK_BUILDING extern template -struct GJK; +struct FCL_EXPORT_EXPL_INST_DECL GJK; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk.h index f5bbc2107..7949bba28 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 FCL_EXPORT GJK +struct 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 60fd0ad17..435062bfe 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 @@ -55,40 +55,43 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_GJK_LIBCCD_BUILDING extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template -class FCL_EXPORT GJKInitializer>; +class FCL_EXPORT_EXPL_INST_DECL GJKInitializer>; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void* triCreateGJKObject( const Vector3d& P1, const Vector3d& P2, const Vector3d& P3); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void* triCreateGJKObject( const Vector3d& P1, const Vector3d& P2, @@ -97,6 +100,7 @@ void* triCreateGJKObject( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool GJKCollide( void* obj1, ccd_support_fn supp1, @@ -112,6 +116,7 @@ bool GJKCollide( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool GJKDistance( void* obj1, ccd_support_fn supp1, @@ -124,6 +129,7 @@ bool GJKDistance( Vector3d* p2); extern template +FCL_EXPORT_EXPL_INST_DECL bool GJKSignedDistance( void* obj1, ccd_support_fn supp1, @@ -134,6 +140,7 @@ bool GJKSignedDistance( double* dist, Vector3d* p1, Vector3d* p2); +#endif struct ccd_obj_t { 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 c22274804..3bcecd36a 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h @@ -73,7 +73,7 @@ using GJKCenterFunction = void (*)(const void* obj, ccd_vec3_t* c); /// @brief initialize GJK stuffs template -class FCL_EXPORT GJKInitializer +class GJKInitializer { public: /// @brief Get GJK support function @@ -93,7 +93,7 @@ class FCL_EXPORT GJKInitializer /// @brief initialize GJK Cylinder template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -104,7 +104,7 @@ class FCL_EXPORT GJKInitializer> /// @brief initialize GJK Sphere template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -115,7 +115,7 @@ class FCL_EXPORT GJKInitializer> /// @brief initialize GJK Ellipsoid template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -126,7 +126,7 @@ class FCL_EXPORT GJKInitializer> /// @brief initialize GJK Box template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -137,7 +137,7 @@ class FCL_EXPORT GJKInitializer> /// @brief initialize GJK Capsule template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -148,7 +148,7 @@ class FCL_EXPORT GJKInitializer> /// @brief initialize GJK Cone template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -159,7 +159,7 @@ class FCL_EXPORT GJKInitializer> /// @brief initialize GJK Convex template -class FCL_EXPORT GJKInitializer> +class GJKInitializer> { public: static GJKSupportFunction getSupportFunction(); @@ -176,11 +176,9 @@ 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 @@ -188,7 +186,6 @@ void triDeleteGJKObject(void* o); /// @brief GJK collision algorithm template -FCL_EXPORT bool GJKCollide( void* obj1, ccd_support_fn supp1, @@ -221,7 +218,6 @@ bool GJKCollide( * @retval is_separated True if the objects are separated, false otherwise. */ template -FCL_EXPORT bool GJKDistance(void* obj1, ccd_support_fn supp1, void* obj2, ccd_support_fn supp2, unsigned int max_iterations, S tolerance, @@ -247,7 +243,6 @@ bool GJKDistance(void* obj1, ccd_support_fn supp1, * @retval is_separated True if the objects are separated, false otherwise. */ 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 9f1309e06..69bde039c 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 @@ -58,12 +58,13 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_MINKOWSKI_DIFF_BUILDING extern template -struct MinkowskiDiff; +struct FCL_EXPORT_EXPL_INST_DECL MinkowskiDiff; +#endif //============================================================================== 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 a1ee9c7da..6e073accf 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 FCL_EXPORT MinkowskiDiff +struct MinkowskiDiff { /// @brief points to two shapes const ShapeBase* shapes[2]; diff --git a/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h b/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h index fd78927a7..e357e7132 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h +++ b/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h @@ -66,8 +66,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_GJK_SOLVER_INDEP_BUILDING extern template -struct GJKSolver_indep; +struct FCL_EXPORT_EXPL_INST_DECL GJKSolver_indep; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/gjk_solver_indep.h b/include/fcl/narrowphase/detail/gjk_solver_indep.h index 44ed5147b..666e9c9a0 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_indep.h +++ b/include/fcl/narrowphase/detail/gjk_solver_indep.h @@ -51,7 +51,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 FCL_EXPORT GJKSolver_indep +struct GJKSolver_indep { using S = S_; diff --git a/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h b/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h index 72072927a..e096b9bd9 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h +++ b/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h @@ -63,8 +63,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_GJK_SOLVER_LIBCCD_BUILDING extern template -struct GJKSolver_libccd; +struct FCL_EXPORT_EXPL_INST_DECL GJKSolver_libccd; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/gjk_solver_libccd.h b/include/fcl/narrowphase/detail/gjk_solver_libccd.h index 218a89481..1b6b2c33d 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_libccd.h +++ b/include/fcl/narrowphase/detail/gjk_solver_libccd.h @@ -51,7 +51,7 @@ namespace detail /// @brief collision and distance solver based on libccd library. template -struct FCL_EXPORT GJKSolver_libccd +struct GJKSolver_libccd { using S = S_; diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box-inl.h index 91ffeca65..b7d7b4ae5 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box-inl.h @@ -49,21 +49,26 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_BOX_BOX_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL void lineClosestApproach(const Vector3& pa, const Vector3& ua, const Vector3& pb, const Vector3& ub, double* alpha, double* beta); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL int intersectRectQuad2(double h[2], double p[8], double ret[16]); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void cullPoints2(int n, double p[], int m, int i0, int iret[]); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL int boxBox2( const Vector3& side1, const Transform3& tf1, @@ -77,9 +82,11 @@ int boxBox2( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool boxBoxIntersect(const Box& s1, const Transform3& tf1, const Box& s2, const Transform3& tf2, std::vector>* contacts_); +#endif //============================================================================== template 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 87a60845f..d7be73443 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/box_box.h @@ -49,7 +49,6 @@ namespace detail { template -FCL_EXPORT void lineClosestApproach(const Vector3& pa, const Vector3& ua, const Vector3& pb, const Vector3& ub, S* alpha, S* beta); @@ -62,7 +61,6 @@ 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 @@ -73,11 +71,9 @@ 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, @@ -92,7 +88,6 @@ int boxBox2( std::vector>& contacts); template -FCL_EXPORT int boxBox2( const Vector3& side1, const Transform3& tf1, @@ -105,7 +100,6 @@ 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-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule-inl.h index b316c956d..14f1e2dc0 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule-inl.h @@ -47,23 +47,29 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_CAPSULE_CAPSULE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL double clamp(double n, double min, double max); //============================================================================== -extern template double closestPtSegmentSegment(const Vector3d& p_FP1, - const Vector3d& p_FQ1, - const Vector3d& p_FP2, - const Vector3d& p_FQ2, double* s, - double* t, Vector3d* p_FC1, - Vector3d* p_FC2); +extern template +FCL_EXPORT_EXPL_INST_DECL +double closestPtSegmentSegment(const Vector3d& p_FP1, + const Vector3d& p_FQ1, + const Vector3d& p_FP2, + const Vector3d& p_FQ2, double* s, + double* t, Vector3d* p_FC1, + Vector3d* p_FC2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool capsuleCapsuleDistance( const Capsule& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, double* dist, Vector3d* p1_res, Vector3d* p2_res); +#endif //============================================================================== template 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 c3917368b..a1303fcaa 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h @@ -49,7 +49,6 @@ namespace detail // Clamp n to lie within the range [min, max] template -FCL_EXPORT S clamp(S n, S min, S max); /** Computes the pair of closest points `(p_FC1, p_FC2)` between two line @@ -73,11 +72,11 @@ S clamp(S n, S min, S max); @tparam S The scalar type for computation. */ template -FCL_EXPORT S closestPtSegmentSegment(const Vector3& p_FP1, - const Vector3& p_FQ1, - const Vector3& p_FP2, - const Vector3& p_FQ2, S* s, S* t, - Vector3* p_FC1, Vector3* p_FC2); +S closestPtSegmentSegment(const Vector3& p_FP1, + const Vector3& p_FQ1, + const Vector3& p_FP2, + const Vector3& p_FQ2, S* s, S* t, + Vector3* p_FC1, Vector3* p_FC2); /** Computes the signed distance between two capsules `s1` and `s2` (with given poses `X_FC1` and `X_FC2` of the two capsules in a common frame `F`). @@ -104,7 +103,6 @@ FCL_EXPORT S closestPtSegmentSegment(const Vector3& p_FP1, @tparam S The scalar type for computation. */ template -FCL_EXPORT bool capsuleCapsuleDistance(const Capsule& s1, const Transform3& X_FC1, const Capsule& s2, const Transform3& X_FC2, S* dist, Vector3* p_FW1, Vector3* p_FW2); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h index 09a86f52e..1bdd6b758 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h @@ -47,7 +47,9 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_HALFSPACE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereHalfspaceIntersect( const Sphere& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -55,6 +57,7 @@ bool sphereHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool ellipsoidHalfspaceIntersect( const Ellipsoid& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -62,12 +65,14 @@ bool ellipsoidHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool boxHalfspaceIntersect( const Box& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool boxHalfspaceIntersect( const Box& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -75,6 +80,7 @@ bool boxHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool capsuleHalfspaceIntersect( const Capsule& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -82,6 +88,7 @@ bool capsuleHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool cylinderHalfspaceIntersect( const Cylinder& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -89,6 +96,7 @@ bool cylinderHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool coneHalfspaceIntersect( const Cone& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -96,19 +104,23 @@ bool coneHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool convexHalfspaceIntersect( const Convex& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, Vector3* contact_points, double* penetration_depth, Vector3* normal); //============================================================================== -extern template bool convexHalfspaceIntersect( +extern template +FCL_EXPORT_EXPL_INST_DECL +bool convexHalfspaceIntersect( const Convex& convex_C, const Transform3& X_FC, const Halfspace& half_space_H, const Transform3& X_FH, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool halfspaceTriangleIntersect( const Halfspace& s1, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, @@ -116,6 +128,7 @@ bool halfspaceTriangleIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool planeHalfspaceIntersect( const Plane& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -126,6 +139,7 @@ bool planeHalfspaceIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool halfspacePlaneIntersect( const Halfspace& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, @@ -135,6 +149,7 @@ bool halfspacePlaneIntersect( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool halfspaceIntersect( const Halfspace& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -142,6 +157,7 @@ bool halfspaceIntersect( Halfspace& s, double& penetration_depth, int& ret); +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h index 62fda4c22..76cb169a9 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/halfspace.h @@ -56,7 +56,6 @@ namespace detail { template -FCL_EXPORT S halfspaceIntersectTolerance(); template <> @@ -68,13 +67,11 @@ 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); @@ -85,36 +82,30 @@ 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); @@ -160,13 +151,12 @@ bool convexHalfspaceIntersect(const Convex& s1, const Transform3& tf1, /// @return `true` if the two geometries are intersecting. /// @tparam S The computational scalar. template -FCL_EXPORT bool convexHalfspaceIntersect( +bool convexHalfspaceIntersect( const Convex& convex_C, const Transform3& X_FC, const Halfspace& half_space_H, const Transform3& X_FH, std::vector>* contacts); 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); @@ -179,7 +169,6 @@ 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, @@ -188,7 +177,6 @@ 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, @@ -204,7 +192,6 @@ 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-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane-inl.h index 1373dce1f..3ddead420 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane-inl.h @@ -47,68 +47,81 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_PLANE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL bool spherePlaneIntersect(const Sphere& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool ellipsoidPlaneIntersect(const Ellipsoid& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool boxPlaneIntersect(const Box& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool capsulePlaneIntersect(const Capsule& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool capsulePlaneIntersect(const Capsule& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool cylinderPlaneIntersect(const Cylinder& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool cylinderPlaneIntersect(const Cylinder& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool conePlaneIntersect(const Cone& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool convexPlaneIntersect(const Convex& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, Vector3* contact_points, double* penetration_depth, Vector3* normal); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool planeTriangleIntersect(const Plane& s1, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, Vector3* contact_points, double* penetration_depth, Vector3* normal); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool planeIntersect(const Plane& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, std::vector>* contacts); +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h index 86b141f24..601456731 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/plane.h @@ -55,7 +55,6 @@ namespace detail { template -FCL_EXPORT S planeIntersectTolerance(); template <> @@ -67,13 +66,11 @@ 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); @@ -86,18 +83,15 @@ 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); @@ -108,36 +102,30 @@ 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_box-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h index 77e0a66f2..29cfce91d 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h @@ -42,18 +42,22 @@ namespace fcl { namespace detail { -extern template FCL_EXPORT bool -sphereBoxIntersect(const Sphere& sphere, const Transform3& X_FS, - const Box& box, const Transform3& X_FB, - std::vector>* contacts); +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_BOX_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +bool sphereBoxIntersect(const Sphere& sphere, const Transform3& X_FS, + const Box& box, const Transform3& X_FB, + std::vector>* contacts); //============================================================================== -extern template FCL_EXPORT bool -sphereBoxDistance(const Sphere& sphere, const Transform3& X_FS, - const Box& box, const Transform3& X_FB, - double* distance, Vector3* p_FSb, - Vector3* p_FBs); +extern template +FCL_EXPORT_EXPL_INST_DECL +bool sphereBoxDistance(const Sphere& sphere, const Transform3& X_FS, + const Box& box, const Transform3& X_FB, + double* distance, Vector3* p_FSb, + Vector3* p_FBs); +#endif //============================================================================== @@ -95,10 +99,10 @@ bool nearestPointInBox(const Vector3& size, const Vector3& p_BQ, //============================================================================== template -FCL_EXPORT bool sphereBoxIntersect(const Sphere& sphere, - const Transform3& X_FS, const Box& box, - const Transform3& X_FB, - std::vector>* contacts) { +bool sphereBoxIntersect(const Sphere& sphere, + const Transform3& X_FS, const Box& box, + const Transform3& X_FB, + std::vector>* contacts) { const S r = sphere.radius; // Find the sphere center C in the box's frame. const Transform3 X_BS = X_FB.inverse() * X_FS; @@ -180,10 +184,10 @@ FCL_EXPORT bool sphereBoxIntersect(const Sphere& sphere, //============================================================================== template -FCL_EXPORT bool sphereBoxDistance(const Sphere& sphere, - const Transform3& X_FS, const Box& box, - const Transform3& X_FB, S* distance, - Vector3* p_FSb, Vector3* p_FBs) { +bool sphereBoxDistance(const Sphere& sphere, + const Transform3& X_FS, const Box& box, + const Transform3& X_FB, S* distance, + Vector3* p_FSb, Vector3* p_FBs) { // Find the sphere center C in the box's frame. const Transform3 X_BS = X_FB.inverse() * X_FS; const Vector3 p_BC = X_BS.translation(); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h index 87fabf8cd..478774b7b 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box.h @@ -107,10 +107,10 @@ namespace detail { @return True if the objects are colliding (including touching). @tparam S The scalar parameter (must be a valid Eigen scalar). */ template -FCL_EXPORT bool sphereBoxIntersect(const Sphere& sphere, - const Transform3& X_FS, const Box& box, - const Transform3& X_FB, - std::vector>* contacts); +bool sphereBoxIntersect(const Sphere& sphere, + const Transform3& X_FS, const Box& box, + const Transform3& X_FB, + std::vector>* contacts); /** Evaluate the minimum separating distance between a sphere and box. If separated, the nearest points on each shape will be returned in frame F. @@ -127,10 +127,10 @@ FCL_EXPORT bool sphereBoxIntersect(const Sphere& sphere, @return True if the objects are separated. @tparam S The scalar parameter (must be a valid Eigen scalar). */ template -FCL_EXPORT bool sphereBoxDistance(const Sphere& sphere, - const Transform3& X_FS, const Box& box, - const Transform3& X_FB, S* distance, - Vector3* p_FSb, Vector3* p_FBs); +bool sphereBoxDistance(const Sphere& sphere, + const Transform3& X_FS, const Box& box, + const Transform3& X_FB, S* distance, + Vector3* p_FSb, Vector3* p_FBs); //@} diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule-inl.h index c85d56991..49b870a32 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule-inl.h @@ -47,7 +47,9 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_CAPSULE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL void lineSegmentPointClosestToPoint( const Vector3 &p, const Vector3 &s1, @@ -56,15 +58,18 @@ void lineSegmentPointClosestToPoint( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereCapsuleIntersect(const Sphere& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereCapsuleDistance(const Sphere& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, double* dist, Vector3* p1, Vector3* p2); +#endif //============================================================================== template 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 2820b32a7..81061f390 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h @@ -53,7 +53,6 @@ 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, @@ -61,13 +60,11 @@ 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_cylinder-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder-inl.h index abda26294..915a7e64f 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder-inl.h @@ -42,22 +42,26 @@ namespace fcl { namespace detail { -extern template FCL_EXPORT bool -sphereCylinderIntersect(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, - std::vector>* contacts); +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_CYLINDER_BUILDING +extern template +FCL_EXPORT_EXPL_INST_DECL +bool sphereCylinderIntersect(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, + std::vector>* contacts); //============================================================================== -extern template FCL_EXPORT bool -sphereCylinderDistance(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, - double* distance, Vector3* p_FSc, - Vector3* p_FCs); +extern template +FCL_EXPORT_EXPL_INST_DECL +bool sphereCylinderDistance(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, + double* distance, Vector3* p_FSc, + Vector3* p_FCs); +#endif //============================================================================== @@ -111,7 +115,7 @@ bool nearestPointInCylinder(const S& height, const S& radius, //============================================================================== template -FCL_EXPORT bool sphereCylinderIntersect( +bool sphereCylinderIntersect( const Sphere& sphere, const Transform3& X_FS, const Cylinder& cylinder, const Transform3& X_FC, std::vector>* contacts) { @@ -223,11 +227,11 @@ FCL_EXPORT bool sphereCylinderIntersect( //============================================================================== template -FCL_EXPORT bool sphereCylinderDistance(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, S* distance, - Vector3* p_FSc, Vector3* p_FCs) { +bool sphereCylinderDistance(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, S* distance, + Vector3* p_FSc, Vector3* p_FCs) { // Find the sphere center S in the cylinder's frame. const Transform3 X_CS = X_FC.inverse() * X_FS; const Vector3 p_CS = X_CS.translation(); diff --git a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.h index 4209b03a0..7f4fe6dad 100644 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.h @@ -102,11 +102,11 @@ namespace detail { @return True if the objects are colliding (including touching). @tparam S The scalar parameter (must be a valid Eigen scalar). */ template -FCL_EXPORT bool sphereCylinderIntersect(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, - std::vector>* contacts); +bool sphereCylinderIntersect(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, + std::vector>* contacts); /** Evaluate the minimum separating distance between a sphere and cylinder. If separated, the nearest points on each shape will be returned in frame F. @@ -123,11 +123,11 @@ FCL_EXPORT bool sphereCylinderIntersect(const Sphere& sphere, @return True if the objects are separated. @tparam S The scalar parameter (must be a valid Eigen scalar). */ template -FCL_EXPORT bool sphereCylinderDistance(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, S* distance, - Vector3* p_FSc, Vector3* p_FCs); +bool sphereCylinderDistance(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, S* distance, + Vector3* p_FSc, Vector3* p_FCs); //@} 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 d12671cfb..2331a1993 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 @@ -47,22 +47,23 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_SPHERE_BUILDING extern template -FCL_EXPORT +FCL_EXPORT_EXPL_INST_DECL bool sphereSphereIntersect(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== extern template -FCL_EXPORT +FCL_EXPORT_EXPL_INST_DECL bool sphereSphereDistance(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, double* dist, Vector3* p1, Vector3* p2); +#endif //============================================================================== template -FCL_EXPORT bool sphereSphereIntersect(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, std::vector>* contacts) @@ -87,7 +88,6 @@ 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-inl.h b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle-inl.h index 0078900df..e6321accf 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle-inl.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle-inl.h @@ -49,35 +49,43 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_TRIANGLE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL double segmentSqrDistance(const Vector3& from, const Vector3& to,const Vector3& p, Vector3& nearest); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool projectInTriangle(const Vector3& p1, const Vector3& p2, const Vector3& p3, const Vector3& normal, const Vector3& p); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereTriangleIntersect(const Sphere& s, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, Vector3* contact_points, double* penetration_depth, Vector3* normal_); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, double* dist); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, double* dist, Vector3* p1, Vector3* p2); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, double* dist, Vector3* p1, Vector3* p2); +#endif //============================================================================== template 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 15a2a70ef..61da0d580 100755 --- a/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.h +++ b/include/fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.h @@ -49,33 +49,27 @@ 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 33a1d4fd6..29e859789 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 @@ -47,8 +47,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_TRIANGLE_DISTANCE_BUILDING extern template -class FCL_EXPORT TriangleDistance; +class FCL_EXPORT_EXPL_INST_DECL TriangleDistance; +#endif //============================================================================== 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 cb4b2e693..cc800f0f1 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 FCL_EXPORT TriangleDistance +class 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 021a47823..44cfe31f4 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 FCL_EXPORT BVHCollisionTraversalNode +class 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 9247d5622..551223d11 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 FCL_EXPORT BVHShapeCollisionTraversalNode +class 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 86743e2d7..47037fced 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 @@ -49,8 +49,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_TRAVERSAL_NODE_BASE_BUILDING extern template -class FCL_EXPORT CollisionTraversalNodeBase; +class FCL_EXPORT_EXPL_INST_DECL CollisionTraversalNodeBase; +#endif //============================================================================== 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 6f6b10ca6..58ea12561 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 FCL_EXPORT CollisionTraversalNodeBase : public TraversalNodeBase +class 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 4c9d6069f..219b7d85d 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/intersect-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/intersect-inl.h @@ -47,8 +47,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_INTERSECT_BUILDING extern template -class FCL_EXPORT Intersect; +class FCL_EXPORT_EXPL_INST_DECL Intersect; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/collision/intersect.h b/include/fcl/narrowphase/detail/traversal/collision/intersect.h index d653b8793..355876eb6 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 FCL_EXPORT Intersect +class 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 0a2731fa1..af9dfa97e 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 @@ -51,11 +51,13 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_MESH_COLLISION_TRAVERSAL_NODE_BUILDING extern template -class FCL_EXPORT MeshCollisionTraversalNodeOBB; +class FCL_EXPORT_EXPL_INST_DECL MeshCollisionTraversalNodeOBB; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshCollisionTraversalNodeOBB& node, const BVHModel>& model1, @@ -67,10 +69,11 @@ bool initialize( //============================================================================== extern template -class FCL_EXPORT MeshCollisionTraversalNodeRSS; +class FCL_EXPORT_EXPL_INST_DECL MeshCollisionTraversalNodeRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshCollisionTraversalNodeRSS& node, const BVHModel>& model1, @@ -82,10 +85,11 @@ bool initialize( //============================================================================== extern template -class FCL_EXPORT MeshCollisionTraversalNodekIOS; +class FCL_EXPORT_EXPL_INST_DECL MeshCollisionTraversalNodekIOS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshCollisionTraversalNodekIOS& node, const BVHModel>& model1, @@ -97,10 +101,11 @@ bool initialize( //============================================================================== extern template -class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS; +class FCL_EXPORT_EXPL_INST_DECL MeshCollisionTraversalNodeOBBRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshCollisionTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -109,6 +114,7 @@ bool initialize( const Transform3& tf2, const CollisionRequest& request, CollisionResult& result); +#endif //============================================================================== 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 7e3d99335..b3f8d7567 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 FCL_EXPORT MeshCollisionTraversalNode : public BVHCollisionTraversalNode +class MeshCollisionTraversalNode : public BVHCollisionTraversalNode { public: @@ -81,7 +81,6 @@ class FCL_EXPORT MeshCollisionTraversalNode : public BVHCollisionTraversalNode -FCL_EXPORT bool initialize( MeshCollisionTraversalNode& node, BVHModel& model1, @@ -96,7 +95,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 FCL_EXPORT MeshCollisionTraversalNodeOBB : public MeshCollisionTraversalNode> +class MeshCollisionTraversalNodeOBB : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodeOBB(); @@ -125,7 +124,6 @@ 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, @@ -136,7 +134,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT MeshCollisionTraversalNodeRSS : public MeshCollisionTraversalNode> +class MeshCollisionTraversalNodeRSS : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodeRSS(); @@ -167,7 +165,6 @@ 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, @@ -178,7 +175,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT MeshCollisionTraversalNodekIOS : public MeshCollisionTraversalNode> +class MeshCollisionTraversalNodekIOS : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodekIOS(); @@ -199,7 +196,6 @@ 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, @@ -210,7 +206,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS : public MeshCollisionTraversalNode> +class MeshCollisionTraversalNodeOBBRSS : public MeshCollisionTraversalNode> { public: MeshCollisionTraversalNodeOBBRSS(); @@ -232,7 +228,6 @@ using MeshCollisionTraversalNodeOBBRSSd = MeshCollisionTraversalNodeOBBRSS -FCL_EXPORT bool initialize( MeshCollisionTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -243,7 +238,6 @@ bool initialize( CollisionResult& result); template -FCL_EXPORT void meshCollisionOrientedNodeLeafTesting( int b1, int b2, @@ -264,7 +258,6 @@ 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-inl.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node-inl.h index 39213d785..eba0d41e6 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node-inl.h @@ -49,8 +49,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_MESH_CONTINUOUS_COLLISION_TRAVERSAL_NODE_BUILDING extern template -struct BVHContinuousCollisionPair; +struct FCL_EXPORT_EXPL_INST_DECL BVHContinuousCollisionPair; +#endif //============================================================================== template 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 82425a51d..a9e7b0130 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 FCL_EXPORT BVHContinuousCollisionPair +struct BVHContinuousCollisionPair { BVHContinuousCollisionPair(); @@ -66,7 +66,7 @@ struct FCL_EXPORT BVHContinuousCollisionPair /// @brief Traversal node for continuous collision between meshes template -class FCL_EXPORT MeshContinuousCollisionTraversalNode +class MeshContinuousCollisionTraversalNode : public BVHCollisionTraversalNode { public: @@ -101,7 +101,6 @@ class FCL_EXPORT 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 a06250a7a..8a658cfd7 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 FCL_EXPORT MeshShapeCollisionTraversalNode +class MeshShapeCollisionTraversalNode : public BVHShapeCollisionTraversalNode { public: @@ -75,7 +75,6 @@ class FCL_EXPORT 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, @@ -88,7 +87,6 @@ bool initialize( bool use_refit = false, bool refit_bottomup = false); template -FCL_EXPORT void meshShapeCollisionOrientedNodeLeafTesting( int b1, int b2, @@ -107,7 +105,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 FCL_EXPORT MeshShapeCollisionTraversalNodeOBB +class MeshShapeCollisionTraversalNodeOBB : public MeshShapeCollisionTraversalNode< OBB, Shape, NarrowPhaseSolver> { @@ -123,7 +121,6 @@ class FCL_EXPORT 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, @@ -135,7 +132,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT MeshShapeCollisionTraversalNodeRSS +class MeshShapeCollisionTraversalNodeRSS : public MeshShapeCollisionTraversalNode< RSS, Shape, NarrowPhaseSolver> { @@ -151,7 +148,6 @@ class FCL_EXPORT 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, @@ -163,7 +159,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT MeshShapeCollisionTraversalNodekIOS +class MeshShapeCollisionTraversalNodekIOS : public MeshShapeCollisionTraversalNode< kIOS, Shape, NarrowPhaseSolver> { @@ -179,7 +175,6 @@ class FCL_EXPORT 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, @@ -191,7 +186,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT MeshShapeCollisionTraversalNodeOBBRSS +class MeshShapeCollisionTraversalNodeOBBRSS : public MeshShapeCollisionTraversalNode< OBBRSS, Shape, NarrowPhaseSolver> { @@ -207,7 +202,6 @@ class FCL_EXPORT 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 d66527960..fc2ca971f 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 FCL_EXPORT ShapeBVHCollisionTraversalNode +class 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 68394d1ce..575807f44 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 FCL_EXPORT ShapeCollisionTraversalNode +class 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 d4fbdfbe7..ed405f592 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,7 +50,6 @@ namespace detail //============================================================================== template -FCL_EXPORT ShapeMeshCollisionTraversalNode::ShapeMeshCollisionTraversalNode() : ShapeBVHCollisionTraversalNode() { @@ -62,7 +61,6 @@ ShapeMeshCollisionTraversalNode::ShapeMeshCollisio //============================================================================== template -FCL_EXPORT void ShapeMeshCollisionTraversalNode::leafTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -131,7 +129,6 @@ void ShapeMeshCollisionTraversalNode::leafTesting( //============================================================================== template -FCL_EXPORT bool ShapeMeshCollisionTraversalNode::canStop() const { return this->request.isSatisfied(*(this->result)); @@ -139,7 +136,6 @@ bool ShapeMeshCollisionTraversalNode::canStop() co //============================================================================== template -FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNode& node, const Shape& model1, @@ -195,14 +191,12 @@ bool initialize( //============================================================================== template -FCL_EXPORT ShapeMeshCollisionTraversalNodeOBB::ShapeMeshCollisionTraversalNodeOBB() : ShapeMeshCollisionTraversalNode, NarrowPhaseSolver>() { } //============================================================================== template -FCL_EXPORT bool ShapeMeshCollisionTraversalNodeOBB::BVTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -213,7 +207,6 @@ 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, @@ -224,14 +217,12 @@ 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); @@ -242,7 +233,6 @@ 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, @@ -253,14 +243,12 @@ 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); @@ -271,7 +259,6 @@ 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, @@ -282,14 +269,12 @@ void ShapeMeshCollisionTraversalNodekIOS::leafTesting( //============================================================================== template -FCL_EXPORT ShapeMeshCollisionTraversalNodeOBBRSS::ShapeMeshCollisionTraversalNodeOBBRSS() : ShapeMeshCollisionTraversalNode, NarrowPhaseSolver>() { } //============================================================================== template -FCL_EXPORT bool ShapeMeshCollisionTraversalNodeOBBRSS::BVTesting(int b1, int b2) const { FCL_UNUSED(b1); @@ -300,7 +285,6 @@ 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, @@ -341,7 +325,6 @@ static bool setupShapeMeshCollisionOrientedNode(OrientedNode -FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeOBB& node, const Shape& model1, @@ -358,7 +341,6 @@ bool initialize( //============================================================================== template -FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodeRSS& node, const Shape& model1, @@ -375,7 +357,6 @@ bool initialize( //============================================================================== template -FCL_EXPORT bool initialize( ShapeMeshCollisionTraversalNodekIOS& node, const Shape& model1, @@ -392,7 +373,6 @@ 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 5ebcc0308..1514a5eec 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 FCL_EXPORT ShapeMeshCollisionTraversalNode +class ShapeMeshCollisionTraversalNode : public ShapeBVHCollisionTraversalNode { public: @@ -74,7 +74,6 @@ class FCL_EXPORT 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, @@ -88,7 +87,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 FCL_EXPORT ShapeMeshCollisionTraversalNodeOBB +class ShapeMeshCollisionTraversalNodeOBB : public ShapeMeshCollisionTraversalNode< Shape, OBB, NarrowPhaseSolver> { @@ -103,7 +102,6 @@ class FCL_EXPORT 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, @@ -115,7 +113,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT ShapeMeshCollisionTraversalNodeRSS +class ShapeMeshCollisionTraversalNodeRSS : public ShapeMeshCollisionTraversalNode, NarrowPhaseSolver> { public: @@ -130,7 +128,6 @@ class FCL_EXPORT 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, @@ -142,7 +139,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT ShapeMeshCollisionTraversalNodekIOS +class ShapeMeshCollisionTraversalNodekIOS : public ShapeMeshCollisionTraversalNode, NarrowPhaseSolver> { public: @@ -157,7 +154,6 @@ class FCL_EXPORT 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, @@ -169,7 +165,7 @@ bool initialize( CollisionResult& result); template -class FCL_EXPORT ShapeMeshCollisionTraversalNodeOBBRSS +class ShapeMeshCollisionTraversalNodeOBBRSS : public ShapeMeshCollisionTraversalNode, NarrowPhaseSolver> { public: @@ -184,7 +180,6 @@ class FCL_EXPORT 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-inl.h b/include/fcl/narrowphase/detail/traversal/collision_node-inl.h index 73d7a7293..2cc487d72 100644 --- a/include/fcl/narrowphase/detail/traversal/collision_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision_node-inl.h @@ -48,24 +48,31 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_NODE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL void collide(CollisionTraversalNodeBase* node, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void selfCollide(CollisionTraversalNodeBase* node, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void distance(DistanceTraversalNodeBase* node, BVHFrontList* front_list, int qsize); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void collide2(MeshCollisionTraversalNodeOBB* node, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void collide2(MeshCollisionTraversalNodeRSS* node, BVHFrontList* front_list); +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/collision_node.h b/include/fcl/narrowphase/detail/traversal/collision_node.h index c00a1a1b6..d15f4ee16 100644 --- a/include/fcl/narrowphase/detail/traversal/collision_node.h +++ b/include/fcl/narrowphase/detail/traversal/collision_node.h @@ -53,27 +53,22 @@ 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 d56cbe2c9..5310bdd6b 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 FCL_EXPORT BVHDistanceTraversalNode +class 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 50f4fc21c..8231fc94b 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 FCL_EXPORT BVHShapeDistanceTraversalNode +class BVHShapeDistanceTraversalNode : public DistanceTraversalNodeBase { public: diff --git a/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data-inl.h b/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data-inl.h index 9c567ace9..59561e6f6 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data-inl.h @@ -47,8 +47,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_CONSERVATIVE_ADVANCEMENT_STACK_DATA_BUILDING extern template -struct ConservativeAdvancementStackData; +struct FCL_EXPORT_EXPL_INST_DECL ConservativeAdvancementStackData; +#endif //============================================================================== template 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 fb95a940d..b372f8436 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 FCL_EXPORT ConservativeAdvancementStackData +struct 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 5fbeb5e0c..6e53347c6 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 @@ -49,8 +49,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_TRAVERSAL_NODE_BASE_BUILDING extern template -class FCL_EXPORT DistanceTraversalNodeBase; +class FCL_EXPORT_EXPL_INST_DECL DistanceTraversalNodeBase; +#endif //============================================================================== 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 e4a69a26c..72437edd0 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 FCL_EXPORT DistanceTraversalNodeBase : public TraversalNodeBase +class 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 44ddde5fe..4ce941a53 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 @@ -50,11 +50,13 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_MESH_CONSERVATIVE_ADVANCEMENT_TRAVERSAL_NODE_BUILDING extern template -class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS; +class FCL_EXPORT_EXPL_INST_DECL MeshConservativeAdvancementTraversalNodeRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshConservativeAdvancementTraversalNodeRSS& node, const BVHModel>& model1, @@ -65,10 +67,11 @@ bool initialize( //============================================================================== extern template -class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS; +class FCL_EXPORT_EXPL_INST_DECL MeshConservativeAdvancementTraversalNodeOBBRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshConservativeAdvancementTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -76,6 +79,7 @@ bool initialize( const BVHModel>& model2, const Transform3& tf2, double w); +#endif //============================================================================== 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 be72620e6..3f8035a6a 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 FCL_EXPORT MeshConservativeAdvancementTraversalNode +class MeshConservativeAdvancementTraversalNode : public MeshDistanceTraversalNode { public: @@ -97,7 +97,6 @@ class FCL_EXPORT 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, @@ -109,7 +108,7 @@ bool initialize( bool refit_bottomup = false); template -class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS +class MeshConservativeAdvancementTraversalNodeRSS : public MeshConservativeAdvancementTraversalNode> { public: @@ -150,7 +149,6 @@ 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, @@ -160,7 +158,7 @@ bool initialize( S w = 1); template -class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS +class MeshConservativeAdvancementTraversalNodeOBBRSS : public MeshConservativeAdvancementTraversalNode> { public: @@ -199,7 +197,6 @@ using MeshConservativeAdvancementTraversalNodeOBBRSSf = MeshConservativeAdvancem using MeshConservativeAdvancementTraversalNodeOBBRSSd = MeshConservativeAdvancementTraversalNodeOBBRSS; template -FCL_EXPORT bool initialize( MeshConservativeAdvancementTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -209,11 +206,9 @@ 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, @@ -228,7 +223,6 @@ bool meshConservativeAdvancementTraversalNodeCanStop( typename BV::S& delta_t); template -FCL_EXPORT bool meshConservativeAdvancementOrientedNodeCanStop( typename BV::S c, typename BV::S min_distance, @@ -243,7 +237,6 @@ 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 558149dc9..1226d0c02 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 @@ -47,11 +47,13 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_MESH_DISTANCE_TRAVERSAL_NODE_BUILDING extern template -class FCL_EXPORT MeshDistanceTraversalNodeRSS; +class FCL_EXPORT_EXPL_INST_DECL MeshDistanceTraversalNodeRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshDistanceTraversalNodeRSS& node, const BVHModel>& model1, @@ -63,10 +65,11 @@ bool initialize( //============================================================================== extern template -class FCL_EXPORT MeshDistanceTraversalNodekIOS; +class FCL_EXPORT_EXPL_INST_DECL MeshDistanceTraversalNodekIOS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshDistanceTraversalNodekIOS& node, const BVHModel>& model1, @@ -78,10 +81,11 @@ bool initialize( //============================================================================== extern template -class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS; +class FCL_EXPORT_EXPL_INST_DECL MeshDistanceTraversalNodeOBBRSS; //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL bool initialize( MeshDistanceTraversalNodeOBBRSS& node, const BVHModel>& model1, @@ -90,6 +94,7 @@ bool initialize( const Transform3& tf2, const DistanceRequest& request, DistanceResult& result); +#endif //============================================================================== 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 92f44617e..894d95683 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 FCL_EXPORT MeshDistanceTraversalNode : public BVHDistanceTraversalNode +class MeshDistanceTraversalNode : public BVHDistanceTraversalNode { public: @@ -80,7 +80,6 @@ class FCL_EXPORT 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, @@ -93,7 +92,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 FCL_EXPORT MeshDistanceTraversalNodeRSS +class MeshDistanceTraversalNodeRSS : public MeshDistanceTraversalNode> { public: @@ -123,7 +122,6 @@ 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, @@ -134,7 +132,7 @@ bool initialize( DistanceResult& result); template -class FCL_EXPORT MeshDistanceTraversalNodekIOS +class MeshDistanceTraversalNodekIOS : public MeshDistanceTraversalNode> { public: @@ -164,7 +162,6 @@ 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, @@ -175,7 +172,7 @@ bool initialize( DistanceResult& result); template -class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS +class MeshDistanceTraversalNodeOBBRSS : public MeshDistanceTraversalNode> { public: @@ -205,7 +202,6 @@ 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, @@ -216,7 +212,6 @@ bool initialize( DistanceResult& result); template -FCL_DEPRECATED_EXPORT void meshDistanceOrientedNodeLeafTesting( int b1, int b2, @@ -234,7 +229,6 @@ void meshDistanceOrientedNodeLeafTesting( DistanceResult& result); template -FCL_EXPORT void meshDistanceOrientedNodeLeafTesting( int b1, int b2, @@ -251,7 +245,6 @@ void meshDistanceOrientedNodeLeafTesting( DistanceResult& result); template -FCL_EXPORT void distancePreprocessOrientedNode( const BVHModel* model1, const BVHModel* model2, @@ -267,7 +260,6 @@ void distancePreprocessOrientedNode( DistanceResult& result); template -FCL_EXPORT void distancePreprocessOrientedNode( const BVHModel* model1, const BVHModel* model2, @@ -282,7 +274,6 @@ 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 a9f8d7597..68b97ec7b 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 FCL_EXPORT MeshShapeConservativeAdvancementTraversalNode +class MeshShapeConservativeAdvancementTraversalNode : public MeshShapeDistanceTraversalNode { public: @@ -140,7 +140,7 @@ bool meshShapeConservativeAdvancementOrientedNodeCanStop( typename BV::S& delta_t); template -class FCL_EXPORT MeshShapeConservativeAdvancementTraversalNodeRSS +class MeshShapeConservativeAdvancementTraversalNodeRSS : public MeshShapeConservativeAdvancementTraversalNode< RSS, Shape, NarrowPhaseSolver> { @@ -168,7 +168,7 @@ bool initialize( typename Shape::S w = 1); template -class FCL_EXPORT MeshShapeConservativeAdvancementTraversalNodeOBBRSS : +class 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 0d40e2ef5..058a5c8a3 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 FCL_EXPORT MeshShapeDistanceTraversalNode +class 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 FCL_EXPORT MeshShapeDistanceTraversalNodeRSS +class MeshShapeDistanceTraversalNodeRSS : public MeshShapeDistanceTraversalNode< RSS, Shape, NarrowPhaseSolver> { @@ -148,7 +148,7 @@ bool initialize( DistanceResult& result); template -class FCL_EXPORT MeshShapeDistanceTraversalNodekIOS +class MeshShapeDistanceTraversalNodekIOS : public MeshShapeDistanceTraversalNode, Shape, NarrowPhaseSolver> { public: @@ -177,7 +177,7 @@ bool initialize( DistanceResult& result); template -class FCL_EXPORT MeshShapeDistanceTraversalNodeOBBRSS +class 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 53176cfb8..3d176a089 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 FCL_EXPORT ShapeBVHDistanceTraversalNode +class 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 525df7215..3e92008e2 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 FCL_EXPORT ShapeConservativeAdvancementTraversalNode +class 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 bfd1e1f64..ad7499257 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 FCL_EXPORT ShapeDistanceTraversalNode +class 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 bf54940a5..069491bb7 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 FCL_EXPORT ShapeMeshConservativeAdvancementTraversalNode +class ShapeMeshConservativeAdvancementTraversalNode : public ShapeMeshDistanceTraversalNode { public: @@ -103,7 +103,7 @@ bool initialize( bool refit_bottomup = false); template -class FCL_EXPORT ShapeMeshConservativeAdvancementTraversalNodeRSS +class ShapeMeshConservativeAdvancementTraversalNodeRSS : public ShapeMeshConservativeAdvancementTraversalNode< Shape, RSS, NarrowPhaseSolver> { @@ -130,7 +130,7 @@ bool initialize( typename Shape::S w = 1); template -class FCL_EXPORT ShapeMeshConservativeAdvancementTraversalNodeOBBRSS +class 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 cdf8c8d00..c059ed10e 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,7 +108,6 @@ bool ShapeMeshDistanceTraversalNode::canStop(S c) //============================================================================== template -FCL_EXPORT bool initialize( ShapeMeshDistanceTraversalNode& node, const Shape& model1, @@ -349,7 +348,6 @@ static bool setupShapeMeshDistanceOrientedNode(OrientedNode -FCL_EXPORT bool initialize(ShapeMeshDistanceTraversalNodeRSS& node, const Shape& model1, const Transform3& tf1, const BVHModel>& model2, const Transform3& tf2, @@ -362,7 +360,6 @@ bool initialize(ShapeMeshDistanceTraversalNodeRSS& nod //============================================================================== template -FCL_EXPORT bool initialize(ShapeMeshDistanceTraversalNodekIOS& node, const Shape& model1, const Transform3& tf1, const BVHModel>& model2, const Transform3& tf2, @@ -375,7 +372,6 @@ 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 438f2053d..1777b8a8b 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 FCL_EXPORT ShapeMeshDistanceTraversalNode +class ShapeMeshDistanceTraversalNode : public ShapeBVHDistanceTraversalNode { public: @@ -89,7 +89,7 @@ bool initialize( bool refit_bottomup = false); template -class FCL_EXPORT ShapeMeshDistanceTraversalNodeRSS +class ShapeMeshDistanceTraversalNodeRSS : public ShapeMeshDistanceTraversalNode< Shape, RSS, NarrowPhaseSolver> { @@ -123,7 +123,7 @@ bool initialize( DistanceResult& result); template -class FCL_EXPORT ShapeMeshDistanceTraversalNodekIOS +class ShapeMeshDistanceTraversalNodekIOS : public ShapeMeshDistanceTraversalNode< Shape, kIOS, NarrowPhaseSolver> { @@ -157,7 +157,7 @@ bool initialize( DistanceResult& result); template -class FCL_EXPORT ShapeMeshDistanceTraversalNodeOBBRSS +class 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 2792dd204..f060a66d6 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 FCL_EXPORT MeshOcTreeCollisionTraversalNode +class 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 542008208..d51f77e69 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 FCL_EXPORT OcTreeCollisionTraversalNode +class 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 a5b904c89..0a8980ddc 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 FCL_EXPORT OcTreeMeshCollisionTraversalNode +class 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 4668dd16c..71c7a720a 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 FCL_EXPORT OcTreeShapeCollisionTraversalNode +class 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 c08ddccbc..002e5b670 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 FCL_EXPORT ShapeOcTreeCollisionTraversalNode +class 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 b299e786c..cafb22e9f 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 FCL_EXPORT MeshOcTreeDistanceTraversalNode +class 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 fcef5cc61..39b75c562 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 FCL_EXPORT OcTreeDistanceTraversalNode +class 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 c1a8cc2e9..726309b80 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 FCL_EXPORT OcTreeMeshDistanceTraversalNode +class 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 bf7abd963..1cad7e1bb 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 FCL_EXPORT OcTreeShapeDistanceTraversalNode +class 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 8b731e160..3e4041ec7 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 FCL_EXPORT ShapeOcTreeDistanceTraversalNode +class 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 a10d835f2..961103a15 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 FCL_EXPORT OcTreeSolver +class 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 96d849b98..f812a35ae 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h @@ -49,8 +49,10 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_NODE_BASE_BUILDING extern template -class FCL_EXPORT TraversalNodeBase; +class FCL_EXPORT_EXPL_INST_DECL TraversalNodeBase; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/detail/traversal/traversal_node_base.h b/include/fcl/narrowphase/detail/traversal/traversal_node_base.h index 2f3b1877e..abcc4ebdf 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 FCL_EXPORT TraversalNodeBase +class 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 1c46c1c41..1cce40833 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h @@ -51,36 +51,44 @@ namespace detail { //============================================================================== +#ifndef FCL_NARROWPHASE_DETAIL_TRAVERSAL_RECURSE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL void collisionRecurse(CollisionTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void collisionRecurse(MeshCollisionTraversalNodeOBB* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void collisionRecurse(MeshCollisionTraversalNodeRSS* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void selfCollisionRecurse(CollisionTraversalNodeBase* node, int b, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void distanceRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void distanceQueueRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list, int qsize); //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase* node, BVHFrontList* front_list); +#endif //============================================================================== template -FCL_EXPORT void collisionRecurse(CollisionTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list) { bool l1 = node->isFirstNodeLeaf(b1); @@ -130,7 +138,6 @@ 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); @@ -216,7 +223,6 @@ 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); @@ -234,7 +240,6 @@ 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); @@ -255,7 +260,6 @@ 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); @@ -318,7 +322,7 @@ void distanceRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFron //============================================================================== /** @brief Bounding volume test structure */ template -struct FCL_EXPORT BVT +struct BVT { /** @brief distance between bvs */ S d; @@ -330,7 +334,7 @@ struct FCL_EXPORT BVT //============================================================================== /** @brief Comparer between two BVT */ template -struct FCL_EXPORT BVT_Comparer +struct BVT_Comparer { bool operator() (const BVT& lhs, const BVT& rhs) const { @@ -340,7 +344,7 @@ struct FCL_EXPORT BVT_Comparer //============================================================================== template -struct FCL_EXPORT BVTQ +struct BVTQ { BVTQ() : qsize(2) {} @@ -382,7 +386,6 @@ struct FCL_EXPORT BVTQ //============================================================================== template -FCL_EXPORT void distanceQueueRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list, int qsize) { BVTQ bvtq; @@ -461,7 +464,6 @@ 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 d586c7e8c..cb9316f08 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_recurse.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_recurse.h @@ -52,37 +52,30 @@ 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-inl.h b/include/fcl/narrowphase/distance-inl.h index 3244631e3..a965efebf 100644 --- a/include/fcl/narrowphase/distance-inl.h +++ b/include/fcl/narrowphase/distance-inl.h @@ -46,7 +46,9 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_DISTANCE_BUILDING extern template +FCL_EXPORT_EXPL_INST_DECL double distance( const CollisionObject* o1, const CollisionObject* o2, @@ -55,10 +57,12 @@ double distance( //============================================================================== extern template +FCL_EXPORT_EXPL_INST_DECL double distance( const CollisionGeometry* o1, const Transform3& tf1, const CollisionGeometry* o2, const Transform3& tf2, const DistanceRequest& request, DistanceResult& result); +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/distance.h b/include/fcl/narrowphase/distance.h index 7629d264f..cda024fe5 100644 --- a/include/fcl/narrowphase/distance.h +++ b/include/fcl/narrowphase/distance.h @@ -49,13 +49,11 @@ 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-inl.h b/include/fcl/narrowphase/distance_request-inl.h index 1c63dea33..0f05e83a9 100644 --- a/include/fcl/narrowphase/distance_request-inl.h +++ b/include/fcl/narrowphase/distance_request-inl.h @@ -46,8 +46,10 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_DISTANCE_REQUEST_BUILDING extern template -struct DistanceRequest; +struct FCL_EXPORT_EXPL_INST_DECL DistanceRequest; +#endif //============================================================================== template diff --git a/include/fcl/narrowphase/distance_request.h b/include/fcl/narrowphase/distance_request.h index c157699be..8dc92a15d 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 FCL_EXPORT DistanceRequest +struct 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 424cffdf7..435e98a60 100644 --- a/include/fcl/narrowphase/distance_result-inl.h +++ b/include/fcl/narrowphase/distance_result-inl.h @@ -44,12 +44,13 @@ namespace fcl { //============================================================================== +#ifndef FCL_NARROWPHASE_DISTANCE_RESULT_BUILDING extern template -struct DistanceResult; +struct FCL_EXPORT_EXPL_INST_DECL DistanceResult; +#endif //============================================================================== template -FCL_EXPORT DistanceResult::DistanceResult(S min_distance_) : min_distance(min_distance_), o1(nullptr), @@ -62,7 +63,6 @@ DistanceResult::DistanceResult(S min_distance_) //============================================================================== template -FCL_EXPORT void DistanceResult::update( S distance, const CollisionGeometry* o1_, @@ -82,7 +82,6 @@ void DistanceResult::update( //============================================================================== template -FCL_EXPORT void DistanceResult::update( S distance, const CollisionGeometry* o1_, @@ -106,7 +105,6 @@ void DistanceResult::update( //============================================================================== template -FCL_EXPORT void DistanceResult::update(const DistanceResult& other_result) { if(min_distance > other_result.min_distance) @@ -123,7 +121,6 @@ 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 97373a32b..66ec7c26d 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 FCL_EXPORT DistanceResult +struct DistanceResult { public: diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 425724e78..a9946be19 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -56,23 +56,11 @@ set_target_properties(${PROJECT_NAME} PROPERTIES # 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") +if(FCL_HIDE_ALL_SYMBOLS AND NOT FCL_STATIC_LIBRARY) + set_target_properties(${PROJECT_NAME} PROPERTIES + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN TRUE + ) endif() # Use the IMPORTED target from newer versions of ccd-config.cmake if available, diff --git a/src/broadphase/broadphase_SSaP.cpp b/src/broadphase/broadphase_SSaP.cpp index dc9271654..ae1511970 100644 --- a/src/broadphase/broadphase_SSaP.cpp +++ b/src/broadphase/broadphase_SSaP.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_SSAP_BUILDING #include "fcl/broadphase/broadphase_SSaP-inl.h" namespace fcl { template -class SSaPCollisionManager; +class FCL_EXPORT SSaPCollisionManager; } // namespace diff --git a/src/broadphase/broadphase_SaP.cpp b/src/broadphase/broadphase_SaP.cpp index cee81176a..98af7c892 100644 --- a/src/broadphase/broadphase_SaP.cpp +++ b/src/broadphase/broadphase_SaP.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_SAP_BUILDING #include "fcl/broadphase/broadphase_SaP-inl.h" namespace fcl { template -class SaPCollisionManager; +class FCL_EXPORT SaPCollisionManager; } // namespace fcl diff --git a/src/broadphase/broadphase_bruteforce.cpp b/src/broadphase/broadphase_bruteforce.cpp index a8f533988..acb369cef 100644 --- a/src/broadphase/broadphase_bruteforce.cpp +++ b/src/broadphase/broadphase_bruteforce.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_BRUTEFORCE_BUILDING #include "fcl/broadphase/broadphase_bruteforce-inl.h" namespace fcl { template -class NaiveCollisionManager; +class FCL_EXPORT NaiveCollisionManager; } // namespace fcl diff --git a/src/broadphase/broadphase_collision_manager.cpp b/src/broadphase/broadphase_collision_manager.cpp index 3cecc24f7..b60b339b6 100644 --- a/src/broadphase/broadphase_collision_manager.cpp +++ b/src/broadphase/broadphase_collision_manager.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_COLLISION_MANAGER_BUILDING #include "fcl/broadphase/broadphase_collision_manager-inl.h" namespace fcl { template -class BroadPhaseCollisionManager; +class FCL_EXPORT BroadPhaseCollisionManager; } // namespace fcl diff --git a/src/broadphase/broadphase_continuous_collision_manager.cpp b/src/broadphase/broadphase_continuous_collision_manager.cpp index d06760a53..ce7f0b538 100644 --- a/src/broadphase/broadphase_continuous_collision_manager.cpp +++ b/src/broadphase/broadphase_continuous_collision_manager.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_CONTINUOUS_COLLISION_MANAGER_BUILDING #include "fcl/broadphase/broadphase_continuous_collision_manager-inl.h" namespace fcl { template -class BroadPhaseContinuousCollisionManager; +class FCL_EXPORT BroadPhaseContinuousCollisionManager; } // namespace fcl diff --git a/src/broadphase/broadphase_dynamic_AABB_tree.cpp b/src/broadphase/broadphase_dynamic_AABB_tree.cpp index 1da6ca3ca..70a46cad0 100644 --- a/src/broadphase/broadphase_dynamic_AABB_tree.cpp +++ b/src/broadphase/broadphase_dynamic_AABB_tree.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DYNAMIC_AABB_TREE_BUILDING #include "fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h" namespace fcl { template -class DynamicAABBTreeCollisionManager; +class FCL_EXPORT DynamicAABBTreeCollisionManager; } // namespace fcl diff --git a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp index 515feda97..26f9967f9 100644 --- a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp +++ b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DYNAMIC_AABB_TREE_ARRAY_BUILDING #include "fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h" namespace fcl { template -class DynamicAABBTreeCollisionManager_Array; +class FCL_EXPORT DynamicAABBTreeCollisionManager_Array; } // namespace fcl diff --git a/src/broadphase/broadphase_interval_tree.cpp b/src/broadphase/broadphase_interval_tree.cpp index 3567fb175..e5222ea82 100644 --- a/src/broadphase/broadphase_interval_tree.cpp +++ b/src/broadphase/broadphase_interval_tree.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_INTERVAL_TREE_BUILDING #include "fcl/broadphase/broadphase_interval_tree-inl.h" namespace fcl { template -class IntervalTreeCollisionManager; +class FCL_EXPORT IntervalTreeCollisionManager; } // namespace fcl diff --git a/src/broadphase/broadphase_spatialhash.cpp b/src/broadphase/broadphase_spatialhash.cpp index 3a9d90eee..778ad0e7c 100644 --- a/src/broadphase/broadphase_spatialhash.cpp +++ b/src/broadphase/broadphase_spatialhash.cpp @@ -35,13 +35,14 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_SPATIALHASH_BUILDING #include "fcl/broadphase/broadphase_spatialhash-inl.h" namespace fcl { template -class SpatialHashingCollisionManager< +class FCL_EXPORT SpatialHashingCollisionManager< double, detail::SimpleHashTable< AABB, CollisionObject*, detail::SpatialHash>>; diff --git a/src/broadphase/detail/interval_tree.cpp b/src/broadphase/detail/interval_tree.cpp index 28419ff2b..ce4928cde 100644 --- a/src/broadphase/detail/interval_tree.cpp +++ b/src/broadphase/detail/interval_tree.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DETAIL_INTERVAL_TREE_BUILDING #include "fcl/broadphase/detail/interval_tree-inl.h" namespace fcl @@ -44,10 +45,10 @@ namespace detail { template -struct it_recursion_node; +struct FCL_EXPORT it_recursion_node; template -class IntervalTree; +class FCL_EXPORT IntervalTree; } // namespace detail } // namespace fcl diff --git a/src/broadphase/detail/interval_tree_node.cpp b/src/broadphase/detail/interval_tree_node.cpp index b3779b78c..d3ceb3e03 100644 --- a/src/broadphase/detail/interval_tree_node.cpp +++ b/src/broadphase/detail/interval_tree_node.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DETAIL_INTERVAL_TREE_NODE_BUILDING #include "fcl/broadphase/detail/interval_tree_node-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -class IntervalTreeNode; +class FCL_EXPORT IntervalTreeNode; } // namespace detail } // namespace fcl diff --git a/src/broadphase/detail/morton.cpp b/src/broadphase/detail/morton.cpp index fa0419f72..58aef5690 100644 --- a/src/broadphase/detail/morton.cpp +++ b/src/broadphase/detail/morton.cpp @@ -36,6 +36,7 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DETAIL_MORTON_BUILDING #include "fcl/broadphase/detail/morton-inl.h" namespace fcl @@ -47,6 +48,7 @@ namespace detail //============================================================================== template +FCL_EXPORT uint32 quantize(double x, uint32 n); //============================================================================== @@ -86,11 +88,11 @@ uint64 morton_code60(uint32 x, uint32 y, uint32 z) //============================================================================== template -struct morton_functor; +struct FCL_EXPORT morton_functor; //============================================================================== template -struct morton_functor; +struct FCL_EXPORT morton_functor; } // namespace detail /// @endcond diff --git a/src/broadphase/detail/simple_interval.cpp b/src/broadphase/detail/simple_interval.cpp index 0271d9bde..b0a490027 100644 --- a/src/broadphase/detail/simple_interval.cpp +++ b/src/broadphase/detail/simple_interval.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DETAIL_SIMPLE_INTERVAL_BUILDING #include "fcl/broadphase/detail/simple_interval-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct SimpleInterval; +struct FCL_EXPORT SimpleInterval; } // namespace detail } // namespace fcl diff --git a/src/broadphase/detail/spatial_hash.cpp b/src/broadphase/detail/spatial_hash.cpp index 01a8e25aa..0ad898166 100644 --- a/src/broadphase/detail/spatial_hash.cpp +++ b/src/broadphase/detail/spatial_hash.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_BROADPHASE_DETAIL_SPATIAL_HASH_BUILDING #include "fcl/broadphase/detail/spatial_hash-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct SpatialHash; +struct FCL_EXPORT SpatialHash; } // namespace detail } // namespace fcl diff --git a/src/common/detail/profiler.cpp b/src/common/detail/profiler.cpp index 6d78ee0d5..47d4ffcdb 100644 --- a/src/common/detail/profiler.cpp +++ b/src/common/detail/profiler.cpp @@ -238,14 +238,14 @@ bool Profiler::Running() } //============================================================================== -struct FCL_EXPORT dataIntVal +struct dataIntVal { std::string name; unsigned long int value; }; //============================================================================== -struct FCL_EXPORT SortIntByValue +struct SortIntByValue { bool operator()(const dataIntVal &a, const dataIntVal &b) const { @@ -254,14 +254,14 @@ struct FCL_EXPORT SortIntByValue }; //============================================================================== -struct FCL_EXPORT dataDoubleVal +struct dataDoubleVal { std::string name; double value; }; //============================================================================== -struct FCL_EXPORT SortDoubleByValue +struct SortDoubleByValue { bool operator()(const dataDoubleVal &a, const dataDoubleVal &b) const { diff --git a/src/geometry/bvh/BVH_utility.cpp b/src/geometry/bvh/BVH_utility.cpp index bfcc8e882..33e48f17a 100644 --- a/src/geometry/bvh/BVH_utility.cpp +++ b/src/geometry/bvh/BVH_utility.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_BHV_UTILITY_BUILDING #include "fcl/geometry/bvh/BVH_utility-inl.h" namespace fcl @@ -42,11 +43,13 @@ namespace fcl //============================================================================== template +FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, double r); //============================================================================== template +FCL_EXPORT void BVHExpand( BVHModel>& model, const Variance3* ucs, double r); diff --git a/src/geometry/collision_geometry.cpp b/src/geometry/collision_geometry.cpp index a898ecde9..98799b173 100644 --- a/src/geometry/collision_geometry.cpp +++ b/src/geometry/collision_geometry.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_COLLISION_GEOMETRY_BUILDING #include "fcl/geometry/collision_geometry-inl.h" namespace fcl { template -class CollisionGeometry; +class FCL_EXPORT CollisionGeometry; } // namespace fcl diff --git a/src/geometry/octree/octree.cpp b/src/geometry/octree/octree.cpp index 1e392e9d2..6d5cd4741 100644 --- a/src/geometry/octree/octree.cpp +++ b/src/geometry/octree/octree.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_OCTREE_BUILDING #include "fcl/geometry/octree/octree-inl.h" #include "fcl/config.h" @@ -46,10 +47,11 @@ namespace fcl //============================================================================== template -class OcTree; +class FCL_EXPORT OcTree; //============================================================================== template +FCL_EXPORT void computeChildBV(const AABB& root_bv, unsigned int i, AABB& child_bv); } // namespace fcl diff --git a/src/geometry/shape/box.cpp b/src/geometry/shape/box.cpp index 9c96f1c86..2ad3d6ff5 100644 --- a/src/geometry/shape/box.cpp +++ b/src/geometry/shape/box.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_BOX_BUILDING #include "fcl/geometry/shape/box-inl.h" namespace fcl { template -class Box; +class FCL_EXPORT Box; } // namespace fcl diff --git a/src/geometry/shape/capsule.cpp b/src/geometry/shape/capsule.cpp index db46b668b..eb3cb9a82 100644 --- a/src/geometry/shape/capsule.cpp +++ b/src/geometry/shape/capsule.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_CAPSULE_BUILDING #include "fcl/geometry/shape/capsule-inl.h" namespace fcl { template -class Capsule; +class FCL_EXPORT Capsule; } // namespace fcl diff --git a/src/geometry/shape/cone.cpp b/src/geometry/shape/cone.cpp index f201ebbd0..2509d6b9e 100644 --- a/src/geometry/shape/cone.cpp +++ b/src/geometry/shape/cone.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_CONE_BUILDING #include "fcl/geometry/shape/cone-inl.h" namespace fcl { template -class Cone; +class FCL_EXPORT Cone; } // namespace fcl diff --git a/src/geometry/shape/convex.cpp b/src/geometry/shape/convex.cpp index 424292371..f0343ec88 100644 --- a/src/geometry/shape/convex.cpp +++ b/src/geometry/shape/convex.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_CONVEX_BUILDING #include "fcl/geometry/shape/convex-inl.h" namespace fcl { template -class Convex; +class FCL_EXPORT Convex; } // namespace fcl diff --git a/src/geometry/shape/cylinder.cpp b/src/geometry/shape/cylinder.cpp index 99933f9ac..d09999037 100644 --- a/src/geometry/shape/cylinder.cpp +++ b/src/geometry/shape/cylinder.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_CYLINDER_BUILDING #include "fcl/geometry/shape/cylinder-inl.h" namespace fcl { template -class Cylinder; +class FCL_EXPORT Cylinder; } // namespace fcl diff --git a/src/geometry/shape/ellipsoid.cpp b/src/geometry/shape/ellipsoid.cpp index d30baea30..b223c41a3 100644 --- a/src/geometry/shape/ellipsoid.cpp +++ b/src/geometry/shape/ellipsoid.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_ELLIPSOID_BUILDING #include "fcl/geometry/shape/ellipsoid-inl.h" namespace fcl { template -class Ellipsoid; +class FCL_EXPORT Ellipsoid; } // namespace fcl diff --git a/src/geometry/shape/halfspace.cpp b/src/geometry/shape/halfspace.cpp index f01e946a4..7f30d0090 100644 --- a/src/geometry/shape/halfspace.cpp +++ b/src/geometry/shape/halfspace.cpp @@ -35,15 +35,17 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_HALFSPACE_BUILDING #include "fcl/geometry/shape/halfspace-inl.h" namespace fcl { template -class Halfspace; +class FCL_EXPORT Halfspace; template +FCL_EXPORT Halfspace transform(const Halfspace& a, const Transform3& tf); } // namespace fcl diff --git a/src/geometry/shape/plane.cpp b/src/geometry/shape/plane.cpp index e61fa63b7..81fcec589 100644 --- a/src/geometry/shape/plane.cpp +++ b/src/geometry/shape/plane.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_PLANE_BUILDING #include "fcl/geometry/shape/plane-inl.h" namespace fcl @@ -42,10 +43,11 @@ namespace fcl //============================================================================== template -class Plane; +class FCL_EXPORT Plane; //============================================================================== template +FCL_EXPORT Plane transform(const Plane& a, const Transform3& tf); } // namespace fcl diff --git a/src/geometry/shape/shape_base.cpp b/src/geometry/shape/shape_base.cpp index 179d73ebb..b2b9bb2cc 100644 --- a/src/geometry/shape/shape_base.cpp +++ b/src/geometry/shape/shape_base.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_BASE_BUILDING #include "fcl/geometry/shape/shape_base-inl.h" namespace fcl { template -class ShapeBase; +class FCL_EXPORT ShapeBase; } // namespace fcl diff --git a/src/geometry/shape/sphere.cpp b/src/geometry/shape/sphere.cpp index b8a857808..2f2aff0e4 100644 --- a/src/geometry/shape/sphere.cpp +++ b/src/geometry/shape/sphere.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_SPHERE_BUILDING #include "fcl/geometry/shape/sphere-inl.h" namespace fcl { template -class Sphere; +class FCL_EXPORT Sphere; } // namespace fcl diff --git a/src/geometry/shape/triangle_p.cpp b/src/geometry/shape/triangle_p.cpp index 86546be31..2fc1ffe02 100644 --- a/src/geometry/shape/triangle_p.cpp +++ b/src/geometry/shape/triangle_p.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_TRIANGLE_P_BUILDING #include "fcl/geometry/shape/triangle_p-inl.h" namespace fcl { template -class TriangleP; +class FCL_EXPORT TriangleP; } // namespace fcl diff --git a/src/geometry/shape/utility.cpp b/src/geometry/shape/utility.cpp index a64ee2511..65fa8f99f 100644 --- a/src/geometry/shape/utility.cpp +++ b/src/geometry/shape/utility.cpp @@ -35,72 +35,89 @@ /** @author Jia Pan */ +#define FCL_GEOMETRY_SHAPE_UTILITY_BUILDING #include "fcl/geometry/shape/utility-inl.h" namespace fcl { //============================================================================== 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); //============================================================================== @@ -109,119 +126,119 @@ namespace detail { //============================================================================== template -struct ComputeBVImpl, Box>; +struct FCL_EXPORT ComputeBVImpl, Box>; //============================================================================== template -struct ComputeBVImpl, Box>; +struct FCL_EXPORT ComputeBVImpl, Box>; //============================================================================== template -struct ComputeBVImpl, Capsule>; +struct FCL_EXPORT ComputeBVImpl, Capsule>; //============================================================================== template -struct ComputeBVImpl, Capsule>; +struct FCL_EXPORT ComputeBVImpl, Capsule>; //============================================================================== template -struct ComputeBVImpl, Cone>; +struct FCL_EXPORT ComputeBVImpl, Cone>; //============================================================================== template -struct ComputeBVImpl, Cone>; +struct FCL_EXPORT ComputeBVImpl, Cone>; //============================================================================== template -struct ComputeBVImpl, Cylinder>; +struct FCL_EXPORT ComputeBVImpl, Cylinder>; //============================================================================== template -struct ComputeBVImpl, Cylinder>; +struct FCL_EXPORT ComputeBVImpl, Cylinder>; //============================================================================== template -struct ComputeBVImpl, Ellipsoid>; +struct FCL_EXPORT ComputeBVImpl, Ellipsoid>; //============================================================================== template -struct ComputeBVImpl, Ellipsoid>; +struct FCL_EXPORT ComputeBVImpl, Ellipsoid>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Halfspace>; +struct FCL_EXPORT ComputeBVImpl, Halfspace>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Plane>; +struct FCL_EXPORT ComputeBVImpl, Plane>; //============================================================================== template -struct ComputeBVImpl, Sphere>; +struct FCL_EXPORT ComputeBVImpl, Sphere>; //============================================================================== template -struct ComputeBVImpl, Sphere>; +struct FCL_EXPORT ComputeBVImpl, Sphere>; //============================================================================== template -struct ComputeBVImpl, TriangleP>; +struct FCL_EXPORT ComputeBVImpl, TriangleP>; //============================================================================== } // namespace detail diff --git a/src/math/bv/AABB.cpp b/src/math/bv/AABB.cpp index a7c382422..844e0894c 100644 --- a/src/math/bv/AABB.cpp +++ b/src/math/bv/AABB.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_AABB_BUILDING #include "fcl/math/bv/AABB-inl.h" namespace fcl { template -class AABB; +class FCL_EXPORT AABB; } // namespace fcl diff --git a/src/math/bv/OBB.cpp b/src/math/bv/OBB.cpp index 1cfa1f6db..f548fdbf0 100644 --- a/src/math/bv/OBB.cpp +++ b/src/math/bv/OBB.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_OBB_BUILDING #include "fcl/math/bv/OBB-inl.h" namespace fcl @@ -42,22 +43,26 @@ namespace fcl //============================================================================== template -class OBB; +class FCL_EXPORT OBB; //============================================================================== template +FCL_EXPORT void computeVertices(const OBB& b, Vector3 vertices[8]); //============================================================================== template +FCL_EXPORT OBB merge_largedist(const OBB& b1, const OBB& b2); //============================================================================== template +FCL_EXPORT OBB merge_smalldist(const OBB& b1, const OBB& b2); //============================================================================== template +FCL_EXPORT bool obbDisjoint( const Matrix3& B, const Vector3& T, @@ -66,6 +71,7 @@ bool obbDisjoint( //============================================================================== template +FCL_EXPORT bool obbDisjoint( const Transform3& tf, const Vector3& a, diff --git a/src/math/bv/OBBRSS.cpp b/src/math/bv/OBBRSS.cpp index 10cb7941a..48e30acc8 100644 --- a/src/math/bv/OBBRSS.cpp +++ b/src/math/bv/OBBRSS.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_OBBRSS_BUILDING #include "fcl/math/bv/OBBRSS-inl.h" namespace fcl @@ -42,10 +43,11 @@ namespace fcl //============================================================================== template -class OBBRSS; +class FCL_EXPORT OBBRSS; //============================================================================== template +FCL_EXPORT OBBRSS translate(const OBBRSS& bv, const Vector3& t); } // namespace fcl diff --git a/src/math/bv/RSS.cpp b/src/math/bv/RSS.cpp index c7db037ca..dec171e98 100644 --- a/src/math/bv/RSS.cpp +++ b/src/math/bv/RSS.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_RSS_BUILDING #include "fcl/math/bv/RSS-inl.h" namespace fcl @@ -42,14 +43,16 @@ namespace fcl //============================================================================== template -class RSS; +class FCL_EXPORT RSS; //============================================================================== template +FCL_EXPORT void clipToRange(double& val, double a, double b); //============================================================================== template +FCL_EXPORT void segCoords( double& t, double& u, @@ -61,6 +64,7 @@ void segCoords( //============================================================================== template +FCL_EXPORT bool inVoronoi( double a, double b, @@ -72,6 +76,7 @@ bool inVoronoi( //============================================================================== template +FCL_EXPORT double rectDistance( const Matrix3& Rab, const Vector3& Tab, @@ -82,6 +87,7 @@ double rectDistance( //============================================================================== template +FCL_EXPORT double rectDistance( const Transform3& tfab, const double a[2], @@ -91,6 +97,7 @@ double rectDistance( //============================================================================== template +FCL_EXPORT RSS translate(const RSS& bv, const Vector3& t); } // namespace fcl diff --git a/src/math/bv/kDOP.cpp b/src/math/bv/kDOP.cpp index 8879a4409..6305d9ac5 100644 --- a/src/math/bv/kDOP.cpp +++ b/src/math/bv/kDOP.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_KDOP_BUILDING #include "fcl/math/bv/kDOP-inl.h" namespace fcl @@ -42,34 +43,39 @@ namespace fcl //============================================================================== template -class KDOP; +class FCL_EXPORT KDOP; //============================================================================== template -class KDOP; +class FCL_EXPORT KDOP; //============================================================================== template -class KDOP; +class FCL_EXPORT KDOP; //============================================================================== template +FCL_EXPORT void minmax(double a, double b, double& minv, double& maxv); //============================================================================== template +FCL_EXPORT void minmax(double p, double& minv, double& maxv); //============================================================================== template +FCL_EXPORT void getDistances(const Vector3& p, double* d); //============================================================================== template +FCL_EXPORT void getDistances(const Vector3& p, double* d); //============================================================================== template +FCL_EXPORT void getDistances(const Vector3& p, double* d); } // namespace fcl diff --git a/src/math/bv/kIOS.cpp b/src/math/bv/kIOS.cpp index 4c17b9224..c038a7526 100644 --- a/src/math/bv/kIOS.cpp +++ b/src/math/bv/kIOS.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_KIOS_BUILDING #include "fcl/math/bv/kIOS-inl.h" namespace fcl { template -class kIOS; +class FCL_EXPORT kIOS; } // namespace fcl diff --git a/src/math/bv/utility.cpp b/src/math/bv/utility.cpp index d2e44a9c9..cef40b1df 100644 --- a/src/math/bv/utility.cpp +++ b/src/math/bv/utility.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_BV_UTILITY_BUILDING #include "fcl/math/bv/utility-inl.h" namespace fcl { @@ -46,22 +47,27 @@ namespace OBB_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(const Vector3d* const ps, OBB& bv); //============================================================================== template +FCL_EXPORT void fit2(const Vector3d* const ps, OBB& bv); //============================================================================== template +FCL_EXPORT void fit3(const Vector3d* const ps, OBB& bv); //============================================================================== template +FCL_EXPORT void fit6(const Vector3d* const ps, OBB& bv); //============================================================================== template +FCL_EXPORT void fitn(const Vector3d* const ps, int n, OBB& bv); //============================================================================== @@ -74,22 +80,27 @@ namespace RSS_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(const Vector3d* const ps, RSS& bv); //============================================================================== template +FCL_EXPORT void fit2(const Vector3d* const ps, RSS& bv); //============================================================================== template +FCL_EXPORT void fit3(const Vector3d* const ps, RSS& bv); //============================================================================== template +FCL_EXPORT void fit6(const Vector3d* const ps, RSS& bv); //============================================================================== template +FCL_EXPORT void fitn(const Vector3d* const ps, int n, RSS& bv); //============================================================================== @@ -102,18 +113,22 @@ namespace kIOS_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(const Vector3d* const ps, kIOS& bv); //============================================================================== template +FCL_EXPORT void fit2(const Vector3d* const ps, kIOS& bv); //============================================================================== template +FCL_EXPORT void fit3(const Vector3d* const ps, kIOS& bv); //============================================================================== template +FCL_EXPORT void fitn(const Vector3d* const ps, int n, kIOS& bv); //============================================================================== @@ -126,18 +141,22 @@ namespace OBBRSS_fit_functions { //============================================================================== template +FCL_EXPORT void fit1(const Vector3d* const ps, OBBRSS& bv); //============================================================================== template +FCL_EXPORT void fit2(const Vector3d* const ps, OBBRSS& bv); //============================================================================== template +FCL_EXPORT void fit3(const Vector3d* const ps, OBBRSS& bv); //============================================================================== template +FCL_EXPORT void fitn(const Vector3d* const ps, int n, OBBRSS& bv); //============================================================================== @@ -146,55 +165,55 @@ void fitn(const Vector3d* const ps, int n, OBBRSS& bv); //============================================================================== template -struct Fitter>; +struct FCL_EXPORT Fitter>; //============================================================================== template -struct Fitter>; +struct FCL_EXPORT Fitter>; //============================================================================== template -struct Fitter>; +struct FCL_EXPORT Fitter>; //============================================================================== template -struct Fitter>; +struct FCL_EXPORT Fitter>; //============================================================================== template -class ConvertBVImpl, AABB>; +class FCL_EXPORT ConvertBVImpl, AABB>; //============================================================================== template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== template -class ConvertBVImpl, OBB>; +class FCL_EXPORT ConvertBVImpl, OBB>; //============================================================================== template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; //============================================================================== template -class ConvertBVImpl, RSS>; +class FCL_EXPORT ConvertBVImpl, RSS>; } // namespace detail } // namespace fcl diff --git a/src/math/detail/polysolver.cpp b/src/math/detail/polysolver.cpp index 3aedfa003..b812d5415 100644 --- a/src/math/detail/polysolver.cpp +++ b/src/math/detail/polysolver.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_DETAIL_POLYSOLVER_BUILDING #include "fcl/math/detail/polysolver-inl.h" namespace fcl @@ -43,7 +44,7 @@ namespace fcl namespace detail { template -class PolySolver; +class FCL_EXPORT PolySolver; } // namespace detail } // namespace fcl diff --git a/src/math/detail/project.cpp b/src/math/detail/project.cpp index e5bbe9472..b9fad0474 100644 --- a/src/math/detail/project.cpp +++ b/src/math/detail/project.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_DETAIL_PROJECT_BUILDING #include "fcl/math/detail/project-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -class Project; +class FCL_EXPORT Project; } // namespace detail } // namespace fcl diff --git a/src/math/geometry.cpp b/src/math/geometry.cpp index 577edcd9c..751279b99 100644 --- a/src/math/geometry.cpp +++ b/src/math/geometry.cpp @@ -35,43 +35,52 @@ /** @author Jia Pan */ +#define FCL_MATH_GEOMETRY_BUILDING #include "fcl/math/geometry-inl.h" namespace fcl { //============================================================================== template +FCL_EXPORT void normalize(Vector3d& v, bool* signal); //============================================================================== template +FCL_EXPORT void hat(Matrix3d& mat, const Vector3d& vec); //============================================================================== template +FCL_EXPORT void eigen(const Matrix3d& m, Vector3d& dout, Matrix3d& vout); //============================================================================== template +FCL_EXPORT void eigen_old(const Matrix3d& m, Vector3d& dout, Matrix3d& vout); //============================================================================== template +FCL_EXPORT void axisFromEigen( const Matrix3d& eigenV, const Vector3d& eigenS, Matrix3d& axis); //============================================================================== template +FCL_EXPORT void axisFromEigen(const Matrix3d& eigenV, const Vector3d& eigenS, Transform3d& tf); //============================================================================== template +FCL_EXPORT Matrix3d generateCoordinateSystem(const Vector3d& x_axis); //============================================================================== template +FCL_EXPORT void getRadiusAndOriginAndRectangleSize( const Vector3d* const ps, const Vector3d* const ps2, @@ -85,6 +94,7 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== template +FCL_EXPORT void getRadiusAndOriginAndRectangleSize( const Vector3d* const ps, const Vector3d* const ps2, @@ -97,6 +107,7 @@ void getRadiusAndOriginAndRectangleSize( //============================================================================== template +FCL_EXPORT void circumCircleComputation( const Vector3d& a, const Vector3d& b, @@ -106,6 +117,7 @@ void circumCircleComputation( //============================================================================== template +FCL_EXPORT double maximumDistance( const Vector3d* const ps, const Vector3d* const ps2, @@ -116,6 +128,7 @@ double maximumDistance( //============================================================================== template +FCL_EXPORT void getExtentAndCenter( const Vector3d* const ps, const Vector3d* const ps2, @@ -128,6 +141,7 @@ void getExtentAndCenter( //============================================================================== template +FCL_EXPORT void getCovariance( const Vector3d* const ps, const Vector3d* const ps2, @@ -141,6 +155,7 @@ namespace detail { //============================================================================== template +FCL_EXPORT double maximumDistance_mesh( const Vector3d* const ps, const Vector3d* const ps2, @@ -151,6 +166,7 @@ double maximumDistance_mesh( //============================================================================== template +FCL_EXPORT double maximumDistance_pointcloud( const Vector3d* const ps, const Vector3d* const ps2, @@ -160,6 +176,7 @@ double maximumDistance_pointcloud( //============================================================================== template +FCL_EXPORT void getExtentAndCenter_pointcloud( const Vector3d* const ps, const Vector3d* const ps2, @@ -171,6 +188,7 @@ void getExtentAndCenter_pointcloud( //============================================================================== template +FCL_EXPORT void getExtentAndCenter_mesh( const Vector3d* const ps, const Vector3d* const ps2, diff --git a/src/math/motion/interp_motion.cpp b/src/math/motion/interp_motion.cpp index aa5e592c9..3d4c2838a 100644 --- a/src/math/motion/interp_motion.cpp +++ b/src/math/motion/interp_motion.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_INTERP_MOTION_BUILDING #include "fcl/math/motion/interp_motion-inl.h" namespace fcl { template -class InterpMotion; +class FCL_EXPORT InterpMotion; } // namespace fcl diff --git a/src/math/motion/motion_base.cpp b/src/math/motion/motion_base.cpp index 981cc8198..fb1bb0ee6 100644 --- a/src/math/motion/motion_base.cpp +++ b/src/math/motion/motion_base.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_BASE_BUILDING #include "fcl/math/motion/motion_base-inl.h" namespace fcl { template -class MotionBase; +class FCL_EXPORT MotionBase; } // namespace fcl diff --git a/src/math/motion/screw_motion.cpp b/src/math/motion/screw_motion.cpp index 65d1066ea..3a80f8579 100644 --- a/src/math/motion/screw_motion.cpp +++ b/src/math/motion/screw_motion.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_SCREW_MOTION_BUILDING #include "fcl/math/motion/screw_motion-inl.h" namespace fcl { template -class ScrewMotion; +class FCL_EXPORT ScrewMotion; } // namespace fcl diff --git a/src/math/motion/spline_motion.cpp b/src/math/motion/spline_motion.cpp index 16601e247..66a07740c 100644 --- a/src/math/motion/spline_motion.cpp +++ b/src/math/motion/spline_motion.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_SPLINE_MOTION_BUILDING #include "fcl/math/motion/spline_motion-inl.h" namespace fcl { template -class SplineMotion; +class FCL_EXPORT SplineMotion; } // namespace fcl diff --git a/src/math/motion/taylor_model/interval.cpp b/src/math/motion/taylor_model/interval.cpp index 236ec3d46..380995867 100644 --- a/src/math/motion/taylor_model/interval.cpp +++ b/src/math/motion/taylor_model/interval.cpp @@ -36,6 +36,7 @@ // This code is based on code developed by Stephane Redon at UNC and Inria for the CATCH library: http://graphics.ewha.ac.kr/CATCH/ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_INTERVAL_BUILDING #include "fcl/math/motion/taylor_model/interval-inl.h" namespace fcl @@ -43,14 +44,16 @@ namespace fcl //============================================================================== template -struct Interval; +struct FCL_EXPORT Interval; //============================================================================== template +FCL_EXPORT Interval bound(const Interval& i, double v); //============================================================================== template +FCL_EXPORT Interval bound(const Interval& i, const Interval& other); } // namespace fcl diff --git a/src/math/motion/taylor_model/interval_matrix.cpp b/src/math/motion/taylor_model/interval_matrix.cpp index 1bb0f9280..02f2dd85d 100644 --- a/src/math/motion/taylor_model/interval_matrix.cpp +++ b/src/math/motion/taylor_model/interval_matrix.cpp @@ -35,6 +35,7 @@ // This code is based on code developed by Stephane Redon at UNC and Inria for the CATCH library: http://graphics.ewha.ac.kr/CATCH/ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_INTERVAL_MATRIX_BUILDING #include "fcl/math/motion/taylor_model/interval_matrix-inl.h" namespace fcl @@ -42,10 +43,11 @@ namespace fcl //============================================================================== template -struct IMatrix3; +struct FCL_EXPORT IMatrix3; //============================================================================== template +FCL_EXPORT IMatrix3 rotationConstrain(const IMatrix3& m); } // namespace fcl diff --git a/src/math/motion/taylor_model/interval_vector.cpp b/src/math/motion/taylor_model/interval_vector.cpp index 9e216a637..a225c3664 100644 --- a/src/math/motion/taylor_model/interval_vector.cpp +++ b/src/math/motion/taylor_model/interval_vector.cpp @@ -35,6 +35,7 @@ // This code is based on code developed by Stephane Redon at UNC and Inria for the CATCH library: http://graphics.ewha.ac.kr/CATCH/ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_INTERVAL_VECTOR_BUILDING #include "fcl/math/motion/taylor_model/interval_vector-inl.h" namespace fcl @@ -42,14 +43,16 @@ namespace fcl //============================================================================== template -struct IVector3; +struct FCL_EXPORT 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/src/math/motion/taylor_model/taylor_matrix.cpp b/src/math/motion/taylor_model/taylor_matrix.cpp index baa926fd8..ce206ff61 100644 --- a/src/math/motion/taylor_model/taylor_matrix.cpp +++ b/src/math/motion/taylor_model/taylor_matrix.cpp @@ -35,6 +35,7 @@ // This code is based on code developed by Stephane Redon at UNC and Inria for the CATCH library: http://graphics.ewha.ac.kr/CATCH/ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_TAYLOR_MATRIX_BUILDING #include "fcl/math/motion/taylor_model/taylor_matrix-inl.h" namespace fcl @@ -42,34 +43,41 @@ namespace fcl //============================================================================== template -class TMatrix3; +class FCL_EXPORT 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 * (double 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/src/math/motion/taylor_model/taylor_model.cpp b/src/math/motion/taylor_model/taylor_model.cpp index 58a98d73e..8273076c1 100644 --- a/src/math/motion/taylor_model/taylor_model.cpp +++ b/src/math/motion/taylor_model/taylor_model.cpp @@ -38,6 +38,7 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_BUILDING #include "fcl/math/motion/taylor_model/taylor_model-inl.h" namespace fcl @@ -45,30 +46,36 @@ namespace fcl //============================================================================== template -class TaylorModel; +class FCL_EXPORT TaylorModel; //============================================================================== template +FCL_EXPORT TaylorModel operator * (double d, const TaylorModel& a); //============================================================================== template +FCL_EXPORT TaylorModel operator + (double d, const TaylorModel& a); //============================================================================== template +FCL_EXPORT TaylorModel operator - (double d, const TaylorModel& a); //============================================================================== template +FCL_EXPORT void generateTaylorModelForCosFunc(TaylorModel& tm, double w, double q0); //============================================================================== template +FCL_EXPORT void generateTaylorModelForSinFunc(TaylorModel& tm, double w, double q0); //============================================================================== template +FCL_EXPORT void generateTaylorModelForLinearFunc(TaylorModel& tm, double p, double v); } // namespace fcl diff --git a/src/math/motion/taylor_model/taylor_vector.cpp b/src/math/motion/taylor_model/taylor_vector.cpp index 81acc6efb..e8be33956 100644 --- a/src/math/motion/taylor_model/taylor_vector.cpp +++ b/src/math/motion/taylor_model/taylor_vector.cpp @@ -35,6 +35,7 @@ // This code is based on code developed by Stephane Redon at UNC and Inria for the CATCH library: http://graphics.ewha.ac.kr/CATCH/ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_TAYLOR_VECTOR_BUILDING #include "fcl/math/motion/taylor_model/taylor_vector-inl.h" namespace fcl @@ -42,22 +43,26 @@ namespace fcl //============================================================================== template -class TVector3; +class FCL_EXPORT 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/src/math/motion/taylor_model/time_interval.cpp b/src/math/motion/taylor_model/time_interval.cpp index 2587db49a..163e67561 100644 --- a/src/math/motion/taylor_model/time_interval.cpp +++ b/src/math/motion/taylor_model/time_interval.cpp @@ -35,12 +35,13 @@ // This code is based on code developed by Stephane Redon at UNC and Inria for the CATCH library: http://graphics.ewha.ac.kr/CATCH/ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TAYLOR_MODEL_TIME_INTERVAL_BUILDING #include "fcl/math/motion/taylor_model/time_interval-inl.h" namespace fcl { template -struct TimeInterval; +struct FCL_EXPORT TimeInterval; } // namespace fcl diff --git a/src/math/motion/translation_motion.cpp b/src/math/motion/translation_motion.cpp index abfbb4165..459501bfb 100644 --- a/src/math/motion/translation_motion.cpp +++ b/src/math/motion/translation_motion.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TRANSLATION_MOTION_BUILDING #include "fcl/math/motion/translation_motion-inl.h" namespace fcl { template -class TranslationMotion; +class FCL_EXPORT TranslationMotion; } // namespace fcl diff --git a/src/math/motion/triangle_motion_bound_visitor.cpp b/src/math/motion/triangle_motion_bound_visitor.cpp index 1fd1f2b01..652ded42d 100644 --- a/src/math/motion/triangle_motion_bound_visitor.cpp +++ b/src/math/motion/triangle_motion_bound_visitor.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_MOTION_TRIANGLE_MOTION_BOUND_VISITOR_BUILDING #include "fcl/math/motion/triangle_motion_bound_visitor-inl.h" namespace fcl { template -class TriangleMotionBoundVisitor; +class FCL_EXPORT TriangleMotionBoundVisitor; } // namespace fcl diff --git a/src/math/rng.cpp b/src/math/rng.cpp index c997dab12..d319b764d 100644 --- a/src/math/rng.cpp +++ b/src/math/rng.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_MATH_RNG_BUILDING #include "fcl/math/rng-inl.h" namespace fcl @@ -42,6 +43,6 @@ namespace fcl //============================================================================== template -class RNG; +class FCL_EXPORT RNG; } // namespace fcl diff --git a/src/math/sampler/sampler_base.cpp b/src/math/sampler/sampler_base.cpp index 593cbdc9c..1cd16d319 100644 --- a/src/math/sampler/sampler_base.cpp +++ b/src/math/sampler/sampler_base.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_BASE_BUILDING #include "fcl/math/sampler/sampler_base.h" namespace fcl { template -class SamplerBase; +class FCL_EXPORT SamplerBase; } // namespace fcl diff --git a/src/math/sampler/sampler_se2.cpp b/src/math/sampler/sampler_se2.cpp index 11495c1f9..a692f1b20 100644 --- a/src/math/sampler/sampler_se2.cpp +++ b/src/math/sampler/sampler_se2.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_SE2_BUILDING #include "fcl/math/sampler/sampler_se2-inl.h" namespace fcl { template -class SamplerSE2; +class FCL_EXPORT SamplerSE2; } // namespace fcl diff --git a/src/math/sampler/sampler_se2_disk.cpp b/src/math/sampler/sampler_se2_disk.cpp index d70aab9bb..f9d84d55c 100644 --- a/src/math/sampler/sampler_se2_disk.cpp +++ b/src/math/sampler/sampler_se2_disk.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_SE2_DISK_BUILDING #include "fcl/math/sampler/sampler_se2_disk-inl.h" namespace fcl { template -class SamplerSE2_disk; +class FCL_EXPORT SamplerSE2_disk; } // namespace fcl diff --git a/src/math/sampler/sampler_se3_euler.cpp b/src/math/sampler/sampler_se3_euler.cpp index 3f97745e1..f251f5c3e 100644 --- a/src/math/sampler/sampler_se3_euler.cpp +++ b/src/math/sampler/sampler_se3_euler.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_SE3_EULER_BUILDING #include "fcl/math/sampler/sampler_se3_euler-inl.h" namespace fcl { template -class SamplerSE3Euler; +class FCL_EXPORT SamplerSE3Euler; } // namespace fcl diff --git a/src/math/sampler/sampler_se3_euler_ball.cpp b/src/math/sampler/sampler_se3_euler_ball.cpp index 3570439c3..9a1eba122 100644 --- a/src/math/sampler/sampler_se3_euler_ball.cpp +++ b/src/math/sampler/sampler_se3_euler_ball.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_SE3_EULER_BALL_BUILDING #include "fcl/math/sampler/sampler_se3_euler_ball-inl.h" namespace fcl { template -class SamplerSE3Euler_ball; +class FCL_EXPORT SamplerSE3Euler_ball; } // namespace fcl diff --git a/src/math/sampler/sampler_se3_quat.cpp b/src/math/sampler/sampler_se3_quat.cpp index 0d0999e7c..ef7f197d1 100644 --- a/src/math/sampler/sampler_se3_quat.cpp +++ b/src/math/sampler/sampler_se3_quat.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_SE3_QUAT_BUILDING #include "fcl/math/sampler/sampler_se3_quat-inl.h" namespace fcl { template -class SamplerSE3Quat; +class FCL_EXPORT SamplerSE3Quat; } // namespace fcl diff --git a/src/math/sampler/sampler_se3_quat_ball.cpp b/src/math/sampler/sampler_se3_quat_ball.cpp index 0db789a15..6c4689f11 100644 --- a/src/math/sampler/sampler_se3_quat_ball.cpp +++ b/src/math/sampler/sampler_se3_quat_ball.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_SAMPLER_SE3_QUAT_BALL_BUILDING #include "fcl/math/sampler/sampler_se3_quat_ball-inl.h" namespace fcl { template -class SamplerSE3Quat_ball; +class FCL_EXPORT SamplerSE3Quat_ball; } // namespace fcl diff --git a/src/math/variance3.cpp b/src/math/variance3.cpp index 91255f896..1a361d0e2 100644 --- a/src/math/variance3.cpp +++ b/src/math/variance3.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_MATH_VARIANCE3_BUILDING #include "fcl/math/variance3-inl.h" namespace fcl { template -class Variance3; +class FCL_EXPORT Variance3; } // namespace fcl diff --git a/src/narrowphase/collision.cpp b/src/narrowphase/collision.cpp index ad5186158..fb574947d 100644 --- a/src/narrowphase/collision.cpp +++ b/src/narrowphase/collision.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_COLLISION_BUILDING #include "fcl/narrowphase/collision-inl.h" namespace fcl @@ -42,6 +43,7 @@ namespace fcl //============================================================================== template +FCL_EXPORT std::size_t collide( const CollisionObject* o1, const CollisionObject* o2, @@ -50,6 +52,7 @@ std::size_t collide( //============================================================================== template +FCL_EXPORT std::size_t collide( const CollisionGeometry* o1, const Transform3& tf1, diff --git a/src/narrowphase/collision_object.cpp b/src/narrowphase/collision_object.cpp index 6362db1f6..cf7011707 100644 --- a/src/narrowphase/collision_object.cpp +++ b/src/narrowphase/collision_object.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_COLLISION_OBJECT_BUILDING #include "fcl/narrowphase/collision_object-inl.h" namespace fcl { template -class CollisionObject; +class FCL_EXPORT CollisionObject; } // namespace fcl diff --git a/src/narrowphase/collision_request.cpp b/src/narrowphase/collision_request.cpp index d47be1ea1..0537d8963 100644 --- a/src/narrowphase/collision_request.cpp +++ b/src/narrowphase/collision_request.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_COLLISION_REQUEST_BUILDING #include "fcl/narrowphase/collision_request-inl.h" namespace fcl { template -struct CollisionRequest; +struct FCL_EXPORT CollisionRequest; } // namespace fcl diff --git a/src/narrowphase/collision_result.cpp b/src/narrowphase/collision_result.cpp index 047193b4c..c2fad791b 100644 --- a/src/narrowphase/collision_result.cpp +++ b/src/narrowphase/collision_result.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_COLLISION_RESULT_BUILDING #include "fcl/narrowphase/collision_result-inl.h" namespace fcl { template -struct CollisionResult; +struct FCL_EXPORT CollisionResult; } // namespace fcl diff --git a/src/narrowphase/contact.cpp b/src/narrowphase/contact.cpp index 4ca0c5ecb..9ab961e08 100644 --- a/src/narrowphase/contact.cpp +++ b/src/narrowphase/contact.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_CONTACT_BUILDING #include "fcl/narrowphase/contact-inl.h" namespace fcl { template -struct Contact; +struct FCL_EXPORT Contact; } // namespace fcl diff --git a/src/narrowphase/contact_point.cpp b/src/narrowphase/contact_point.cpp index 415e985e1..276d16cfa 100644 --- a/src/narrowphase/contact_point.cpp +++ b/src/narrowphase/contact_point.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_CONTACT_POINT_BUILDING #include "fcl/narrowphase/contact_point-inl.h" namespace fcl @@ -42,15 +43,17 @@ namespace fcl //============================================================================== template -struct ContactPoint; +struct FCL_EXPORT ContactPoint; //============================================================================== template +FCL_EXPORT bool comparePenDepth( const ContactPoint& _cp1, const ContactPoint& _cp2); //============================================================================== template +FCL_EXPORT void flipNormal(std::vector>& contacts); } // namespace fcl diff --git a/src/narrowphase/continuous_collision.cpp b/src/narrowphase/continuous_collision.cpp index bbbce19a9..866d86865 100644 --- a/src/narrowphase/continuous_collision.cpp +++ b/src/narrowphase/continuous_collision.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_CONTINUOUS_COLLISION_BUILDING #include "fcl/narrowphase/continuous_collision-inl.h" namespace fcl @@ -42,6 +43,7 @@ namespace fcl //============================================================================== template +FCL_EXPORT double continuousCollide( const CollisionGeometry* o1, const MotionBase* motion1, @@ -52,6 +54,7 @@ double continuousCollide( //============================================================================== template +FCL_EXPORT double continuousCollide( const CollisionGeometry* o1, const Transform3& tf1_beg, @@ -64,6 +67,7 @@ double continuousCollide( //============================================================================== template +FCL_EXPORT double continuousCollide( const CollisionObject* o1, const Transform3& tf1_end, @@ -74,6 +78,7 @@ double continuousCollide( //============================================================================== template +FCL_EXPORT double collide( const ContinuousCollisionObject* o1, const ContinuousCollisionObject* o2, diff --git a/src/narrowphase/continuous_collision_object.cpp b/src/narrowphase/continuous_collision_object.cpp index 93b767204..3b99c9c06 100644 --- a/src/narrowphase/continuous_collision_object.cpp +++ b/src/narrowphase/continuous_collision_object.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_CONTINUOUS_COLLISION_OBJECT_BUILDING #include "fcl/narrowphase/continuous_collision_object-inl.h" namespace fcl { template -class ContinuousCollisionObject; +class FCL_EXPORT ContinuousCollisionObject; } // namespace fcl diff --git a/src/narrowphase/continuous_collision_request.cpp b/src/narrowphase/continuous_collision_request.cpp index 46dc3ea0e..36fa7f0e2 100644 --- a/src/narrowphase/continuous_collision_request.cpp +++ b/src/narrowphase/continuous_collision_request.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_CONTINUOUS_COLLISION_REQUEST_BUILDING #include "fcl/narrowphase/continuous_collision_request-inl.h" namespace fcl { template -struct ContinuousCollisionRequest; +struct FCL_EXPORT ContinuousCollisionRequest; } // namespace fcl diff --git a/src/narrowphase/continuous_collision_result.cpp b/src/narrowphase/continuous_collision_result.cpp index 3d9c559f2..126c46a80 100644 --- a/src/narrowphase/continuous_collision_result.cpp +++ b/src/narrowphase/continuous_collision_result.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_CONTINUOUS_COLLISION_RESULT_BUILDING #include "fcl/narrowphase/continuous_collision_result-inl.h" namespace fcl { template -struct ContinuousCollisionResult; +struct FCL_EXPORT ContinuousCollisionResult; } // namespace fcl diff --git a/src/narrowphase/cost_source.cpp b/src/narrowphase/cost_source.cpp index 9c606381a..d14560da3 100644 --- a/src/narrowphase/cost_source.cpp +++ b/src/narrowphase/cost_source.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_COST_SOURCE_BUILDING #include "fcl/narrowphase/cost_source-inl.h" namespace fcl { template -struct CostSource; +struct FCL_EXPORT CostSource; } // namespace fcl diff --git a/src/narrowphase/detail/convexity_based_algorithm/epa.cpp b/src/narrowphase/detail/convexity_based_algorithm/epa.cpp index eae9f1784..7132f294f 100644 --- a/src/narrowphase/detail/convexity_based_algorithm/epa.cpp +++ b/src/narrowphase/detail/convexity_based_algorithm/epa.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_EPA_BUILDING #include "fcl/narrowphase/detail/convexity_based_algorithm/epa-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct EPA; +struct FCL_EXPORT EPA; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/convexity_based_algorithm/gjk.cpp b/src/narrowphase/detail/convexity_based_algorithm/gjk.cpp index 6b693ebe9..b5373106c 100644 --- a/src/narrowphase/detail/convexity_based_algorithm/gjk.cpp +++ b/src/narrowphase/detail/convexity_based_algorithm/gjk.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_GJK_BUILDING #include "fcl/narrowphase/detail/convexity_based_algorithm/gjk-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct GJK; +struct FCL_EXPORT GJK; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/convexity_based_algorithm/gjk_libccd.cpp b/src/narrowphase/detail/convexity_based_algorithm/gjk_libccd.cpp index 7c3714e59..d2853dd6c 100644 --- a/src/narrowphase/detail/convexity_based_algorithm/gjk_libccd.cpp +++ b/src/narrowphase/detail/convexity_based_algorithm/gjk_libccd.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_GJK_LIBCCD_BUILDING #include "fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h" namespace fcl @@ -45,39 +46,41 @@ namespace detail //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template -class GJKInitializer>; +class FCL_EXPORT GJKInitializer>; //============================================================================== template +FCL_EXPORT void* triCreateGJKObject( const Vector3d& P1, const Vector3d& P2, const Vector3d& P3); //============================================================================== template +FCL_EXPORT void* triCreateGJKObject( const Vector3d& P1, const Vector3d& P2, @@ -86,6 +89,7 @@ void* triCreateGJKObject( //============================================================================== template +FCL_EXPORT bool GJKCollide( void* obj1, ccd_support_fn supp1, @@ -101,6 +105,7 @@ bool GJKCollide( //============================================================================== template +FCL_EXPORT bool GJKDistance( void* obj1, ccd_support_fn supp1, @@ -113,6 +118,7 @@ bool GJKDistance( Vector3d* p2); template +FCL_EXPORT bool GJKSignedDistance( void* obj1, ccd_support_fn supp1, diff --git a/src/narrowphase/detail/convexity_based_algorithm/minkowski_diff.cpp b/src/narrowphase/detail/convexity_based_algorithm/minkowski_diff.cpp index af2d7117b..62b185f16 100644 --- a/src/narrowphase/detail/convexity_based_algorithm/minkowski_diff.cpp +++ b/src/narrowphase/detail/convexity_based_algorithm/minkowski_diff.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_CONVEXITY_BASED_ALGORITHM_MINKOWSKI_DIFF_BUILDING #include "fcl/narrowphase/detail/convexity_based_algorithm/minkowski_diff-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct MinkowskiDiff; +struct FCL_EXPORT MinkowskiDiff; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/gjk_solver_indep.cpp b/src/narrowphase/detail/gjk_solver_indep.cpp index 8c17e3a77..531b57127 100755 --- a/src/narrowphase/detail/gjk_solver_indep.cpp +++ b/src/narrowphase/detail/gjk_solver_indep.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_GJK_SOLVER_INDEP_BUILDING #include "fcl/narrowphase/detail/gjk_solver_indep-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct GJKSolver_indep; +struct FCL_EXPORT GJKSolver_indep; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/gjk_solver_libccd.cpp b/src/narrowphase/detail/gjk_solver_libccd.cpp index e906a069f..797df7f6e 100755 --- a/src/narrowphase/detail/gjk_solver_libccd.cpp +++ b/src/narrowphase/detail/gjk_solver_libccd.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_GJK_SOLVER_LIBCCD_BUILDING #include "fcl/narrowphase/detail/gjk_solver_libccd-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct GJKSolver_libccd; +struct FCL_EXPORT GJKSolver_libccd; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/primitive_shape_algorithm/box_box.cpp b/src/narrowphase/detail/primitive_shape_algorithm/box_box.cpp index aa2718274..6839db183 100755 --- a/src/narrowphase/detail/primitive_shape_algorithm/box_box.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/box_box.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_BOX_BOX_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/box_box-inl.h" namespace fcl @@ -45,20 +46,24 @@ namespace detail //============================================================================== template +FCL_EXPORT void lineClosestApproach(const Vector3& pa, const Vector3& ua, const Vector3& pb, const Vector3& ub, double* alpha, double* beta); //============================================================================== template +FCL_EXPORT int intersectRectQuad2(double h[2], double p[8], double ret[16]); //============================================================================== template +FCL_EXPORT void cullPoints2(int n, double p[], int m, int i0, int iret[]); //============================================================================== template +FCL_EXPORT int boxBox2( const Vector3& side1, const Transform3& tf1, @@ -72,6 +77,7 @@ int boxBox2( //============================================================================== template +FCL_EXPORT bool boxBoxIntersect(const Box& s1, const Transform3& tf1, const Box& s2, const Transform3& tf2, std::vector>* contacts_); diff --git a/src/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.cpp b/src/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.cpp index bf72d5cfa..bfc1288a4 100644 --- a/src/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_CAPSULE_CAPSULE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule-inl.h" namespace fcl @@ -45,18 +46,22 @@ namespace detail //============================================================================== template +FCL_EXPORT double clamp(double n, double min, double max); //============================================================================== -template double closestPtSegmentSegment(const Vector3d& p_FP1, - const Vector3d& p_FQ1, - const Vector3d& p_FP2, - const Vector3d& p_FQ2, double* s, - double* t, Vector3d* p_FC1, - Vector3d* p_FC2); +template +FCL_EXPORT +double closestPtSegmentSegment(const Vector3d& p_FP1, + const Vector3d& p_FQ1, + const Vector3d& p_FP2, + const Vector3d& p_FQ2, double* s, + double* t, Vector3d* p_FC1, + Vector3d* p_FC2); //============================================================================== template +FCL_EXPORT bool capsuleCapsuleDistance( const Capsule& s1, const Transform3& tf1, const Capsule& s2, const Transform3& tf2, diff --git a/src/narrowphase/detail/primitive_shape_algorithm/halfspace.cpp b/src/narrowphase/detail/primitive_shape_algorithm/halfspace.cpp index 4f39570d2..12cd659dc 100755 --- a/src/narrowphase/detail/primitive_shape_algorithm/halfspace.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/halfspace.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_HALFSPACE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h" namespace fcl @@ -59,6 +60,7 @@ double halfspaceIntersectTolerance() //============================================================================== template +FCL_EXPORT bool sphereHalfspaceIntersect( const Sphere& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -66,6 +68,7 @@ bool sphereHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool ellipsoidHalfspaceIntersect( const Ellipsoid& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -73,12 +76,14 @@ bool ellipsoidHalfspaceIntersect( //============================================================================== 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, @@ -86,6 +91,7 @@ bool boxHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool capsuleHalfspaceIntersect( const Capsule& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -93,6 +99,7 @@ bool capsuleHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool cylinderHalfspaceIntersect( const Cylinder& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -100,6 +107,7 @@ bool cylinderHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool coneHalfspaceIntersect( const Cone& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -107,6 +115,7 @@ bool coneHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool convexHalfspaceIntersect( const Convex& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -114,6 +123,7 @@ bool convexHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool convexHalfspaceIntersect(const Convex& convex_C, const Transform3& X_FC, const Halfspace& half_space_H, @@ -122,6 +132,7 @@ bool convexHalfspaceIntersect(const Convex& convex_C, //============================================================================== template +FCL_EXPORT bool halfspaceTriangleIntersect( const Halfspace& s1, const Transform3& tf1, const Vector3& P1, const Vector3& P2, const Vector3& P3, const Transform3& tf2, @@ -129,6 +140,7 @@ bool halfspaceTriangleIntersect( //============================================================================== template +FCL_EXPORT bool planeHalfspaceIntersect( const Plane& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, @@ -139,6 +151,7 @@ bool planeHalfspaceIntersect( //============================================================================== template +FCL_EXPORT bool halfspacePlaneIntersect( const Halfspace& s1, const Transform3& tf1, const Plane& s2, const Transform3& tf2, @@ -148,6 +161,7 @@ bool halfspacePlaneIntersect( //============================================================================== template +FCL_EXPORT bool halfspaceIntersect( const Halfspace& s1, const Transform3& tf1, const Halfspace& s2, const Transform3& tf2, diff --git a/src/narrowphase/detail/primitive_shape_algorithm/intersect.cpp b/src/narrowphase/detail/primitive_shape_algorithm/intersect.cpp index b4d8a2253..68e412603 100644 --- a/src/narrowphase/detail/primitive_shape_algorithm/intersect.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/intersect.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_INTERSECT_BUILDING #include "fcl/narrowphase/detail/traversal/collision/intersect-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -class Intersect; +class FCL_EXPORT Intersect; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/primitive_shape_algorithm/plane.cpp b/src/narrowphase/detail/primitive_shape_algorithm/plane.cpp index 5cee207ea..eecc16653 100755 --- a/src/narrowphase/detail/primitive_shape_algorithm/plane.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/plane.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_PLANE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/plane-inl.h" namespace fcl @@ -59,64 +60,75 @@ 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); //============================================================================== 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); //============================================================================== 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, double* 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, double* 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/src/narrowphase/detail/primitive_shape_algorithm/sphere_box.cpp b/src/narrowphase/detail/primitive_shape_algorithm/sphere_box.cpp index 291ad3063..9f6641066 100644 --- a/src/narrowphase/detail/primitive_shape_algorithm/sphere_box.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/sphere_box.cpp @@ -34,6 +34,7 @@ /** @author Sean Curtis (sean@tri.global) (2018) */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_BOX_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/sphere_box-inl.h" namespace fcl @@ -43,18 +44,20 @@ namespace detail { //============================================================================== -template bool -sphereBoxIntersect(const Sphere& sphere, const Transform3& X_FS, - const Box& box, const Transform3& X_FB, - std::vector>* contacts); +template +FCL_EXPORT +bool sphereBoxIntersect(const Sphere& sphere, const Transform3& X_FS, + const Box& box, const Transform3& X_FB, + std::vector>* contacts); //============================================================================== -template bool -sphereBoxDistance(const Sphere& sphere, const Transform3& X_FS, - const Box& box, const Transform3& X_FB, - double* distance, Vector3* p_FSb, - Vector3* p_FBs); +template +FCL_EXPORT +bool sphereBoxDistance(const Sphere& sphere, const Transform3& X_FS, + const Box& box, const Transform3& X_FB, + double* distance, Vector3* p_FSb, + Vector3* p_FBs); } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.cpp b/src/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.cpp index 90d553d5e..f1c3d3a45 100755 --- a/src/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_CAPSULE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule-inl.h" namespace fcl @@ -45,6 +46,7 @@ namespace detail //============================================================================== template +FCL_EXPORT void lineSegmentPointClosestToPoint( const Vector3 &p, const Vector3 &s1, @@ -53,12 +55,14 @@ void lineSegmentPointClosestToPoint( //============================================================================== 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, double* dist, Vector3* p1, Vector3* p2); diff --git a/src/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.cpp b/src/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.cpp index d9e87d599..04cbcfcd9 100644 --- a/src/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder.cpp @@ -34,6 +34,7 @@ /** @author Sean Curtis (sean@tri.global) (2018) */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_CYLINDER_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/sphere_cylinder-inl.h" namespace fcl @@ -42,22 +43,24 @@ namespace fcl namespace detail { -template bool -sphereCylinderIntersect(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, - std::vector>* contacts); +template +FCL_EXPORT +bool sphereCylinderIntersect(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, + std::vector>* contacts); //============================================================================== -template bool -sphereCylinderDistance(const Sphere& sphere, - const Transform3& X_FS, - const Cylinder& cylinder, - const Transform3& X_FC, - double* distance, Vector3* p_FSc, - Vector3* p_FCs); +template +FCL_EXPORT +bool sphereCylinderDistance(const Sphere& sphere, + const Transform3& X_FS, + const Cylinder& cylinder, + const Transform3& X_FC, + double* distance, Vector3* p_FSc, + Vector3* p_FCs); } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/primitive_shape_algorithm/sphere_sphere.cpp b/src/narrowphase/detail/primitive_shape_algorithm/sphere_sphere.cpp index e4e76ecc7..2c160a55d 100755 --- a/src/narrowphase/detail/primitive_shape_algorithm/sphere_sphere.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/sphere_sphere.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_SPHERE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/sphere_sphere-inl.h" namespace fcl @@ -45,12 +46,14 @@ namespace detail //============================================================================== template +FCL_EXPORT bool sphereSphereIntersect(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, std::vector>* contacts); //============================================================================== template +FCL_EXPORT bool sphereSphereDistance(const Sphere& s1, const Transform3& tf1, const Sphere& s2, const Transform3& tf2, double* dist, Vector3* p1, Vector3* p2); diff --git a/src/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.cpp b/src/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.cpp index 29b6173be..60481751f 100755 --- a/src/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/sphere_triangle.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_SPHERE_TRIANGLE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/sphere_triangle-inl.h" namespace fcl @@ -45,31 +46,37 @@ namespace detail //============================================================================== template +FCL_EXPORT double segmentSqrDistance(const Vector3& from, const Vector3& to,const Vector3& p, Vector3& nearest); //============================================================================== 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, double* penetration_depth, Vector3* normal_); //============================================================================== template +FCL_EXPORT bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, double* dist); //============================================================================== template +FCL_EXPORT bool sphereTriangleDistance(const Sphere& sp, const Transform3& tf, const Vector3& P1, const Vector3& P2, const Vector3& P3, double* 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, double* dist, Vector3* p1, Vector3* p2); diff --git a/src/narrowphase/detail/primitive_shape_algorithm/triangle_distance.cpp b/src/narrowphase/detail/primitive_shape_algorithm/triangle_distance.cpp index 2bb3a20b8..3f49f7d65 100644 --- a/src/narrowphase/detail/primitive_shape_algorithm/triangle_distance.cpp +++ b/src/narrowphase/detail/primitive_shape_algorithm/triangle_distance.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_PRIMITIVE_SHAPE_ALGORITHM_TRIANGLE_DISTANCE_BUILDING #include "fcl/narrowphase/detail/primitive_shape_algorithm/triangle_distance-inl.h" namespace fcl @@ -45,7 +46,7 @@ namespace detail //============================================================================== template -class TriangleDistance; +class FCL_EXPORT TriangleDistance; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/traversal/collision/collision_traversal_node_base.cpp b/src/narrowphase/detail/traversal/collision/collision_traversal_node_base.cpp index 89783e3ff..b6e879ee9 100644 --- a/src/narrowphase/detail/traversal/collision/collision_traversal_node_base.cpp +++ b/src/narrowphase/detail/traversal/collision/collision_traversal_node_base.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_TRAVERSAL_NODE_BASE_BUILDING #include "fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -class CollisionTraversalNodeBase; +class FCL_EXPORT CollisionTraversalNodeBase; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.cpp b/src/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.cpp index 46d34aa59..430b1bf53 100644 --- a/src/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.cpp +++ b/src/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_MESH_COLLISION_TRAVERSAL_NODE_BUILDING #include "fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h" namespace fcl @@ -45,10 +46,11 @@ namespace detail //============================================================================== template -class MeshCollisionTraversalNodeOBB; +class FCL_EXPORT MeshCollisionTraversalNodeOBB; //============================================================================== template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodeOBB& node, const BVHModel>& model1, @@ -60,10 +62,11 @@ bool initialize( //============================================================================== template -class MeshCollisionTraversalNodeRSS; +class FCL_EXPORT MeshCollisionTraversalNodeRSS; //============================================================================== template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodeRSS& node, const BVHModel>& model1, @@ -75,10 +78,11 @@ bool initialize( //============================================================================== template -class MeshCollisionTraversalNodekIOS; +class FCL_EXPORT MeshCollisionTraversalNodekIOS; //============================================================================== template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodekIOS& node, const BVHModel>& model1, @@ -90,10 +94,11 @@ bool initialize( //============================================================================== template -class MeshCollisionTraversalNodeOBBRSS; +class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS; //============================================================================== template +FCL_EXPORT bool initialize( MeshCollisionTraversalNodeOBBRSS& node, const BVHModel>& model1, diff --git a/src/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.cpp b/src/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.cpp index d34c701f0..d1190e049 100644 --- a/src/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.cpp +++ b/src/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_MESH_CONTINUOUS_COLLISION_TRAVERSAL_NODE_BUILDING #include "fcl/narrowphase/detail/traversal/collision/mesh_continuous_collision_traversal_node-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct BVHContinuousCollisionPair; +struct FCL_EXPORT BVHContinuousCollisionPair; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/traversal/collision_node.cpp b/src/narrowphase/detail/traversal/collision_node.cpp index 352cd40af..8514d7ba1 100644 --- a/src/narrowphase/detail/traversal/collision_node.cpp +++ b/src/narrowphase/detail/traversal/collision_node.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_COLLISION_NODE_BUILDING #include "fcl/narrowphase/detail/traversal/collision_node-inl.h" namespace fcl @@ -45,22 +46,27 @@ namespace detail //============================================================================== template +FCL_EXPORT void collide(CollisionTraversalNodeBase* node, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void selfCollide(CollisionTraversalNodeBase* node, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void distance(DistanceTraversalNodeBase* node, BVHFrontList* front_list, int qsize); //============================================================================== template +FCL_EXPORT void collide2(MeshCollisionTraversalNodeOBB* node, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void collide2(MeshCollisionTraversalNodeRSS* node, BVHFrontList* front_list); } // namespace detail diff --git a/src/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.cpp b/src/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.cpp index b2501b6b8..228140468 100644 --- a/src/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.cpp +++ b/src/narrowphase/detail/traversal/distance/conservative_advancement_stack_data.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_CONSERVATIVE_ADVANCEMENT_STACK_DATA_BUILDING #include "fcl/narrowphase/detail/traversal/distance/conservative_advancement_stack_data-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -struct ConservativeAdvancementStackData; +struct FCL_EXPORT ConservativeAdvancementStackData; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/traversal/distance/distance_traversal_node_base.cpp b/src/narrowphase/detail/traversal/distance/distance_traversal_node_base.cpp index b6cca4994..49cadbac1 100644 --- a/src/narrowphase/detail/traversal/distance/distance_traversal_node_base.cpp +++ b/src/narrowphase/detail/traversal/distance/distance_traversal_node_base.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_TRAVERSAL_NODE_BASE_BUILDING #include "fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -class DistanceTraversalNodeBase; +class FCL_EXPORT DistanceTraversalNodeBase; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.cpp b/src/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.cpp index ed7d8cc0a..ae1a8a119 100644 --- a/src/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.cpp +++ b/src/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_MESH_CONSERVATIVE_ADVANCEMENT_TRAVERSAL_NODE_BUILDING #include "fcl/narrowphase/detail/traversal/distance/mesh_conservative_advancement_traversal_node-inl.h" namespace fcl @@ -45,10 +46,11 @@ namespace detail //============================================================================== template -class MeshConservativeAdvancementTraversalNodeRSS; +class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS; //============================================================================== template +FCL_EXPORT bool initialize( MeshConservativeAdvancementTraversalNodeRSS& node, const BVHModel>& model1, @@ -59,10 +61,11 @@ bool initialize( //============================================================================== template -class MeshConservativeAdvancementTraversalNodeOBBRSS; +class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS; //============================================================================== template +FCL_EXPORT bool initialize( MeshConservativeAdvancementTraversalNodeOBBRSS& node, const BVHModel>& model1, diff --git a/src/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.cpp b/src/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.cpp index 7d862c143..ef5808460 100644 --- a/src/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.cpp +++ b/src/narrowphase/detail/traversal/distance/mesh_distance_traversal_node.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_DISTANCE_MESH_DISTANCE_TRAVERSAL_NODE_BUILDING #include "fcl/narrowphase/detail/traversal/distance/mesh_distance_traversal_node-inl.h" namespace fcl @@ -45,10 +46,11 @@ namespace detail //============================================================================== template -class MeshDistanceTraversalNodeRSS; +class FCL_EXPORT MeshDistanceTraversalNodeRSS; //============================================================================== template +FCL_EXPORT bool initialize( MeshDistanceTraversalNodeRSS& node, const BVHModel>& model1, @@ -60,10 +62,11 @@ bool initialize( //============================================================================== template -class MeshDistanceTraversalNodekIOS; +class FCL_EXPORT MeshDistanceTraversalNodekIOS; //============================================================================== template +FCL_EXPORT bool initialize( MeshDistanceTraversalNodekIOS& node, const BVHModel>& model1, @@ -75,10 +78,11 @@ bool initialize( //============================================================================== template -class MeshDistanceTraversalNodeOBBRSS; +class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS; //============================================================================== template +FCL_EXPORT bool initialize( MeshDistanceTraversalNodeOBBRSS& node, const BVHModel>& model1, diff --git a/src/narrowphase/detail/traversal/traversal_node_base.cpp b/src/narrowphase/detail/traversal/traversal_node_base.cpp index 4a11aaf84..6b7aef288 100644 --- a/src/narrowphase/detail/traversal/traversal_node_base.cpp +++ b/src/narrowphase/detail/traversal/traversal_node_base.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_NODE_BASE_BUILDING #include "fcl/narrowphase/detail/traversal/traversal_node_base-inl.h" namespace fcl @@ -44,7 +45,7 @@ namespace detail { template -class TraversalNodeBase; +class FCL_EXPORT TraversalNodeBase; } // namespace detail } // namespace fcl diff --git a/src/narrowphase/detail/traversal/traversal_recurse.cpp b/src/narrowphase/detail/traversal/traversal_recurse.cpp index a382a3200..2a83d4f14 100644 --- a/src/narrowphase/detail/traversal/traversal_recurse.cpp +++ b/src/narrowphase/detail/traversal/traversal_recurse.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DETAIL_TRAVERSAL_RECURSE_BUILDING #include "fcl/narrowphase/detail/traversal/traversal_recurse-inl.h" namespace fcl @@ -45,30 +46,37 @@ namespace detail //============================================================================== template +FCL_EXPORT void collisionRecurse(CollisionTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void collisionRecurse(MeshCollisionTraversalNodeOBB* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void collisionRecurse(MeshCollisionTraversalNodeRSS* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void selfCollisionRecurse(CollisionTraversalNodeBase* node, int b, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void distanceRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list); //============================================================================== template +FCL_EXPORT void distanceQueueRecurse(DistanceTraversalNodeBase* node, int b1, int b2, BVHFrontList* front_list, int qsize); //============================================================================== template +FCL_EXPORT void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase* node, BVHFrontList* front_list); } // namespace detail diff --git a/src/narrowphase/distance.cpp b/src/narrowphase/distance.cpp index 5ef7dc6be..d0c7920cf 100644 --- a/src/narrowphase/distance.cpp +++ b/src/narrowphase/distance.cpp @@ -35,6 +35,7 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DISTANCE_BUILDING #include "fcl/narrowphase/distance-inl.h" namespace fcl @@ -42,6 +43,7 @@ namespace fcl //============================================================================== template +FCL_EXPORT double distance( const CollisionObject* o1, const CollisionObject* o2, @@ -50,6 +52,7 @@ double distance( //============================================================================== template +FCL_EXPORT double distance( const CollisionGeometry* o1, const Transform3& tf1, const CollisionGeometry* o2, const Transform3& tf2, diff --git a/src/narrowphase/distance_request.cpp b/src/narrowphase/distance_request.cpp index e6940139b..e8a34fd91 100644 --- a/src/narrowphase/distance_request.cpp +++ b/src/narrowphase/distance_request.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DISTANCE_REQUEST_BUILDING #include "fcl/narrowphase/distance_request-inl.h" namespace fcl { template -struct DistanceRequest; +struct FCL_EXPORT DistanceRequest; } // namespace fcl diff --git a/src/narrowphase/distance_result.cpp b/src/narrowphase/distance_result.cpp index 1fefd21e8..a7b4fe406 100644 --- a/src/narrowphase/distance_result.cpp +++ b/src/narrowphase/distance_result.cpp @@ -35,12 +35,13 @@ /** @author Jia Pan */ +#define FCL_NARROWPHASE_DISTANCE_RESULT_BUILDING #include "fcl/narrowphase/distance_result-inl.h" namespace fcl { template -struct DistanceResult; +struct FCL_EXPORT DistanceResult; } // namespace fcl diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 50e1c1c7b..5ef5ecc0c 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -32,7 +32,7 @@ execute_process(COMMAND cmake -E remove_directory ${CMAKE_BINARY_DIR}/test_resul execute_process(COMMAND cmake -E make_directory ${CMAKE_BINARY_DIR}/test_results) include_directories(${GTEST_INCLUDE_DIRS}) -add_library(test_fcl_utility test_fcl_utility.cpp) +add_library(test_fcl_utility STATIC test_fcl_utility.cpp) target_link_libraries(test_fcl_utility fcl) # test file list diff --git a/test/geometry/shape/test_convex.cpp b/test/geometry/shape/test_convex.cpp index 1857ce36a..41fd6188b 100644 --- a/test/geometry/shape/test_convex.cpp +++ b/test/geometry/shape/test_convex.cpp @@ -46,6 +46,7 @@ #include "eigen_matrix_compare.h" #include "expect_throws_message.h" #include "fcl/common/types.h" +#include "fcl/math/constants.h" namespace fcl { class ConvexTester { @@ -776,8 +777,9 @@ GTEST_TEST(ConvexGeometry, WaterTightValidation) { class TessellatedSphere final : public Polytope { public: TessellatedSphere() : Polytope(1.0) { + const auto pi = constants::pi(); // The angle between the latitude lines measured along the prime meridian. - const double dphi = M_PI / 8; + const double dphi = pi / 8; auto slice_height = [dphi](int slice_index) { // Assumes 1 <= slice_index < 8. return std::cos(slice_index * dphi); @@ -790,7 +792,7 @@ class TessellatedSphere final : public Polytope { vertices_->push_back({0, 0, 1}); // Now create the bands of vertices between slices 1 & 2, 2 & 3, etc. // The angle between the longitude lines measured along the equator. - const double dtheta = 2 * M_PI / 8; + const double dtheta = 2 * pi / 8; for (int slice = 1; slice < 8; ++slice) { double z = slice_height(slice); double r = slice_radius(slice); diff --git a/test/gtest/cmake/internal_utils.cmake b/test/gtest/cmake/internal_utils.cmake index 8cb21894c..5cdea5a12 100644 --- a/test/gtest/cmake/internal_utils.cmake +++ b/test/gtest/cmake/internal_utils.cmake @@ -37,7 +37,9 @@ macro(fix_default_compiler_settings_) # We prefer more strict warning checking for building Google Test. # Replaces /W3 with /W4 in defaults. - string(REPLACE "/W3" "-W4" ${flag_var} "${${flag_var}}") + if(${flag_var} MATCHES "/W[0-4]") + STRING(REGEX REPLACE "/W[0-4]" "/W4" ${flag_var} "${${flag_var}}") + endif() endforeach() endif() endmacro()