diff --git a/CMakeLists.txt b/CMakeLists.txt index 7d5031b66f78481a8eba152d452dbb63e1efcc2b..c2acb4bf77b2822abb68548f36cf92e1ac3cfad8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -35,9 +35,9 @@ cmake_minimum_required(VERSION 3.10) set(CXX_DISABLE_WERROR TRUE) -set(PROJECT_NAME hpp-fcl) +set(PROJECT_NAME coal) set(PROJECT_DESCRIPTION - "HPP fork of FCL -- The Flexible Collision Library" + "Coal, The Collision Detection Library. Previously known as HPP-FCL, fork of FCL -- The Flexible Collision Library" ) SET(PROJECT_USE_CMAKE_EXPORT TRUE) SET(PROJECT_COMPATIBILITY_VERSION AnyNewerVersion) @@ -188,131 +188,131 @@ endif() FIND_PACKAGE(assimp REQUIRED) SET(${PROJECT_NAME}_HEADERS - include/hpp/fcl/collision_data.h - include/hpp/fcl/BV/kIOS.h - include/hpp/fcl/BV/BV.h - include/hpp/fcl/BV/RSS.h - include/hpp/fcl/BV/OBBRSS.h - include/hpp/fcl/BV/BV_node.h - include/hpp/fcl/BV/AABB.h - include/hpp/fcl/BV/OBB.h - include/hpp/fcl/BV/kDOP.h - include/hpp/fcl/broadphase/broadphase.h - include/hpp/fcl/broadphase/broadphase_SSaP.h - include/hpp/fcl/broadphase/broadphase_SaP.h - include/hpp/fcl/broadphase/broadphase_bruteforce.h - include/hpp/fcl/broadphase/broadphase_collision_manager.h - include/hpp/fcl/broadphase/broadphase_continuous_collision_manager-inl.h - include/hpp/fcl/broadphase/broadphase_continuous_collision_manager.h - include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h - include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h - include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h - include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h - include/hpp/fcl/broadphase/broadphase_interval_tree.h - include/hpp/fcl/broadphase/broadphase_spatialhash-inl.h - include/hpp/fcl/broadphase/broadphase_spatialhash.h - include/hpp/fcl/broadphase/broadphase_callbacks.h - include/hpp/fcl/broadphase/default_broadphase_callbacks.h - include/hpp/fcl/broadphase/detail/hierarchy_tree-inl.h - include/hpp/fcl/broadphase/detail/hierarchy_tree.h - include/hpp/fcl/broadphase/detail/hierarchy_tree_array-inl.h - include/hpp/fcl/broadphase/detail/hierarchy_tree_array.h - include/hpp/fcl/broadphase/detail/interval_tree.h - include/hpp/fcl/broadphase/detail/interval_tree_node.h - include/hpp/fcl/broadphase/detail/morton-inl.h - include/hpp/fcl/broadphase/detail/morton.h - include/hpp/fcl/broadphase/detail/node_base-inl.h - include/hpp/fcl/broadphase/detail/node_base.h - include/hpp/fcl/broadphase/detail/node_base_array-inl.h - include/hpp/fcl/broadphase/detail/node_base_array.h - include/hpp/fcl/broadphase/detail/simple_hash_table-inl.h - include/hpp/fcl/broadphase/detail/simple_hash_table.h - include/hpp/fcl/broadphase/detail/simple_interval-inl.h - include/hpp/fcl/broadphase/detail/simple_interval.h - include/hpp/fcl/broadphase/detail/sparse_hash_table-inl.h - include/hpp/fcl/broadphase/detail/sparse_hash_table.h - include/hpp/fcl/broadphase/detail/spatial_hash-inl.h - include/hpp/fcl/broadphase/detail/spatial_hash.h - include/hpp/fcl/narrowphase/narrowphase.h - include/hpp/fcl/narrowphase/gjk.h - include/hpp/fcl/narrowphase/narrowphase_defaults.h - include/hpp/fcl/narrowphase/minkowski_difference.h - include/hpp/fcl/narrowphase/support_functions.h - include/hpp/fcl/shape/convex.h - include/hpp/fcl/shape/details/convex.hxx - include/hpp/fcl/shape/geometric_shape_to_BVH_model.h - include/hpp/fcl/shape/geometric_shapes.h - include/hpp/fcl/shape/geometric_shapes_traits.h - include/hpp/fcl/shape/geometric_shapes_utility.h - include/hpp/fcl/distance_func_matrix.h - include/hpp/fcl/collision.h - include/hpp/fcl/collision_func_matrix.h - include/hpp/fcl/contact_patch.h - include/hpp/fcl/contact_patch_func_matrix.h - include/hpp/fcl/contact_patch/contact_patch_solver.h - include/hpp/fcl/contact_patch/contact_patch_solver.hxx - include/hpp/fcl/distance.h - include/hpp/fcl/math/matrix_3f.h - include/hpp/fcl/math/vec_3f.h - include/hpp/fcl/math/types.h - include/hpp/fcl/math/transform.h - include/hpp/fcl/data_types.h - include/hpp/fcl/BVH/BVH_internal.h - include/hpp/fcl/BVH/BVH_model.h - include/hpp/fcl/BVH/BVH_front.h - include/hpp/fcl/BVH/BVH_utility.h - include/hpp/fcl/collision_object.h - include/hpp/fcl/collision_utility.h - include/hpp/fcl/hfield.h - include/hpp/fcl/fwd.hh - include/hpp/fcl/logging.h - include/hpp/fcl/mesh_loader/assimp.h - include/hpp/fcl/mesh_loader/loader.h - include/hpp/fcl/internal/BV_fitter.h - include/hpp/fcl/internal/BV_splitter.h - include/hpp/fcl/internal/shape_shape_func.h - include/hpp/fcl/internal/shape_shape_contact_patch_func.h - include/hpp/fcl/internal/intersect.h - include/hpp/fcl/internal/tools.h - include/hpp/fcl/internal/traversal_node_base.h - include/hpp/fcl/internal/traversal_node_bvh_shape.h - include/hpp/fcl/internal/traversal_node_bvhs.h - include/hpp/fcl/internal/traversal_node_hfield_shape.h - include/hpp/fcl/internal/traversal_node_setup.h - include/hpp/fcl/internal/traversal_node_shapes.h - include/hpp/fcl/internal/traversal_recurse.h - include/hpp/fcl/internal/traversal.h - include/hpp/fcl/serialization/fwd.h - include/hpp/fcl/serialization/serializer.h - include/hpp/fcl/serialization/archive.h - include/hpp/fcl/serialization/transform.h - include/hpp/fcl/serialization/AABB.h - include/hpp/fcl/serialization/BV_node.h - include/hpp/fcl/serialization/BV_splitter.h - include/hpp/fcl/serialization/BVH_model.h - include/hpp/fcl/serialization/collision_data.h - include/hpp/fcl/serialization/contact_patch.h - include/hpp/fcl/serialization/collision_object.h - include/hpp/fcl/serialization/convex.h - include/hpp/fcl/serialization/eigen.h - include/hpp/fcl/serialization/geometric_shapes.h - include/hpp/fcl/serialization/memory.h - include/hpp/fcl/serialization/OBB.h - include/hpp/fcl/serialization/RSS.h - include/hpp/fcl/serialization/OBBRSS.h - include/hpp/fcl/serialization/kIOS.h - include/hpp/fcl/serialization/kDOP.h - include/hpp/fcl/serialization/hfield.h - include/hpp/fcl/serialization/quadrilateral.h - include/hpp/fcl/serialization/triangle.h - include/hpp/fcl/timings.h + include/coal/collision_data.h + include/coal/BV/kIOS.h + include/coal/BV/BV.h + include/coal/BV/RSS.h + include/coal/BV/OBBRSS.h + include/coal/BV/BV_node.h + include/coal/BV/AABB.h + include/coal/BV/OBB.h + include/coal/BV/kDOP.h + include/coal/broadphase/broadphase.h + include/coal/broadphase/broadphase_SSaP.h + include/coal/broadphase/broadphase_SaP.h + include/coal/broadphase/broadphase_bruteforce.h + include/coal/broadphase/broadphase_collision_manager.h + include/coal/broadphase/broadphase_continuous_collision_manager-inl.h + include/coal/broadphase/broadphase_continuous_collision_manager.h + include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h + include/coal/broadphase/broadphase_dynamic_AABB_tree.h + include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h + include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h + include/coal/broadphase/broadphase_interval_tree.h + include/coal/broadphase/broadphase_spatialhash-inl.h + include/coal/broadphase/broadphase_spatialhash.h + include/coal/broadphase/broadphase_callbacks.h + include/coal/broadphase/default_broadphase_callbacks.h + include/coal/broadphase/detail/hierarchy_tree-inl.h + include/coal/broadphase/detail/hierarchy_tree.h + include/coal/broadphase/detail/hierarchy_tree_array-inl.h + include/coal/broadphase/detail/hierarchy_tree_array.h + include/coal/broadphase/detail/interval_tree.h + include/coal/broadphase/detail/interval_tree_node.h + include/coal/broadphase/detail/morton-inl.h + include/coal/broadphase/detail/morton.h + include/coal/broadphase/detail/node_base-inl.h + include/coal/broadphase/detail/node_base.h + include/coal/broadphase/detail/node_base_array-inl.h + include/coal/broadphase/detail/node_base_array.h + include/coal/broadphase/detail/simple_hash_table-inl.h + include/coal/broadphase/detail/simple_hash_table.h + include/coal/broadphase/detail/simple_interval-inl.h + include/coal/broadphase/detail/simple_interval.h + include/coal/broadphase/detail/sparse_hash_table-inl.h + include/coal/broadphase/detail/sparse_hash_table.h + include/coal/broadphase/detail/spatial_hash-inl.h + include/coal/broadphase/detail/spatial_hash.h + include/coal/narrowphase/narrowphase.h + include/coal/narrowphase/gjk.h + include/coal/narrowphase/narrowphase_defaults.h + include/coal/narrowphase/minkowski_difference.h + include/coal/narrowphase/support_functions.h + include/coal/shape/convex.h + include/coal/shape/details/convex.hxx + include/coal/shape/geometric_shape_to_BVH_model.h + include/coal/shape/geometric_shapes.h + include/coal/shape/geometric_shapes_traits.h + include/coal/shape/geometric_shapes_utility.h + include/coal/distance_func_matrix.h + include/coal/collision.h + include/coal/collision_func_matrix.h + include/coal/contact_patch.h + include/coal/contact_patch_func_matrix.h + include/coal/contact_patch/contact_patch_solver.h + include/coal/contact_patch/contact_patch_solver.hxx + include/coal/distance.h + include/coal/math/matrix_3f.h + include/coal/math/vec_3f.h + include/coal/math/types.h + include/coal/math/transform.h + include/coal/data_types.h + include/coal/BVH/BVH_internal.h + include/coal/BVH/BVH_model.h + include/coal/BVH/BVH_front.h + include/coal/BVH/BVH_utility.h + include/coal/collision_object.h + include/coal/collision_utility.h + include/coal/hfield.h + include/coal/fwd.hh + include/coal/logging.h + include/coal/mesh_loader/assimp.h + include/coal/mesh_loader/loader.h + include/coal/internal/BV_fitter.h + include/coal/internal/BV_splitter.h + include/coal/internal/shape_shape_func.h + include/coal/internal/shape_shape_contact_patch_func.h + include/coal/internal/intersect.h + include/coal/internal/tools.h + include/coal/internal/traversal_node_base.h + include/coal/internal/traversal_node_bvh_shape.h + include/coal/internal/traversal_node_bvhs.h + include/coal/internal/traversal_node_hfield_shape.h + include/coal/internal/traversal_node_setup.h + include/coal/internal/traversal_node_shapes.h + include/coal/internal/traversal_recurse.h + include/coal/internal/traversal.h + include/coal/serialization/fwd.h + include/coal/serialization/serializer.h + include/coal/serialization/archive.h + include/coal/serialization/transform.h + include/coal/serialization/AABB.h + include/coal/serialization/BV_node.h + include/coal/serialization/BV_splitter.h + include/coal/serialization/BVH_model.h + include/coal/serialization/collision_data.h + include/coal/serialization/contact_patch.h + include/coal/serialization/collision_object.h + include/coal/serialization/convex.h + include/coal/serialization/eigen.h + include/coal/serialization/geometric_shapes.h + include/coal/serialization/memory.h + include/coal/serialization/OBB.h + include/coal/serialization/RSS.h + include/coal/serialization/OBBRSS.h + include/coal/serialization/kIOS.h + include/coal/serialization/kDOP.h + include/coal/serialization/hfield.h + include/coal/serialization/quadrilateral.h + include/coal/serialization/triangle.h + include/coal/timings.h ) IF(HPP_FCL_HAS_OCTOMAP) LIST(APPEND ${PROJECT_NAME}_HEADERS - include/hpp/fcl/octree.h - include/hpp/fcl/serialization/octree.h - include/hpp/fcl/internal/traversal_node_octree.h + include/coal/octree.h + include/coal/serialization/octree.h + include/coal/internal/traversal_node_octree.h ) ENDIF(HPP_FCL_HAS_OCTOMAP) @@ -325,7 +325,7 @@ if(BUILD_TESTING) add_subdirectory(test) endif(BUILD_TESTING) -pkg_config_append_libs("hpp-fcl") +pkg_config_append_libs("coal") IF(HPP_FCL_HAS_OCTOMAP) # FCL_HAVE_OCTOMAP kept for backward compatibility reasons. PKG_CONFIG_APPEND_CFLAGS( diff --git a/include/coal/BV/AABB.h b/include/coal/BV/AABB.h index 4f228416ff1e6d7f8d6592b029b90d57abac12ef..c0aa81b672d54cfa2a732f3f9a1cb15840daeffa 100644 --- a/include/coal/BV/AABB.h +++ b/include/coal/BV/AABB.h @@ -38,7 +38,7 @@ #ifndef COAL_AABB_H #define COAL_AABB_H -#include "hpp/fcl/data_types.h" +#include "coal/data_types.h" namespace coal { @@ -52,7 +52,7 @@ class Halfspace; /// @brief A class describing the AABB collision structure, which is a box in 3D /// space determined by two diagonal points -class HPP_FCL_DLLAPI AABB { +class COAL_DLLAPI AABB { public: /// @brief The min point in the AABB Vec3f min_; @@ -253,14 +253,14 @@ static inline AABB rotate(const AABB& aabb, const Matrix3f& R) { /// @brief Check collision between two aabbs, b1 is in configuration (R0, T0) /// and b2 is in identity. -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const AABB& b1, - const AABB& b2); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const AABB& b1, + const AABB& b2); /// @brief Check collision between two aabbs, b1 is in configuration (R0, T0) /// and b2 is in identity. -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const AABB& b1, - const AABB& b2, const CollisionRequest& request, - FCL_REAL& sqrDistLowerBound); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const AABB& b1, + const AABB& b2, const CollisionRequest& request, + FCL_REAL& sqrDistLowerBound); } // namespace coal #endif diff --git a/include/coal/BV/BV.h b/include/coal/BV/BV.h index 1dad8f132bddfebffe81dfc36f52deac6795d1a8..7cca2048946294a283f15584a70ba691739a80ed 100644 --- a/include/coal/BV/BV.h +++ b/include/coal/BV/BV.h @@ -38,13 +38,13 @@ #ifndef COAL_BV_H #define COAL_BV_H -#include <hpp/fcl/BV/kDOP.h> -#include <hpp/fcl/BV/AABB.h> -#include <hpp/fcl/BV/OBB.h> -#include <hpp/fcl/BV/RSS.h> -#include <hpp/fcl/BV/OBBRSS.h> -#include <hpp/fcl/BV/kIOS.h> -#include <hpp/fcl/math/transform.h> +#include "coal/BV/kDOP.h" +#include "coal/BV/AABB.h" +#include "coal/BV/OBB.h" +#include "coal/BV/RSS.h" +#include "coal/BV/OBBRSS.h" +#include "coal/BV/kIOS.h" +#include "coal/math/transform.h" /** @brief Main namespace */ namespace coal { diff --git a/include/coal/BV/BV_node.h b/include/coal/BV/BV_node.h index 86cab10360df21d511905d8fd539781cdaa7d11a..9e7adfad65e2f8c923c6ad1c6f0d0d24bf3cc1b4 100644 --- a/include/coal/BV/BV_node.h +++ b/include/coal/BV/BV_node.h @@ -38,8 +38,8 @@ #ifndef COAL_BV_NODE_H #define COAL_BV_NODE_H -#include <hpp/fcl/data_types.h> -#include <hpp/fcl/BV/BV.h> +#include "coal/data_types.h" +#include "coal/BV/BV.h" namespace coal { @@ -48,7 +48,7 @@ namespace coal { /// @{ /// @brief BVNodeBase encodes the tree structure for BVH -struct HPP_FCL_DLLAPI BVNodeBase { +struct COAL_DLLAPI BVNodeBase { /// @brief An index for first child node or primitive /// If the value is positive, it is the index of the first child bv node /// If the value is negative, it is -(primitive index + 1) @@ -103,7 +103,7 @@ struct HPP_FCL_DLLAPI BVNodeBase { /// structure providing in BVNodeBase and also the geometry data provided in BV /// template parameter. template <typename BV> -struct HPP_FCL_DLLAPI BVNode : public BVNodeBase { +struct COAL_DLLAPI BVNode : public BVNodeBase { typedef BVNodeBase Base; /// @brief bounding volume storing the geometry diff --git a/include/coal/BV/OBB.h b/include/coal/BV/OBB.h index b47bef7d362d5be157f69436144d1cc9e248646b..d9bd0c503b3c38bb883e2d381154a2c9391207bd 100644 --- a/include/coal/BV/OBB.h +++ b/include/coal/BV/OBB.h @@ -38,7 +38,7 @@ #ifndef COAL_OBB_H #define COAL_OBB_H -#include "hpp/fcl/data_types.h" +#include "coal/data_types.h" namespace coal { @@ -48,7 +48,7 @@ struct CollisionRequest; /// @{ /// @brief Oriented bounding box class -struct HPP_FCL_DLLAPI OBB { +struct COAL_DLLAPI OBB { EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// @brief Orientation of OBB. axis[i] is the ith column of the orientation @@ -125,26 +125,26 @@ struct HPP_FCL_DLLAPI OBB { }; /// @brief Translate the OBB bv -HPP_FCL_DLLAPI OBB translate(const OBB& bv, const Vec3f& t); +COAL_DLLAPI OBB translate(const OBB& bv, const Vec3f& t); /// @brief Check collision between two obbs, b1 is in configuration (R0, T0) and /// b2 is in identity. -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBB& b1, - const OBB& b2); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBB& b1, + const OBB& b2); /// @brief Check collision between two obbs, b1 is in configuration (R0, T0) and /// b2 is in identity. -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBB& b1, - const OBB& b2, const CollisionRequest& request, - FCL_REAL& sqrDistLowerBound); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBB& b1, + const OBB& b2, const CollisionRequest& request, + FCL_REAL& sqrDistLowerBound); /// Check collision between two boxes /// @param B, T orientation and position of first box, /// @param a half dimensions of first box, /// @param b half dimensions of second box. /// The second box is in identity configuration. -HPP_FCL_DLLAPI bool obbDisjoint(const Matrix3f& B, const Vec3f& T, - const Vec3f& a, const Vec3f& b); +COAL_DLLAPI bool obbDisjoint(const Matrix3f& B, const Vec3f& T, const Vec3f& a, + const Vec3f& b); } // namespace coal #endif diff --git a/include/coal/BV/OBBRSS.h b/include/coal/BV/OBBRSS.h index 5529ec95b1d50e11b39a6effd836a047bb32c333..5e1da89fac7688af5f97cb494343b8a79dfccefc 100644 --- a/include/coal/BV/OBBRSS.h +++ b/include/coal/BV/OBBRSS.h @@ -38,8 +38,8 @@ #ifndef COAL_OBBRSS_H #define COAL_OBBRSS_H -#include "hpp/fcl/BV/OBB.h" -#include "hpp/fcl/BV/RSS.h" +#include "coal/BV/OBB.h" +#include "coal/BV/RSS.h" namespace coal { @@ -50,7 +50,7 @@ struct CollisionRequest; /// @brief Class merging the OBB and RSS, can handle collision and distance /// simultaneously -struct HPP_FCL_DLLAPI OBBRSS { +struct COAL_DLLAPI OBBRSS { EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// @brief OBB member, for rotation diff --git a/include/coal/BV/RSS.h b/include/coal/BV/RSS.h index 2250dac5bc18c9314444a377109d9b86f5b36c58..e0916fe2959a87834b5aef61539df15a70f32e84 100644 --- a/include/coal/BV/RSS.h +++ b/include/coal/BV/RSS.h @@ -38,7 +38,7 @@ #ifndef COAL_RSS_H #define COAL_RSS_H -#include "hpp/fcl/data_types.h" +#include "coal/data_types.h" #include <boost/math/constants/constants.hpp> @@ -50,7 +50,7 @@ struct CollisionRequest; /// @{ /// @brief A class for rectangle sphere-swept bounding volume -struct HPP_FCL_DLLAPI RSS { +struct COAL_DLLAPI RSS { EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// @brief Orientation of RSS. axis[i] is the ith column of the orientation @@ -153,20 +153,20 @@ struct HPP_FCL_DLLAPI RSS { /// not the RSS. But the direction P - Q is the correct direction for cloest /// 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) -HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f& R0, const Vec3f& T0, - const RSS& b1, const RSS& b2, Vec3f* P = NULL, - Vec3f* Q = NULL); +COAL_DLLAPI FCL_REAL distance(const Matrix3f& R0, const Vec3f& T0, + const RSS& b1, const RSS& b2, Vec3f* P = NULL, + Vec3f* Q = NULL); /// @brief Check collision between two RSSs, b1 is in configuration (R0, T0) and /// b2 is in identity. -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1, - const RSS& b2); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1, + const RSS& b2); /// @brief Check collision between two RSSs, b1 is in configuration (R0, T0) and /// b2 is in identity. -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1, - const RSS& b2, const CollisionRequest& request, - FCL_REAL& sqrDistLowerBound); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const RSS& b1, + const RSS& b2, const CollisionRequest& request, + FCL_REAL& sqrDistLowerBound); } // namespace coal diff --git a/include/coal/BV/kDOP.h b/include/coal/BV/kDOP.h index 7186a9213e60c34a58b597d26b08e5cb37f5d709..5a68e15ad6c6b70db1f04962bcf406deab410be3 100644 --- a/include/coal/BV/kDOP.h +++ b/include/coal/BV/kDOP.h @@ -38,8 +38,8 @@ #ifndef COAL_KDOP_H #define COAL_KDOP_H -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/data_types.h" +#include "coal/fwd.hh" +#include "coal/data_types.h" namespace coal { @@ -88,7 +88,7 @@ struct CollisionRequest; /// (-1, 1, -1) and (1, -1, 1) --> indices 10 and 22 /// (1, -1, -1) and (-1, 1, 1) --> indices 11 and 23 template <short N> -class HPP_FCL_DLLAPI KDOP { +class COAL_DLLAPI KDOP { protected: /// @brief Origin's distances to N KDOP planes Eigen::Array<FCL_REAL, N, 1> dist_; @@ -183,7 +183,7 @@ bool overlap(const Matrix3f& /*R0*/, const Vec3f& /*T0*/, const KDOP<N>& /*b1*/, /// @brief translate the KDOP BV template <short N> -HPP_FCL_DLLAPI KDOP<N> translate(const KDOP<N>& bv, const Vec3f& t); +COAL_DLLAPI KDOP<N> translate(const KDOP<N>& bv, const Vec3f& t); } // namespace coal diff --git a/include/coal/BV/kIOS.h b/include/coal/BV/kIOS.h index e96608d6ed15b8a4af8227149c751a821971a3f1..36eaee61673a56835f70d787b406b1d3e8da946e 100644 --- a/include/coal/BV/kIOS.h +++ b/include/coal/BV/kIOS.h @@ -38,7 +38,7 @@ #ifndef COAL_KIOS_H #define COAL_KIOS_H -#include "hpp/fcl/BV/OBB.h" +#include "coal/BV/OBB.h" namespace coal { @@ -49,9 +49,9 @@ struct CollisionRequest; /// @brief A class describing the kIOS collision structure, which is a set of /// spheres. -class HPP_FCL_DLLAPI kIOS { +class COAL_DLLAPI kIOS { /// @brief One sphere in kIOS - struct HPP_FCL_DLLAPI kIOS_Sphere { + struct COAL_DLLAPI kIOS_Sphere { EIGEN_MAKE_ALIGNED_OPERATOR_NEW Vec3f o; @@ -166,26 +166,26 @@ class HPP_FCL_DLLAPI kIOS { }; /// @brief Translate the kIOS BV -HPP_FCL_DLLAPI kIOS translate(const kIOS& bv, const Vec3f& t); +COAL_DLLAPI kIOS translate(const kIOS& bv, const Vec3f& t); /// @brief Check collision between two kIOSs, b1 is in configuration (R0, T0) /// and b2 is in identity. /// @todo Not efficient -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const kIOS& b1, - const kIOS& b2); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const kIOS& b1, + const kIOS& b2); /// @brief Check collision between two kIOSs, b1 is in configuration (R0, T0) /// and b2 is in identity. /// @todo Not efficient -HPP_FCL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const kIOS& b1, - const kIOS& b2, const CollisionRequest& request, - FCL_REAL& sqrDistLowerBound); +COAL_DLLAPI bool overlap(const Matrix3f& R0, const Vec3f& T0, const kIOS& b1, + const kIOS& b2, const CollisionRequest& request, + FCL_REAL& sqrDistLowerBound); /// @brief Approximate distance between two kIOS bounding volumes /// @todo P and Q is not returned, need implementation -HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f& R0, const Vec3f& T0, - const kIOS& b1, const kIOS& b2, - Vec3f* P = NULL, Vec3f* Q = NULL); +COAL_DLLAPI FCL_REAL distance(const Matrix3f& R0, const Vec3f& T0, + const kIOS& b1, const kIOS& b2, Vec3f* P = NULL, + Vec3f* Q = NULL); } // namespace coal diff --git a/include/coal/BVH/BVH_front.h b/include/coal/BVH/BVH_front.h index 3ec1522d1d9041501043cca4816f95f7e58bb297..fe471b9b31261ebe427b527402c3db50f5c110ee 100644 --- a/include/coal/BVH/BVH_front.h +++ b/include/coal/BVH/BVH_front.h @@ -40,7 +40,7 @@ #include <list> -#include <hpp/fcl/config.hh> +#include "coal/config.hh" namespace coal { @@ -49,7 +49,7 @@ namespace coal { /// the traversal terminates while performing a query during a given time /// instance. The front list reflects the subset of a BVTT that is traversed for /// that particular proximity query. -struct HPP_FCL_DLLAPI BVHFrontNode { +struct COAL_DLLAPI BVHFrontNode { /// @brief The nodes to start in the future, i.e. the wave front of the /// traversal tree. unsigned int left, right; diff --git a/include/coal/BVH/BVH_internal.h b/include/coal/BVH/BVH_internal.h index 892911959cab73950750dcd2900b3d5b7161df1e..49884639a3cb702d0a0d5a2b911a742abb65c4be 100644 --- a/include/coal/BVH/BVH_internal.h +++ b/include/coal/BVH/BVH_internal.h @@ -38,7 +38,7 @@ #ifndef COAL_BVH_INTERNAL_H #define COAL_BVH_INTERNAL_H -#include <hpp/fcl/data_types.h> +#include "coal/data_types.h" namespace coal { diff --git a/include/coal/BVH/BVH_model.h b/include/coal/BVH/BVH_model.h index 16ae11e67a07434f9da89abc8c5b1ca443679665..71b830188ebe9d584f0238ad6414870b5ef15027 100644 --- a/include/coal/BVH/BVH_model.h +++ b/include/coal/BVH/BVH_model.h @@ -39,10 +39,10 @@ #ifndef COAL_BVH_MODEL_H #define COAL_BVH_MODEL_H -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/collision_object.h" -#include "hpp/fcl/BVH/BVH_internal.h" -#include "hpp/fcl/BV/BV_node.h" +#include "coal/fwd.hh" +#include "coal/collision_object.h" +#include "coal/BVH/BVH_internal.h" +#include "coal/BV/BV_node.h" #include <vector> #include <memory> @@ -62,7 +62,7 @@ class BVSplitter; /// @brief A base class describing the bounding hierarchy of a mesh model or a /// point cloud model (which is viewed as a degraded version of mesh) -class HPP_FCL_DLLAPI BVHModelBase : public CollisionGeometry { +class COAL_DLLAPI BVHModelBase : public CollisionGeometry { public: /// @brief Geometry point data std::shared_ptr<std::vector<Vec3f>> vertices; @@ -311,7 +311,7 @@ class HPP_FCL_DLLAPI BVHModelBase : public CollisionGeometry { /// cloud model (which is viewed as a degraded version of mesh) \tparam BV one /// of the bounding volume class in \ref Bounding_Volume. template <typename BV> -class HPP_FCL_DLLAPI BVHModel : public BVHModelBase { +class COAL_DLLAPI BVHModel : public BVHModelBase { typedef BVHModelBase Base; public: diff --git a/include/coal/BVH/BVH_utility.h b/include/coal/BVH/BVH_utility.h index 27093fb37a22138c7a9676f8d59df93664d6a0cd..21434736c145e9c6a5c8c2ac67eaad31214e2814 100644 --- a/include/coal/BVH/BVH_utility.h +++ b/include/coal/BVH/BVH_utility.h @@ -38,78 +38,77 @@ #ifndef COAL_BVH_UTILITY_H #define COAL_BVH_UTILITY_H -#include <hpp/fcl/BVH/BVH_model.h> +#include "coal/BVH/BVH_model.h" namespace coal { /// @brief Extract the part of the BVHModel that is inside an AABB. /// A triangle in collision with the AABB is considered inside. template <typename BV> -HPP_FCL_DLLAPI BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, - const Transform3f& pose, - const AABB& aabb); +COAL_DLLAPI BVHModel<BV>* BVHExtract(const BVHModel<BV>& model, + const Transform3f& pose, const AABB& aabb); template <> -HPP_FCL_DLLAPI BVHModel<OBB>* BVHExtract(const BVHModel<OBB>& model, - const Transform3f& pose, - const AABB& aabb); +COAL_DLLAPI BVHModel<OBB>* BVHExtract(const BVHModel<OBB>& model, + const Transform3f& pose, + const AABB& aabb); +template <> +COAL_DLLAPI BVHModel<AABB>* BVHExtract(const BVHModel<AABB>& model, + const Transform3f& pose, + const AABB& aabb); template <> -HPP_FCL_DLLAPI BVHModel<AABB>* BVHExtract(const BVHModel<AABB>& model, - const Transform3f& pose, - const AABB& aabb); +COAL_DLLAPI BVHModel<RSS>* BVHExtract(const BVHModel<RSS>& model, + const Transform3f& pose, + const AABB& aabb); template <> -HPP_FCL_DLLAPI BVHModel<RSS>* BVHExtract(const BVHModel<RSS>& model, +COAL_DLLAPI BVHModel<kIOS>* BVHExtract(const BVHModel<kIOS>& model, + const Transform3f& pose, + const AABB& aabb); +template <> +COAL_DLLAPI BVHModel<OBBRSS>* BVHExtract(const BVHModel<OBBRSS>& model, const Transform3f& pose, const AABB& aabb); template <> -HPP_FCL_DLLAPI BVHModel<kIOS>* BVHExtract(const BVHModel<kIOS>& model, - const Transform3f& pose, - const AABB& aabb); -template <> -HPP_FCL_DLLAPI BVHModel<OBBRSS>* BVHExtract(const BVHModel<OBBRSS>& model, +COAL_DLLAPI BVHModel<KDOP<16> >* BVHExtract(const BVHModel<KDOP<16> >& model, const Transform3f& pose, const AABB& aabb); template <> -HPP_FCL_DLLAPI BVHModel<KDOP<16> >* BVHExtract(const BVHModel<KDOP<16> >& model, - const Transform3f& pose, - const AABB& aabb); -template <> -HPP_FCL_DLLAPI BVHModel<KDOP<18> >* BVHExtract(const BVHModel<KDOP<18> >& model, - const Transform3f& pose, - const AABB& aabb); +COAL_DLLAPI BVHModel<KDOP<18> >* BVHExtract(const BVHModel<KDOP<18> >& model, + const Transform3f& pose, + const AABB& aabb); template <> -HPP_FCL_DLLAPI BVHModel<KDOP<24> >* BVHExtract(const BVHModel<KDOP<24> >& model, - const Transform3f& pose, - const AABB& aabb); +COAL_DLLAPI BVHModel<KDOP<24> >* BVHExtract(const BVHModel<KDOP<24> >& model, + const Transform3f& pose, + const AABB& aabb); /// @brief Compute the covariance matrix for a set or subset of points. if ts = /// null, then indices refer to points directly; otherwise refer to triangles -HPP_FCL_DLLAPI void getCovariance(Vec3f* ps, Vec3f* ps2, Triangle* ts, - unsigned int* indices, unsigned int n, - Matrix3f& M); +COAL_DLLAPI void getCovariance(Vec3f* ps, Vec3f* ps2, Triangle* ts, + unsigned int* indices, unsigned int n, + Matrix3f& M); /// @brief Compute the RSS bounding volume parameters: radius, rectangle size /// and the origin, given the BV axises. -HPP_FCL_DLLAPI void getRadiusAndOriginAndRectangleSize( +COAL_DLLAPI void getRadiusAndOriginAndRectangleSize( Vec3f* ps, Vec3f* ps2, Triangle* ts, unsigned int* indices, unsigned int n, const Matrix3f& axes, Vec3f& origin, FCL_REAL l[2], FCL_REAL& r); /// @brief Compute the bounding volume extent and center for a set or subset of /// points, given the BV axises. -HPP_FCL_DLLAPI void getExtentAndCenter(Vec3f* ps, Vec3f* ps2, Triangle* ts, - unsigned int* indices, unsigned int n, - Matrix3f& axes, Vec3f& center, - Vec3f& extent); +COAL_DLLAPI void getExtentAndCenter(Vec3f* ps, Vec3f* ps2, Triangle* ts, + unsigned int* indices, unsigned int n, + Matrix3f& axes, Vec3f& center, + Vec3f& extent); /// @brief Compute the center and radius for a triangle's circumcircle -HPP_FCL_DLLAPI void circumCircleComputation(const Vec3f& a, const Vec3f& b, - const Vec3f& c, Vec3f& center, - FCL_REAL& radius); +COAL_DLLAPI void circumCircleComputation(const Vec3f& a, const Vec3f& b, + const Vec3f& c, Vec3f& center, + FCL_REAL& radius); /// @brief Compute the maximum distance from a given center point to a point /// cloud -HPP_FCL_DLLAPI FCL_REAL maximumDistance(Vec3f* ps, Vec3f* ps2, Triangle* ts, - unsigned int* indices, unsigned int n, - const Vec3f& query); +COAL_DLLAPI FCL_REAL maximumDistance(Vec3f* ps, Vec3f* ps2, Triangle* ts, + unsigned int* indices, unsigned int n, + const Vec3f& query); } // namespace coal diff --git a/include/coal/broadphase/broadphase.h b/include/coal/broadphase/broadphase.h index fafd6f9549128fc7ab21e22374bf6b888182dbff..887dbb141156a7a8026b1058c537a628eb88fce9 100644 --- a/include/coal/broadphase/broadphase.h +++ b/include/coal/broadphase/broadphase.h @@ -35,14 +35,14 @@ #ifndef COAL_BROADPHASE_BROADPHASE_H #define COAL_BROADPHASE_BROADPHASE_H -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h" -#include "hpp/fcl/broadphase/broadphase_bruteforce.h" -#include "hpp/fcl/broadphase/broadphase_SaP.h" -#include "hpp/fcl/broadphase/broadphase_SSaP.h" -#include "hpp/fcl/broadphase/broadphase_interval_tree.h" -#include "hpp/fcl/broadphase/broadphase_spatialhash.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" +#include "coal/broadphase/broadphase_bruteforce.h" +#include "coal/broadphase/broadphase_SaP.h" +#include "coal/broadphase/broadphase_SSaP.h" +#include "coal/broadphase/broadphase_interval_tree.h" +#include "coal/broadphase/broadphase_spatialhash.h" -#include "hpp/fcl/broadphase/default_broadphase_callbacks.h" +#include "coal/broadphase/default_broadphase_callbacks.h" #endif // ifndef COAL_BROADPHASE_BROADPHASE_H diff --git a/include/coal/broadphase/broadphase_SSaP.h b/include/coal/broadphase/broadphase_SSaP.h index d3511c5f0cd03c8d54969d52d955942751def3a9..fdb46cb21ba7f25d92d6d3127ed2911473e17604 100644 --- a/include/coal/broadphase/broadphase_SSaP.h +++ b/include/coal/broadphase/broadphase_SSaP.h @@ -39,12 +39,12 @@ #define COAL_BROAD_PHASE_SSAP_H #include <vector> -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/broadphase_collision_manager.h" namespace coal { /// @brief Simple SAP collision manager -class HPP_FCL_DLLAPI SSaPCollisionManager : public BroadPhaseCollisionManager { +class COAL_DLLAPI SSaPCollisionManager : public BroadPhaseCollisionManager { public: typedef BroadPhaseCollisionManager Base; using Base::getObjects; diff --git a/include/coal/broadphase/broadphase_SaP.h b/include/coal/broadphase/broadphase_SaP.h index 8ae3f48f33d428dcae42b80f1a485183b4e23086..209ad6af3687de76030d9296e66bba4884084bae 100644 --- a/include/coal/broadphase/broadphase_SaP.h +++ b/include/coal/broadphase/broadphase_SaP.h @@ -41,12 +41,12 @@ #include <map> #include <list> -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/broadphase_collision_manager.h" namespace coal { /// @brief Rigorous SAP collision manager -class HPP_FCL_DLLAPI SaPCollisionManager : public BroadPhaseCollisionManager { +class COAL_DLLAPI SaPCollisionManager : public BroadPhaseCollisionManager { public: typedef BroadPhaseCollisionManager Base; using Base::getObjects; @@ -168,7 +168,7 @@ class HPP_FCL_DLLAPI SaPCollisionManager : public BroadPhaseCollisionManager { }; /// @brief Functor to help unregister one object - class HPP_FCL_DLLAPI isUnregistered { + class COAL_DLLAPI isUnregistered { CollisionObject* obj; public: @@ -179,7 +179,7 @@ class HPP_FCL_DLLAPI SaPCollisionManager : public BroadPhaseCollisionManager { /// @brief Functor to help remove collision pairs no longer valid (i.e., /// should be culled away) - class HPP_FCL_DLLAPI isNotValidPair { + class COAL_DLLAPI isNotValidPair { CollisionObject* obj1; CollisionObject* obj2; diff --git a/include/coal/broadphase/broadphase_bruteforce.h b/include/coal/broadphase/broadphase_bruteforce.h index ac5dce5eed9e52cce7e18586acd9ff865148f59c..ab1f9d564ed9d2b40907b94d975b5e880ec22e01 100644 --- a/include/coal/broadphase/broadphase_bruteforce.h +++ b/include/coal/broadphase/broadphase_bruteforce.h @@ -39,12 +39,12 @@ #define COAL_BROAD_PHASE_BRUTE_FORCE_H #include <list> -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/broadphase_collision_manager.h" namespace coal { /// @brief Brute force N-body collision manager -class HPP_FCL_DLLAPI NaiveCollisionManager : public BroadPhaseCollisionManager { +class COAL_DLLAPI NaiveCollisionManager : public BroadPhaseCollisionManager { public: typedef BroadPhaseCollisionManager Base; using Base::getObjects; diff --git a/include/coal/broadphase/broadphase_callbacks.h b/include/coal/broadphase/broadphase_callbacks.h index d63318dbf87003758366fd8a6273c0f32aba59d6..56fe4f1cd23ca2c7acb33114e0180a0d39978c34 100644 --- a/include/coal/broadphase/broadphase_callbacks.h +++ b/include/coal/broadphase/broadphase_callbacks.h @@ -37,8 +37,8 @@ #ifndef COAL_BROADPHASE_BROAD_PHASE_CALLBACKS_H #define COAL_BROADPHASE_BROAD_PHASE_CALLBACKS_H -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/data_types.h" +#include "coal/fwd.hh" +#include "coal/data_types.h" namespace coal { @@ -46,7 +46,7 @@ namespace coal { /// This class can be supersed by child classes to provide desired behaviors /// according to the application (e.g, only listing the potential /// CollisionObjects in collision). -struct HPP_FCL_DLLAPI CollisionCallBackBase { +struct COAL_DLLAPI CollisionCallBackBase { /// @brief Initialization of the callback before running the collision /// broadphase manager. virtual void init() {}; @@ -69,7 +69,7 @@ struct HPP_FCL_DLLAPI CollisionCallBackBase { /// This class can be supersed by child classes to provide desired behaviors /// according to the application (e.g, only listing the potential /// CollisionObjects in collision). -struct HPP_FCL_DLLAPI DistanceCallBackBase { +struct COAL_DLLAPI DistanceCallBackBase { /// @brief Initialization of the callback before running the collision /// broadphase manager. virtual void init() {}; diff --git a/include/coal/broadphase/broadphase_collision_manager.h b/include/coal/broadphase/broadphase_collision_manager.h index 76ad5d4b15a25fd5929d3ccd6f5d070840ea6c20..a394878afc21776544d4c20520b071625f34d953 100644 --- a/include/coal/broadphase/broadphase_collision_manager.h +++ b/include/coal/broadphase/broadphase_collision_manager.h @@ -42,15 +42,15 @@ #include <vector> #include <boost/function.hpp> -#include "hpp/fcl/collision_object.h" -#include "hpp/fcl/broadphase/broadphase_callbacks.h" +#include "coal/collision_object.h" +#include "coal/broadphase/broadphase_callbacks.h" namespace coal { /// @brief Base class for broad phase collision. It helps to accelerate the /// collision/distance between N objects. Also support self collision, self /// distance and collision/distance with another M objects. -class HPP_FCL_DLLAPI BroadPhaseCollisionManager { +class COAL_DLLAPI BroadPhaseCollisionManager { public: BroadPhaseCollisionManager(); diff --git a/include/coal/broadphase/broadphase_continuous_collision_manager-inl.h b/include/coal/broadphase/broadphase_continuous_collision_manager-inl.h index 93c038aee707f150e59b7c13549aaa50022c7b87..441a615bcebc0faa69664e657ae0c56cdd4b635e 100644 --- a/include/coal/broadphase/broadphase_continuous_collision_manager-inl.h +++ b/include/coal/broadphase/broadphase_continuous_collision_manager-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_BROADPHASECONTINUOUSCOLLISIONMANAGER_INL_H #define COAL_BROADPHASE_BROADPHASECONTINUOUSCOLLISIONMANAGER_INL_H -#include "hpp/fcl/broadphase/broadphase_continuous_collision_manager.h" +#include "coal/broadphase/broadphase_continuous_collision_manager.h" #include <algorithm> namespace coal { diff --git a/include/coal/broadphase/broadphase_continuous_collision_manager.h b/include/coal/broadphase/broadphase_continuous_collision_manager.h index 4dd102db5cfb68c5b3c039d2ccb367de16e3e0f4..c2cec955ef8fe7617d8f62ee924ae4bff8d1f334 100644 --- a/include/coal/broadphase/broadphase_continuous_collision_manager.h +++ b/include/coal/broadphase/broadphase_continuous_collision_manager.h @@ -38,9 +38,9 @@ #ifndef COAL_BROADPHASE_BROADPHASECONTINUOUSCOLLISIONMANAGER_H #define COAL_BROADPHASE_BROADPHASECONTINUOUSCOLLISIONMANAGER_H -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" -#include "hpp/fcl/collision_object.h" -#include "hpp/fcl/narrowphase/continuous_collision_object.h" +#include "coal/broadphase/broadphase_collision_manager.h" +#include "coal/collision_object.h" +#include "coal/narrowphase/continuous_collision_object.h" namespace coal { @@ -62,7 +62,7 @@ using ContinuousDistanceCallBack = bool (*)(ContinuousCollisionObject* o1, /// accelerate the continuous collision/distance between N objects. Also support /// self collision, self distance and collision/distance with another M objects. template <typename S> -class HPP_FCL_DLLAPI BroadPhaseContinuousCollisionManager { +class COAL_DLLAPI BroadPhaseContinuousCollisionManager { public: BroadPhaseContinuousCollisionManager(); @@ -138,6 +138,6 @@ using BroadPhaseContinuousCollisionManagerd = } // namespace coal -#include "hpp/fcl/broadphase/broadphase_continuous_collision_manager-inl.h" +#include "coal/broadphase/broadphase_continuous_collision_manager-inl.h" #endif diff --git a/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h b/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h index 45a114c7945e1a8a1a3874775c57f73313a6ef94..924b505efe76f5623eee591f2ec458a17c32085b 100644 --- a/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h +++ b/include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h @@ -38,16 +38,16 @@ #ifndef COAL_BROAD_PHASE_DYNAMIC_AABB_TREE_INL_H #define COAL_BROAD_PHASE_DYNAMIC_AABB_TREE_INL_H -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" #include <limits> #if HPP_FCL_HAVE_OCTOMAP -#include "hpp/fcl/octree.h" +#include "coal/octree.h" #endif -#include "hpp/fcl/BV/BV.h" -#include "hpp/fcl/shape/geometric_shapes_utility.h" +#include "coal/BV/BV.h" +#include "coal/shape/geometric_shapes_utility.h" namespace coal { namespace detail { diff --git a/include/coal/broadphase/broadphase_dynamic_AABB_tree.h b/include/coal/broadphase/broadphase_dynamic_AABB_tree.h index deabdf4bda53dbb16964281300cc497226077f74..d3ecd549787ab510a0e3bcfda9fae90228464f08 100644 --- a/include/coal/broadphase/broadphase_dynamic_AABB_tree.h +++ b/include/coal/broadphase/broadphase_dynamic_AABB_tree.h @@ -41,16 +41,16 @@ #include <unordered_map> #include <functional> -#include "hpp/fcl/fwd.hh" -// #include "hpp/fcl/BV/utility.h" -#include "hpp/fcl/shape/geometric_shapes.h" -// #include "hpp/fcl/geometry/shape/utility.h" -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" -#include "hpp/fcl/broadphase/detail/hierarchy_tree.h" +#include "coal/fwd.hh" +// #include "coal/BV/utility.h" +#include "coal/shape/geometric_shapes.h" +// #include "coal/geometry/shape/utility.h" +#include "coal/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/detail/hierarchy_tree.h" namespace coal { -class HPP_FCL_DLLAPI DynamicAABBTreeCollisionManager +class COAL_DLLAPI DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager { public: typedef BroadPhaseCollisionManager Base; @@ -145,6 +145,6 @@ class HPP_FCL_DLLAPI DynamicAABBTreeCollisionManager } // namespace coal -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree-inl.h" #endif diff --git a/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h b/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h index b12283592884c13965dcca0cdec74f194bdfd2de..70327aa92333f487ce8dcd820d67cb7ab8d65e8b 100644 --- a/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h +++ b/include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h @@ -38,11 +38,11 @@ #ifndef COAL_BROAD_PHASE_DYNAMIC_AABB_TREE_ARRAY_INL_H #define COAL_BROAD_PHASE_DYNAMIC_AABB_TREE_ARRAY_INL_H -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h" -#include "hpp/fcl/shape/geometric_shapes_utility.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" +#include "coal/shape/geometric_shapes_utility.h" #if HPP_FCL_HAVE_OCTOMAP -#include "hpp/fcl/octree.h" +#include "coal/octree.h" #endif namespace coal { diff --git a/include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h b/include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h index cb1c24a913d6250d6cd2c2d3a4187d6f1c1ca08f..35f17cd8216a24c5df84881ef285fc88801bffb1 100644 --- a/include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h +++ b/include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h @@ -42,16 +42,16 @@ #include <functional> #include <limits> -#include "hpp/fcl/fwd.hh" -// #include "hpp/fcl/BV/utility.h" -#include "hpp/fcl/shape/geometric_shapes.h" -// #include "hpp/fcl/geometry/shape/utility.h" -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" -#include "hpp/fcl/broadphase/detail/hierarchy_tree_array.h" +#include "coal/fwd.hh" +// #include "coal/BV/utility.h" +#include "coal/shape/geometric_shapes.h" +// #include "coal/geometry/shape/utility.h" +#include "coal/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/detail/hierarchy_tree_array.h" namespace coal { -class HPP_FCL_DLLAPI DynamicAABBTreeArrayCollisionManager +class COAL_DLLAPI DynamicAABBTreeArrayCollisionManager : public BroadPhaseCollisionManager { public: typedef BroadPhaseCollisionManager Base; @@ -141,6 +141,6 @@ class HPP_FCL_DLLAPI DynamicAABBTreeArrayCollisionManager } // namespace coal -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h" #endif diff --git a/include/coal/broadphase/broadphase_interval_tree.h b/include/coal/broadphase/broadphase_interval_tree.h index 97a1db7b873cd88c9dcf6ecf6f56a92c965ac388..a97799c299f11334396c3c7ed8c258d07a8a608f 100644 --- a/include/coal/broadphase/broadphase_interval_tree.h +++ b/include/coal/broadphase/broadphase_interval_tree.h @@ -41,13 +41,13 @@ #include <deque> #include <map> -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" -#include "hpp/fcl/broadphase/detail/interval_tree.h" +#include "coal/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/detail/interval_tree.h" namespace coal { /// @brief Collision manager based on interval tree -class HPP_FCL_DLLAPI IntervalTreeCollisionManager +class COAL_DLLAPI IntervalTreeCollisionManager : public BroadPhaseCollisionManager { public: typedef BroadPhaseCollisionManager Base; @@ -114,7 +114,7 @@ class HPP_FCL_DLLAPI IntervalTreeCollisionManager protected: /// @brief SAP end point /// @brief SAP end point - struct HPP_FCL_DLLAPI EndPoint { + struct COAL_DLLAPI EndPoint { /// @brief object related with the end point CollisionObject* obj; @@ -130,7 +130,7 @@ class HPP_FCL_DLLAPI IntervalTreeCollisionManager /// @brief Extention interval tree's interval to SAP interval, adding more /// information - struct HPP_FCL_DLLAPI SAPInterval : public detail::SimpleInterval { + struct COAL_DLLAPI SAPInterval : public detail::SimpleInterval { CollisionObject* obj; SAPInterval(FCL_REAL low_, FCL_REAL high_, CollisionObject* obj_); diff --git a/include/coal/broadphase/broadphase_spatialhash-inl.h b/include/coal/broadphase/broadphase_spatialhash-inl.h index 5b0eb7df965775fc6a5ff94e7d646edc58f14f1d..fd4ffa0bbeab00fde1814206318a7876687ed98a 100644 --- a/include/coal/broadphase/broadphase_spatialhash-inl.h +++ b/include/coal/broadphase/broadphase_spatialhash-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_BROADPAHSESPATIALHASH_INL_H #define COAL_BROADPHASE_BROADPAHSESPATIALHASH_INL_H -#include "hpp/fcl/broadphase/broadphase_spatialhash.h" +#include "coal/broadphase/broadphase_spatialhash.h" namespace coal { diff --git a/include/coal/broadphase/broadphase_spatialhash.h b/include/coal/broadphase/broadphase_spatialhash.h index 5e5b18920d4b4d4b04fc1757ac169e5cb07433bf..17f37e05228019a39100a18906ecc6fc2157cf1a 100644 --- a/include/coal/broadphase/broadphase_spatialhash.h +++ b/include/coal/broadphase/broadphase_spatialhash.h @@ -40,11 +40,11 @@ #include <list> #include <map> -#include "hpp/fcl/BV/AABB.h" -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" -#include "hpp/fcl/broadphase/detail/simple_hash_table.h" -#include "hpp/fcl/broadphase/detail/sparse_hash_table.h" -#include "hpp/fcl/broadphase/detail/spatial_hash.h" +#include "coal/BV/AABB.h" +#include "coal/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/detail/simple_hash_table.h" +#include "coal/broadphase/detail/sparse_hash_table.h" +#include "coal/broadphase/detail/spatial_hash.h" namespace coal { @@ -162,6 +162,6 @@ class SpatialHashingCollisionManager : public BroadPhaseCollisionManager { } // namespace coal -#include "hpp/fcl/broadphase/broadphase_spatialhash-inl.h" +#include "coal/broadphase/broadphase_spatialhash-inl.h" #endif diff --git a/include/coal/broadphase/default_broadphase_callbacks.h b/include/coal/broadphase/default_broadphase_callbacks.h index 09bf73eeb6b4ff9b43332eba43a6481900c01fdc..a124cd8d050e1753396b65a27f4554951da19527 100644 --- a/include/coal/broadphase/default_broadphase_callbacks.h +++ b/include/coal/broadphase/default_broadphase_callbacks.h @@ -39,14 +39,14 @@ #ifndef COAL_BROADPHASE_DEFAULT_BROADPHASE_CALLBACKS_H #define COAL_BROADPHASE_DEFAULT_BROADPHASE_CALLBACKS_H -#include "hpp/fcl/broadphase/broadphase_callbacks.h" -#include "hpp/fcl/collision.h" -#include "hpp/fcl/distance.h" -// #include "hpp/fcl/narrowphase/continuous_collision.h" -// #include "hpp/fcl/narrowphase/continuous_collision_request.h" -// #include "hpp/fcl/narrowphase/continuous_collision_result.h" -// #include "hpp/fcl/narrowphase/distance_request.h" -// #include "hpp/fcl/narrowphase/distance_result.h" +#include "coal/broadphase/broadphase_callbacks.h" +#include "coal/collision.h" +#include "coal/distance.h" +// #include "coal/narrowphase/continuous_collision.h" +// #include "coal/narrowphase/continuous_collision_request.h" +// #include "coal/narrowphase/continuous_collision_result.h" +// #include "coal/narrowphase/distance_request.h" +// #include "coal/narrowphase/distance_result.h" namespace coal { @@ -193,7 +193,7 @@ bool defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2, /// @brief Default collision callback to check collision between collision /// objects. -struct HPP_FCL_DLLAPI CollisionCallBackDefault : CollisionCallBackBase { +struct COAL_DLLAPI CollisionCallBackDefault : CollisionCallBackBase { /// @brief Initialize the callback. /// Clears the collision result and sets the done boolean to false. void init() { data.clear(); } @@ -207,7 +207,7 @@ struct HPP_FCL_DLLAPI CollisionCallBackDefault : CollisionCallBackBase { /// @brief Default distance callback to check collision between collision /// objects. -struct HPP_FCL_DLLAPI DistanceCallBackDefault : DistanceCallBackBase { +struct COAL_DLLAPI DistanceCallBackDefault : DistanceCallBackBase { /// @brief Initialize the callback. /// Clears the distance result and sets the done boolean to false. void init() { data.clear(); } @@ -220,7 +220,7 @@ struct HPP_FCL_DLLAPI DistanceCallBackDefault : DistanceCallBackBase { }; /// @brief Collision callback to collect collision pairs potentially in contacts -struct HPP_FCL_DLLAPI CollisionCallBackCollect : CollisionCallBackBase { +struct COAL_DLLAPI CollisionCallBackCollect : CollisionCallBackBase { typedef std::pair<CollisionObject*, CollisionObject*> CollisionPair; /// @brief Default constructor. diff --git a/include/coal/broadphase/detail/hierarchy_tree-inl.h b/include/coal/broadphase/detail/hierarchy_tree-inl.h index 2b3119e35e125745946cabe7cb4fc024e092aea3..85d0c8899e3b7ec48cfba210d5ad9a1fa0b9d7ea 100644 --- a/include/coal/broadphase/detail/hierarchy_tree-inl.h +++ b/include/coal/broadphase/detail/hierarchy_tree-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_HIERARCHY_TREE_INL_H #define COAL_HIERARCHY_TREE_INL_H -#include "hpp/fcl/broadphase/detail/hierarchy_tree.h" +#include "coal/broadphase/detail/hierarchy_tree.h" namespace coal { diff --git a/include/coal/broadphase/detail/hierarchy_tree.h b/include/coal/broadphase/detail/hierarchy_tree.h index baaeb7b3b345d2b3532cd4e1cbbef91cadfd3396..8eb2f46daa8b4ff75f83321962463c84511bc8e1 100644 --- a/include/coal/broadphase/detail/hierarchy_tree.h +++ b/include/coal/broadphase/detail/hierarchy_tree.h @@ -42,10 +42,10 @@ #include <map> #include <functional> #include <iostream> -#include "hpp/fcl/warning.hh" -#include "hpp/fcl/BV/AABB.h" -#include "hpp/fcl/broadphase/detail/morton.h" -#include "hpp/fcl/broadphase/detail/node_base.h" +#include "coal/warning.hh" +#include "coal/BV/AABB.h" +#include "coal/broadphase/detail/morton.h" +#include "coal/broadphase/detail/node_base.h" namespace coal { @@ -287,6 +287,6 @@ size_t select(const BV& query, const NodeBase<BV>& node1, } // namespace detail } // namespace coal -#include "hpp/fcl/broadphase/detail/hierarchy_tree-inl.h" +#include "coal/broadphase/detail/hierarchy_tree-inl.h" #endif diff --git a/include/coal/broadphase/detail/hierarchy_tree_array-inl.h b/include/coal/broadphase/detail/hierarchy_tree_array-inl.h index 131b82b879328b3f38ed368684e08d6c288835e5..d9ba6c84f6435ef6bbe824351191162f6c055246 100644 --- a/include/coal/broadphase/detail/hierarchy_tree_array-inl.h +++ b/include/coal/broadphase/detail/hierarchy_tree_array-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_HIERARCHY_TREE_ARRAY_INL_H #define COAL_HIERARCHY_TREE_ARRAY_INL_H -#include "hpp/fcl/broadphase/detail/hierarchy_tree_array.h" +#include "coal/broadphase/detail/hierarchy_tree_array.h" #include <algorithm> #include <iostream> diff --git a/include/coal/broadphase/detail/hierarchy_tree_array.h b/include/coal/broadphase/detail/hierarchy_tree_array.h index d5d9b66abdd155ed89d091a349a67229925c568b..23e2c2bcc3333748da757d95181c9ddecc8d18c9 100644 --- a/include/coal/broadphase/detail/hierarchy_tree_array.h +++ b/include/coal/broadphase/detail/hierarchy_tree_array.h @@ -42,10 +42,10 @@ #include <map> #include <functional> -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/BV/AABB.h" -#include "hpp/fcl/broadphase/detail/morton.h" -#include "hpp/fcl/broadphase/detail/node_base_array.h" +#include "coal/fwd.hh" +#include "coal/BV/AABB.h" +#include "coal/broadphase/detail/morton.h" +#include "coal/broadphase/detail/node_base_array.h" namespace coal { @@ -295,6 +295,6 @@ size_t select(const BV& query, size_t node1, size_t node2, NodeBase<BV>* nodes); } // namespace detail } // namespace coal -#include "hpp/fcl/broadphase/detail/hierarchy_tree_array-inl.h" +#include "coal/broadphase/detail/hierarchy_tree_array-inl.h" #endif diff --git a/include/coal/broadphase/detail/interval_tree.h b/include/coal/broadphase/detail/interval_tree.h index 46001856b7a8ce3c117c07c984ba8da1436295c3..b17c8b238030bc314fc6a8b812504ec2ee8f244b 100644 --- a/include/coal/broadphase/detail/interval_tree.h +++ b/include/coal/broadphase/detail/interval_tree.h @@ -42,7 +42,7 @@ #include <limits> #include <cstdlib> -#include "hpp/fcl/broadphase/detail/interval_tree_node.h" +#include "coal/broadphase/detail/interval_tree_node.h" namespace coal { namespace detail { @@ -50,7 +50,7 @@ namespace detail { /// @brief Class describes the information needed when we take the /// right branch in searching for intervals but possibly come back /// and check the left branch as well. -struct HPP_FCL_DLLAPI it_recursion_node { +struct COAL_DLLAPI it_recursion_node { public: IntervalTreeNode* start_node; @@ -60,7 +60,7 @@ struct HPP_FCL_DLLAPI it_recursion_node { }; /// @brief Interval tree -class HPP_FCL_DLLAPI IntervalTree { +class COAL_DLLAPI IntervalTree { public: IntervalTree(); diff --git a/include/coal/broadphase/detail/interval_tree_node-inl.h b/include/coal/broadphase/detail/interval_tree_node-inl.h index 58e01c3fcdbbf4cd875d2c0f077aca1a1ec72d52..1edd7e6d226c7e4952c755f81b829093e0c1f088 100644 --- a/include/coal/broadphase/detail/interval_tree_node-inl.h +++ b/include/coal/broadphase/detail/interval_tree_node-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_INTERVALTREENODE_INL_H #define COAL_BROADPHASE_DETAIL_INTERVALTREENODE_INL_H -#include "hpp/fcl/broadphase/detail/interval_tree_node.h" +#include "coal/broadphase/detail/interval_tree_node.h" #include <iostream> #include <algorithm> diff --git a/include/coal/broadphase/detail/interval_tree_node.h b/include/coal/broadphase/detail/interval_tree_node.h index a6956de2bb02e4be8a109a5759e1ec037ed0ede5..b053a2f9c2d5789c582d56abaa2e0352b585dc7c 100644 --- a/include/coal/broadphase/detail/interval_tree_node.h +++ b/include/coal/broadphase/detail/interval_tree_node.h @@ -38,17 +38,17 @@ #ifndef COAL_BROADPHASE_DETAIL_INTERVALTREENODE_H #define COAL_BROADPHASE_DETAIL_INTERVALTREENODE_H -#include "hpp/fcl/broadphase/detail/simple_interval.h" -#include "hpp/fcl/fwd.hh" +#include "coal/broadphase/detail/simple_interval.h" +#include "coal/fwd.hh" namespace coal { namespace detail { -class HPP_FCL_DLLAPI IntervalTree; +class COAL_DLLAPI IntervalTree; /// @brief The node for interval tree -class HPP_FCL_DLLAPI IntervalTreeNode { +class COAL_DLLAPI IntervalTreeNode { public: friend class IntervalTree; diff --git a/include/coal/broadphase/detail/morton-inl.h b/include/coal/broadphase/detail/morton-inl.h index 80354a76d1f0aa9da462d813f02f99d5543eb1ce..4f27aef9147c76f81ff57c2faff73ac506c72f8f 100644 --- a/include/coal/broadphase/detail/morton-inl.h +++ b/include/coal/broadphase/detail/morton-inl.h @@ -39,7 +39,7 @@ #ifndef COAL_MORTON_INL_H #define COAL_MORTON_INL_H -#include "hpp/fcl/broadphase/detail/morton.h" +#include "coal/broadphase/detail/morton.h" namespace coal { /// @cond IGNORE namespace detail { diff --git a/include/coal/broadphase/detail/morton.h b/include/coal/broadphase/detail/morton.h index a43abdf9a05317877b87c2382893472f7556613f..549e7df0b01d919d45eec7c4877422fc3daa1792 100644 --- a/include/coal/broadphase/detail/morton.h +++ b/include/coal/broadphase/detail/morton.h @@ -39,7 +39,7 @@ #ifndef COAL_MORTON_H #define COAL_MORTON_H -#include "hpp/fcl/BV/AABB.h" +#include "coal/BV/AABB.h" #include <cstdint> #include <bitset> @@ -52,11 +52,11 @@ template <typename S> uint32_t quantize(S x, uint32_t n); /// @brief compute 30 bit morton code -HPP_FCL_DLLAPI +COAL_DLLAPI uint32_t morton_code(uint32_t x, uint32_t y, uint32_t z); /// @brief compute 60 bit morton code -HPP_FCL_DLLAPI +COAL_DLLAPI uint64_t morton_code60(uint32_t x, uint32_t y, uint32_t z); /// @brief Functor to compute the morton code for a given AABB @@ -115,6 +115,6 @@ struct morton_functor<S, std::bitset<N>> { /// @endcond } // namespace coal -#include "hpp/fcl/broadphase/detail/morton-inl.h" +#include "coal/broadphase/detail/morton-inl.h" #endif diff --git a/include/coal/broadphase/detail/node_base-inl.h b/include/coal/broadphase/detail/node_base-inl.h index a4b30052b94c0e2250050a623bd38256a1668a88..db63bcee1de90e67ed056d5b8c2489e32bac0f52 100644 --- a/include/coal/broadphase/detail/node_base-inl.h +++ b/include/coal/broadphase/detail/node_base-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_NODEBASE_INL_H #define COAL_BROADPHASE_DETAIL_NODEBASE_INL_H -#include "hpp/fcl/broadphase/detail/node_base.h" +#include "coal/broadphase/detail/node_base.h" namespace coal { namespace detail { diff --git a/include/coal/broadphase/detail/node_base.h b/include/coal/broadphase/detail/node_base.h index 33ba4789200f069952bcb6b8e433036eeebbab72..179495e6f15755822ba9ce64e90c6e14349dc1b9 100644 --- a/include/coal/broadphase/detail/node_base.h +++ b/include/coal/broadphase/detail/node_base.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_NODEBASE_H #define COAL_BROADPHASE_DETAIL_NODEBASE_H -#include "hpp/fcl/data_types.h" +#include "coal/data_types.h" namespace coal { @@ -74,6 +74,6 @@ struct NodeBase { } // namespace detail } // namespace coal -#include "hpp/fcl/broadphase/detail/node_base-inl.h" +#include "coal/broadphase/detail/node_base-inl.h" #endif diff --git a/include/coal/broadphase/detail/node_base_array-inl.h b/include/coal/broadphase/detail/node_base_array-inl.h index b2f4f6ba2c6ebd34707e81831ca7dcdcd21f9b27..a48fceef939c4f3fbf479cd299f1684f58ca51d3 100644 --- a/include/coal/broadphase/detail/node_base_array-inl.h +++ b/include/coal/broadphase/detail/node_base_array-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_NODEBASEARRAY_INL_H #define COAL_BROADPHASE_DETAIL_NODEBASEARRAY_INL_H -#include "hpp/fcl/broadphase/detail/node_base_array.h" +#include "coal/broadphase/detail/node_base_array.h" namespace coal { diff --git a/include/coal/broadphase/detail/node_base_array.h b/include/coal/broadphase/detail/node_base_array.h index 814b401e685b5d692b305d13edff58987616339d..5c18ef1f7523761ff0839e4b2eab40fde14872e2 100644 --- a/include/coal/broadphase/detail/node_base_array.h +++ b/include/coal/broadphase/detail/node_base_array.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_NODEBASEARRAY_H #define COAL_BROADPHASE_DETAIL_NODEBASEARRAY_H -#include "hpp/fcl/data_types.h" +#include "coal/data_types.h" namespace coal { @@ -70,6 +70,6 @@ struct NodeBase { } // namespace detail } // namespace coal -#include "hpp/fcl/broadphase/detail/node_base_array-inl.h" +#include "coal/broadphase/detail/node_base_array-inl.h" #endif diff --git a/include/coal/broadphase/detail/simple_hash_table-inl.h b/include/coal/broadphase/detail/simple_hash_table-inl.h index 9922982e5f746fbcd05f6684a0fcd8bfded7dd1b..1243d957d0f289d572d82783752d97002125dd45 100644 --- a/include/coal/broadphase/detail/simple_hash_table-inl.h +++ b/include/coal/broadphase/detail/simple_hash_table-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_SIMPLEHASHTABLE_INL_H #define COAL_BROADPHASE_SIMPLEHASHTABLE_INL_H -#include "hpp/fcl/broadphase/detail/simple_hash_table.h" +#include "coal/broadphase/detail/simple_hash_table.h" #include <iterator> namespace coal { diff --git a/include/coal/broadphase/detail/simple_hash_table.h b/include/coal/broadphase/detail/simple_hash_table.h index 8c480a3fbafc0cfb0f63e403dd6df3084761c38b..1b47490266d09d77bd384f2c942e986056617cc5 100644 --- a/include/coal/broadphase/detail/simple_hash_table.h +++ b/include/coal/broadphase/detail/simple_hash_table.h @@ -82,6 +82,6 @@ class SimpleHashTable { } // namespace detail } // namespace coal -#include "hpp/fcl/broadphase/detail/simple_hash_table-inl.h" +#include "coal/broadphase/detail/simple_hash_table-inl.h" #endif diff --git a/include/coal/broadphase/detail/simple_interval-inl.h b/include/coal/broadphase/detail/simple_interval-inl.h index 4625c31e69e57641a2454625c7cadc35c8ea5168..95075cbc19426df136380ae47c42fef70914db8c 100644 --- a/include/coal/broadphase/detail/simple_interval-inl.h +++ b/include/coal/broadphase/detail/simple_interval-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_SIMPLEINTERVAL_INL_H #define COAL_BROADPHASE_DETAIL_SIMPLEINTERVAL_INL_H -#include "hpp/fcl/broadphase/detail/simple_interval.h" +#include "coal/broadphase/detail/simple_interval.h" #include <algorithm> namespace coal { diff --git a/include/coal/broadphase/detail/simple_interval.h b/include/coal/broadphase/detail/simple_interval.h index d94f81e4dc3a7b534435e5735cd8912c19094be2..7b654048c55456ad058faeb0a4f6d57863eae584 100644 --- a/include/coal/broadphase/detail/simple_interval.h +++ b/include/coal/broadphase/detail/simple_interval.h @@ -38,15 +38,15 @@ #ifndef COAL_BROADPHASE_DETAIL_SIMPLEINTERVAL_H #define COAL_BROADPHASE_DETAIL_SIMPLEINTERVAL_H -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/data_types.h" +#include "coal/fwd.hh" +#include "coal/data_types.h" namespace coal { namespace detail { /// @brief Interval trees implemented using red-black-trees as described in /// the book Introduction_To_Algorithms_ by Cormen, Leisserson, and Rivest. -struct HPP_FCL_DLLAPI SimpleInterval { +struct COAL_DLLAPI SimpleInterval { public: virtual ~SimpleInterval(); diff --git a/include/coal/broadphase/detail/sparse_hash_table-inl.h b/include/coal/broadphase/detail/sparse_hash_table-inl.h index 519e493967e2679cbd616678233e08bf4f330834..299f9871ab60c602acffcb654b97a90517216e42 100644 --- a/include/coal/broadphase/detail/sparse_hash_table-inl.h +++ b/include/coal/broadphase/detail/sparse_hash_table-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_SPARSEHASHTABLE_INL_H #define COAL_BROADPHASE_SPARSEHASHTABLE_INL_H -#include "hpp/fcl/broadphase/detail/sparse_hash_table.h" +#include "coal/broadphase/detail/sparse_hash_table.h" namespace coal { diff --git a/include/coal/broadphase/detail/sparse_hash_table.h b/include/coal/broadphase/detail/sparse_hash_table.h index be28e379bdf33c7f7f40c7542fd7c0cd68bc65f0..13c4aeeca5b7f49bc8c4e235c63eaad9cc9e2cd8 100644 --- a/include/coal/broadphase/detail/sparse_hash_table.h +++ b/include/coal/broadphase/detail/sparse_hash_table.h @@ -88,6 +88,6 @@ class SparseHashTable { } // namespace detail } // namespace coal -#include "hpp/fcl/broadphase/detail/sparse_hash_table-inl.h" +#include "coal/broadphase/detail/sparse_hash_table-inl.h" #endif diff --git a/include/coal/broadphase/detail/spatial_hash-inl.h b/include/coal/broadphase/detail/spatial_hash-inl.h index 76714036e8cee620bef2f5a2b746f86b07d0e391..499aee8488937dff24b88a99622d9688bcd6d4fe 100644 --- a/include/coal/broadphase/detail/spatial_hash-inl.h +++ b/include/coal/broadphase/detail/spatial_hash-inl.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_SPATIALHASH_INL_H #define COAL_BROADPHASE_SPATIALHASH_INL_H -#include "hpp/fcl/broadphase/detail/spatial_hash.h" +#include "coal/broadphase/detail/spatial_hash.h" #include <algorithm> namespace coal { diff --git a/include/coal/broadphase/detail/spatial_hash.h b/include/coal/broadphase/detail/spatial_hash.h index e51a403a81efdb6f2941f47a68f7586368d8deb0..a5301a7939780416a300b4c07dd0b90cd2b4d2f9 100644 --- a/include/coal/broadphase/detail/spatial_hash.h +++ b/include/coal/broadphase/detail/spatial_hash.h @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_SPATIALHASH_H #define COAL_BROADPHASE_SPATIALHASH_H -#include "hpp/fcl/BV/AABB.h" +#include "coal/BV/AABB.h" #include <vector> namespace coal { @@ -46,7 +46,7 @@ namespace coal { namespace detail { /// @brief Spatial hash function: hash an AABB to a set of integer values -struct HPP_FCL_DLLAPI SpatialHash { +struct COAL_DLLAPI SpatialHash { SpatialHash(const AABB& scene_limit_, FCL_REAL cell_size_); std::vector<unsigned int> operator()(const AABB& aabb) const; diff --git a/include/coal/collision.h b/include/coal/collision.h index 0a53146b02ad5350693a0f997e9d3c51d88e86d6..39ae20b63954a3522a16107ca765a572f157774d 100644 --- a/include/coal/collision.h +++ b/include/coal/collision.h @@ -39,11 +39,11 @@ #ifndef COAL_COLLISION_H #define COAL_COLLISION_H -#include <hpp/fcl/data_types.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/collision_func_matrix.h> -#include <hpp/fcl/timings.h> +#include "coal/data_types.h" +#include "coal/collision_object.h" +#include "coal/collision_data.h" +#include "coal/collision_func_matrix.h" +#include "coal/timings.h" namespace coal { @@ -54,19 +54,19 @@ namespace coal { /// depth; otherwise only contact primitive id is returned), this function /// performs the collision between them. /// Return value is the number of contacts generated between the two objects. -HPP_FCL_DLLAPI std::size_t collide(const CollisionObject* o1, - const CollisionObject* o2, - const CollisionRequest& request, - CollisionResult& result); +COAL_DLLAPI std::size_t collide(const CollisionObject* o1, + const CollisionObject* o2, + const CollisionRequest& request, + CollisionResult& result); /// @copydoc collide(const CollisionObject*, const CollisionObject*, const /// CollisionRequest&, CollisionResult&) -HPP_FCL_DLLAPI std::size_t collide(const CollisionGeometry* o1, - const Transform3f& tf1, - const CollisionGeometry* o2, - const Transform3f& tf2, - const CollisionRequest& request, - CollisionResult& result); +COAL_DLLAPI std::size_t collide(const CollisionGeometry* o1, + const Transform3f& tf1, + const CollisionGeometry* o2, + const Transform3f& tf2, + const CollisionRequest& request, + CollisionResult& result); /// @brief This class reduces the cost of identifying the geometry pair. /// This is mostly useful for repeated shape-shape queries. @@ -75,7 +75,7 @@ HPP_FCL_DLLAPI std::size_t collide(const CollisionGeometry* o1, /// ComputeCollision calc_collision (o1, o2); /// std::size_t ncontacts = calc_collision(tf1, tf2, request, result); /// \endcode -class HPP_FCL_DLLAPI ComputeCollision { +class COAL_DLLAPI ComputeCollision { public: /// @brief Default constructor from two Collision Geometries. ComputeCollision(const CollisionGeometry* o1, const CollisionGeometry* o2); diff --git a/include/coal/collision_data.h b/include/coal/collision_data.h index cec422aaa77b9fb2bf7b2e7b794a6f31aba35124..505716a7a93ae77110c4fb75cec68fb7eb105f2b 100644 --- a/include/coal/collision_data.h +++ b/include/coal/collision_data.h @@ -45,17 +45,17 @@ #include <limits> #include <numeric> -#include "hpp/fcl/collision_object.h" -#include "hpp/fcl/config.hh" -#include "hpp/fcl/data_types.h" -#include "hpp/fcl/timings.h" -#include "hpp/fcl/narrowphase/narrowphase_defaults.h" -#include "hpp/fcl/logging.h" +#include "coal/collision_object.h" +#include "coal/config.hh" +#include "coal/data_types.h" +#include "coal/timings.h" +#include "coal/narrowphase/narrowphase_defaults.h" +#include "coal/logging.h" namespace coal { /// @brief Contact information returned by collision -struct HPP_FCL_DLLAPI Contact { +struct COAL_DLLAPI Contact { /// @brief collision object 1 const CollisionGeometry* o1; @@ -167,13 +167,13 @@ struct HPP_FCL_DLLAPI Contact { struct QueryResult; /// @brief base class for all query requests -struct HPP_FCL_DLLAPI QueryRequest { +struct COAL_DLLAPI QueryRequest { // @brief Initial guess to use for the GJK algorithm GJKInitialGuess gjk_initial_guess; /// @brief whether enable gjk initial guess /// @Deprecated Use gjk_initial_guess instead - HPP_FCL_DEPRECATED_MESSAGE(Use gjk_initial_guess instead) + COAL_DEPRECATED_MESSAGE(Use gjk_initial_guess instead) bool enable_cached_gjk_guess; /// @brief the gjk initial guess set by user @@ -272,7 +272,7 @@ struct HPP_FCL_DLLAPI QueryRequest { }; /// @brief base class for all query results -struct HPP_FCL_DLLAPI QueryResult { +struct COAL_DLLAPI QueryResult { /// @brief stores the last GJK ray when relevant. Vec3f cached_gjk_guess; @@ -308,7 +308,7 @@ enum CollisionRequestFlag { }; /// @brief request to the collision algorithm -struct HPP_FCL_DLLAPI CollisionRequest : QueryRequest { +struct COAL_DLLAPI CollisionRequest : QueryRequest { /// @brief The maximum number of contacts that can be returned size_t num_max_contacts; @@ -317,7 +317,7 @@ struct HPP_FCL_DLLAPI CollisionRequest : QueryRequest { bool enable_contact; /// Whether a lower bound on distance is returned when objects are disjoint - HPP_FCL_DEPRECATED_MESSAGE(A lower bound on distance is always computed.) + COAL_DEPRECATED_MESSAGE(A lower bound on distance is always computed.) bool enable_distance_lower_bound; /// @brief Distance below which objects are considered in collision. @@ -387,7 +387,7 @@ inline FCL_REAL Contact::getDistanceToCollision( } /// @brief collision result -struct HPP_FCL_DLLAPI CollisionResult : QueryResult { +struct COAL_DLLAPI CollisionResult : QueryResult { private: /// @brief contact information std::vector<Contact> contacts; @@ -508,7 +508,7 @@ struct HPP_FCL_DLLAPI CollisionResult : QueryResult { /// stored in a counter-clockwise fashion. /// @note If needed, the internal algorithms of hpp-fcl can easily be extended /// to compute a contact volume instead of a contact patch. -struct HPP_FCL_DLLAPI ContactPatch { +struct COAL_DLLAPI ContactPatch { public: using Polygon = std::vector<Vec2f>; @@ -722,7 +722,7 @@ inline void constructContactPatchFrameFromContact(const Contact& contact, using SupportSet = ContactPatch; /// @brief Request for a contact patch computation. -struct HPP_FCL_DLLAPI ContactPatchRequest { +struct COAL_DLLAPI ContactPatchRequest { /// @brief Maximum number of contact patches that will be computed. size_t max_num_patch; @@ -820,7 +820,7 @@ struct HPP_FCL_DLLAPI ContactPatchRequest { }; /// @brief Result for a contact patch computation. -struct HPP_FCL_DLLAPI ContactPatchResult { +struct COAL_DLLAPI ContactPatchResult { using ContactPatchVector = std::vector<ContactPatch>; using ContactPatchRef = std::reference_wrapper<ContactPatch>; using ContactPatchRefVector = std::vector<ContactPatchRef>; @@ -983,11 +983,11 @@ struct HPP_FCL_DLLAPI ContactPatchResult { struct DistanceResult; /// @brief request to the distance computation -struct HPP_FCL_DLLAPI DistanceRequest : QueryRequest { +struct COAL_DLLAPI DistanceRequest : QueryRequest { /// @brief whether to return the nearest points. /// Nearest points are always computed and are the points of the shapes that /// achieve a distance of `DistanceResult::min_distance`. - HPP_FCL_DEPRECATED_MESSAGE( + COAL_DEPRECATED_MESSAGE( Nearest points are always computed : they are the points of the shapes that achieve a distance of `DistanceResult::min_distance` @@ -1049,7 +1049,7 @@ struct HPP_FCL_DLLAPI DistanceRequest : QueryRequest { }; /// @brief distance result -struct HPP_FCL_DLLAPI DistanceResult : QueryResult { +struct COAL_DLLAPI DistanceResult : QueryResult { public: /// @brief minimum distance between two objects. /// If two objects are in collision and diff --git a/include/coal/collision_func_matrix.h b/include/coal/collision_func_matrix.h index 5d504c69cc83811bd4f208b0f7b83a7a653dc29e..4311d46136eec8b59f65c5359b09ec4afdf03cee 100644 --- a/include/coal/collision_func_matrix.h +++ b/include/coal/collision_func_matrix.h @@ -38,16 +38,16 @@ #ifndef COAL_COLLISION_FUNC_MATRIX_H #define COAL_COLLISION_FUNC_MATRIX_H -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/collision_object.h" +#include "coal/collision_data.h" +#include "coal/narrowphase/narrowphase.h" namespace coal { /// @brief collision matrix stores the functions for collision between different /// types of objects and provides a uniform call interface -struct HPP_FCL_DLLAPI CollisionFunctionMatrix { +struct COAL_DLLAPI CollisionFunctionMatrix { /// @brief the uniform call interface for collision: for collision, we need /// know /// 1. two objects o1 and o2 and their configuration in world coordinate tf1 diff --git a/include/coal/collision_object.h b/include/coal/collision_object.h index efad46b3ced5dc9a5797ced5ca5ac4460cf86687..5e7900ff0ea1cffd7a85e357513862ff50a23b68 100644 --- a/include/coal/collision_object.h +++ b/include/coal/collision_object.h @@ -41,10 +41,10 @@ #include <limits> #include <typeinfo> -#include <hpp/fcl/deprecated.hh> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/BV/AABB.h> -#include <hpp/fcl/math/transform.h> +#include "coal/deprecated.hh" +#include "coal/fwd.hh" +#include "coal/BV/AABB.h" +#include "coal/math/transform.h" namespace coal { @@ -91,7 +91,7 @@ enum NODE_TYPE { /// @{ /// @brief The geometry for the object for collision or distance computation -class HPP_FCL_DLLAPI CollisionGeometry { +class COAL_DLLAPI CollisionGeometry { public: CollisionGeometry() : aabb_center(Vec3f::Constant((std::numeric_limits<FCL_REAL>::max)())), @@ -211,7 +211,7 @@ class HPP_FCL_DLLAPI CollisionGeometry { /// @brief the object for collision or distance computation, contains the /// geometry and the transform information -class HPP_FCL_DLLAPI CollisionObject { +class COAL_DLLAPI CollisionObject { public: CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_, bool compute_local_aabb = true) diff --git a/include/coal/collision_utility.h b/include/coal/collision_utility.h index e151dd5338dba3152635cf795e138915fa6d0233..7f72d0e9c5895aafd89f3db8c16befe53dbf7f7e 100644 --- a/include/coal/collision_utility.h +++ b/include/coal/collision_utility.h @@ -18,13 +18,13 @@ #ifndef COAL_COLLISION_UTILITY_H #define COAL_COLLISION_UTILITY_H -#include <hpp/fcl/collision_object.h> +#include "coal/collision_object.h" namespace coal { -HPP_FCL_DLLAPI CollisionGeometry* extract(const CollisionGeometry* model, - const Transform3f& pose, - const AABB& aabb); +COAL_DLLAPI CollisionGeometry* extract(const CollisionGeometry* model, + const Transform3f& pose, + const AABB& aabb); /** * \brief Returns the name associated to a NODE_TYPE diff --git a/include/coal/contact_patch.h b/include/coal/contact_patch.h index 7b9159bd39b4f34fb56f600049bb39956f17e7bf..edea02d2cbfa534cd12e43ea5b358103ac3e0236 100644 --- a/include/coal/contact_patch.h +++ b/include/coal/contact_patch.h @@ -37,10 +37,10 @@ #ifndef COAL_CONTACT_PATCH_H #define COAL_CONTACT_PATCH_H -#include "hpp/fcl/data_types.h" -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/contact_patch/contact_patch_solver.h" -#include "hpp/fcl/contact_patch_func_matrix.h" +#include "coal/data_types.h" +#include "coal/collision_data.h" +#include "coal/contact_patch/contact_patch_solver.h" +#include "coal/contact_patch_func_matrix.h" namespace coal { @@ -49,22 +49,22 @@ namespace coal { /// more info on the content of the input/output of this function. Also, please /// read @ref ContactPatch if you want to fully understand what is meant by /// "contact patch". -HPP_FCL_DLLAPI void computeContactPatch(const CollisionGeometry* o1, - const Transform3f& tf1, - const CollisionGeometry* o2, - const Transform3f& tf2, - const CollisionResult& collision_result, - const ContactPatchRequest& request, - ContactPatchResult& result); +COAL_DLLAPI void computeContactPatch(const CollisionGeometry* o1, + const Transform3f& tf1, + const CollisionGeometry* o2, + const Transform3f& tf2, + const CollisionResult& collision_result, + const ContactPatchRequest& request, + ContactPatchResult& result); /// @copydoc computeContactPatch(const CollisionGeometry*, const Transform3f&, // const CollisionGeometry*, const Transform3f&, const CollisionResult&, const // ContactPatchRequest&, ContactPatchResult&); -HPP_FCL_DLLAPI void computeContactPatch(const CollisionObject* o1, - const CollisionObject* o2, - const CollisionResult& collision_result, - const ContactPatchRequest& request, - ContactPatchResult& result); +COAL_DLLAPI void computeContactPatch(const CollisionObject* o1, + const CollisionObject* o2, + const CollisionResult& collision_result, + const ContactPatchRequest& request, + ContactPatchResult& result); /// @brief This class reduces the cost of identifying the geometry pair. /// This is usefull for repeated shape-shape queries. @@ -74,7 +74,7 @@ HPP_FCL_DLLAPI void computeContactPatch(const CollisionObject* o1, /// ComputeContactPatch calc_patch (o1, o2); /// calc_patch(tf1, tf2, collision_result, patch_request, patch_result); /// \endcode -class HPP_FCL_DLLAPI ComputeContactPatch { +class COAL_DLLAPI ComputeContactPatch { public: /// @brief Default constructor from two Collision Geometries. ComputeContactPatch(const CollisionGeometry* o1, const CollisionGeometry* o2); diff --git a/include/coal/contact_patch/contact_patch_solver.h b/include/coal/contact_patch/contact_patch_solver.h index e6af26b57a3e928cb3021b291fbcab5300eedf37..2d230c141e2f03fc4b8b36181ed0c0a2a5451da6 100644 --- a/include/coal/contact_patch/contact_patch_solver.h +++ b/include/coal/contact_patch/contact_patch_solver.h @@ -36,9 +36,9 @@ #ifndef COAL_CONTACT_PATCH_SOLVER_H #define COAL_CONTACT_PATCH_SOLVER_H -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/logging.h" -#include "hpp/fcl/narrowphase/gjk.h" +#include "coal/collision_data.h" +#include "coal/logging.h" +#include "coal/narrowphase/gjk.h" namespace coal { @@ -56,7 +56,7 @@ namespace coal { /// /// TODO(louis): algo improvement: /// - The clipping algo is currently n1 * n2; it can be done in n1 + n2. -struct HPP_FCL_DLLAPI ContactPatchSolver { +struct COAL_DLLAPI ContactPatchSolver { // Note: `ContactPatch` is an alias for `SupportSet`. // The two can be used interchangeably. using ShapeSupportData = details::ShapeSupportData; @@ -203,6 +203,6 @@ struct HPP_FCL_DLLAPI ContactPatchSolver { } // namespace coal -#include "hpp/fcl/contact_patch/contact_patch_solver.hxx" +#include "coal/contact_patch/contact_patch_solver.hxx" #endif // COAL_CONTACT_PATCH_SOLVER_H diff --git a/include/coal/contact_patch/contact_patch_solver.hxx b/include/coal/contact_patch/contact_patch_solver.hxx index d6cc0c96a9d8a0dc286323f158034c8ff3a2170e..9eecdd071e6c1a28e915fa177a2ce3e7def720af 100644 --- a/include/coal/contact_patch/contact_patch_solver.hxx +++ b/include/coal/contact_patch/contact_patch_solver.hxx @@ -37,8 +37,8 @@ #ifndef COAL_CONTACT_PATCH_SOLVER_HXX #define COAL_CONTACT_PATCH_SOLVER_HXX -#include "hpp/fcl/data_types.h" -#include "hpp/fcl/shape/geometric_shapes_traits.h" +#include "coal/data_types.h" +#include "coal/shape/geometric_shapes_traits.h" namespace coal { diff --git a/include/coal/contact_patch_func_matrix.h b/include/coal/contact_patch_func_matrix.h index faa01a9a5a431772a8c68ece8abf9816901e9f8a..50b08d291b40224df652c93b9286e627363c3a1f 100644 --- a/include/coal/contact_patch_func_matrix.h +++ b/include/coal/contact_patch_func_matrix.h @@ -37,16 +37,16 @@ #ifndef COAL_CONTACT_PATCH_FUNC_MATRIX_H #define COAL_CONTACT_PATCH_FUNC_MATRIX_H -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/contact_patch/contact_patch_solver.h" -#include "hpp/fcl/narrowphase/narrowphase.h" +#include "coal/collision_data.h" +#include "coal/contact_patch/contact_patch_solver.h" +#include "coal/narrowphase/narrowphase.h" namespace coal { /// @brief The contact patch matrix stores the functions for contact patches /// computation between different types of objects and provides a uniform call /// interface -struct HPP_FCL_DLLAPI ContactPatchFunctionMatrix { +struct COAL_DLLAPI ContactPatchFunctionMatrix { /// @brief the uniform call interface for computing contact patches: we need /// know /// 1. two objects o1 and o2 and their configuration in world coordinate tf1 diff --git a/include/coal/data_types.h b/include/coal/data_types.h index 2cbb183e9a85ce5595fb51d34c80592de7e10c2d..0759485bf2523079cdbdbcd8192a75fb20c6c4e7 100644 --- a/include/coal/data_types.h +++ b/include/coal/data_types.h @@ -42,7 +42,7 @@ #include <Eigen/Core> #include <Eigen/Geometry> -#include <hpp/fcl/config.hh> +#include "coal/config.hh" #ifdef HPP_FCL_HAS_OCTOMAP #define OCTOMAP_VERSION_AT_LEAST(x, y, z) \ @@ -94,7 +94,7 @@ enum GJKConvergenceCriterion { Default, DualityGap, Hybrid }; enum GJKConvergenceCriterionType { Relative, Absolute }; /// @brief Triangle with 3 indices for points -class HPP_FCL_DLLAPI Triangle { +class COAL_DLLAPI Triangle { public: typedef std::size_t index_type; typedef int size_type; @@ -140,7 +140,7 @@ class HPP_FCL_DLLAPI Triangle { }; /// @brief Quadrilateral with 4 indices for points -struct HPP_FCL_DLLAPI Quadrilateral { +struct COAL_DLLAPI Quadrilateral { typedef std::size_t index_type; typedef int size_type; diff --git a/include/coal/distance.h b/include/coal/distance.h index f734c760ae6b46c5160f7cabc82f614959b9be4e..bf4beef7a6fee8f0549dba8fd90cd9cacc529136 100644 --- a/include/coal/distance.h +++ b/include/coal/distance.h @@ -38,10 +38,10 @@ #ifndef COAL_DISTANCE_H #define COAL_DISTANCE_H -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/distance_func_matrix.h> -#include <hpp/fcl/timings.h> +#include "coal/collision_object.h" +#include "coal/collision_data.h" +#include "coal/distance_func_matrix.h" +#include "coal/timings.h" namespace coal { @@ -49,19 +49,19 @@ namespace coal { /// 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. -HPP_FCL_DLLAPI FCL_REAL distance(const CollisionObject* o1, - const CollisionObject* o2, - const DistanceRequest& request, - DistanceResult& result); +COAL_DLLAPI FCL_REAL distance(const CollisionObject* o1, + const CollisionObject* o2, + const DistanceRequest& request, + DistanceResult& result); /// @copydoc distance(const CollisionObject*, const CollisionObject*, const /// DistanceRequest&, DistanceResult&) -HPP_FCL_DLLAPI FCL_REAL distance(const CollisionGeometry* o1, - const Transform3f& tf1, - const CollisionGeometry* o2, - const Transform3f& tf2, - const DistanceRequest& request, - DistanceResult& result); +COAL_DLLAPI FCL_REAL distance(const CollisionGeometry* o1, + const Transform3f& tf1, + const CollisionGeometry* o2, + const Transform3f& tf2, + const DistanceRequest& request, + DistanceResult& result); /// This class reduces the cost of identifying the geometry pair. /// This is mostly useful for repeated shape-shape queries. @@ -70,7 +70,7 @@ HPP_FCL_DLLAPI FCL_REAL distance(const CollisionGeometry* o1, /// ComputeDistance calc_distance (o1, o2); /// FCL_REAL distance = calc_distance(tf1, tf2, request, result); /// \endcode -class HPP_FCL_DLLAPI ComputeDistance { +class COAL_DLLAPI ComputeDistance { public: ComputeDistance(const CollisionGeometry* o1, const CollisionGeometry* o2); diff --git a/include/coal/distance_func_matrix.h b/include/coal/distance_func_matrix.h index 29d79a5cb20dd390218429f78746860718c6b287..d6bd5b7e66b66f08bc759854c17263fc8b9ab148 100644 --- a/include/coal/distance_func_matrix.h +++ b/include/coal/distance_func_matrix.h @@ -38,15 +38,15 @@ #ifndef COAL_DISTANCE_FUNC_MATRIX_H #define COAL_DISTANCE_FUNC_MATRIX_H -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/collision_object.h" +#include "coal/collision_data.h" +#include "coal/narrowphase/narrowphase.h" namespace coal { /// @brief distance matrix stores the functions for distance between different /// types of objects and provides a uniform call interface -struct HPP_FCL_DLLAPI DistanceFunctionMatrix { +struct COAL_DLLAPI DistanceFunctionMatrix { /// @brief the uniform call interface for distance: for distance, we need know /// 1. two objects o1 and o2 and their configuration in world coordinate tf1 /// and tf2; diff --git a/include/coal/fwd.hh b/include/coal/fwd.hh index 14b673c20f35be0dffb3166c37c83b68e9fba9d9..e699a7b169e5968e094e7e7013a33385aa62f83c 100644 --- a/include/coal/fwd.hh +++ b/include/coal/fwd.hh @@ -43,9 +43,9 @@ #include <sstream> #include <stdexcept> -#include <hpp/fcl/config.hh> -#include <hpp/fcl/deprecated.hh> -#include <hpp/fcl/warning.hh> +#include "coal/config.hh" +#include "coal/deprecated.hh" +#include "coal/warning.hh" #if _WIN32 #define HPP_FCL_PRETTY_FUNCTION __FUNCSIG__ diff --git a/include/coal/hfield.h b/include/coal/hfield.h index af6b4362905fffc15e427c7eee9e536d5e533fbe..571d150cab2e6034e1cbecd6b2fee60713758d4d 100644 --- a/include/coal/hfield.h +++ b/include/coal/hfield.h @@ -37,11 +37,11 @@ #ifndef COAL_HEIGHT_FIELD_H #define COAL_HEIGHT_FIELD_H -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/data_types.h" -#include "hpp/fcl/collision_object.h" -#include "hpp/fcl/BV/BV_node.h" -#include "hpp/fcl/BVH/BVH_internal.h" +#include "coal/fwd.hh" +#include "coal/data_types.h" +#include "coal/collision_object.h" +#include "coal/BV/BV_node.h" +#include "coal/BVH/BVH_internal.h" #include <vector> @@ -50,7 +50,7 @@ namespace coal { /// @addtogroup Construction_Of_HeightField /// @{ -struct HPP_FCL_DLLAPI HFNodeBase { +struct COAL_DLLAPI HFNodeBase { EIGEN_MAKE_ALIGNED_OPERATOR_NEW enum class FaceOrientation { @@ -125,7 +125,7 @@ inline int operator&(int a, HFNodeBase::FaceOrientation b) { } template <typename BV> -struct HPP_FCL_DLLAPI HFNode : public HFNodeBase { +struct COAL_DLLAPI HFNode : public HFNodeBase { EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef HFNodeBase Base; @@ -199,7 +199,7 @@ struct UpdateBoundingVolume<AABB> { /// The height field is centered at the origin and the corners of the geometry /// correspond to the following coordinates [± x_dim/2; ± y_dim/2]. template <typename BV> -class HPP_FCL_DLLAPI HeightField : public CollisionGeometry { +class COAL_DLLAPI HeightField : public CollisionGeometry { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/include/coal/internal/BV_fitter.h b/include/coal/internal/BV_fitter.h index 4461b0b2200e31e86e91ea1ce2776d9431eafd52..93f1267826d0cf5369f09603ec0c536713d236e9 100644 --- a/include/coal/internal/BV_fitter.h +++ b/include/coal/internal/BV_fitter.h @@ -38,10 +38,10 @@ #ifndef COAL_BV_FITTER_H #define COAL_BV_FITTER_H -#include <hpp/fcl/BVH/BVH_internal.h> -#include <hpp/fcl/BV/kIOS.h> -#include <hpp/fcl/BV/OBBRSS.h> -#include <hpp/fcl/BV/AABB.h> +#include "coal/BVH/BVH_internal.h" +#include "coal/BV/kIOS.h" +#include "coal/BV/OBBRSS.h" +#include "coal/BV/AABB.h" #include <iostream> namespace coal { @@ -73,7 +73,7 @@ void fit<AABB>(Vec3f* ps, unsigned int n, AABB& bv); /// @brief The class for the default algorithm fitting a bounding volume to a /// set of points template <typename BV> -class HPP_FCL_DLLAPI BVFitterTpl { +class COAL_DLLAPI BVFitterTpl { public: /// @brief default deconstructor virtual ~BVFitterTpl() {} @@ -118,7 +118,7 @@ class HPP_FCL_DLLAPI BVFitterTpl { /// @brief The class for the default algorithm fitting a bounding volume to a /// set of points template <typename BV> -class HPP_FCL_DLLAPI BVFitter : public BVFitterTpl<BV> { +class COAL_DLLAPI BVFitter : public BVFitterTpl<BV> { typedef BVFitterTpl<BV> Base; public: @@ -167,7 +167,7 @@ class HPP_FCL_DLLAPI BVFitter : public BVFitterTpl<BV> { /// @brief Specification of BVFitter for OBB bounding volume template <> -class HPP_FCL_DLLAPI BVFitter<OBB> : public BVFitterTpl<OBB> { +class COAL_DLLAPI BVFitter<OBB> : public BVFitterTpl<OBB> { public: /// @brief Compute a bounding volume that fits a set of primitives (points or /// triangles). The primitive data was set by set function and @@ -177,7 +177,7 @@ class HPP_FCL_DLLAPI BVFitter<OBB> : public BVFitterTpl<OBB> { /// @brief Specification of BVFitter for RSS bounding volume template <> -class HPP_FCL_DLLAPI BVFitter<RSS> : public BVFitterTpl<RSS> { +class COAL_DLLAPI BVFitter<RSS> : public BVFitterTpl<RSS> { public: /// @brief Compute a bounding volume that fits a set of primitives (points or /// triangles). The primitive data was set by set function and @@ -187,7 +187,7 @@ class HPP_FCL_DLLAPI BVFitter<RSS> : public BVFitterTpl<RSS> { /// @brief Specification of BVFitter for kIOS bounding volume template <> -class HPP_FCL_DLLAPI BVFitter<kIOS> : public BVFitterTpl<kIOS> { +class COAL_DLLAPI BVFitter<kIOS> : public BVFitterTpl<kIOS> { public: /// @brief Compute a bounding volume that fits a set of primitives (points or /// triangles). The primitive data was set by set function and @@ -197,7 +197,7 @@ class HPP_FCL_DLLAPI BVFitter<kIOS> : public BVFitterTpl<kIOS> { /// @brief Specification of BVFitter for OBBRSS bounding volume template <> -class HPP_FCL_DLLAPI BVFitter<OBBRSS> : public BVFitterTpl<OBBRSS> { +class COAL_DLLAPI BVFitter<OBBRSS> : public BVFitterTpl<OBBRSS> { public: /// @brief Compute a bounding volume that fits a set of primitives (points or /// triangles). The primitive data was set by set function and @@ -207,7 +207,7 @@ class HPP_FCL_DLLAPI BVFitter<OBBRSS> : public BVFitterTpl<OBBRSS> { /// @brief Specification of BVFitter for AABB bounding volume template <> -class HPP_FCL_DLLAPI BVFitter<AABB> : public BVFitterTpl<AABB> { +class COAL_DLLAPI BVFitter<AABB> : public BVFitterTpl<AABB> { public: /// @brief Compute a bounding volume that fits a set of primitives (points or /// triangles). The primitive data was set by set function and diff --git a/include/coal/internal/BV_splitter.h b/include/coal/internal/BV_splitter.h index d5edd706cb40bb7d878ec4350465d8b35d4619e2..01fabf1c72b212499b6e9f7f37747c491390acf6 100644 --- a/include/coal/internal/BV_splitter.h +++ b/include/coal/internal/BV_splitter.h @@ -38,9 +38,9 @@ #ifndef COAL_BV_SPLITTER_H #define COAL_BV_SPLITTER_H -#include <hpp/fcl/BVH/BVH_internal.h> -#include <hpp/fcl/BV/kIOS.h> -#include <hpp/fcl/BV/OBBRSS.h> +#include "coal/BVH/BVH_internal.h" +#include "coal/BV/kIOS.h" +#include "coal/BV/OBBRSS.h" #include <vector> #include <iostream> @@ -207,74 +207,74 @@ class BVSplitter { }; template <> -bool HPP_FCL_DLLAPI BVSplitter<OBB>::apply(const Vec3f& q) const; +bool COAL_DLLAPI BVSplitter<OBB>::apply(const Vec3f& q) const; template <> -bool HPP_FCL_DLLAPI BVSplitter<RSS>::apply(const Vec3f& q) const; +bool COAL_DLLAPI BVSplitter<RSS>::apply(const Vec3f& q) const; template <> -bool HPP_FCL_DLLAPI BVSplitter<kIOS>::apply(const Vec3f& q) const; +bool COAL_DLLAPI BVSplitter<kIOS>::apply(const Vec3f& q) const; template <> -bool HPP_FCL_DLLAPI BVSplitter<OBBRSS>::apply(const Vec3f& q) const; +bool COAL_DLLAPI BVSplitter<OBBRSS>::apply(const Vec3f& q) const; template <> -void HPP_FCL_DLLAPI BVSplitter<OBB>::computeRule_bvcenter( +void COAL_DLLAPI BVSplitter<OBB>::computeRule_bvcenter( const OBB& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<OBB>::computeRule_mean( +void COAL_DLLAPI BVSplitter<OBB>::computeRule_mean( const OBB& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<OBB>::computeRule_median( +void COAL_DLLAPI BVSplitter<OBB>::computeRule_median( const OBB& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<RSS>::computeRule_bvcenter( +void COAL_DLLAPI BVSplitter<RSS>::computeRule_bvcenter( const RSS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<RSS>::computeRule_mean( +void COAL_DLLAPI BVSplitter<RSS>::computeRule_mean( const RSS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<RSS>::computeRule_median( +void COAL_DLLAPI BVSplitter<RSS>::computeRule_median( const RSS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<kIOS>::computeRule_bvcenter( +void COAL_DLLAPI BVSplitter<kIOS>::computeRule_bvcenter( const kIOS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<kIOS>::computeRule_mean( +void COAL_DLLAPI BVSplitter<kIOS>::computeRule_mean( const kIOS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<kIOS>::computeRule_median( +void COAL_DLLAPI BVSplitter<kIOS>::computeRule_median( const kIOS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<OBBRSS>::computeRule_bvcenter( +void COAL_DLLAPI BVSplitter<OBBRSS>::computeRule_bvcenter( const OBBRSS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<OBBRSS>::computeRule_mean( +void COAL_DLLAPI BVSplitter<OBBRSS>::computeRule_mean( const OBBRSS& bv, unsigned int* primitive_indices, unsigned int num_primitives); template <> -void HPP_FCL_DLLAPI BVSplitter<OBBRSS>::computeRule_median( +void COAL_DLLAPI BVSplitter<OBBRSS>::computeRule_median( const OBBRSS& bv, unsigned int* primitive_indices, unsigned int num_primitives); diff --git a/include/coal/internal/intersect.h b/include/coal/internal/intersect.h index d6dd5f5188b72d6a288c30d46c76602abf643ded..0353df055b89297b362057ce29724649b3687613 100644 --- a/include/coal/internal/intersect.h +++ b/include/coal/internal/intersect.h @@ -40,21 +40,21 @@ /// @cond INTERNAL -#include <hpp/fcl/math/transform.h> +#include "coal/math/transform.h" namespace coal { /// @brief CCD intersect kernel among primitives -class HPP_FCL_DLLAPI Intersect { +class COAL_DLLAPI Intersect { public: static bool buildTrianglePlane(const Vec3f& v1, const Vec3f& v2, const Vec3f& v3, Vec3f* n, FCL_REAL* t); }; // class Intersect /// @brief Project functions -class HPP_FCL_DLLAPI Project { +class COAL_DLLAPI Project { public: - struct HPP_FCL_DLLAPI ProjectResult { + struct COAL_DLLAPI ProjectResult { /// @brief Parameterization of the projected point (based on the simplex to /// be projected, use 2 or 3 or 4 of the array) FCL_REAL parameterization[4]; @@ -94,7 +94,7 @@ class HPP_FCL_DLLAPI Project { }; /// @brief Triangle distance functions -class HPP_FCL_DLLAPI TriangleDistance { +class COAL_DLLAPI TriangleDistance { public: /// @brief Returns closest points between an segment pair. /// The first segment is P + t * A diff --git a/include/coal/internal/shape_shape_contact_patch_func.h b/include/coal/internal/shape_shape_contact_patch_func.h index 1f6fc49239b195f00a76a6207f693cc436cda88c..e854fb57751b0c360c762d69c38a96641ce302ca 100644 --- a/include/coal/internal/shape_shape_contact_patch_func.h +++ b/include/coal/internal/shape_shape_contact_patch_func.h @@ -37,11 +37,11 @@ #ifndef COAL_INTERNAL_SHAPE_SHAPE_CONTACT_PATCH_FUNC_H #define COAL_INTERNAL_SHAPE_SHAPE_CONTACT_PATCH_FUNC_H -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/collision_utility.h" -#include "hpp/fcl/narrowphase/narrowphase.h" -#include "hpp/fcl/contact_patch/contact_patch_solver.h" -#include "hpp/fcl/shape/geometric_shapes_traits.h" +#include "coal/collision_data.h" +#include "coal/collision_utility.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/contact_patch/contact_patch_solver.h" +#include "coal/shape/geometric_shapes_traits.h" namespace coal { diff --git a/include/coal/internal/shape_shape_func.h b/include/coal/internal/shape_shape_func.h index cee08823c651f84aaf0dadd4b9d92424446dd067..64b11d3b82de2e9888b303d15b2b27c8a821b3ea 100644 --- a/include/coal/internal/shape_shape_func.h +++ b/include/coal/internal/shape_shape_func.h @@ -40,10 +40,10 @@ /// @cond INTERNAL -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/collision_utility.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes_traits.h> +#include "coal/collision_data.h" +#include "coal/collision_utility.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes_traits.h" namespace coal { @@ -212,19 +212,19 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1, #define SHAPE_SHAPE_DISTANCE_SPECIALIZATION(T1, T2) \ template <> \ - HPP_FCL_DLLAPI FCL_REAL internal::ShapeShapeDistance<T1, T2>( \ + COAL_DLLAPI FCL_REAL internal::ShapeShapeDistance<T1, T2>( \ const CollisionGeometry* o1, const Transform3f& tf1, \ const CollisionGeometry* o2, const Transform3f& tf2, \ const GJKSolver* nsolver, const bool compute_signed_distance, Vec3f& p1, \ Vec3f& p2, Vec3f& normal); \ template <> \ - HPP_FCL_DLLAPI FCL_REAL internal::ShapeShapeDistance<T2, T1>( \ + COAL_DLLAPI FCL_REAL internal::ShapeShapeDistance<T2, T1>( \ const CollisionGeometry* o1, const Transform3f& tf1, \ const CollisionGeometry* o2, const Transform3f& tf2, \ const GJKSolver* nsolver, const bool compute_signed_distance, Vec3f& p1, \ Vec3f& p2, Vec3f& normal); \ template <> \ - inline HPP_FCL_DLLAPI FCL_REAL ShapeShapeDistance<T1, T2>( \ + inline COAL_DLLAPI FCL_REAL ShapeShapeDistance<T1, T2>( \ const CollisionGeometry* o1, const Transform3f& tf1, \ const CollisionGeometry* o2, const Transform3f& tf2, \ const GJKSolver* nsolver, const DistanceRequest& request, \ @@ -239,7 +239,7 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1, return result.min_distance; \ } \ template <> \ - inline HPP_FCL_DLLAPI FCL_REAL ShapeShapeDistance<T2, T1>( \ + inline COAL_DLLAPI FCL_REAL ShapeShapeDistance<T2, T1>( \ const CollisionGeometry* o1, const Transform3f& tf1, \ const CollisionGeometry* o2, const Transform3f& tf2, \ const GJKSolver* nsolver, const DistanceRequest& request, \ @@ -256,13 +256,13 @@ std::size_t ShapeShapeCollide(const CollisionGeometry* o1, #define SHAPE_SELF_DISTANCE_SPECIALIZATION(T) \ template <> \ - HPP_FCL_DLLAPI FCL_REAL internal::ShapeShapeDistance<T, T>( \ + COAL_DLLAPI FCL_REAL internal::ShapeShapeDistance<T, T>( \ const CollisionGeometry* o1, const Transform3f& tf1, \ const CollisionGeometry* o2, const Transform3f& tf2, \ const GJKSolver* nsolver, const bool compute_signed_distance, Vec3f& p1, \ Vec3f& p2, Vec3f& normal); \ template <> \ - inline HPP_FCL_DLLAPI FCL_REAL ShapeShapeDistance<T, T>( \ + inline COAL_DLLAPI FCL_REAL ShapeShapeDistance<T, T>( \ const CollisionGeometry* o1, const Transform3f& tf1, \ const CollisionGeometry* o2, const Transform3f& tf2, \ const GJKSolver* nsolver, const DistanceRequest& request, \ diff --git a/include/coal/internal/tools.h b/include/coal/internal/tools.h index e9a918a129933e6ee5e3563cbd4e992ce5ac7ef4..cb3eb0e0e6413df4326fa0e0d2eb4023b9fa6a87 100644 --- a/include/coal/internal/tools.h +++ b/include/coal/internal/tools.h @@ -38,13 +38,13 @@ #ifndef COAL_INTERNAL_TOOLS_H #define COAL_INTERNAL_TOOLS_H -#include <hpp/fcl/fwd.hh> +#include "coal/fwd.hh" #include <cmath> #include <iostream> #include <limits> -#include <hpp/fcl/data_types.h> +#include "coal/data_types.h" namespace coal { diff --git a/include/coal/internal/traversal.h b/include/coal/internal/traversal.h index eb74e2ab8d30644dae877ddfcb2d9507ba05e0ba..033ae89dd7a88292909b8f704a527b7dbdaf229b 100644 --- a/include/coal/internal/traversal.h +++ b/include/coal/internal/traversal.h @@ -45,7 +45,7 @@ enum { RelativeTransformationIsIdentity = 1 }; namespace details { template <bool enabled> -struct HPP_FCL_DLLAPI RelativeTransformation { +struct COAL_DLLAPI RelativeTransformation { RelativeTransformation() : R(Matrix3f::Identity()) {} const Matrix3f& _R() const { return R; } @@ -56,7 +56,7 @@ struct HPP_FCL_DLLAPI RelativeTransformation { }; template <> -struct HPP_FCL_DLLAPI RelativeTransformation<false> { +struct COAL_DLLAPI RelativeTransformation<false> { static const Matrix3f& _R() { HPP_FCL_THROW_PRETTY("should never reach this point", std::logic_error); } diff --git a/include/coal/internal/traversal_node_base.h b/include/coal/internal/traversal_node_base.h index b27334b4c0e0f370751527d1797f370ceb5609ec..3dc33f3219be078f5674cd29eab5760ffe7c29f4 100644 --- a/include/coal/internal/traversal_node_base.h +++ b/include/coal/internal/traversal_node_base.h @@ -40,9 +40,9 @@ /// @cond INTERNAL -#include <hpp/fcl/data_types.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision_data.h> +#include "coal/data_types.h" +#include "coal/math/transform.h" +#include "coal/collision_data.h" namespace coal { diff --git a/include/coal/internal/traversal_node_bvh_hfield.h b/include/coal/internal/traversal_node_bvh_hfield.h index dc43abbc58e28b888f983bd11b4f2e9c20f4c1b7..c9c1c659a162da54601692b33c965a9bde1ef4d7 100644 --- a/include/coal/internal/traversal_node_bvh_hfield.h +++ b/include/coal/internal/traversal_node_bvh_hfield.h @@ -39,17 +39,17 @@ /// @cond INTERNAL -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/internal/traversal_node_hfield_shape.h> -#include <hpp/fcl/BV/BV_node.h> -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/hfield.h> -#include <hpp/fcl/internal/intersect.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/internal/traversal.h> +#include "coal/collision_data.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/traversal_node_hfield_shape.h" +#include "coal/BV/BV_node.h" +#include "coal/BV/BV.h" +#include "coal/BVH/BVH_model.h" +#include "coal/hfield.h" +#include "coal/internal/intersect.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/internal/traversal.h" #include <limits> #include <vector> diff --git a/include/coal/internal/traversal_node_bvh_shape.h b/include/coal/internal/traversal_node_bvh_shape.h index 7e03bf9dd2ebe744bca33c9ffa45e5e0b283124c..3b5d09ce6b988987edd492835f7076df9991bcf5 100644 --- a/include/coal/internal/traversal_node_bvh_shape.h +++ b/include/coal/internal/traversal_node_bvh_shape.h @@ -40,14 +40,14 @@ /// @cond INTERNAL -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/internal/traversal.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/collision_data.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/traversal.h" +#include "coal/BVH/BVH_model.h" +#include "coal/internal/shape_shape_func.h" namespace coal { diff --git a/include/coal/internal/traversal_node_bvhs.h b/include/coal/internal/traversal_node_bvhs.h index 56cb923b52ebb54e5fae60ac15a3fa38747dd83f..2f6fd1c91e6f2b07a7da00203903a89379c628af 100644 --- a/include/coal/internal/traversal_node_bvhs.h +++ b/include/coal/internal/traversal_node_bvhs.h @@ -40,16 +40,16 @@ /// @cond INTERNAL -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/BV/BV_node.h> -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/internal/intersect.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/internal/traversal.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/collision_data.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/BV/BV_node.h" +#include "coal/BV/BV.h" +#include "coal/BVH/BVH_model.h" +#include "coal/internal/intersect.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/internal/traversal.h" +#include "coal/internal/shape_shape_func.h" #include <cassert> diff --git a/include/coal/internal/traversal_node_hfield_shape.h b/include/coal/internal/traversal_node_hfield_shape.h index 2b62dead1caeda87f49287896e91dfe8e89fe336..afc8c4bf8d9021fa148570a593290f9ed5b15e8f 100644 --- a/include/coal/internal/traversal_node_hfield_shape.h +++ b/include/coal/internal/traversal_node_hfield_shape.h @@ -39,16 +39,16 @@ /// @cond INTERNAL -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/internal/shape_shape_func.h> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/internal/traversal.h> -#include <hpp/fcl/internal/intersect.h> -#include <hpp/fcl/hfield.h> -#include <hpp/fcl/shape/convex.h> +#include "coal/collision_data.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/shape_shape_func.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/traversal.h" +#include "coal/internal/intersect.h" +#include "coal/hfield.h" +#include "coal/shape/convex.h" namespace coal { diff --git a/include/coal/internal/traversal_node_octree.h b/include/coal/internal/traversal_node_octree.h index 55a622cd1d3369a7d8be96bb0fbb3f48c57b1490..33bd2e1f08b1838b227ee14c63bf746a15646b29 100644 --- a/include/coal/internal/traversal_node_octree.h +++ b/include/coal/internal/traversal_node_octree.h @@ -41,20 +41,20 @@ /// @cond INTERNAL -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/internal/traversal_node_hfield_shape.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/hfield.h> -#include <hpp/fcl/octree.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/collision_data.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/traversal_node_hfield_shape.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/hfield.h" +#include "coal/octree.h" +#include "coal/BVH/BVH_model.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/shape_shape_func.h" namespace coal { /// @brief Algorithms for collision related with octree -class HPP_FCL_DLLAPI OcTreeSolver { +class COAL_DLLAPI OcTreeSolver { private: const GJKSolver* solver; @@ -1005,7 +1005,7 @@ class HPP_FCL_DLLAPI OcTreeSolver { /// @{ /// @brief Traversal node for octree collision -class HPP_FCL_DLLAPI OcTreeCollisionTraversalNode +class COAL_DLLAPI OcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: OcTreeCollisionTraversalNode(const CollisionRequest& request) @@ -1034,7 +1034,7 @@ class HPP_FCL_DLLAPI OcTreeCollisionTraversalNode /// @brief Traversal node for shape-octree collision template <typename S> -class HPP_FCL_DLLAPI ShapeOcTreeCollisionTraversalNode +class COAL_DLLAPI ShapeOcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: ShapeOcTreeCollisionTraversalNode(const CollisionRequest& request) @@ -1067,7 +1067,7 @@ class HPP_FCL_DLLAPI ShapeOcTreeCollisionTraversalNode /// @brief Traversal node for octree-shape collision template <typename S> -class HPP_FCL_DLLAPI OcTreeShapeCollisionTraversalNode +class COAL_DLLAPI OcTreeShapeCollisionTraversalNode : public CollisionTraversalNodeBase { public: OcTreeShapeCollisionTraversalNode(const CollisionRequest& request) @@ -1099,7 +1099,7 @@ class HPP_FCL_DLLAPI OcTreeShapeCollisionTraversalNode /// @brief Traversal node for mesh-octree collision template <typename BV> -class HPP_FCL_DLLAPI MeshOcTreeCollisionTraversalNode +class COAL_DLLAPI MeshOcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: MeshOcTreeCollisionTraversalNode(const CollisionRequest& request) @@ -1131,7 +1131,7 @@ class HPP_FCL_DLLAPI MeshOcTreeCollisionTraversalNode /// @brief Traversal node for octree-mesh collision template <typename BV> -class HPP_FCL_DLLAPI OcTreeMeshCollisionTraversalNode +class COAL_DLLAPI OcTreeMeshCollisionTraversalNode : public CollisionTraversalNodeBase { public: OcTreeMeshCollisionTraversalNode(const CollisionRequest& request) @@ -1163,7 +1163,7 @@ class HPP_FCL_DLLAPI OcTreeMeshCollisionTraversalNode /// @brief Traversal node for octree-height-field collision template <typename BV> -class HPP_FCL_DLLAPI OcTreeHeightFieldCollisionTraversalNode +class COAL_DLLAPI OcTreeHeightFieldCollisionTraversalNode : public CollisionTraversalNodeBase { public: OcTreeHeightFieldCollisionTraversalNode(const CollisionRequest& request) @@ -1194,7 +1194,7 @@ class HPP_FCL_DLLAPI OcTreeHeightFieldCollisionTraversalNode /// @brief Traversal node for octree-height-field collision template <typename BV> -class HPP_FCL_DLLAPI HeightFieldOcTreeCollisionTraversalNode +class COAL_DLLAPI HeightFieldOcTreeCollisionTraversalNode : public CollisionTraversalNodeBase { public: HeightFieldOcTreeCollisionTraversalNode(const CollisionRequest& request) @@ -1229,7 +1229,7 @@ class HPP_FCL_DLLAPI HeightFieldOcTreeCollisionTraversalNode /// @{ /// @brief Traversal node for octree distance -class HPP_FCL_DLLAPI OcTreeDistanceTraversalNode +class COAL_DLLAPI OcTreeDistanceTraversalNode : public DistanceTraversalNodeBase { public: OcTreeDistanceTraversalNode() { @@ -1257,7 +1257,7 @@ class HPP_FCL_DLLAPI OcTreeDistanceTraversalNode /// @brief Traversal node for shape-octree distance template <typename Shape> -class HPP_FCL_DLLAPI ShapeOcTreeDistanceTraversalNode +class COAL_DLLAPI ShapeOcTreeDistanceTraversalNode : public DistanceTraversalNodeBase { public: ShapeOcTreeDistanceTraversalNode() { @@ -1281,7 +1281,7 @@ class HPP_FCL_DLLAPI ShapeOcTreeDistanceTraversalNode /// @brief Traversal node for octree-shape distance template <typename Shape> -class HPP_FCL_DLLAPI OcTreeShapeDistanceTraversalNode +class COAL_DLLAPI OcTreeShapeDistanceTraversalNode : public DistanceTraversalNodeBase { public: OcTreeShapeDistanceTraversalNode() { @@ -1305,7 +1305,7 @@ class HPP_FCL_DLLAPI OcTreeShapeDistanceTraversalNode /// @brief Traversal node for mesh-octree distance template <typename BV> -class HPP_FCL_DLLAPI MeshOcTreeDistanceTraversalNode +class COAL_DLLAPI MeshOcTreeDistanceTraversalNode : public DistanceTraversalNodeBase { public: MeshOcTreeDistanceTraversalNode() { @@ -1329,7 +1329,7 @@ class HPP_FCL_DLLAPI MeshOcTreeDistanceTraversalNode /// @brief Traversal node for octree-mesh distance template <typename BV> -class HPP_FCL_DLLAPI OcTreeMeshDistanceTraversalNode +class COAL_DLLAPI OcTreeMeshDistanceTraversalNode : public DistanceTraversalNodeBase { public: OcTreeMeshDistanceTraversalNode() { diff --git a/include/coal/internal/traversal_node_setup.h b/include/coal/internal/traversal_node_setup.h index b3644f5283c26c3ef805e15a67841a3e84b32544..d63af3da6c9e115d233813a00a19be1959e50728 100644 --- a/include/coal/internal/traversal_node_setup.h +++ b/include/coal/internal/traversal_node_setup.h @@ -40,20 +40,20 @@ /// @cond INTERNAL -#include <hpp/fcl/internal/tools.h> -#include <hpp/fcl/internal/traversal_node_shapes.h> +#include "coal/internal/tools.h" +#include "coal/internal/traversal_node_shapes.h" -#include <hpp/fcl/internal/traversal_node_bvhs.h> -#include <hpp/fcl/internal/traversal_node_bvh_shape.h> +#include "coal/internal/traversal_node_bvhs.h" +#include "coal/internal/traversal_node_bvh_shape.h" // #include <hpp/fcl/internal/traversal_node_hfields.h> -#include <hpp/fcl/internal/traversal_node_hfield_shape.h> +#include "coal/internal/traversal_node_hfield_shape.h" #ifdef HPP_FCL_HAS_OCTOMAP -#include <hpp/fcl/internal/traversal_node_octree.h> +#include "coal/internal/traversal_node_octree.h" #endif -#include <hpp/fcl/BVH/BVH_utility.h> +#include "coal/BVH/BVH_utility.h" namespace coal { diff --git a/include/coal/internal/traversal_node_shapes.h b/include/coal/internal/traversal_node_shapes.h index 4e0326a946312b70b445fc2cbe972decee042f70..b38885888193024def61f780708080a4aa00a741 100644 --- a/include/coal/internal/traversal_node_shapes.h +++ b/include/coal/internal/traversal_node_shapes.h @@ -40,11 +40,11 @@ /// @cond INTERNAL -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/BV/BV.h" -#include "hpp/fcl/shape/geometric_shapes_utility.h" -#include "hpp/fcl/internal/traversal_node_base.h" -#include "hpp/fcl/internal/shape_shape_func.h" +#include "coal/collision_data.h" +#include "coal/BV/BV.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/shape_shape_func.h" namespace coal { @@ -53,7 +53,7 @@ namespace coal { /// @brief Traversal node for collision between two shapes template <typename S1, typename S2> -class HPP_FCL_DLLAPI ShapeCollisionTraversalNode +class COAL_DLLAPI ShapeCollisionTraversalNode : public CollisionTraversalNodeBase { public: ShapeCollisionTraversalNode(const CollisionRequest& request) @@ -88,7 +88,7 @@ class HPP_FCL_DLLAPI ShapeCollisionTraversalNode /// @brief Traversal node for distance between two shapes template <typename S1, typename S2> -class HPP_FCL_DLLAPI ShapeDistanceTraversalNode +class COAL_DLLAPI ShapeDistanceTraversalNode : public DistanceTraversalNodeBase { public: ShapeDistanceTraversalNode() : DistanceTraversalNodeBase() { diff --git a/include/coal/internal/traversal_recurse.h b/include/coal/internal/traversal_recurse.h index 2d19879ece90da361656be5bb1cbe578dbf055b8..ad28bcd24cb3abf5f51fb83e4d6fd910bea2b097 100644 --- a/include/coal/internal/traversal_recurse.h +++ b/include/coal/internal/traversal_recurse.h @@ -40,10 +40,10 @@ /// @cond INTERNAL -#include <hpp/fcl/BVH/BVH_front.h> +#include "coal/BVH/BVH_front.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/traversal_node_bvhs.h" #include <queue> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/internal/traversal_node_bvhs.h> namespace coal { diff --git a/include/coal/math/matrix_3f.h b/include/coal/math/matrix_3f.h index 408d0229aecd3a49ca0e4b2819468244eed9e971..70f555a02e8e35a6ab471cd6ae0d657303e653d4 100644 --- a/include/coal/math/matrix_3f.h +++ b/include/coal/math/matrix_3f.h @@ -38,9 +38,9 @@ #ifndef COAL_MATRIX_3F_H #define COAL_MATRIX_3F_H -#warning "This file is deprecated. Include <hpp/fcl/data_types.h> instead." +#warning "This file is deprecated. Include <coal/data_types.h> instead." // List of equivalent includes. -#include <hpp/fcl/data_types.h> +#include "coal/data_types.h" #endif diff --git a/include/coal/math/transform.h b/include/coal/math/transform.h index dfa468c6e02a48e9f0291394af5de83891fb4ab6..0795da1f6a56349b0d2979f8757b8e8f4ca264dd 100644 --- a/include/coal/math/transform.h +++ b/include/coal/math/transform.h @@ -38,12 +38,12 @@ #ifndef COAL_TRANSFORM_H #define COAL_TRANSFORM_H -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/data_types.h" +#include "coal/fwd.hh" +#include "coal/data_types.h" namespace coal { -HPP_FCL_DEPRECATED typedef Eigen::Quaternion<FCL_REAL> Quaternion3f; +COAL_DEPRECATED typedef Eigen::Quaternion<FCL_REAL> Quaternion3f; typedef Eigen::Quaternion<FCL_REAL> Quatf; static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) { @@ -52,7 +52,7 @@ static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) { } /// @brief Simple transform class used locally by InterpMotion -class HPP_FCL_DLLAPI Transform3f { +class COAL_DLLAPI Transform3f { /// @brief Matrix cache Matrix3f R; diff --git a/include/coal/math/types.h b/include/coal/math/types.h index ea9569499ca4991d57d610c7ebd3388bd29de9da..4b9b5a91f28ce842ac802a07defed139652189a4 100644 --- a/include/coal/math/types.h +++ b/include/coal/math/types.h @@ -38,9 +38,9 @@ #ifndef COAL_MATH_TYPES_H #define COAL_MATH_TYPES_H -#warning "This file is deprecated. Include <hpp/fcl/data_types.h> instead." +#warning "This file is deprecated. Include <coal/data_types.h> instead." // List of equivalent includes. -#include <hpp/fcl/data_types.h> +#include "coal/data_types.h" #endif diff --git a/include/coal/math/vec_3f.h b/include/coal/math/vec_3f.h index 62df29a0e67f1c9bb3bce22b9771b16c414a41cd..5b79b21915c39fe011261c7f66c0cf3c89596a8c 100644 --- a/include/coal/math/vec_3f.h +++ b/include/coal/math/vec_3f.h @@ -38,9 +38,9 @@ #ifndef COAL_VEC_3F_H #define COAL_VEC_3F_H -#warning "This file is deprecated. Include <hpp/fcl/data_types.h> instead." +#warning "This file is deprecated. Include <coal/data_types.h> instead." // List of equivalent includes. -#include <hpp/fcl/data_types.h> +#include "coal/data_types.h" #endif diff --git a/include/coal/mesh_loader/assimp.h b/include/coal/mesh_loader/assimp.h index d5672a44a555ef32a448e5dee6a69b36de668f4d..484a604ccc9f27c7706aeaf52f0d1a639b6706e7 100644 --- a/include/coal/mesh_loader/assimp.h +++ b/include/coal/mesh_loader/assimp.h @@ -38,10 +38,10 @@ #ifndef COAL_MESH_LOADER_ASSIMP_H #define COAL_MESH_LOADER_ASSIMP_H -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/config.hh> -#include <hpp/fcl/BV/OBBRSS.h> -#include <hpp/fcl/BVH/BVH_model.h> +#include "coal/fwd.hh" +#include "coal/config.hh" +#include "coal/BV/OBBRSS.h" +#include "coal/BVH/BVH_model.h" struct aiScene; namespace Assimp { @@ -52,12 +52,12 @@ namespace coal { namespace internal { -struct HPP_FCL_DLLAPI TriangleAndVertices { +struct COAL_DLLAPI TriangleAndVertices { std::vector<coal::Vec3f> vertices_; std::vector<coal::Triangle> triangles_; }; -struct HPP_FCL_DLLAPI Loader { +struct COAL_DLLAPI Loader { Loader(); ~Loader(); @@ -75,9 +75,8 @@ struct HPP_FCL_DLLAPI Loader { * @param[in] vertices_offset Current number of vertices in the model * @param tv Triangles and Vertices of the mesh submodels */ -HPP_FCL_DLLAPI void buildMesh(const coal::Vec3f& scale, const aiScene* scene, - unsigned vertices_offset, - TriangleAndVertices& tv); +COAL_DLLAPI void buildMesh(const coal::Vec3f& scale, const aiScene* scene, + unsigned vertices_offset, TriangleAndVertices& tv); /** * @brief Convert an assimp scene to a mesh diff --git a/include/coal/mesh_loader/loader.h b/include/coal/mesh_loader/loader.h index 16787359222bb701ecc1de537f998a7d9fd62761..c24f48d00f43267a74dee2e6f25cf102e1620d33 100644 --- a/include/coal/mesh_loader/loader.h +++ b/include/coal/mesh_loader/loader.h @@ -38,10 +38,10 @@ #ifndef COAL_MESH_LOADER_LOADER_H #define COAL_MESH_LOADER_LOADER_H -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/config.hh> -#include <hpp/fcl/data_types.h> -#include <hpp/fcl/collision_object.h> +#include "coal/fwd.hh" +#include "coal/config.hh" +#include "coal/data_types.h" +#include "coal/collision_object.h" #include <map> #include <ctime> @@ -49,7 +49,7 @@ namespace coal { /// Base class for building polyhedron from files. /// This class builds a new object for each file. -class HPP_FCL_DLLAPI MeshLoader { +class COAL_DLLAPI MeshLoader { public: virtual ~MeshLoader() {} @@ -70,7 +70,7 @@ class HPP_FCL_DLLAPI MeshLoader { /// This class builds a new object for each different file. /// If method CachedMeshLoader::load is called twice with the same arguments, /// the second call returns the result of the first call. -class HPP_FCL_DLLAPI CachedMeshLoader : public MeshLoader { +class COAL_DLLAPI CachedMeshLoader : public MeshLoader { public: virtual ~CachedMeshLoader() {} @@ -78,7 +78,7 @@ class HPP_FCL_DLLAPI CachedMeshLoader : public MeshLoader { virtual BVHModelPtr_t load(const std::string& filename, const Vec3f& scale); - struct HPP_FCL_DLLAPI Key { + struct COAL_DLLAPI Key { std::string filename; Vec3f scale; @@ -86,7 +86,7 @@ class HPP_FCL_DLLAPI CachedMeshLoader : public MeshLoader { bool operator<(const CachedMeshLoader::Key& b) const; }; - struct HPP_FCL_DLLAPI Value { + struct COAL_DLLAPI Value { BVHModelPtr_t model; std::time_t mtime; }; diff --git a/include/coal/narrowphase/gjk.h b/include/coal/narrowphase/gjk.h index b84e6eadfdc1a6743a026909536fdea6991b58a2..b37407f93e9674cd9a86e43798b9a55eae053a30 100644 --- a/include/coal/narrowphase/gjk.h +++ b/include/coal/narrowphase/gjk.h @@ -41,7 +41,7 @@ #include <vector> -#include "hpp/fcl/narrowphase/minkowski_difference.h" +#include "coal/narrowphase/minkowski_difference.h" namespace coal { @@ -50,8 +50,8 @@ namespace details { /// @brief class for GJK algorithm /// /// @note The computations are performed in the frame of the first shape. -struct HPP_FCL_DLLAPI GJK { - struct HPP_FCL_DLLAPI SimplexV { +struct COAL_DLLAPI GJK { + struct COAL_DLLAPI SimplexV { /// @brief support vector for shape 0 and 1. Vec3f w0, w1; /// @brief support vector (i.e., the furthest point on the shape along the @@ -68,7 +68,7 @@ struct HPP_FCL_DLLAPI GJK { /// Since GJK does not need any more storage, it reuses these vertices /// throughout the algorithm by using multiple instance of this `Simplex` /// class. - struct HPP_FCL_DLLAPI Simplex { + struct COAL_DLLAPI Simplex { /// @brief simplex vertex SimplexV* vertex[4]; /// @brief size of simplex (number of vertices) @@ -255,9 +255,9 @@ struct HPP_FCL_DLLAPI GJK { }; /// @brief class for EPA algorithm -struct HPP_FCL_DLLAPI EPA { +struct COAL_DLLAPI EPA { typedef GJK::SimplexV SimplexVertex; - struct HPP_FCL_DLLAPI SimplexFace { + struct COAL_DLLAPI SimplexFace { Vec3f n; FCL_REAL d; bool ignore; // If the origin does not project inside the face, we @@ -278,7 +278,7 @@ struct HPP_FCL_DLLAPI EPA { /// @brief The simplex list of EPA is a linked list of faces. /// Note: EPA's linked list does **not** own any memory. /// The memory it refers to is contiguous and owned by a std::vector. - struct HPP_FCL_DLLAPI SimplexFaceList { + struct COAL_DLLAPI SimplexFaceList { SimplexFace* root; size_t count; SimplexFaceList() : root(nullptr), count(0) {} @@ -318,7 +318,7 @@ struct HPP_FCL_DLLAPI EPA { fb->adjacent_faces[eb] = fa; } - struct HPP_FCL_DLLAPI SimplexHorizon { + struct COAL_DLLAPI SimplexHorizon { SimplexFace* current_face; // current face in the horizon SimplexFace* first_face; // first face in the horizon size_t num_faces; // number of faces in the horizon diff --git a/include/coal/narrowphase/minkowski_difference.h b/include/coal/narrowphase/minkowski_difference.h index 619b00c788648fdf6903231524fea91a93c1c3f8..677373e568ca7e7900e5e006d332633e9d02a645 100644 --- a/include/coal/narrowphase/minkowski_difference.h +++ b/include/coal/narrowphase/minkowski_difference.h @@ -39,9 +39,9 @@ #ifndef COAL_MINKOWSKI_DIFFERENCE_H #define COAL_MINKOWSKI_DIFFERENCE_H -#include "hpp/fcl/shape/geometric_shapes.h" -#include "hpp/fcl/math/transform.h" -#include "hpp/fcl/narrowphase/support_functions.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/math/transform.h" +#include "coal/narrowphase/support_functions.h" namespace coal { @@ -50,7 +50,7 @@ namespace details { /// @brief Minkowski difference class of two shapes /// /// @note The Minkowski difference is expressed in the frame of the first shape. -struct HPP_FCL_DLLAPI MinkowskiDiff { +struct COAL_DLLAPI MinkowskiDiff { typedef Eigen::Array<FCL_REAL, 1, 2> Array2d; /// @brief points to two shapes diff --git a/include/coal/narrowphase/narrowphase.h b/include/coal/narrowphase/narrowphase.h index b0f463d59d97deea9bd4a37227b380ad26e8cf6d..28380ad21c84827826a7a6c66d7bc4a4783783a4 100644 --- a/include/coal/narrowphase/narrowphase.h +++ b/include/coal/narrowphase/narrowphase.h @@ -42,10 +42,10 @@ #include <limits> -#include <hpp/fcl/narrowphase/gjk.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/narrowphase/narrowphase_defaults.h> -#include <hpp/fcl/logging.h> +#include "coal/narrowphase/gjk.h" +#include "coal/collision_data.h" +#include "coal/narrowphase/narrowphase_defaults.h" +#include "coal/logging.h" namespace coal { @@ -54,7 +54,7 @@ namespace coal { /// inspiration from the code of the GJK in bullet. Since then, both GJK and EPA /// have been largely modified to be faster and more robust to numerical /// accuracy and edge cases. -struct HPP_FCL_DLLAPI GJKSolver { +struct COAL_DLLAPI GJKSolver { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -72,7 +72,7 @@ struct HPP_FCL_DLLAPI GJKSolver { /// @brief Whether smart guess can be provided /// @Deprecated Use gjk_initial_guess instead - HPP_FCL_DEPRECATED_MESSAGE(Use gjk_initial_guess instead) + COAL_DEPRECATED_MESSAGE(Use gjk_initial_guess instead) bool enable_cached_guess; /// @brief smart guess diff --git a/include/coal/narrowphase/narrowphase_defaults.h b/include/coal/narrowphase/narrowphase_defaults.h index 5ed5bb22412564a926d409f5184d51046a7b81e1..54ce75328397597101d622d2d0f29bed9bd16c1d 100644 --- a/include/coal/narrowphase/narrowphase_defaults.h +++ b/include/coal/narrowphase/narrowphase_defaults.h @@ -38,7 +38,7 @@ #ifndef COAL_NARROWPHASE_DEFAULTS_H #define COAL_NARROWPHASE_DEFAULTS_H -#include <hpp/fcl/data_types.h> +#include "coal/data_types.h" namespace coal { diff --git a/include/coal/narrowphase/support_functions.h b/include/coal/narrowphase/support_functions.h index d1ecec32c098a3254ed10d9810f13416d8f79747..5bc3facbaf379c1fec060c465082184002467c30 100644 --- a/include/coal/narrowphase/support_functions.h +++ b/include/coal/narrowphase/support_functions.h @@ -39,9 +39,9 @@ #ifndef COAL_SUPPORT_FUNCTIONS_H #define COAL_SUPPORT_FUNCTIONS_H -#include "hpp/fcl/shape/geometric_shapes.h" -#include "hpp/fcl/math/transform.h" -#include "hpp/fcl/collision_data.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/math/transform.h" +#include "coal/collision_data.h" namespace coal { @@ -77,7 +77,7 @@ template <int _SupportOptions = SupportOptions::NoSweptSphere> Vec3f getSupport(const ShapeBase* shape, const Vec3f& dir, int& hint); /// @brief Stores temporary data for the computation of support points. -struct HPP_FCL_DLLAPI ShapeSupportData { +struct COAL_DLLAPI ShapeSupportData { // @brief Tracks which points have been visited in a ConvexBase. std::vector<int8_t> visited; @@ -298,8 +298,8 @@ void getShapeSupportSet(const LargeConvex* convex, SupportSet& support_set, /// @param[in] cloud data which contains the 2d points of the support set which /// convex-hull we want to compute. /// @param[out] 2d points of the the support set's convex-hull. -HPP_FCL_DLLAPI void computeSupportSetConvexHull(SupportSet::Polygon& cloud, - SupportSet::Polygon& cvx_hull); +COAL_DLLAPI void computeSupportSetConvexHull(SupportSet::Polygon& cloud, + SupportSet::Polygon& cvx_hull); } // namespace details diff --git a/include/coal/octree.h b/include/coal/octree.h index 2ee09b5eb555265ed7b694fb0ddc370df1a6a916..c3635c64346fe95de5af3011d259675530f245fa 100644 --- a/include/coal/octree.h +++ b/include/coal/octree.h @@ -42,15 +42,15 @@ #include <algorithm> #include <octomap/octomap.h> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/BV/AABB.h> -#include <hpp/fcl/collision_object.h> +#include "coal/fwd.hh" +#include "coal/BV/AABB.h" +#include "coal/collision_object.h" namespace coal { /// @brief Octree is one type of collision geometry which can encode uncertainty /// information in the sensor data. -class HPP_FCL_DLLAPI OcTree : public CollisionGeometry { +class COAL_DLLAPI OcTree : public CollisionGeometry { protected: shared_ptr<const octomap::OcTree> tree; @@ -330,7 +330,7 @@ static inline void computeChildBV(const AABB& root_bv, unsigned int i, /// /// \returns An OcTree that can be used for collision checking and more. /// -HPP_FCL_DLLAPI OcTreePtr_t +COAL_DLLAPI OcTreePtr_t makeOctree(const Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3>& point_cloud, const FCL_REAL resolution); diff --git a/include/coal/serialization/AABB.h b/include/coal/serialization/AABB.h index 853cf073cf89f4da78d0c7e14e799263d7c2cdfb..75e9be045f67d2f39ce829c740c515ef3be78500 100644 --- a/include/coal/serialization/AABB.h +++ b/include/coal/serialization/AABB.h @@ -5,8 +5,8 @@ #ifndef COAL_SERIALIZATION_AABB_H #define COAL_SERIALIZATION_AABB_H -#include "hpp/fcl/BV/AABB.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/BV/AABB.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/BVH_model.h b/include/coal/serialization/BVH_model.h index 4783004c521465d1674ef59dd981be8eda3a929e..6fee61b9885b6dcf3bf8c388f8e494e545a8a559 100644 --- a/include/coal/serialization/BVH_model.h +++ b/include/coal/serialization/BVH_model.h @@ -5,14 +5,14 @@ #ifndef HPP_FCL_SERIALIZATION_BVH_MODEL_H #define HPP_FCL_SERIALIZATION_BVH_MODEL_H -#include "hpp/fcl/BVH/BVH_model.h" - -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/BV_node.h" -#include "hpp/fcl/serialization/BV_splitter.h" -#include "hpp/fcl/serialization/collision_object.h" -#include "hpp/fcl/serialization/memory.h" -#include "hpp/fcl/serialization/triangle.h" +#include "coal/BVH/BVH_model.h" + +#include "coal/serialization/fwd.h" +#include "coal/serialization/BV_node.h" +#include "coal/serialization/BV_splitter.h" +#include "coal/serialization/collision_object.h" +#include "coal/serialization/memory.h" +#include "coal/serialization/triangle.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/BV_node.h b/include/coal/serialization/BV_node.h index 2fc0406d3e20a5ff9dd9793d75f3d92809a2809b..6e207ee662aa02f153c75415ba097d4290f620ca 100644 --- a/include/coal/serialization/BV_node.h +++ b/include/coal/serialization/BV_node.h @@ -5,10 +5,10 @@ #ifndef COAL_SERIALIZATION_BV_NODE_H #define COAL_SERIALIZATION_BV_NODE_H -#include "hpp/fcl/BV/BV_node.h" +#include "coal/BV/BV_node.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/OBBRSS.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/OBBRSS.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/BV_splitter.h b/include/coal/serialization/BV_splitter.h index 1cd38055063ab8f1820b290f6f1d15f01e4c95fa..9f6d7e98f731b1e05a60e46fd0ffde1fc14f2cc7 100644 --- a/include/coal/serialization/BV_splitter.h +++ b/include/coal/serialization/BV_splitter.h @@ -5,9 +5,9 @@ #ifndef COAL_SERIALIZATION_BV_SPLITTER_H #define COAL_SERIALIZATION_BV_SPLITTER_H -#include "hpp/fcl/internal/BV_splitter.h" +#include "coal/internal/BV_splitter.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/OBB.h b/include/coal/serialization/OBB.h index 0a584b35028423c4e5cc381235e33c355d7e6d8b..298ec15a6251a2e013946a7cfa521557014a3ceb 100644 --- a/include/coal/serialization/OBB.h +++ b/include/coal/serialization/OBB.h @@ -5,9 +5,9 @@ #ifndef COAL_SERIALIZATION_OBB_H #define COAL_SERIALIZATION_OBB_H -#include "hpp/fcl/BV/OBB.h" +#include "coal/BV/OBB.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/OBBRSS.h b/include/coal/serialization/OBBRSS.h index 2e769d9d23e6226b66d1eba0a666b67a9fd69c2a..990587c7fb6834b53a59b55ed8e69b620298967f 100644 --- a/include/coal/serialization/OBBRSS.h +++ b/include/coal/serialization/OBBRSS.h @@ -5,11 +5,11 @@ #ifndef COAL_SERIALIZATION_OBBRSS_H #define COAL_SERIALIZATION_OBBRSS_H -#include "hpp/fcl/BV/OBBRSS.h" +#include "coal/BV/OBBRSS.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/OBB.h" -#include "hpp/fcl/serialization/RSS.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/OBB.h" +#include "coal/serialization/RSS.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/RSS.h b/include/coal/serialization/RSS.h index 06b586993f385986c22cd2578daa68e99fafa68a..0e317c1f9f6a19ced170496852aab97ccad220a6 100644 --- a/include/coal/serialization/RSS.h +++ b/include/coal/serialization/RSS.h @@ -5,9 +5,9 @@ #ifndef COAL_SERIALIZATION_RSS_H #define COAL_SERIALIZATION_RSS_H -#include "hpp/fcl/BV/RSS.h" +#include "coal/BV/RSS.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/archive.h b/include/coal/serialization/archive.h index 5063e2c3e6d6439ed0174da593e73372378e5765..428c7ee367640a8295de01a5c748e89cca2d9193 100644 --- a/include/coal/serialization/archive.h +++ b/include/coal/serialization/archive.h @@ -7,7 +7,7 @@ #ifndef COAL_SERIALIZATION_ARCHIVE_H #define COAL_SERIALIZATION_ARCHIVE_H -#include "hpp/fcl/fwd.hh" +#include "coal/fwd.hh" #include <boost/serialization/nvp.hpp> #include <boost/archive/text_iarchive.hpp> diff --git a/include/coal/serialization/collision_data.h b/include/coal/serialization/collision_data.h index b1a15ab4e7fe7adfa5421cd7af6be163698e712e..829fb54463a09a234df65ac74a04fe53a3fe5b64 100644 --- a/include/coal/serialization/collision_data.h +++ b/include/coal/serialization/collision_data.h @@ -5,8 +5,8 @@ #ifndef COAL_SERIALIZATION_COLLISION_DATA_H #define COAL_SERIALIZATION_COLLISION_DATA_H -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/collision_data.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/collision_object.h b/include/coal/serialization/collision_object.h index e1c26582e75bfd2b9dd0834ebd0d967744100974..6d8a91c04adf7c8faae75c18e2399c3ec5bc5014 100644 --- a/include/coal/serialization/collision_object.h +++ b/include/coal/serialization/collision_object.h @@ -5,10 +5,10 @@ #ifndef COAL_SERIALIZATION_COLLISION_OBJECT_H #define COAL_SERIALIZATION_COLLISION_OBJECT_H -#include "hpp/fcl/collision_object.h" +#include "coal/collision_object.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/AABB.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/AABB.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/contact_patch.h b/include/coal/serialization/contact_patch.h index e9024e1579f1e8b072e09704562b2f3eeb6e049a..cdad604787f03efa30ab8bd8ef23e1b27a13dced 100644 --- a/include/coal/serialization/contact_patch.h +++ b/include/coal/serialization/contact_patch.h @@ -5,9 +5,9 @@ #ifndef COAL_SERIALIZATION_CONTACT_PATCH_H #define COAL_SERIALIZATION_CONTACT_PATCH_H -#include "hpp/fcl/collision_data.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/transform.h" +#include "coal/collision_data.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/transform.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/convex.h b/include/coal/serialization/convex.h index 390007e2d68531343ae9165d72706516a69640a7..ea5bb59ac9f392c2722717c48e5b69e58c2f2a47 100644 --- a/include/coal/serialization/convex.h +++ b/include/coal/serialization/convex.h @@ -5,13 +5,13 @@ #ifndef COAL_SERIALIZATION_CONVEX_H #define COAL_SERIALIZATION_CONVEX_H -#include "hpp/fcl/shape/convex.h" +#include "coal/shape/convex.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/geometric_shapes.h" -#include "hpp/fcl/serialization/memory.h" -#include "hpp/fcl/serialization/triangle.h" -#include "hpp/fcl/serialization/quadrilateral.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/geometric_shapes.h" +#include "coal/serialization/memory.h" +#include "coal/serialization/triangle.h" +#include "coal/serialization/quadrilateral.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/fwd.h b/include/coal/serialization/fwd.h index 6657898e75a598bfbddfbe787be232919c0b4aee..04fe25ad51603625c95b92addd8daceaf6bd9597 100644 --- a/include/coal/serialization/fwd.h +++ b/include/coal/serialization/fwd.h @@ -18,8 +18,8 @@ #include <boost/serialization/shared_ptr.hpp> #include <boost/serialization/export.hpp> -#include "hpp/fcl/fwd.hh" -#include "hpp/fcl/serialization/eigen.h" +#include "coal/fwd.h" +#include "coal/serialization/eigen.h" #define HPP_FCL_SERIALIZATION_SPLIT(Type) \ template <class Archive> \ diff --git a/include/coal/serialization/geometric_shapes.h b/include/coal/serialization/geometric_shapes.h index 7edd1560072c1b5a782d0170da65e2d1c3febd94..18f0753b3a021e53f4ec1589d4eb0c20ca569bc2 100644 --- a/include/coal/serialization/geometric_shapes.h +++ b/include/coal/serialization/geometric_shapes.h @@ -5,9 +5,9 @@ #ifndef COAL_SERIALIZATION_GEOMETRIC_SHAPES_H #define COAL_SERIALIZATION_GEOMETRIC_SHAPES_H -#include "hpp/fcl/shape/geometric_shapes.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/collision_object.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/collision_object.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/hfield.h b/include/coal/serialization/hfield.h index 544de9d2e277a119ce1a4f09975220d074ff88f5..682f7d2c5b68cea25ab6b165b6d2646e6a0a0cde 100644 --- a/include/coal/serialization/hfield.h +++ b/include/coal/serialization/hfield.h @@ -5,10 +5,10 @@ #ifndef COAL_SERIALIZATION_HFIELD_H #define COAL_SERIALIZATION_HFIELD_H -#include "hpp/fcl/hfield.h" +#include "coal/hfield.h" -#include "hpp/fcl/serialization/fwd.h" -#include "hpp/fcl/serialization/OBBRSS.h" +#include "coal/serialization/fwd.h" +#include "coal/serialization/OBBRSS.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/kDOP.h b/include/coal/serialization/kDOP.h index 954df2993616e02f0d81c8f63aedc69a900d52de..f4cf992c64fa06caa1a46a539842fa378452666b 100644 --- a/include/coal/serialization/kDOP.h +++ b/include/coal/serialization/kDOP.h @@ -5,9 +5,9 @@ #ifndef COAL_SERIALIZATION_kDOP_H #define COAL_SERIALIZATION_kDOP_H -#include "hpp/fcl/BV/kDOP.h" +#include "coal/BV/kDOP.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/kIOS.h b/include/coal/serialization/kIOS.h index 27a0e5a69e3a1703d34cf353d139dc39b6ff86ec..2a024e0569ac2565d74e2ad6e8833d96474dc6de 100644 --- a/include/coal/serialization/kIOS.h +++ b/include/coal/serialization/kIOS.h @@ -5,10 +5,10 @@ #ifndef COAL_SERIALIZATION_kIOS_H #define COAL_SERIALIZATION_kIOS_H -#include "hpp/fcl/BV/kIOS.h" +#include "coal/BV/kIOS.h" -#include "hpp/fcl/serialization/OBB.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/serialization/OBB.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/octree.h b/include/coal/serialization/octree.h index 42a8afcdc10615b6e81349ab92259ef8197f881b..17edf12ad52a68b0790a9c09cc743a13e6e816ad 100644 --- a/include/coal/serialization/octree.h +++ b/include/coal/serialization/octree.h @@ -10,8 +10,8 @@ #include <boost/serialization/string.hpp> -#include "hpp/fcl/octree.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/octree.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/quadrilateral.h b/include/coal/serialization/quadrilateral.h index eb2792e98a7e6a58b1f0822783cf6b5d09ded619..b805f5bde0d09221bffefc6957a939eb892ad4dd 100644 --- a/include/coal/serialization/quadrilateral.h +++ b/include/coal/serialization/quadrilateral.h @@ -5,8 +5,8 @@ #ifndef COAL_SERIALIZATION_QUADRILATERAL_H #define COAL_SERIALIZATION_QUADRILATERAL_H -#include "hpp/fcl/data_types.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/data_types.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/serializer.h b/include/coal/serialization/serializer.h index 8990cc3fafbf7e6a342a1e290c20d6a13e8311ca..daef9fc6458e72f24eb950d94591c56de2c81710 100644 --- a/include/coal/serialization/serializer.h +++ b/include/coal/serialization/serializer.h @@ -5,7 +5,7 @@ #ifndef COAL_SERIALIZATION_SERIALIZER_H #define COAL_SERIALIZATION_SERIALIZER_H -#include "hpp/fcl/serialization/archive.h" +#include "coal/serialization/archive.h" namespace coal { namespace serialization { diff --git a/include/coal/serialization/transform.h b/include/coal/serialization/transform.h index 0f5c11e1fef771f2f159a0857f68d5d3c954f6a3..e2905e999e0668baf2aedceca780431eca5fe4fe 100644 --- a/include/coal/serialization/transform.h +++ b/include/coal/serialization/transform.h @@ -5,8 +5,8 @@ #ifndef COAL_SERIALIZATION_TRANSFORM_H #define COAL_SERIALIZATION_TRANSFORM_H -#include "hpp/fcl/math/transform.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/math/transform.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/serialization/triangle.h b/include/coal/serialization/triangle.h index 2ca478543d81cdb18a2b3fb7f0084e5569d960e4..052706be52619f405423938582e12790d7876be1 100644 --- a/include/coal/serialization/triangle.h +++ b/include/coal/serialization/triangle.h @@ -5,8 +5,8 @@ #ifndef COAL_SERIALIZATION_TRIANGLE_H #define COAL_SERIALIZATION_TRIANGLE_H -#include "hpp/fcl/data_types.h" -#include "hpp/fcl/serialization/fwd.h" +#include "coal/data_types.h" +#include "coal/serialization/fwd.h" namespace boost { namespace serialization { diff --git a/include/coal/shape/convex.h b/include/coal/shape/convex.h index fc2f2481473e81fd7ac9b3787572c485b0b08743..067160ad66e7e4f957dbd72f87750119e85c62f2 100644 --- a/include/coal/shape/convex.h +++ b/include/coal/shape/convex.h @@ -38,7 +38,7 @@ #ifndef COAL_SHAPE_CONVEX_H #define COAL_SHAPE_CONVEX_H -#include "hpp/fcl/shape/geometric_shapes.h" +#include "coal/shape/geometric_shapes.h" namespace coal { @@ -107,6 +107,6 @@ class Convex : public ConvexBase { } // namespace coal -#include "hpp/fcl/shape/details/convex.hxx" +#include "coal/shape/details/convex.hxx" #endif diff --git a/include/coal/shape/geometric_shape_to_BVH_model.h b/include/coal/shape/geometric_shape_to_BVH_model.h index c6d51bc7a7af86c11d5ff031aa60e9e082e65ef1..0dd176265729844d61c25e5f372cd2d06e4bb258 100644 --- a/include/coal/shape/geometric_shape_to_BVH_model.h +++ b/include/coal/shape/geometric_shape_to_BVH_model.h @@ -38,8 +38,8 @@ #ifndef COAL_GEOMETRIC_SHAPE_TO_BVH_MODEL_H #define COAL_GEOMETRIC_SHAPE_TO_BVH_MODEL_H -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/BVH/BVH_model.h> +#include "coal/shape/geometric_shapes.h" +#include "coal/BVH/BVH_model.h" #include <boost/math/constants/constants.hpp> namespace coal { diff --git a/include/coal/shape/geometric_shapes.h b/include/coal/shape/geometric_shapes.h index b0c1481f9a96a1fa2f9cd8d9689645b81de8cab2..4a639e868f8183e81e661dea692b7a80b7a4e47d 100644 --- a/include/coal/shape/geometric_shapes.h +++ b/include/coal/shape/geometric_shapes.h @@ -43,8 +43,8 @@ #include <boost/math/constants/constants.hpp> -#include "hpp/fcl/collision_object.h" -#include "hpp/fcl/data_types.h" +#include "coal/collision_object.h" +#include "coal/data_types.h" #ifdef HPP_FCL_HAS_QHULL namespace orgQhull { @@ -55,7 +55,7 @@ class Qhull; namespace coal { /// @brief Base class for all basic geometric shapes -class HPP_FCL_DLLAPI ShapeBase : public CollisionGeometry { +class COAL_DLLAPI ShapeBase : public CollisionGeometry { public: ShapeBase() {} @@ -105,7 +105,7 @@ class HPP_FCL_DLLAPI ShapeBase : public CollisionGeometry { /// @{ /// @brief Triangle stores the points instead of only indices of points -class HPP_FCL_DLLAPI TriangleP : public ShapeBase { +class COAL_DLLAPI TriangleP : public ShapeBase { public: TriangleP() {}; @@ -160,7 +160,7 @@ class HPP_FCL_DLLAPI TriangleP : public ShapeBase { }; /// @brief Center at zero point, axis aligned box -class HPP_FCL_DLLAPI Box : public ShapeBase { +class COAL_DLLAPI Box : public ShapeBase { public: Box(FCL_REAL x, FCL_REAL y, FCL_REAL z) : ShapeBase(), halfSide(x / 2, y / 2, z / 2) {} @@ -234,7 +234,7 @@ class HPP_FCL_DLLAPI Box : public ShapeBase { }; /// @brief Center at zero point sphere -class HPP_FCL_DLLAPI Sphere : public ShapeBase { +class COAL_DLLAPI Sphere : public ShapeBase { public: /// @brief Default constructor Sphere() {} @@ -299,7 +299,7 @@ class HPP_FCL_DLLAPI Sphere : public ShapeBase { }; /// @brief Ellipsoid centered at point zero -class HPP_FCL_DLLAPI Ellipsoid : public ShapeBase { +class COAL_DLLAPI Ellipsoid : public ShapeBase { public: /// @brief Default constructor Ellipsoid() {} @@ -377,7 +377,7 @@ class HPP_FCL_DLLAPI Ellipsoid : public ShapeBase { /// It is \f$ { x~\in~\mathbb{R}^3, d(x, AB) \leq radius } \f$ /// where \f$ d(x, AB) \f$ is the distance between the point x and the capsule /// segment AB, with \f$ A = (0,0,-halfLength), B = (0,0,halfLength) \f$. -class HPP_FCL_DLLAPI Capsule : public ShapeBase { +class COAL_DLLAPI Capsule : public ShapeBase { public: /// @brief Default constructor Capsule() {} @@ -461,7 +461,7 @@ class HPP_FCL_DLLAPI Capsule : public ShapeBase { /// @brief Cone /// The base of the cone is at \f$ z = - halfLength \f$ and the top is at /// \f$ z = halfLength \f$. -class HPP_FCL_DLLAPI Cone : public ShapeBase { +class COAL_DLLAPI Cone : public ShapeBase { public: /// @brief Default constructor Cone() {} @@ -551,7 +551,7 @@ class HPP_FCL_DLLAPI Cone : public ShapeBase { /// @brief Cylinder along Z axis. /// The cylinder is defined at its centroid. -class HPP_FCL_DLLAPI Cylinder : public ShapeBase { +class COAL_DLLAPI Cylinder : public ShapeBase { public: /// @brief Default constructor Cylinder() {} @@ -634,7 +634,7 @@ class HPP_FCL_DLLAPI Cylinder : public ShapeBase { /// @brief Base for convex polytope. /// @note Inherited classes are responsible for filling ConvexBase::neighbors; -class HPP_FCL_DLLAPI ConvexBase : public ShapeBase { +class COAL_DLLAPI ConvexBase : public ShapeBase { public: /// @brief Build a convex hull based on Qhull library /// and store the vertices and optionally the triangles @@ -653,7 +653,7 @@ class HPP_FCL_DLLAPI ConvexBase : public ShapeBase { const char* qhullCommand = NULL); // TODO(louis): put this method in private sometime in the future. - HPP_FCL_DEPRECATED static ConvexBase* convexHull( + COAL_DEPRECATED static ConvexBase* convexHull( const Vec3f* points, unsigned int num_points, bool keepTriangles, const char* qhullCommand = NULL); @@ -676,7 +676,7 @@ class HPP_FCL_DLLAPI ConvexBase : public ShapeBase { void buildDoubleDescription(); #endif - struct HPP_FCL_DLLAPI Neighbors { + struct COAL_DLLAPI Neighbors { unsigned char count_; unsigned int* n_; @@ -881,7 +881,7 @@ class Convex; /// are outside the half space. /// Note: prefer using a Halfspace instead of a Plane if possible, it has better /// behavior w.r.t. collision detection algorithms. -class HPP_FCL_DLLAPI Halfspace : public ShapeBase { +class COAL_DLLAPI Halfspace : public ShapeBase { public: /// @brief Construct a half space with normal direction and offset Halfspace(const Vec3f& n_, FCL_REAL d_) : ShapeBase(), n(n_), d(d_) { @@ -972,7 +972,7 @@ class HPP_FCL_DLLAPI Halfspace : public ShapeBase { /// A plane can be viewed as two half spaces; it has no priviledged direction. /// Note: prefer using a Halfspace instead of a Plane if possible, it has better /// behavior w.r.t. collision detection algorithms. -class HPP_FCL_DLLAPI Plane : public ShapeBase { +class COAL_DLLAPI Plane : public ShapeBase { public: /// @brief Construct a plane with normal direction and offset Plane(const Vec3f& n_, FCL_REAL d_) : ShapeBase(), n(n_), d(d_) { diff --git a/include/coal/shape/geometric_shapes_traits.h b/include/coal/shape/geometric_shapes_traits.h index 8997113155b10c2689996bda6f0653d3eb1e2a3a..fcc769e66a4295fdb87f28887e53d8723d36df59 100644 --- a/include/coal/shape/geometric_shapes_traits.h +++ b/include/coal/shape/geometric_shapes_traits.h @@ -37,7 +37,7 @@ #ifndef COAL_GEOMETRIC_SHAPES_TRAITS_H #define COAL_GEOMETRIC_SHAPES_TRAITS_H -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" namespace coal { diff --git a/include/coal/shape/geometric_shapes_utility.h b/include/coal/shape/geometric_shapes_utility.h index 05ce509c1c771dd4c36c40299d42da04d2d2a8dd..3773afda08e8d9338fa27941976c0263dddbc8eb 100644 --- a/include/coal/shape/geometric_shapes_utility.h +++ b/include/coal/shape/geometric_shapes_utility.h @@ -39,9 +39,9 @@ #define COAL_GEOMETRIC_SHAPES_UTILITY_H #include <vector> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/internal/BV_fitter.h> +#include "coal/shape/geometric_shapes.h" +#include "coal/BV/BV.h" +#include "coal/internal/BV_fitter.h" namespace coal { @@ -49,22 +49,22 @@ namespace coal { namespace details { /// @brief get the vertices of some convex shape which can bound the given shape /// in a specific configuration -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Box& box, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Sphere& sphere, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Ellipsoid& ellipsoid, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Capsule& capsule, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Cone& cone, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Cylinder& cylinder, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const ConvexBase& convex, - const Transform3f& tf); -HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const TriangleP& triangle, - const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const Box& box, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const Sphere& sphere, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const Ellipsoid& ellipsoid, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const Capsule& capsule, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const Cone& cone, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const Cylinder& cylinder, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const ConvexBase& convex, + const Transform3f& tf); +COAL_DLLAPI std::vector<Vec3f> getBoundVertices(const TriangleP& triangle, + const Transform3f& tf); } // namespace details /// @endcond @@ -81,180 +81,179 @@ inline void computeBV(const S& s, const Transform3f& tf, BV& bv) { } template <> -HPP_FCL_DLLAPI void computeBV<AABB, Box>(const Box& s, const Transform3f& tf, +COAL_DLLAPI void computeBV<AABB, Box>(const Box& s, const Transform3f& tf, + AABB& bv); + +template <> +COAL_DLLAPI void computeBV<AABB, Sphere>(const Sphere& s, const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Sphere>(const Sphere& s, +COAL_DLLAPI void computeBV<AABB, Ellipsoid>(const Ellipsoid& e, const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Ellipsoid>(const Ellipsoid& e, - const Transform3f& tf, AABB& bv); +COAL_DLLAPI void computeBV<AABB, Capsule>(const Capsule& s, + const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Capsule>(const Capsule& s, - const Transform3f& tf, AABB& bv); +COAL_DLLAPI void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf, + AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf, - AABB& bv); +COAL_DLLAPI void computeBV<AABB, Cylinder>(const Cylinder& s, + const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Cylinder>(const Cylinder& s, - const Transform3f& tf, AABB& bv); +COAL_DLLAPI void computeBV<AABB, ConvexBase>(const ConvexBase& s, + const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, ConvexBase>(const ConvexBase& s, - const Transform3f& tf, - AABB& bv); +COAL_DLLAPI void computeBV<AABB, TriangleP>(const TriangleP& s, + const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, TriangleP>(const TriangleP& s, - const Transform3f& tf, AABB& bv); +COAL_DLLAPI void computeBV<AABB, Halfspace>(const Halfspace& s, + const Transform3f& tf, AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Halfspace>(const Halfspace& s, - const Transform3f& tf, AABB& bv); +COAL_DLLAPI void computeBV<AABB, Plane>(const Plane& s, const Transform3f& tf, + AABB& bv); template <> -HPP_FCL_DLLAPI void computeBV<AABB, Plane>(const Plane& s, - const Transform3f& tf, AABB& bv); +COAL_DLLAPI void computeBV<OBB, Box>(const Box& s, const Transform3f& tf, + OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Box>(const Box& s, const Transform3f& tf, +COAL_DLLAPI void computeBV<OBB, Sphere>(const Sphere& s, const Transform3f& tf, OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Sphere>(const Sphere& s, - const Transform3f& tf, OBB& bv); +COAL_DLLAPI void computeBV<OBB, Capsule>(const Capsule& s, + const Transform3f& tf, OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Capsule>(const Capsule& s, - const Transform3f& tf, OBB& bv); +COAL_DLLAPI void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf, + OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf, - OBB& bv); +COAL_DLLAPI void computeBV<OBB, Cylinder>(const Cylinder& s, + const Transform3f& tf, OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Cylinder>(const Cylinder& s, - const Transform3f& tf, OBB& bv); - -template <> -HPP_FCL_DLLAPI void computeBV<OBB, ConvexBase>(const ConvexBase& s, - const Transform3f& tf, OBB& bv); +COAL_DLLAPI void computeBV<OBB, ConvexBase>(const ConvexBase& s, + const Transform3f& tf, OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Halfspace>(const Halfspace& s, - const Transform3f& tf, OBB& bv); +COAL_DLLAPI void computeBV<OBB, Halfspace>(const Halfspace& s, + const Transform3f& tf, OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<RSS, Halfspace>(const Halfspace& s, - const Transform3f& tf, RSS& bv); +COAL_DLLAPI void computeBV<RSS, Halfspace>(const Halfspace& s, + const Transform3f& tf, RSS& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBBRSS, Halfspace>(const Halfspace& s, - const Transform3f& tf, - OBBRSS& bv); +COAL_DLLAPI void computeBV<OBBRSS, Halfspace>(const Halfspace& s, + const Transform3f& tf, + OBBRSS& bv); template <> -HPP_FCL_DLLAPI void computeBV<kIOS, Halfspace>(const Halfspace& s, - const Transform3f& tf, kIOS& bv); +COAL_DLLAPI void computeBV<kIOS, Halfspace>(const Halfspace& s, + const Transform3f& tf, kIOS& bv); template <> -HPP_FCL_DLLAPI void computeBV<KDOP<16>, Halfspace>(const Halfspace& s, - const Transform3f& tf, - KDOP<16>& bv); +COAL_DLLAPI void computeBV<KDOP<16>, Halfspace>(const Halfspace& s, + const Transform3f& tf, + KDOP<16>& bv); template <> -HPP_FCL_DLLAPI void computeBV<KDOP<18>, Halfspace>(const Halfspace& s, - const Transform3f& tf, - KDOP<18>& bv); +COAL_DLLAPI void computeBV<KDOP<18>, Halfspace>(const Halfspace& s, + const Transform3f& tf, + KDOP<18>& bv); template <> -HPP_FCL_DLLAPI void computeBV<KDOP<24>, Halfspace>(const Halfspace& s, - const Transform3f& tf, - KDOP<24>& bv); +COAL_DLLAPI void computeBV<KDOP<24>, Halfspace>(const Halfspace& s, + const Transform3f& tf, + KDOP<24>& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf, - OBB& bv); +COAL_DLLAPI void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf, + OBB& bv); template <> -HPP_FCL_DLLAPI void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf, - RSS& bv); +COAL_DLLAPI void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf, + RSS& bv); template <> -HPP_FCL_DLLAPI void computeBV<OBBRSS, Plane>(const Plane& s, - const Transform3f& tf, OBBRSS& bv); +COAL_DLLAPI void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3f& tf, + OBBRSS& bv); template <> -HPP_FCL_DLLAPI void computeBV<kIOS, Plane>(const Plane& s, - const Transform3f& tf, kIOS& bv); +COAL_DLLAPI void computeBV<kIOS, Plane>(const Plane& s, const Transform3f& tf, + kIOS& bv); template <> -HPP_FCL_DLLAPI void computeBV<KDOP<16>, Plane>(const Plane& s, - const Transform3f& tf, - KDOP<16>& bv); +COAL_DLLAPI void computeBV<KDOP<16>, Plane>(const Plane& s, + const Transform3f& tf, + KDOP<16>& bv); template <> -HPP_FCL_DLLAPI void computeBV<KDOP<18>, Plane>(const Plane& s, - const Transform3f& tf, - KDOP<18>& bv); +COAL_DLLAPI void computeBV<KDOP<18>, Plane>(const Plane& s, + const Transform3f& tf, + KDOP<18>& bv); template <> -HPP_FCL_DLLAPI void computeBV<KDOP<24>, Plane>(const Plane& s, - const Transform3f& tf, - KDOP<24>& bv); +COAL_DLLAPI void computeBV<KDOP<24>, Plane>(const Plane& s, + const Transform3f& tf, + KDOP<24>& bv); /// @brief construct a box shape (with a configuration) from a given bounding /// volume -HPP_FCL_DLLAPI void constructBox(const AABB& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const AABB& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const OBB& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const OBB& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const OBBRSS& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const OBBRSS& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const kIOS& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const kIOS& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const RSS& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const RSS& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const KDOP<16>& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const KDOP<16>& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const KDOP<18>& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const KDOP<18>& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const KDOP<24>& bv, Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const KDOP<24>& bv, Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const AABB& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const AABB& bv, const Transform3f& tf_bv, + Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const OBB& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const OBB& bv, const Transform3f& tf_bv, Box& box, + Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const OBBRSS& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const OBBRSS& bv, const Transform3f& tf_bv, + Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const kIOS& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const kIOS& bv, const Transform3f& tf_bv, + Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const RSS& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const RSS& bv, const Transform3f& tf_bv, Box& box, + Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const KDOP<16>& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const KDOP<16>& bv, const Transform3f& tf_bv, + Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const KDOP<18>& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const KDOP<18>& bv, const Transform3f& tf_bv, + Box& box, Transform3f& tf); -HPP_FCL_DLLAPI void constructBox(const KDOP<24>& bv, const Transform3f& tf_bv, - Box& box, Transform3f& tf); +COAL_DLLAPI void constructBox(const KDOP<24>& bv, const Transform3f& tf_bv, + Box& box, Transform3f& tf); -HPP_FCL_DLLAPI Halfspace transform(const Halfspace& a, const Transform3f& tf); +COAL_DLLAPI Halfspace transform(const Halfspace& a, const Transform3f& tf); -HPP_FCL_DLLAPI Plane transform(const Plane& a, const Transform3f& tf); +COAL_DLLAPI Plane transform(const Plane& a, const Transform3f& tf); -HPP_FCL_DLLAPI std::array<Halfspace, 2> transformToHalfspaces( +COAL_DLLAPI std::array<Halfspace, 2> transformToHalfspaces( const Plane& a, const Transform3f& tf); } // namespace coal diff --git a/include/coal/timings.h b/include/coal/timings.h index 5316a832a1502ac29de298a3416eb18928e23075..9b361d852450c17e823820d08680a911a8d113f4 100644 --- a/include/coal/timings.h +++ b/include/coal/timings.h @@ -5,7 +5,7 @@ #ifndef COAL_TIMINGS_FWD_H #define COAL_TIMINGS_FWD_H -#include "hpp/fcl/fwd.hh" +#include "coal/fwd.hh" #ifdef HPP_FCL_WITH_CXX11_SUPPORT #include <chrono> @@ -28,7 +28,7 @@ struct CPUTimes { /// using the modern std::chrono library. /// Importantly, this class will only have an effect for C++11 and more. /// -struct HPP_FCL_DLLAPI Timer { +struct COAL_DLLAPI Timer { #ifdef HPP_FCL_WITH_CXX11_SUPPORT typedef std::chrono::steady_clock clock_type; typedef clock_type::duration duration_type; diff --git a/python/broadphase/broadphase.cc b/python/broadphase/broadphase.cc index dd99421ad300140080af6068b49953622959d86c..edcffde1f6732bac21275eacd2a1e0d2d7f0f4e4 100644 --- a/python/broadphase/broadphase.cc +++ b/python/broadphase/broadphase.cc @@ -32,17 +32,17 @@ // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. -#include <hpp/fcl/fwd.hh> +#include "coal/fwd.hh" #include "../fcl.hh" #include "../utils/std-pair.hh" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h" -#include "hpp/fcl/broadphase/broadphase_bruteforce.h" -#include "hpp/fcl/broadphase/broadphase_SaP.h" -#include "hpp/fcl/broadphase/broadphase_SSaP.h" -#include "hpp/fcl/broadphase/broadphase_interval_tree.h" -#include "hpp/fcl/broadphase/broadphase_spatialhash.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" +#include "coal/broadphase/broadphase_bruteforce.h" +#include "coal/broadphase/broadphase_SaP.h" +#include "coal/broadphase/broadphase_SSaP.h" +#include "coal/broadphase/broadphase_interval_tree.h" +#include "coal/broadphase/broadphase_spatialhash.h" HPP_FCL_COMPILER_DIAGNOSTIC_PUSH HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS diff --git a/python/broadphase/broadphase_callbacks.hh b/python/broadphase/broadphase_callbacks.hh index c5d64f37f7732b85928baa5f343910c417813488..998894eb0ffee93de7b3d1cab1f9ba7ad8efea87 100644 --- a/python/broadphase/broadphase_callbacks.hh +++ b/python/broadphase/broadphase_callbacks.hh @@ -37,8 +37,8 @@ #include <eigenpy/eigenpy.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/broadphase/broadphase_callbacks.h> +#include "coal/fwd.hh" +#include "coal/broadphase/broadphase_callbacks.h" #include "../fcl.hh" diff --git a/python/broadphase/broadphase_collision_manager.hh b/python/broadphase/broadphase_collision_manager.hh index 70578b439fd34d396c60972a05800273a4beae11..ba37eaf0b62f9e6b2337ee27b3051aecec7d9160 100644 --- a/python/broadphase/broadphase_collision_manager.hh +++ b/python/broadphase/broadphase_collision_manager.hh @@ -37,9 +37,9 @@ #include <eigenpy/eigenpy.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/broadphase/broadphase_collision_manager.h> -#include <hpp/fcl/broadphase/default_broadphase_callbacks.h> +#include "coal/fwd.hh" +#include "coal/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/default_broadphase_callbacks.h" #include "../fcl.hh" diff --git a/python/broadphase/fwd.hh b/python/broadphase/fwd.hh index c2cc67082411387eeb43d2af6099a8e25843b3b5..1367cc065ffbb5f6f61299d01edf1ae4bd257f05 100644 --- a/python/broadphase/fwd.hh +++ b/python/broadphase/fwd.hh @@ -5,7 +5,7 @@ #ifndef COAL_PYTHON_BROADPHASE_FWD_HH #define COAL_PYTHON_BROADPHASE_FWD_HH -#include "hppfcl/fwd.hh" +#include "coal/fwd.hh" namespace coal { namespace python { diff --git a/python/collision-geometries.cc b/python/collision-geometries.cc index cec7ea32b16544d15831e188ff79f497203dea3d..acc14597d8e594c7e38feebc4c4182a76bc9c79b 100644 --- a/python/collision-geometries.cc +++ b/python/collision-geometries.cc @@ -38,18 +38,18 @@ #include "fcl.hh" #include "deprecation.hh" -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/shape/convex.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/hfield.h> - -#include <hpp/fcl/serialization/memory.h> -#include <hpp/fcl/serialization/AABB.h> -#include <hpp/fcl/serialization/BVH_model.h> -#include <hpp/fcl/serialization/hfield.h> -#include <hpp/fcl/serialization/geometric_shapes.h> -#include <hpp/fcl/serialization/convex.h> +#include "coal/fwd.hh" +#include "coal/shape/geometric_shapes.h" +#include "coal/shape/convex.h" +#include "coal/BVH/BVH_model.h" +#include "coal/hfield.h" + +#include "coal/serialization/memory.h" +#include "coal/serialization/AABB.h" +#include "coal/serialization/BVH_model.h" +#include "coal/serialization/hfield.h" +#include "coal/serialization/geometric_shapes.h" +#include "coal/serialization/convex.h" #include "pickle.hh" #include "serializable.hh" @@ -57,8 +57,8 @@ #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC // FIXME for a reason I do not understand, doxygen fails to understand that // BV_splitter is not defined in hpp/fcl/BVH/BVH_model.h -#include <hpp/fcl/internal/BV_splitter.h> -#include <hpp/fcl/broadphase/detail/hierarchy_tree.h> +#include "coal/internal/BV_splitter.h" +#include "coal/broadphase/detail/hierarchy_tree.h" #include "doxygen_autodoc/hpp/fcl/BVH/BVH_model.h" #include "doxygen_autodoc/hpp/fcl/BV/AABB.h" diff --git a/python/collision.cc b/python/collision.cc index a3a47deb4eb5782f9c8c0ebeeec3e145ff5b378b..7bbb5a10815686cb2e73fdd955f8518a3c8c48b5 100644 --- a/python/collision.cc +++ b/python/collision.cc @@ -34,12 +34,12 @@ #include <eigenpy/eigenpy.hpp> -#include <hpp/fcl/fwd.hh> -HPP_FCL_COMPILER_DIAGNOSTIC_PUSH -HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS -#include <hpp/fcl/collision.h> -#include <hpp/fcl/serialization/collision_data.h> -HPP_FCL_COMPILER_DIAGNOSTIC_POP +#include "coal/fwd.hh" +COAL_COMPILER_DIAGNOSTIC_PUSH +COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS +#include "coal/collision.h" +#include "coal/serialization/collision_data.h" +COAL_COMPILER_DIAGNOSTIC_POP #include "fcl.hh" #include "deprecation.hh" diff --git a/python/contact_patch.cc b/python/contact_patch.cc index d09c9f2460d7010ee8d9c13715991952bb725111..42d26835b3bd8263447069b352c11f3917e4ebdf 100644 --- a/python/contact_patch.cc +++ b/python/contact_patch.cc @@ -34,9 +34,9 @@ #include <eigenpy/eigenpy.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/contact_patch.h> -#include <hpp/fcl/serialization/collision_data.h> +#include "coal/fwd.hh" +#include "coal/contact_patch.h" +#include "coal/serialization/collision_data.h" #include "fcl.hh" #include "deprecation.hh" diff --git a/python/distance.cc b/python/distance.cc index 21209eae42177c66497fffd6901f1c83c311b498..4ae1b26d1c8f61505c8750d986174d80d2845ee6 100644 --- a/python/distance.cc +++ b/python/distance.cc @@ -36,13 +36,14 @@ #include "fcl.hh" -HPP_FCL_COMPILER_DIAGNOSTIC_PUSH -HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/serialization/collision_data.h> +COAL_COMPILER_DIAGNOSTIC_PUSH +COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS +#include "coal/fwd.hh" +#include "coal/distance.h" +#include "coal/serialization/collision_data.h" + #include "deprecation.hh" -HPP_FCL_COMPILER_DIAGNOSTIC_POP +COAL_COMPILER_DIAGNOSTIC_POP #include "serializable.hh" diff --git a/python/fcl.cc b/python/fcl.cc index d0fea53b82b4cf0702166f639afce1f2452f5ec4..c0c6e5489fe42adfdd01ea1afe33b7dfeff4826d 100644 --- a/python/fcl.cc +++ b/python/fcl.cc @@ -36,13 +36,13 @@ #include "fcl.hh" -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/BVH/BVH_model.h> +#include "coal/fwd.hh" +#include "coal/shape/geometric_shapes.h" +#include "coal/BVH/BVH_model.h" -#include <hpp/fcl/mesh_loader/loader.h> +#include "coal/mesh_loader/loader.h" -#include <hpp/fcl/collision.h> +#include "coal/collision.h" #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC #include "doxygen_autodoc/hpp/fcl/mesh_loader/loader.h" diff --git a/python/fwd.hh b/python/fwd.hh index 6d0cbff2f6213c30ff426d9bdde52c20972eaad0..018ec0e6a167ee62c27fe9a50714ac171c616f33 100644 --- a/python/fwd.hh +++ b/python/fwd.hh @@ -5,7 +5,7 @@ #ifndef COAL_PYTHON_FWD_HH #define COAL_PYTHON_FWD_HH -#include <hpp/fcl/fwd.hh> +#include "coal/fwd.hh" #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC namespace doxygen { using hpp::fcl::shared_ptr; diff --git a/python/gjk.cc b/python/gjk.cc index 1b4f7765ac950251d425104d4deb28123a5bcb7f..d1b13dbbf6c6b97326836d32e746dbf5590e5033 100644 --- a/python/gjk.cc +++ b/python/gjk.cc @@ -36,8 +36,8 @@ #include "fcl.hh" -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/narrowphase/gjk.h> +#include "coal/fwd.hh" +#include "coal/narrowphase/gjk.h" #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC #include "doxygen_autodoc/functions.h" diff --git a/python/math.cc b/python/math.cc index 5e1c4c69884c622a8346bb262c31ada58b7a496c..7d372c731bfb0b2c3a244b25af2e8bc84945d92c 100644 --- a/python/math.cc +++ b/python/math.cc @@ -35,9 +35,9 @@ #include <eigenpy/eigenpy.hpp> #include <eigenpy/geometry.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/serialization/transform.h> +#include "coal/fwd.hh" +#include "coal/math/transform.h" +#include "coal/serialization/transform.h" #include "fcl.hh" #include "pickle.hh" diff --git a/python/octree.cc b/python/octree.cc index b6bdc376a812c5df9b587ac98b4d008b7ee4f672..9fa4bf660ba72cc602b4803af783a828ad808f08 100644 --- a/python/octree.cc +++ b/python/octree.cc @@ -3,8 +3,8 @@ #include <eigenpy/std-vector.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/octree.h> +#include "coal/fwd.hh" +#include "coal/octree.h" #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC #include "doxygen_autodoc/functions.h" diff --git a/python/serializable.hh b/python/serializable.hh index 87c1690fea1fe97e051f977c8a99c8328b97ab1b..2ab337fb5987e0195901b04ad9e01f02799d72a8 100644 --- a/python/serializable.hh +++ b/python/serializable.hh @@ -9,8 +9,8 @@ #include <boost/python.hpp> -#include "hpp/fcl/serialization/archive.h" -#include "hpp/fcl/serialization/serializer.h" +#include "coal/serialization/archive.h" +#include "coal/serialization/serializer.h" namespace coal { namespace python { diff --git a/python/version.cc b/python/version.cc index 4bc0eea9337a880f1653e78372991ee355de950e..f0c2e3dd162213ef01b9a0c0425b10d8309cadf0 100644 --- a/python/version.cc +++ b/python/version.cc @@ -2,28 +2,28 @@ // Copyright (c) 2019-2023 CNRS INRIA // -#include "hpp/fcl/config.hh" +#include "coal/config.hh" #include "fcl.hh" #include <boost/preprocessor/stringize.hpp> namespace bp = boost::python; inline bool checkVersionAtLeast(int major, int minor, int patch) { - return HPP_FCL_VERSION_AT_LEAST(major, minor, patch); + return COAL_VERSION_AT_LEAST(major, minor, patch); } inline bool checkVersionAtMost(int major, int minor, int patch) { - return HPP_FCL_VERSION_AT_MOST(major, minor, patch); + return COAL_VERSION_AT_MOST(major, minor, patch); } void exposeVersion() { // Define release numbers of the current hpp-fcl version. bp::scope().attr("__version__") = - BOOST_PP_STRINGIZE(HPP_FCL_MAJOR_VERSION) "." BOOST_PP_STRINGIZE(HPP_FCL_MINOR_VERSION) "." BOOST_PP_STRINGIZE(HPP_FCL_PATCH_VERSION); - bp::scope().attr("__raw_version__") = HPP_FCL_VERSION; - bp::scope().attr("HPP_FCL_MAJOR_VERSION") = HPP_FCL_MAJOR_VERSION; - bp::scope().attr("HPP_FCL_MINOR_VERSION") = HPP_FCL_MINOR_VERSION; - bp::scope().attr("HPP_FCL_PATCH_VERSION") = HPP_FCL_PATCH_VERSION; + BOOST_PP_STRINGIZE(COAL_MAJOR_VERSION) "." BOOST_PP_STRINGIZE(COAL_MINOR_VERSION) "." BOOST_PP_STRINGIZE(COAL_PATCH_VERSION); + bp::scope().attr("__raw_version__") = COAL_VERSION; + bp::scope().attr("COAL_MAJOR_VERSION") = COAL_MAJOR_VERSION; + bp::scope().attr("COAL_MINOR_VERSION") = COAL_MINOR_VERSION; + bp::scope().attr("COAL_PATCH_VERSION") = COAL_PATCH_VERSION; #if HPP_FCL_HAS_QHULL bp::scope().attr("WITH_QHULL") = true; @@ -39,11 +39,11 @@ void exposeVersion() { bp::def("checkVersionAtLeast", &checkVersionAtLeast, bp::args("major", "minor", "patch"), - "Checks if the current version of hpp-fcl is at least" + "Checks if the current version of coal is at least" " the version provided by the input arguments."); bp::def("checkVersionAtMost", &checkVersionAtMost, bp::args("major", "minor", "patch"), - "Checks if the current version of hpp-fcl is at most" + "Checks if the current version of coal is at most" " the version provided by the input arguments."); } diff --git a/src/BV/AABB.cpp b/src/BV/AABB.cpp index 40a3523757c272f5cb2788b70138829f43e0be89..c7b427a7515a8436fec42de76a419ff1d298513e 100644 --- a/src/BV/AABB.cpp +++ b/src/BV/AABB.cpp @@ -35,11 +35,11 @@ /** \author Jia Pan */ -#include <hpp/fcl/BV/AABB.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/BV/AABB.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/collision_data.h" #include <limits> -#include <hpp/fcl/collision_data.h> namespace coal { diff --git a/src/BV/OBB.cpp b/src/BV/OBB.cpp index 44036f7f3cc50a367cba1e973e37c9581d95c69f..8fee27530b03fefb68925daa9ba1955321a199e0 100644 --- a/src/BV/OBB.cpp +++ b/src/BV/OBB.cpp @@ -35,11 +35,11 @@ /** \author Jia Pan, Florent Lamiraux */ -#include <hpp/fcl/BV/OBB.h> -#include <hpp/fcl/BVH/BVH_utility.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/internal/tools.h> +#include "coal/BV/OBB.h" +#include "coal/BVH/BVH_utility.h" +#include "coal/math/transform.h" +#include "coal/collision_data.h" +#include "coal/internal/tools.h" #include <iostream> #include <limits> @@ -310,7 +310,7 @@ inline FCL_REAL obbDisjoint_check_B_axis(const Matrix3f& B, const Vec3f& T, } template <int ib, int jb = (ib + 1) % 3, int kb = (ib + 2) % 3> -struct HPP_FCL_LOCAL obbDisjoint_check_Ai_cross_Bi { +struct COAL_LOCAL obbDisjoint_check_Ai_cross_Bi { static inline bool run(int ia, int ja, int ka, const Matrix3f& B, const Vec3f& T, const Vec3f& a, const Vec3f& b, const Matrix3f& Bf, const FCL_REAL& breakDistance2, diff --git a/src/BV/OBBRSS.cpp b/src/BV/OBBRSS.cpp index d74381f9c8788c828fded8586412bba81a4c0e03..18a0c83f7f12cf28573cfd2078c3e93a944fac0c 100644 --- a/src/BV/OBBRSS.cpp +++ b/src/BV/OBBRSS.cpp @@ -35,7 +35,7 @@ /** \author Jia Pan */ -#include <hpp/fcl/BV/OBBRSS.h> +#include "coal/BV/OBBRSS.h" namespace coal { diff --git a/src/BV/RSS.cpp b/src/BV/RSS.cpp index f793d2fadf65d18c765017aa261173a931281c47..ead66ce7a32cb28217b67e881ce618c7af756698 100644 --- a/src/BV/RSS.cpp +++ b/src/BV/RSS.cpp @@ -35,10 +35,10 @@ /** \author Jia Pan */ -#include <hpp/fcl/BV/RSS.h> -#include <hpp/fcl/BVH/BVH_utility.h> -#include <hpp/fcl/internal/tools.h> -#include <hpp/fcl/collision_data.h> +#include "coal/BV/RSS.h" +#include "coal/BVH/BVH_utility.h" +#include "coal/internal/tools.h" +#include "coal/collision_data.h" #include <iostream> diff --git a/src/BV/kDOP.cpp b/src/BV/kDOP.cpp index 6d9b4c9f65a496c93f4bdca94342268dc533b32e..80e94990e5673831105f7ef0e75d20f17a82bc03 100644 --- a/src/BV/kDOP.cpp +++ b/src/BV/kDOP.cpp @@ -35,12 +35,12 @@ /** \author Jia Pan */ -#include <hpp/fcl/BV/kDOP.h> +#include "coal/collision_data.h" +#include "coal/BV/kDOP.h" + #include <limits> #include <iostream> -#include <hpp/fcl/collision_data.h> - namespace coal { /// @brief Find the smaller and larger one of two values diff --git a/src/BV/kIOS.cpp b/src/BV/kIOS.cpp index 48bb080243ac2a3117f6ee58cd469c6b7fb015a3..2b50f4b65cb3b825db0335d1a99e5ea5f1be3fad 100644 --- a/src/BV/kIOS.cpp +++ b/src/BV/kIOS.cpp @@ -35,9 +35,9 @@ /** \author Jia Pan */ -#include <hpp/fcl/BV/kIOS.h> -#include <hpp/fcl/BVH/BVH_utility.h> -#include <hpp/fcl/math/transform.h> +#include "coal/BV/kIOS.h" +#include "coal/BVH/BVH_utility.h" +#include "coal/math/transform.h" #include <iostream> #include <limits> diff --git a/src/BVH/BVH_model.cpp b/src/BVH/BVH_model.cpp index 30271906fe545bd783897879c4917acde5265cd7..cd45cabf6d30c8b7e2dc3b82cc7b68ca48d0eff9 100644 --- a/src/BVH/BVH_model.cpp +++ b/src/BVH/BVH_model.cpp @@ -36,17 +36,17 @@ /** \author Jia Pan */ -#include "hpp/fcl/BV/BV_node.h" -#include <hpp/fcl/BVH/BVH_model.h> +#include "coal/BV/BV_node.h" +#include "coal/BVH/BVH_model.h" -#include <iostream> -#include <string.h> +#include "coal/BV/BV.h" +#include "coal/shape/convex.h" -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/shape/convex.h> +#include "coal/internal/BV_splitter.h" +#include "coal/internal/BV_fitter.h" -#include <hpp/fcl/internal/BV_splitter.h> -#include <hpp/fcl/internal/BV_fitter.h> +#include <iostream> +#include <string.h> namespace coal { diff --git a/src/BVH/BVH_utility.cpp b/src/BVH/BVH_utility.cpp index 638acf3e33621bb4e045c2e74411c878901f7a28..2072921b2c4ac25766a737bbc786be87f619bce9 100644 --- a/src/BVH/BVH_utility.cpp +++ b/src/BVH/BVH_utility.cpp @@ -35,10 +35,10 @@ /** \author Jia Pan */ -#include <hpp/fcl/BVH/BVH_utility.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/BVH/BVH_utility.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/shape_shape_func.h" namespace coal { diff --git a/src/BVH/BV_fitter.cpp b/src/BVH/BV_fitter.cpp index 86b0bc3fa7592804619cc5b10f8c9681213978b7..3c0a80bf0f50123629dce756b6c7f872508391b8 100644 --- a/src/BVH/BV_fitter.cpp +++ b/src/BVH/BV_fitter.cpp @@ -35,10 +35,11 @@ /** \author Jia Pan */ -#include <hpp/fcl/internal/BV_fitter.h> -#include <hpp/fcl/BVH/BVH_utility.h> +#include "coal/internal/BV_fitter.h" +#include "coal/BVH/BVH_utility.h" +#include "coal/internal/tools.h" + #include <limits> -#include <hpp/fcl/internal/tools.h> namespace coal { diff --git a/src/BVH/BV_splitter.cpp b/src/BVH/BV_splitter.cpp index 7e4dbbc170c0b79b5549c1e30d1ada927066cad9..1a78e332c53323a0a4cd854394ce86bb8ab2a315 100644 --- a/src/BVH/BV_splitter.cpp +++ b/src/BVH/BV_splitter.cpp @@ -35,7 +35,7 @@ /** \author Jia Pan */ -#include <hpp/fcl/internal/BV_splitter.h> +#include "coal/internal/BV_splitter.h" namespace coal { diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 74e7fb304516ec4327daef3af641a53b1a07a646..cb3639f4db89c64ee98487c5c0e9a62fa91d594f 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -179,9 +179,9 @@ SET(PROJECT_HEADERS_FULL_PATH) FOREACH(header ${${PROJECT_NAME}_HEADERS}) LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_SOURCE_DIR}/${header}) ENDFOREACH() -LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/hpp/fcl/config.hh) -LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/hpp/fcl/deprecated.hh) -LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/hpp/fcl/warning.hh) +LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/coal/config.hh) +LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/coal/deprecated.hh) +LIST(APPEND PROJECT_HEADERS_FULL_PATH ${PROJECT_BINARY_DIR}/include/coal/warning.hh) add_library(${LIBRARY_NAME} SHARED ${PROJECT_HEADERS_FULL_PATH} diff --git a/src/broadphase/broadphase_SSaP.cpp b/src/broadphase/broadphase_SSaP.cpp index 71000e45db66e243cb9c01601c390ebd97240083..124f8c6718f157d5669a5939604fa25e86b0060c 100644 --- a/src/broadphase/broadphase_SSaP.cpp +++ b/src/broadphase/broadphase_SSaP.cpp @@ -35,7 +35,7 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_SSaP.h" +#include "coal/broadphase/broadphase_SSaP.h" namespace coal { @@ -64,7 +64,7 @@ struct SortByZLow { }; /** @brief Dummy collision object with a point AABB */ -class HPP_FCL_DLLAPI DummyCollisionObject : public CollisionObject { +class COAL_DLLAPI DummyCollisionObject : public CollisionObject { public: DummyCollisionObject(const AABB& aabb_) : CollisionObject(shared_ptr<CollisionGeometry>()) { diff --git a/src/broadphase/broadphase_SaP.cpp b/src/broadphase/broadphase_SaP.cpp index 59871347ec24821f6b669167570748161d982a1d..61f039d539add6568f70bdbfea6fea7363a7c8f5 100644 --- a/src/broadphase/broadphase_SaP.cpp +++ b/src/broadphase/broadphase_SaP.cpp @@ -35,7 +35,7 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_SaP.h" +#include "coal/broadphase/broadphase_SaP.h" namespace coal { diff --git a/src/broadphase/broadphase_bruteforce.cpp b/src/broadphase/broadphase_bruteforce.cpp index 0eb81752fd1fff337bff598d579f96ff7d8c46b4..f1a241d71c2a51ef588ec61b826130df8a0c3355 100644 --- a/src/broadphase/broadphase_bruteforce.cpp +++ b/src/broadphase/broadphase_bruteforce.cpp @@ -35,7 +35,7 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_bruteforce.h" +#include "coal/broadphase/broadphase_bruteforce.h" #include <iterator> #include <algorithm> diff --git a/src/broadphase/broadphase_collision_manager.cpp b/src/broadphase/broadphase_collision_manager.cpp index 2c5c340a246f0e3ee0dd0429876dc5d780aaa38d..59e1a854eed68adb3b34a168670340690b52f708 100644 --- a/src/broadphase/broadphase_collision_manager.cpp +++ b/src/broadphase/broadphase_collision_manager.cpp @@ -35,7 +35,7 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_collision_manager.h" +#include "coal/broadphase/broadphase_collision_manager.h" namespace coal { diff --git a/src/broadphase/broadphase_dynamic_AABB_tree.cpp b/src/broadphase/broadphase_dynamic_AABB_tree.cpp index 7fceeb57c725c702a41109b23e21a6acede46224..efc82c6da110c77165fa72a41268fdeac3ed4ac4 100644 --- a/src/broadphase/broadphase_dynamic_AABB_tree.cpp +++ b/src/broadphase/broadphase_dynamic_AABB_tree.cpp @@ -35,16 +35,16 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" - -#include <limits> +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" #ifdef HPP_FCL_HAVE_OCTOMAP -#include "hpp/fcl/octree.h" +#include "coal/octree.h" #endif -#include "hpp/fcl/BV/BV.h" -#include "hpp/fcl/shape/geometric_shapes_utility.h" +#include "coal/BV/BV.h" +#include "coal/shape/geometric_shapes_utility.h" + +#include <limits> namespace coal { namespace detail { diff --git a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp index ced67ae1a6e10db0df9c75a44003a53956cd1cd2..6c1e65bd74cc6a900a9794178587ccbe8552d39c 100644 --- a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp +++ b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp @@ -35,10 +35,10 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" #ifdef HPP_FCL_HAVE_OCTOMAP -#include "hpp/fcl/octree.h" +#include "coal/octree.h" #endif namespace coal { namespace detail { @@ -262,7 +262,7 @@ bool collisionRecurse( } //============================================================================== -inline HPP_FCL_DLLAPI bool collisionRecurse( +inline COAL_DLLAPI bool collisionRecurse( DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* nodes, size_t root_id, CollisionObject* query, CollisionCallBackBase* callback) { DynamicAABBTreeArrayCollisionManager::DynamicAABBNode* root = nodes + root_id; diff --git a/src/broadphase/broadphase_interval_tree.cpp b/src/broadphase/broadphase_interval_tree.cpp index b9cc6f9db52fd23a3e415392da5b5985af75fd3b..9107335dcae4024aa4ef867556ff0e9570241511 100644 --- a/src/broadphase/broadphase_interval_tree.cpp +++ b/src/broadphase/broadphase_interval_tree.cpp @@ -35,7 +35,7 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/broadphase_interval_tree.h" +#include "coal/broadphase/broadphase_interval_tree.h" namespace coal { diff --git a/src/broadphase/default_broadphase_callbacks.cpp b/src/broadphase/default_broadphase_callbacks.cpp index 55db074dad663cee654597850f47338c917c8b5b..222e77b85c6241fc25aa101d1425ea58f22b4211 100644 --- a/src/broadphase/default_broadphase_callbacks.cpp +++ b/src/broadphase/default_broadphase_callbacks.cpp @@ -34,7 +34,7 @@ /** @author Sean Curtis (sean@tri.global) */ -#include "hpp/fcl/broadphase/default_broadphase_callbacks.h" +#include "coal/broadphase/default_broadphase_callbacks.h" #include <algorithm> namespace coal { diff --git a/src/broadphase/detail/interval_tree.cpp b/src/broadphase/detail/interval_tree.cpp index 88b1119cc69c019b14d3dceb8534b209b0f3a318..63fdd8d760b558fa4353fee9ad41bc95a6a25190 100644 --- a/src/broadphase/detail/interval_tree.cpp +++ b/src/broadphase/detail/interval_tree.cpp @@ -38,7 +38,7 @@ #ifndef COAL_INTERVAL_TREE_INL_H #define COAL_INTERVAL_TREE_INL_H -#include "hpp/fcl/broadphase/detail/interval_tree.h" +#include "coal/broadphase/detail/interval_tree.h" #include <algorithm> diff --git a/src/broadphase/detail/interval_tree_node.cpp b/src/broadphase/detail/interval_tree_node.cpp index afb55734ee18eea6ba87e64b7e3e76b4b6a5edd3..51a1a457ae985a9838f9c7f69a254276a157b96e 100644 --- a/src/broadphase/detail/interval_tree_node.cpp +++ b/src/broadphase/detail/interval_tree_node.cpp @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_INTERVALTREENODE_INL_H #define COAL_BROADPHASE_DETAIL_INTERVALTREENODE_INL_H -#include "hpp/fcl/broadphase/detail/interval_tree_node.h" +#include "coal/broadphase/detail/interval_tree_node.h" #include <iostream> #include <algorithm> diff --git a/src/broadphase/detail/morton-inl.h b/src/broadphase/detail/morton-inl.h index 80354a76d1f0aa9da462d813f02f99d5543eb1ce..4f27aef9147c76f81ff57c2faff73ac506c72f8f 100644 --- a/src/broadphase/detail/morton-inl.h +++ b/src/broadphase/detail/morton-inl.h @@ -39,7 +39,7 @@ #ifndef COAL_MORTON_INL_H #define COAL_MORTON_INL_H -#include "hpp/fcl/broadphase/detail/morton.h" +#include "coal/broadphase/detail/morton.h" namespace coal { /// @cond IGNORE namespace detail { diff --git a/src/broadphase/detail/morton.cpp b/src/broadphase/detail/morton.cpp index 83fc06ced178a796c72e346757610b98d56cb58c..17e554f0e7ee93ed5df524d70e03b3ab0a45702c 100644 --- a/src/broadphase/detail/morton.cpp +++ b/src/broadphase/detail/morton.cpp @@ -36,7 +36,7 @@ /** @author Jia Pan */ -#include "hpp/fcl/broadphase/detail/morton-inl.h" +#include "coal/broadphase/detail/morton-inl.h" namespace coal { diff --git a/src/broadphase/detail/simple_interval.cpp b/src/broadphase/detail/simple_interval.cpp index 4625c31e69e57641a2454625c7cadc35c8ea5168..95075cbc19426df136380ae47c42fef70914db8c 100644 --- a/src/broadphase/detail/simple_interval.cpp +++ b/src/broadphase/detail/simple_interval.cpp @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_DETAIL_SIMPLEINTERVAL_INL_H #define COAL_BROADPHASE_DETAIL_SIMPLEINTERVAL_INL_H -#include "hpp/fcl/broadphase/detail/simple_interval.h" +#include "coal/broadphase/detail/simple_interval.h" #include <algorithm> namespace coal { diff --git a/src/broadphase/detail/spatial_hash.cpp b/src/broadphase/detail/spatial_hash.cpp index 46afc7d32091f2a6d23507d1b9e93fe0b43fc827..ba45f0e9b490548a817f9d065148d68f06d33e5f 100644 --- a/src/broadphase/detail/spatial_hash.cpp +++ b/src/broadphase/detail/spatial_hash.cpp @@ -38,7 +38,7 @@ #ifndef COAL_BROADPHASE_SPATIALHASH_INL_H #define COAL_BROADPHASE_SPATIALHASH_INL_H -#include "hpp/fcl/broadphase/detail/spatial_hash.h" +#include "coal/broadphase/detail/spatial_hash.h" #include <algorithm> namespace coal { diff --git a/src/collision.cpp b/src/collision.cpp index 3b2f5e41b78610acc87197c1e01f57f89d05284f..0cc76d8e9f8efc497b2226854c1da02deb5260fc 100644 --- a/src/collision.cpp +++ b/src/collision.cpp @@ -35,10 +35,10 @@ /** \author Jia Pan */ -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_utility.h> -#include <hpp/fcl/collision_func_matrix.h> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/collision.h" +#include "coal/collision_utility.h" +#include "coal/collision_func_matrix.h" +#include "coal/narrowphase/narrowphase.h" namespace coal { diff --git a/src/collision_data.cpp b/src/collision_data.cpp index 51f0083a6d305b5ddb9eb1595f3aef1a50d73f8a..7561ba8310a71f546697a82a57011f28222cd567 100644 --- a/src/collision_data.cpp +++ b/src/collision_data.cpp @@ -36,7 +36,7 @@ /** \author Jia Pan */ -#include <hpp/fcl/collision_data.h> +#include "coal/collision_data.h" namespace coal { diff --git a/src/collision_func_matrix.cpp b/src/collision_func_matrix.cpp index 11347a048ce5f7fbe09c1cca69b06e49dd09e2e7..6a23dd85683cfea2a713c694da4b6e5a8077c4bd 100644 --- a/src/collision_func_matrix.cpp +++ b/src/collision_func_matrix.cpp @@ -35,13 +35,13 @@ /** \author Jia Pan */ -#include <hpp/fcl/collision_func_matrix.h> +#include "coal/collision_func_matrix.h" -#include <hpp/fcl/internal/traversal_node_setup.h> +#include "coal/internal/traversal_node_setup.h" #include <../src/collision_node.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/internal/shape_shape_func.h> -#include <hpp/fcl/shape/geometric_shapes_traits.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/internal/shape_shape_func.h" +#include "coal/shape/geometric_shapes_traits.h" #include <../src/traits_traversal.h> namespace coal { @@ -98,7 +98,7 @@ BVH_SHAPE_DEFAULT_TO_ORIENTED(OBBRSS); /// - 0 if the query should be made with non-aligned object frames. template <typename T_BVH, typename T_SH, int _Options = details::bvh_shape_traits<T_BVH, T_SH>::Options> -struct HPP_FCL_LOCAL BVHShapeCollider { +struct COAL_LOCAL BVHShapeCollider { static std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, @@ -165,7 +165,7 @@ struct HPP_FCL_LOCAL BVHShapeCollider { /// into the frame of object 2 before computing collisions. /// - 0 if the query should be made with non-aligned object frames. template <typename BV, typename Shape> -struct HPP_FCL_LOCAL HeightFieldShapeCollider { +struct COAL_LOCAL HeightFieldShapeCollider { typedef HeightField<BV> HF; static std::size_t collide(const CollisionGeometry* o1, diff --git a/src/collision_node.cpp b/src/collision_node.cpp index a5e196533d04ed2538e028bafb46cbd368c22da7..c263dc95e326c4357e6a861d7994881c5d23576f 100644 --- a/src/collision_node.cpp +++ b/src/collision_node.cpp @@ -36,7 +36,7 @@ /** \author Jia Pan */ #include <../src/collision_node.h> -#include <hpp/fcl/internal/traversal_recurse.h> +#include "coal/internal/traversal_recurse.h" namespace coal { diff --git a/src/collision_node.h b/src/collision_node.h index 9c48e8a7b756749dd3413eafc45fb87f9338c7be..f2780cfc538e84888c428658db57d4a1aa10e09f 100644 --- a/src/collision_node.h +++ b/src/collision_node.h @@ -40,9 +40,9 @@ /// @cond INTERNAL -#include <hpp/fcl/BVH/BVH_front.h> -#include <hpp/fcl/internal/traversal_node_base.h> -#include <hpp/fcl/internal/traversal_node_bvhs.h> +#include "coal/BVH/BVH_front.h" +#include "coal/internal/traversal_node_base.h" +#include "coal/internal/traversal_node_bvhs.h" /// @brief collision and distance function on traversal nodes. these functions /// provide a higher level abstraction for collision functions provided in @@ -56,18 +56,18 @@ namespace coal { /// do not collide. /// @param front_list list of nodes visited by the query, can be used to /// accelerate computation -/// \todo should be HPP_FCL_LOCAL but used in unit test. -HPP_FCL_DLLAPI void collide(CollisionTraversalNodeBase* node, - const CollisionRequest& request, - CollisionResult& result, - BVHFrontList* front_list = NULL, - bool recursive = true); +/// \todo should be COAL_LOCAL but used in unit test. +COAL_DLLAPI void collide(CollisionTraversalNodeBase* node, + const CollisionRequest& request, + CollisionResult& result, + BVHFrontList* front_list = NULL, + bool recursive = true); /// @brief distance computation on distance traversal node; can use front list -/// to accelerate \todo should be HPP_FCL_LOCAL but used in unit test. -HPP_FCL_DLLAPI void distance(DistanceTraversalNodeBase* node, - BVHFrontList* front_list = NULL, - unsigned int qsize = 2); +/// to accelerate \todo should be COAL_LOCAL but used in unit test. +COAL_DLLAPI void distance(DistanceTraversalNodeBase* node, + BVHFrontList* front_list = NULL, + unsigned int qsize = 2); } // namespace coal /// @endcond diff --git a/src/collision_object.cpp b/src/collision_object.cpp index f335f7fced4480fa68ee4771523049ae38911603..a0501b146e8745f08079e07d605db866bb6477c2 100644 --- a/src/collision_object.cpp +++ b/src/collision_object.cpp @@ -35,7 +35,7 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/collision_object.h> +#include "coal/collision_object.h" namespace coal { bool CollisionGeometry::isUncertain() const { diff --git a/src/collision_utility.cpp b/src/collision_utility.cpp index 932a6ecd3c172dced595081933f10c943a06f595..8310408884217d5c5f2fcf0a15146e224cf4b3dc 100644 --- a/src/collision_utility.cpp +++ b/src/collision_utility.cpp @@ -14,9 +14,8 @@ // received a copy of the GNU Lesser General Public License along with // hpp-fcl. If not, see <http://www.gnu.org/licenses/>. -#include <hpp/fcl/collision_utility.h> - -#include <hpp/fcl/BVH/BVH_utility.h> +#include "coal/collision_utility.h" +#include "coal/BVH/BVH_utility.h" namespace coal { namespace details { diff --git a/src/contact_patch.cpp b/src/contact_patch.cpp index c5870e190f26209e01b127b73d10a8dc7825e94c..9b6c2236470a5d13ef2fbdd6dc24f510877b98d9 100644 --- a/src/contact_patch.cpp +++ b/src/contact_patch.cpp @@ -34,8 +34,8 @@ /** \author Louis Montaut */ -#include "hpp/fcl/contact_patch.h" -#include "hpp/fcl/collision_utility.h" +#include "coal/contact_patch.h" +#include "coal/collision_utility.h" namespace coal { diff --git a/src/contact_patch/contact_patch_solver.cpp b/src/contact_patch/contact_patch_solver.cpp index d6b07bdcf3163ff7ab99be6989d90e71fc2f2df1..fdb16217ee9c60e3c93e1482c65bf36a34b45122 100644 --- a/src/contact_patch/contact_patch_solver.cpp +++ b/src/contact_patch/contact_patch_solver.cpp @@ -34,7 +34,7 @@ /** \authors Louis Montaut */ -#include "hpp/fcl/contact_patch/contact_patch_solver.h" +#include "coal/contact_patch/contact_patch_solver.h" namespace coal { diff --git a/src/contact_patch_func_matrix.cpp b/src/contact_patch_func_matrix.cpp index 0ab71ea5d6c5cad4b14008c8d6465bf14b498827..b1b0f90cf00fa4918fb5534a496584a2278c89d7 100644 --- a/src/contact_patch_func_matrix.cpp +++ b/src/contact_patch_func_matrix.cpp @@ -34,11 +34,10 @@ /** \author Louis Montaut */ -#include "hpp/fcl/contact_patch_func_matrix.h" -#include "hpp/fcl/shape/geometric_shapes.h" -#include "hpp/fcl/internal/shape_shape_contact_patch_func.h" - -#include "hpp/fcl/BV/BV.h" +#include "coal/contact_patch_func_matrix.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/shape_shape_contact_patch_func.h" +#include "coal/BV/BV.h" namespace coal { @@ -117,7 +116,7 @@ struct BVHComputeContactPatch { } }; -HPP_FCL_LOCAL void contact_patch_function_not_implemented( +COAL_LOCAL void contact_patch_function_not_implemented( const CollisionGeometry* o1, const Transform3f& /*tf1*/, const CollisionGeometry* o2, const Transform3f& /*tf2*/, const CollisionResult& /*collision_result*/, diff --git a/src/distance.cpp b/src/distance.cpp index b220630282527368ae7f3f02b8272c9017a08bb3..e802f587225ef9cb04d325e589dceeea711dd716 100644 --- a/src/distance.cpp +++ b/src/distance.cpp @@ -35,10 +35,10 @@ /** \author Jia Pan */ -#include <hpp/fcl/distance.h> -#include <hpp/fcl/collision_utility.h> -#include <hpp/fcl/distance_func_matrix.h> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/distance.h" +#include "coal/collision_utility.h" +#include "coal/distance_func_matrix.h" +#include "coal/narrowphase/narrowphase.h" #include <iostream> diff --git a/src/distance/box_halfspace.cpp b/src/distance/box_halfspace.cpp index 8dffb32e4d1bbc2657795bcc30224c4bcaaae63b..39f8a792a99ba9c8196f96cb0e6ddc73789d69be 100644 --- a/src/distance/box_halfspace.cpp +++ b/src/distance/box_halfspace.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/box_plane.cpp b/src/distance/box_plane.cpp index 159739a8b2efb429e8d05ac1065b7f44a5fa60a8..f0c45e3fd74ee84dc922f6753b23bd4e99772950 100644 --- a/src/distance/box_plane.cpp +++ b/src/distance/box_plane.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/box_sphere.cpp b/src/distance/box_sphere.cpp index e3a8bb462a09aca55cff7bb0ac1e7242276c513d..220c20eb907b414ab7d47a59b97b189226058100 100644 --- a/src/distance/box_sphere.cpp +++ b/src/distance/box_sphere.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/capsule_capsule.cpp b/src/distance/capsule_capsule.cpp index 58ac989ba76cd78a4bd6de2a0a2e2b622a49b4ed..c229f80e7fd78eebcca3a7d736ddba33c4d86420 100644 --- a/src/distance/capsule_capsule.cpp +++ b/src/distance/capsule_capsule.cpp @@ -31,9 +31,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/shape_shape_func.h" // Note that partial specialization of template functions is not allowed. // Therefore, two implementations with the default narrow phase solvers are diff --git a/src/distance/capsule_halfspace.cpp b/src/distance/capsule_halfspace.cpp index 294fe70419757d05907d97d62f15c0a95e607ced..15daa03d524926d909ff89f2d0719a4fb60c6dec 100644 --- a/src/distance/capsule_halfspace.cpp +++ b/src/distance/capsule_halfspace.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/capsule_plane.cpp b/src/distance/capsule_plane.cpp index 24ac3e3214c67b480adfc7d19af3a5a23aaad961..9644e43e7201eacdf736954f45a7e74dd7ad5ec3 100644 --- a/src/distance/capsule_plane.cpp +++ b/src/distance/capsule_plane.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/cone_halfspace.cpp b/src/distance/cone_halfspace.cpp index 10356c4ebeac40a40e203aeae1f6a02dc535daf2..39649095a6586d1d7490870df772b30693a9bc52 100644 --- a/src/distance/cone_halfspace.cpp +++ b/src/distance/cone_halfspace.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/cone_plane.cpp b/src/distance/cone_plane.cpp index 0b95a1576d96e6f9841c6c47441ac660aff3edaa..ddd863ff5fca13993e75a8cda01f17d19b963ea4 100644 --- a/src/distance/cone_plane.cpp +++ b/src/distance/cone_plane.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/convex_halfspace.cpp b/src/distance/convex_halfspace.cpp index 552b41dd8fb2acf80b104f2a63c61dafd9874ed3..22fc88ad475d34c88cf6d50f1ee2363ce113de83 100644 --- a/src/distance/convex_halfspace.cpp +++ b/src/distance/convex_halfspace.cpp @@ -34,9 +34,9 @@ /** \author Joseph Mirabel */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/convex_plane.cpp b/src/distance/convex_plane.cpp index da1752c535e6df1cfaee0947d9d9109cd99e0df3..e2ece56edafdacb39320cba122418fe75abbea90 100644 --- a/src/distance/convex_plane.cpp +++ b/src/distance/convex_plane.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/cylinder_halfspace.cpp b/src/distance/cylinder_halfspace.cpp index 58850b15e5162d414db5b3a496c0076b8355ac37..17b599908de5340edcd94877b3aa68a551425164 100644 --- a/src/distance/cylinder_halfspace.cpp +++ b/src/distance/cylinder_halfspace.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/cylinder_plane.cpp b/src/distance/cylinder_plane.cpp index 975d8389f707be6f8aa77a962b5dca44d6a465b3..fd1e31b79c6bfb8fc1dd5169a0c2eb2b052ac103 100644 --- a/src/distance/cylinder_plane.cpp +++ b/src/distance/cylinder_plane.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/ellipsoid_halfspace.cpp b/src/distance/ellipsoid_halfspace.cpp index edd376f9fb565114a396b870cb0547a70f5a974b..836eb493ff61d1acda8292d6c47178907df55047 100644 --- a/src/distance/ellipsoid_halfspace.cpp +++ b/src/distance/ellipsoid_halfspace.cpp @@ -34,10 +34,10 @@ /** \author Louis Montaut */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/ellipsoid_plane.cpp b/src/distance/ellipsoid_plane.cpp index f37a03a2f663c8fee4a4cf76538a6693524c02e5..77d7cd2e9f536ea990de876a7aa52e463549e837 100644 --- a/src/distance/ellipsoid_plane.cpp +++ b/src/distance/ellipsoid_plane.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/halfspace_halfspace.cpp b/src/distance/halfspace_halfspace.cpp index eb39873e92e78275178e6011147aa48d8eb92381..260b12ec0fa75656cbabc1f142622ee851a8d06c 100644 --- a/src/distance/halfspace_halfspace.cpp +++ b/src/distance/halfspace_halfspace.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/halfspace_plane.cpp b/src/distance/halfspace_plane.cpp index ed595868fc839772bdfd9289f3d42cdb816bf2f8..096b8ea40ce3b998f9ebda2a234b260c10878797 100644 --- a/src/distance/halfspace_plane.cpp +++ b/src/distance/halfspace_plane.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/plane_plane.cpp b/src/distance/plane_plane.cpp index bab49f7996358c648a6dc612461b0ef71a586a3f..a716999e85c6e58f2b3b70c467c1df2e8295615f 100644 --- a/src/distance/plane_plane.cpp +++ b/src/distance/plane_plane.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/sphere_capsule.cpp b/src/distance/sphere_capsule.cpp index 05a15c39db092be8c39039889c8dff44dba1bc08..d02101177b532ed9675a060932ff51ebabaaaff5 100644 --- a/src/distance/sphere_capsule.cpp +++ b/src/distance/sphere_capsule.cpp @@ -33,10 +33,10 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/sphere_cylinder.cpp b/src/distance/sphere_cylinder.cpp index 24bed10f1f7271f1026cf91b8f480ed720d53b3f..c97bec1d5c95a1d965124fe3be995a292e76cf25 100644 --- a/src/distance/sphere_cylinder.cpp +++ b/src/distance/sphere_cylinder.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/sphere_halfspace.cpp b/src/distance/sphere_halfspace.cpp index 6f09b4fe824153de43d94511a7a2a1357889c58d..3f3d580cb35095545e2ce3feb6442d180b317f27 100644 --- a/src/distance/sphere_halfspace.cpp +++ b/src/distance/sphere_halfspace.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/sphere_plane.cpp b/src/distance/sphere_plane.cpp index 5aa1ec725283689bf8c14701e12dbd473cec7118..a3d5a262bd37101bd56b9ec16d2253ee45e06901 100644 --- a/src/distance/sphere_plane.cpp +++ b/src/distance/sphere_plane.cpp @@ -36,10 +36,10 @@ /** \author Florent Lamiraux */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/sphere_sphere.cpp b/src/distance/sphere_sphere.cpp index d7403e4bd15d70ca3ea9ec382d3487b1ef6eab24..ea60685adcd9fa7e3ebe41b8c6dc13a04939dd6c 100644 --- a/src/distance/sphere_sphere.cpp +++ b/src/distance/sphere_sphere.cpp @@ -33,10 +33,10 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/internal/shape_shape_func.h> -#include <hpp/fcl/internal/traversal_node_base.h> +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/shape_shape_func.h" +#include "coal/internal/traversal_node_base.h" #include "../narrowphase/details.h" diff --git a/src/distance/triangle_halfspace.cpp b/src/distance/triangle_halfspace.cpp index 5925376cd049fe84168473c725103556f223ca71..a74cdc8bae5772b998aefe09453c41faed7bf655 100644 --- a/src/distance/triangle_halfspace.cpp +++ b/src/distance/triangle_halfspace.cpp @@ -34,9 +34,9 @@ /** \author Joseph Mirabel */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/triangle_plane.cpp b/src/distance/triangle_plane.cpp index c77ddd6481dbf91c4bf3b8984b48c3439d7fc89d..89b60f7a9296d3804db06aa29f20ffc925e0487d 100644 --- a/src/distance/triangle_plane.cpp +++ b/src/distance/triangle_plane.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/triangle_sphere.cpp b/src/distance/triangle_sphere.cpp index f0d670ea780482a9d128a86e8f95d65e21e7d406..aed68996179673e7b51e34cbdbd286396296cad0 100644 --- a/src/distance/triangle_sphere.cpp +++ b/src/distance/triangle_sphere.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance/triangle_triangle.cpp b/src/distance/triangle_triangle.cpp index 91ac7c20b719f6023b0e2e9fc113698917b54317..602e9efb8aa7f627c110ff670825af9f9577809e 100644 --- a/src/distance/triangle_triangle.cpp +++ b/src/distance/triangle_triangle.cpp @@ -34,9 +34,9 @@ /** \author Louis Montaut */ -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/shape/geometric_shapes.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "../narrowphase/details.h" namespace coal { diff --git a/src/distance_func_matrix.cpp b/src/distance_func_matrix.cpp index e9ccc50e13a8ff6a2f097c6bf69511d7fee19bdd..7e140ba969f7431f92f0c7fb76a97be5e799c07a 100644 --- a/src/distance_func_matrix.cpp +++ b/src/distance_func_matrix.cpp @@ -35,12 +35,12 @@ /** \author Jia Pan */ -#include <hpp/fcl/distance_func_matrix.h> +#include "coal/distance_func_matrix.h" #include <../src/collision_node.h> -#include <hpp/fcl/internal/shape_shape_func.h> -#include <hpp/fcl/internal/traversal_node_setup.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" +#include "coal/internal/traversal_node_setup.h" +#include "coal/internal/shape_shape_func.h" #include <../src/traits_traversal.h> namespace coal { @@ -66,7 +66,7 @@ FCL_REAL Distance(const CollisionGeometry* o1, const Transform3f& tf1, #endif -HPP_FCL_LOCAL FCL_REAL distance_function_not_implemented( +COAL_LOCAL FCL_REAL distance_function_not_implemented( const CollisionGeometry* o1, const Transform3f& /*tf1*/, const CollisionGeometry* o2, const Transform3f& /*tf2*/, const GJKSolver* /*nsolver*/, const DistanceRequest& /*request*/, @@ -83,7 +83,7 @@ HPP_FCL_LOCAL FCL_REAL distance_function_not_implemented( } template <typename T_BVH, typename T_SH> -struct HPP_FCL_LOCAL BVHShapeDistancer { +struct COAL_LOCAL BVHShapeDistancer { static FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver* nsolver, @@ -129,7 +129,7 @@ FCL_REAL orientedBVHShapeDistance(const CollisionGeometry* o1, } // namespace details template <typename T_SH> -struct HPP_FCL_LOCAL BVHShapeDistancer<RSS, T_SH> { +struct COAL_LOCAL BVHShapeDistancer<RSS, T_SH> { static FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver* nsolver, @@ -142,7 +142,7 @@ struct HPP_FCL_LOCAL BVHShapeDistancer<RSS, T_SH> { }; template <typename T_SH> -struct HPP_FCL_LOCAL BVHShapeDistancer<kIOS, T_SH> { +struct COAL_LOCAL BVHShapeDistancer<kIOS, T_SH> { static FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver* nsolver, @@ -155,7 +155,7 @@ struct HPP_FCL_LOCAL BVHShapeDistancer<kIOS, T_SH> { }; template <typename T_SH> -struct HPP_FCL_LOCAL BVHShapeDistancer<OBBRSS, T_SH> { +struct COAL_LOCAL BVHShapeDistancer<OBBRSS, T_SH> { static FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver* nsolver, @@ -168,7 +168,7 @@ struct HPP_FCL_LOCAL BVHShapeDistancer<OBBRSS, T_SH> { }; template <typename T_HF, typename T_SH> -struct HPP_FCL_LOCAL HeightFieldShapeDistancer { +struct COAL_LOCAL HeightFieldShapeDistancer { static FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1, const CollisionGeometry* o2, const Transform3f& tf2, const GJKSolver* nsolver, diff --git a/src/hfield.cpp b/src/hfield.cpp index 2a44f01d20e9ed625840bfdab8aec70f8eaa2ebc..af53913798953d68ab154c752728b05cda79969e 100644 --- a/src/hfield.cpp +++ b/src/hfield.cpp @@ -34,16 +34,16 @@ /** \author Justin Carpentier */ -#include <hpp/fcl/hfield.h> +#include "coal/hfield.h" -#include <iostream> -#include <string.h> +#include "coal/BV/BV.h" +#include "coal/shape/convex.h" -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/shape/convex.h> +#include "coal/internal/BV_splitter.h" +#include "coal/internal/BV_fitter.h" -#include <hpp/fcl/internal/BV_splitter.h> -#include <hpp/fcl/internal/BV_fitter.h> +#include <iostream> +#include <string.h> namespace coal { diff --git a/src/intersect.cpp b/src/intersect.cpp index 876b9fd7f53895dd723c741b94c5453a38b0fbfc..6feb74e18f605aa2643de42e41cd5a83553371e2 100644 --- a/src/intersect.cpp +++ b/src/intersect.cpp @@ -35,12 +35,13 @@ /** \author Jia Pan */ -#include <hpp/fcl/internal/intersect.h> +#include "coal/internal/intersect.h" +#include "coal/internal/tools.h" + #include <iostream> #include <limits> #include <vector> #include <cmath> -#include <hpp/fcl/internal/tools.h> namespace coal { diff --git a/src/math/transform.cpp b/src/math/transform.cpp index 480039ab042ef670a5c2cce9db61db5670b28715..5843b03ad3a16e60d60792fa556d001390ae9b06 100644 --- a/src/math/transform.cpp +++ b/src/math/transform.cpp @@ -35,7 +35,7 @@ /** \author Jia Pan */ -#include <hpp/fcl/math/transform.h> +#include "coal/math/transform.h" namespace coal { diff --git a/src/mesh_loader/assimp.cpp b/src/mesh_loader/assimp.cpp index 31bb61fa7fac23cf120466315bed17c7803a15a3..4efd6b7c8d45af24177648a6e6134f55d50e3354 100644 --- a/src/mesh_loader/assimp.cpp +++ b/src/mesh_loader/assimp.cpp @@ -35,7 +35,7 @@ #if !(__cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) #define nullptr NULL #endif -#include <hpp/fcl/mesh_loader/assimp.h> +#include "coal/mesh_loader/assimp.h" // Assimp >= 5.0 is forcing the use of C++11 keywords. A fix has been submitted // https://github.com/assimp/assimp/pull/2758. The next lines fixes the bug for diff --git a/src/mesh_loader/loader.cpp b/src/mesh_loader/loader.cpp index 992b7bd162b1f402724ab20dd3e5d58557264fb6..8304b4974e2475845812ec9892f02d190881fa9c 100644 --- a/src/mesh_loader/loader.cpp +++ b/src/mesh_loader/loader.cpp @@ -34,16 +34,16 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include <hpp/fcl/mesh_loader/loader.h> -#include <hpp/fcl/mesh_loader/assimp.h> +#include "coal/mesh_loader/loader.h" +#include "coal/mesh_loader/assimp.h" #include <boost/filesystem.hpp> #ifdef HPP_FCL_HAS_OCTOMAP -#include <hpp/fcl/octree.h> +#include "coal/octree.h" #endif -#include <hpp/fcl/BV/BV.h> +#include "coal/BV/BV.h" namespace coal { bool CachedMeshLoader::Key::operator<(const CachedMeshLoader::Key& b) const { diff --git a/src/narrowphase/details.h b/src/narrowphase/details.h index 14cba9f77f5c84260d41ad02ed089680805d67b9..df6b5e2d6ffa5fa0072c156dedacb7d5d5c277a3 100644 --- a/src/narrowphase/details.h +++ b/src/narrowphase/details.h @@ -39,8 +39,8 @@ #ifndef COAL_SRC_NARROWPHASE_DETAILS_H #define COAL_SRC_NARROWPHASE_DETAILS_H -#include <hpp/fcl/internal/traversal_node_setup.h> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/internal/traversal_node_setup.h" +#include "coal/narrowphase/narrowphase.h" namespace coal { namespace details { diff --git a/src/narrowphase/gjk.cpp b/src/narrowphase/gjk.cpp index ab0541488b7a47d2ac603c1cb32633a84c511b89..450cc2f4b0189e3c104b28cb1757ff72c572c0c7 100644 --- a/src/narrowphase/gjk.cpp +++ b/src/narrowphase/gjk.cpp @@ -36,12 +36,12 @@ /** \author Jia Pan */ -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/narrowphase/gjk.h> -#include <hpp/fcl/internal/intersect.h> -#include <hpp/fcl/internal/tools.h> -#include <hpp/fcl/shape/geometric_shapes_traits.h> -#include <hpp/fcl/narrowphase/narrowphase_defaults.h> +#include "coal/shape/geometric_shapes.h" +#include "coal/narrowphase/gjk.h" +#include "coal/internal/intersect.h" +#include "coal/internal/tools.h" +#include "coal/shape/geometric_shapes_traits.h" +#include "coal/narrowphase/narrowphase_defaults.h" namespace coal { diff --git a/src/narrowphase/minkowski_difference.cpp b/src/narrowphase/minkowski_difference.cpp index 5edd3dda1ca69e09480cd3a917ede84f7bb4299d..636313c0c209137a9576debf196002996fb71eb6 100644 --- a/src/narrowphase/minkowski_difference.cpp +++ b/src/narrowphase/minkowski_difference.cpp @@ -36,8 +36,8 @@ /** \authors Jia Pan, Florent Lamiraux, Josef Mirabel, Louis Montaut */ -#include "hpp/fcl/narrowphase/minkowski_difference.h" -#include "hpp/fcl/shape/geometric_shapes_traits.h" +#include "coal/narrowphase/minkowski_difference.h" +#include "coal/shape/geometric_shapes_traits.h" namespace coal { namespace details { @@ -283,9 +283,9 @@ void MinkowskiDiff::set(const ShapeBase* shape0, const ShapeBase* shape1, shape0, shape1, identity, swept_sphere_radius, data); } // clang-format off -template void HPP_FCL_DLLAPI MinkowskiDiff::set<SupportOptions::NoSweptSphere>(const ShapeBase*, const ShapeBase*); +template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::NoSweptSphere>(const ShapeBase*, const ShapeBase*); -template void HPP_FCL_DLLAPI MinkowskiDiff::set<SupportOptions::WithSweptSphere>(const ShapeBase*, const ShapeBase*); +template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::WithSweptSphere>(const ShapeBase*, const ShapeBase*); // clang-format on // ============================================================================ @@ -303,20 +303,20 @@ void MinkowskiDiff::set(const ShapeBase* shape0, const ShapeBase* shape1) { shape0, shape1, true, swept_sphere_radius, data); } // clang-format off -template void HPP_FCL_DLLAPI MinkowskiDiff::set<SupportOptions::NoSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3f&, const Transform3f&); +template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::NoSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3f&, const Transform3f&); -template void HPP_FCL_DLLAPI MinkowskiDiff::set<SupportOptions::WithSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3f&, const Transform3f&); +template void COAL_DLLAPI MinkowskiDiff::set<SupportOptions::WithSweptSphere>(const ShapeBase*, const ShapeBase*, const Transform3f&, const Transform3f&); // clang-format on // ============================================================================ // clang-format off -template Vec3f HPP_FCL_DLLAPI MinkowskiDiff::support0<SupportOptions::NoSweptSphere>(const Vec3f&, int&) const; +template Vec3f COAL_DLLAPI MinkowskiDiff::support0<SupportOptions::NoSweptSphere>(const Vec3f&, int&) const; -template Vec3f HPP_FCL_DLLAPI MinkowskiDiff::support0<SupportOptions::WithSweptSphere>(const Vec3f&, int&) const; +template Vec3f COAL_DLLAPI MinkowskiDiff::support0<SupportOptions::WithSweptSphere>(const Vec3f&, int&) const; -template Vec3f HPP_FCL_DLLAPI MinkowskiDiff::support1<SupportOptions::NoSweptSphere>(const Vec3f&, int&) const; +template Vec3f COAL_DLLAPI MinkowskiDiff::support1<SupportOptions::NoSweptSphere>(const Vec3f&, int&) const; -template Vec3f HPP_FCL_DLLAPI MinkowskiDiff::support1<SupportOptions::WithSweptSphere>(const Vec3f&, int&) const; +template Vec3f COAL_DLLAPI MinkowskiDiff::support1<SupportOptions::WithSweptSphere>(const Vec3f&, int&) const; // clang-format on } // namespace details diff --git a/src/narrowphase/support_functions.cpp b/src/narrowphase/support_functions.cpp index 3f817ef471ba1bf7d9ca706311cbeacc1ce5b29f..947ffb60e9eef001c48af0e1cd13f049c1a0c314 100644 --- a/src/narrowphase/support_functions.cpp +++ b/src/narrowphase/support_functions.cpp @@ -36,7 +36,7 @@ /** \authors Jia Pan, Florent Lamiraux, Josef Mirabel, Louis Montaut */ -#include "hpp/fcl/narrowphase/support_functions.h" +#include "coal/narrowphase/support_functions.h" #include <algorithm> @@ -89,20 +89,19 @@ Vec3f getSupport(const ShapeBase* shape, const Vec3f& dir, int& hint) { // Explicit instantiation // clang-format off -template HPP_FCL_DLLAPI Vec3f getSupport<SupportOptions::NoSweptSphere>(const ShapeBase*, const Vec3f&, int&); +template COAL_DLLAPI Vec3f getSupport<SupportOptions::NoSweptSphere>(const ShapeBase*, const Vec3f&, int&); -template HPP_FCL_DLLAPI Vec3f getSupport<SupportOptions::WithSweptSphere>(const ShapeBase*, const Vec3f&, int&); +template COAL_DLLAPI Vec3f getSupport<SupportOptions::WithSweptSphere>(const ShapeBase*, const Vec3f&, int&); // clang-format on // ============================================================================ -#define getShapeSupportTplInstantiation(ShapeType) \ - template HPP_FCL_DLLAPI void getShapeSupport<SupportOptions::NoSweptSphere>( \ - const ShapeType* shape_, const Vec3f& dir, Vec3f& support, int& hint, \ - ShapeSupportData& support_data); \ - \ - template HPP_FCL_DLLAPI void \ - getShapeSupport<SupportOptions::WithSweptSphere>( \ - const ShapeType* shape_, const Vec3f& dir, Vec3f& support, int& hint, \ +#define getShapeSupportTplInstantiation(ShapeType) \ + template COAL_DLLAPI void getShapeSupport<SupportOptions::NoSweptSphere>( \ + const ShapeType* shape_, const Vec3f& dir, Vec3f& support, int& hint, \ + ShapeSupportData& support_data); \ + \ + template COAL_DLLAPI void getShapeSupport<SupportOptions::WithSweptSphere>( \ + const ShapeType* shape_, const Vec3f& dir, Vec3f& support, int& hint, \ ShapeSupportData& support_data); // ============================================================================ @@ -507,21 +506,20 @@ getShapeSupportTplInstantiation(LargeConvex) // Explicit instantiation // clang-format off -template HPP_FCL_DLLAPI void getSupportSet<SupportOptions::NoSweptSphere>(const ShapeBase*, SupportSet&, int&, size_t, FCL_REAL); +template COAL_DLLAPI void getSupportSet<SupportOptions::NoSweptSphere>(const ShapeBase*, SupportSet&, int&, size_t, FCL_REAL); -template HPP_FCL_DLLAPI void getSupportSet<SupportOptions::WithSweptSphere>(const ShapeBase*, SupportSet&, int&, size_t, FCL_REAL); +template COAL_DLLAPI void getSupportSet<SupportOptions::WithSweptSphere>(const ShapeBase*, SupportSet&, int&, size_t, FCL_REAL); // clang-format on // ============================================================================ -#define getShapeSupportSetTplInstantiation(ShapeType) \ - template HPP_FCL_DLLAPI void \ - getShapeSupportSet<SupportOptions::NoSweptSphere>( \ - const ShapeType* shape_, SupportSet& support_set, int& hint, \ - ShapeSupportData& data, size_t num_sampled_supports, FCL_REAL tol); \ - \ - template HPP_FCL_DLLAPI void \ - getShapeSupportSet<SupportOptions::WithSweptSphere>( \ - const ShapeType* shape_, SupportSet& support_set, int& hint, \ +#define getShapeSupportSetTplInstantiation(ShapeType) \ + template COAL_DLLAPI void getShapeSupportSet<SupportOptions::NoSweptSphere>( \ + const ShapeType* shape_, SupportSet& support_set, int& hint, \ + ShapeSupportData& data, size_t num_sampled_supports, FCL_REAL tol); \ + \ + template COAL_DLLAPI void \ + getShapeSupportSet<SupportOptions::WithSweptSphere>( \ + const ShapeType* shape_, SupportSet& support_set, int& hint, \ ShapeSupportData& data, size_t num_sampled_supports, FCL_REAL tol); // ============================================================================ @@ -984,13 +982,13 @@ void getShapeSupportSet(const LargeConvex* convex, SupportSet& support_set, support_data, num_sampled_supports, tol); } //clang-format off -getShapeSupportSetTplInstantiation(LargeConvex) - // clang-format on +getShapeSupportSetTplInstantiation(LargeConvex); +// clang-format on - // ============================================================================ - HPP_FCL_DLLAPI - void computeSupportSetConvexHull(SupportSet::Polygon& cloud, - SupportSet::Polygon& cvx_hull) { +// ============================================================================ +COAL_DLLAPI +void computeSupportSetConvexHull(SupportSet::Polygon& cloud, + SupportSet::Polygon& cvx_hull) { cvx_hull.clear(); if (cloud.size() <= 2) { diff --git a/src/octree.cpp b/src/octree.cpp index 7fc5aacecb0e1cba9d4134f6a563bfa3dfe97a74..2abfe37077afaffa8f112fd7bf24be04e28c2fed 100644 --- a/src/octree.cpp +++ b/src/octree.cpp @@ -32,7 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include <hpp/fcl/octree.h> +#include "coal/octree.h" + #include <array> namespace coal { diff --git a/src/serialization/serialization.cpp b/src/serialization/serialization.cpp index c4fe900fe6ec5dc6c2f2d7c2468269b4780c5050..e97a00ba86574718750aa4dfcfaaaa2302bc7d7a 100644 --- a/src/serialization/serialization.cpp +++ b/src/serialization/serialization.cpp @@ -34,18 +34,18 @@ /** \author Justin Carpentier */ -#include "hpp/fcl/serialization/fwd.h" +#include "coal/serialization/fwd.h" using namespace coal; -#include "hpp/fcl/serialization/transform.h" -#include "hpp/fcl/serialization/collision_data.h" -#include "hpp/fcl/serialization/geometric_shapes.h" -#include "hpp/fcl/serialization/convex.h" -#include "hpp/fcl/serialization/hfield.h" -#include "hpp/fcl/serialization/BVH_model.h" +#include "coal/serialization/transform.h" +#include "coal/serialization/collision_data.h" +#include "coal/serialization/geometric_shapes.h" +#include "coal/serialization/convex.h" +#include "coal/serialization/hfield.h" +#include "coal/serialization/BVH_model.h" #ifdef HPP_FCL_HAS_OCTOMAP -#include "hpp/fcl/serialization/octree.h" +#include "coal/serialization/octree.h" #endif HPP_FCL_SERIALIZATION_DEFINE_EXPORT(CollisionRequest) diff --git a/src/shape/convex.cpp b/src/shape/convex.cpp index 69be540569cb4d2363d596341e2c8cb5b487b6d1..dcfb586f61a1fc6e03fa44de6e66c4b6e5587e02 100644 --- a/src/shape/convex.cpp +++ b/src/shape/convex.cpp @@ -1,4 +1,4 @@ -#include <hpp/fcl/shape/convex.h> +#include "coal/shape/convex.h" #ifdef HPP_FCL_HAS_QHULL #include <libqhullcpp/QhullError.h> diff --git a/src/shape/geometric_shapes.cpp b/src/shape/geometric_shapes.cpp index 87b5d739a4a92f04339dad23a32fcb993f1d524b..517ad3f3595cf2bf917cf44f0768500a1d4d38b8 100644 --- a/src/shape/geometric_shapes.cpp +++ b/src/shape/geometric_shapes.cpp @@ -35,8 +35,8 @@ /** \author Jia Pan */ -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> +#include "coal/shape/geometric_shapes.h" +#include "coal/shape/geometric_shapes_utility.h" namespace coal { diff --git a/src/shape/geometric_shapes_utility.cpp b/src/shape/geometric_shapes_utility.cpp index b01d11472313b542a5a854a86bedf7cc2aba1d0a..f9bbd85f692927a17b4357d3e5559393ccd7f060 100644 --- a/src/shape/geometric_shapes_utility.cpp +++ b/src/shape/geometric_shapes_utility.cpp @@ -35,9 +35,9 @@ /** \author Jia Pan */ -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/internal/BV_fitter.h> -#include <hpp/fcl/internal/tools.h> +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/BV_fitter.h" +#include "coal/internal/tools.h" namespace coal { diff --git a/src/traits_traversal.h b/src/traits_traversal.h index c3ae4883aff8fbf31aa4aa9e2e74dec1af5e8863..45defd06d866194f24655f227ea457908232c098 100644 --- a/src/traits_traversal.h +++ b/src/traits_traversal.h @@ -7,53 +7,53 @@ /** \author Lucile Remigy, Joseph Mirabel */ -#include <hpp/fcl/collision_func_matrix.h> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/collision_func_matrix.h" +#include "coal/narrowphase/narrowphase.h" #include <../src/collision_node.h> -#include <hpp/fcl/internal/traversal_node_setup.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/traversal_node_setup.h" +#include "coal/internal/shape_shape_func.h" namespace coal { // TraversalTraitsCollision for collision_func_matrix.cpp template <typename TypeA, typename TypeB> -struct HPP_FCL_LOCAL TraversalTraitsCollision {}; +struct COAL_LOCAL TraversalTraitsCollision {}; #ifdef HPP_FCL_HAS_OCTOMAP template <typename T_SH> -struct HPP_FCL_LOCAL TraversalTraitsCollision<T_SH, OcTree> { +struct COAL_LOCAL TraversalTraitsCollision<T_SH, OcTree> { typedef ShapeOcTreeCollisionTraversalNode<T_SH> CollisionTraversal_t; }; template <typename T_SH> -struct HPP_FCL_LOCAL TraversalTraitsCollision<OcTree, T_SH> { +struct COAL_LOCAL TraversalTraitsCollision<OcTree, T_SH> { typedef OcTreeShapeCollisionTraversalNode<T_SH> CollisionTraversal_t; }; template <> -struct HPP_FCL_LOCAL TraversalTraitsCollision<OcTree, OcTree> { +struct COAL_LOCAL TraversalTraitsCollision<OcTree, OcTree> { typedef OcTreeCollisionTraversalNode CollisionTraversal_t; }; template <typename T_BVH> -struct HPP_FCL_LOCAL TraversalTraitsCollision<OcTree, BVHModel<T_BVH> > { +struct COAL_LOCAL TraversalTraitsCollision<OcTree, BVHModel<T_BVH> > { typedef OcTreeMeshCollisionTraversalNode<T_BVH> CollisionTraversal_t; }; template <typename T_BVH> -struct HPP_FCL_LOCAL TraversalTraitsCollision<BVHModel<T_BVH>, OcTree> { +struct COAL_LOCAL TraversalTraitsCollision<BVHModel<T_BVH>, OcTree> { typedef MeshOcTreeCollisionTraversalNode<T_BVH> CollisionTraversal_t; }; template <typename T_HF> -struct HPP_FCL_LOCAL TraversalTraitsCollision<OcTree, HeightField<T_HF> > { +struct COAL_LOCAL TraversalTraitsCollision<OcTree, HeightField<T_HF> > { typedef OcTreeHeightFieldCollisionTraversalNode<T_HF> CollisionTraversal_t; }; template <typename T_HF> -struct HPP_FCL_LOCAL TraversalTraitsCollision<HeightField<T_HF>, OcTree> { +struct COAL_LOCAL TraversalTraitsCollision<HeightField<T_HF>, OcTree> { typedef HeightFieldOcTreeCollisionTraversalNode<T_HF> CollisionTraversal_t; }; @@ -62,32 +62,32 @@ struct HPP_FCL_LOCAL TraversalTraitsCollision<HeightField<T_HF>, OcTree> { // TraversalTraitsDistance for distance_func_matrix.cpp template <typename TypeA, typename TypeB> -struct HPP_FCL_LOCAL TraversalTraitsDistance {}; +struct COAL_LOCAL TraversalTraitsDistance {}; #ifdef HPP_FCL_HAS_OCTOMAP template <typename T_SH> -struct HPP_FCL_LOCAL TraversalTraitsDistance<T_SH, OcTree> { +struct COAL_LOCAL TraversalTraitsDistance<T_SH, OcTree> { typedef ShapeOcTreeDistanceTraversalNode<T_SH> CollisionTraversal_t; }; template <typename T_SH> -struct HPP_FCL_LOCAL TraversalTraitsDistance<OcTree, T_SH> { +struct COAL_LOCAL TraversalTraitsDistance<OcTree, T_SH> { typedef OcTreeShapeDistanceTraversalNode<T_SH> CollisionTraversal_t; }; template <> -struct HPP_FCL_LOCAL TraversalTraitsDistance<OcTree, OcTree> { +struct COAL_LOCAL TraversalTraitsDistance<OcTree, OcTree> { typedef OcTreeDistanceTraversalNode CollisionTraversal_t; }; template <typename T_BVH> -struct HPP_FCL_LOCAL TraversalTraitsDistance<OcTree, BVHModel<T_BVH> > { +struct COAL_LOCAL TraversalTraitsDistance<OcTree, BVHModel<T_BVH> > { typedef OcTreeMeshDistanceTraversalNode<T_BVH> CollisionTraversal_t; }; template <typename T_BVH> -struct HPP_FCL_LOCAL TraversalTraitsDistance<BVHModel<T_BVH>, OcTree> { +struct COAL_LOCAL TraversalTraitsDistance<BVHModel<T_BVH>, OcTree> { typedef MeshOcTreeDistanceTraversalNode<T_BVH> CollisionTraversal_t; }; diff --git a/src/traversal/traversal_recurse.cpp b/src/traversal/traversal_recurse.cpp index 96b755545eafc4fc772ad2b0e6ade38764df8f2a..01ed51e1c1b8e27eae3f517a9ccceced3148e4f4 100644 --- a/src/traversal/traversal_recurse.cpp +++ b/src/traversal/traversal_recurse.cpp @@ -35,7 +35,7 @@ /** \author Jia Pan */ -#include <hpp/fcl/internal/traversal_recurse.h> +#include "coal/internal/traversal_recurse.h" #include <vector> @@ -202,7 +202,7 @@ void distanceRecurse(DistanceTraversalNodeBase* node, unsigned int b1, } /** @brief Bounding volume test structure */ -struct HPP_FCL_LOCAL BVT { +struct COAL_LOCAL BVT { /** @brief distance between bvs */ FCL_REAL d; @@ -211,13 +211,13 @@ struct HPP_FCL_LOCAL BVT { }; /** @brief Comparer between two BVT */ -struct HPP_FCL_LOCAL BVT_Comparer { +struct COAL_LOCAL BVT_Comparer { bool operator()(const BVT& lhs, const BVT& rhs) const { return lhs.d > rhs.d; } }; -struct HPP_FCL_LOCAL BVTQ { +struct COAL_LOCAL BVTQ { BVTQ() : qsize(2) {} bool empty() const { return pq.empty(); } diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 2891ad7893d67ef12098e5dc0921b49354b8c563..adfdeb82b91eda5ad31a41fdf441cabfebc45d7a 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -7,7 +7,7 @@ macro(add_fcl_test test_name source) ADD_UNIT_TEST(${test_name} ${source}) target_link_libraries(${test_name} PUBLIC - hpp-fcl + ${LIBRARY_NAME} Boost::filesystem utility ) diff --git a/test/accelerated_gjk.cpp b/test/accelerated_gjk.cpp index 98160e78af4549d5bd0ff489bcde18075d5c0c49..be71edefc6f35324b306ad9f85c974c3fe265903 100644 --- a/test/accelerated_gjk.cpp +++ b/test/accelerated_gjk.cpp @@ -38,9 +38,9 @@ #include <boost/test/included/unit_test.hpp> #include <Eigen/Geometry> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/internal/tools.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/tools.h" #include "utility.h" diff --git a/test/benchmark.cpp b/test/benchmark.cpp index 49afac16a0eaedb410119b6c4d760d08c63dc4b8..372c8f06f7242434dfb62d39a8d2833cff6b8194 100644 --- a/test/benchmark.cpp +++ b/test/benchmark.cpp @@ -16,10 +16,10 @@ #include <boost/filesystem.hpp> -#include <hpp/fcl/internal/traversal_node_setup.h> -#include <hpp/fcl/internal/traversal_node_bvhs.h> +#include "coal/internal/traversal_node_setup.h" +#include "coal/internal/traversal_node_bvhs.h" #include "../src/collision_node.h" -#include <hpp/fcl/internal/BV_splitter.h> +#include "coal/internal/BV_splitter.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/box_box_collision.cpp b/test/box_box_collision.cpp index cfa19eff6fb45dd1e7ef0c2f724f6214f6e336a2..af49add91859f697e3ea1620e1f56dc35e339617 100644 --- a/test/box_box_collision.cpp +++ b/test/box_box_collision.cpp @@ -2,9 +2,9 @@ #include <boost/test/included/unit_test.hpp> #include <Eigen/Geometry> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/internal/tools.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/tools.h" #include "utility.h" diff --git a/test/box_box_distance.cpp b/test/box_box_distance.cpp index 7d21bd4874d00295f7d6386bd5d27f8cf26de307..f1a8c11441020051b2f0a317a072bb0ad1808db3 100644 --- a/test/box_box_distance.cpp +++ b/test/box_box_distance.cpp @@ -44,11 +44,11 @@ #include <cmath> #include <iostream> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/distance.h" +#include "coal/math/transform.h" +#include "coal/collision.h" +#include "coal/collision_object.h" +#include "coal/shape/geometric_shapes.h" #include "utility.h" diff --git a/test/broadphase.cpp b/test/broadphase.cpp index d2efdc82a4de3f77b3c96477a8fb7124e642bfa5..b0ed10f06824cda4ebb8ad7fdb67ff47a9c36c87 100644 --- a/test/broadphase.cpp +++ b/test/broadphase.cpp @@ -38,10 +38,10 @@ #define BOOST_TEST_MODULE FCL_BROADPHASE #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/config.hh> -#include <hpp/fcl/broadphase/broadphase.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> -#include <hpp/fcl/math/transform.h> +#include "coal/config.hh" +#include "coal/broadphase/broadphase.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" +#include "coal/math/transform.h" #include "utility.h" #if USE_GOOGLEHASH diff --git a/test/broadphase_collision_1.cpp b/test/broadphase_collision_1.cpp index 9fdc98f60f416862e1918a371454cb9e0375de61..3ea150af4db4fb2e5321eac046c6f043e3f422d6 100644 --- a/test/broadphase_collision_1.cpp +++ b/test/broadphase_collision_1.cpp @@ -38,16 +38,16 @@ #define BOOST_TEST_MODULE BROADPHASE_COLLISION_1 #include <boost/test/included/unit_test.hpp> -#include "hpp/fcl/broadphase/broadphase_bruteforce.h" -#include "hpp/fcl/broadphase/broadphase_spatialhash.h" -#include "hpp/fcl/broadphase/broadphase_SaP.h" -#include "hpp/fcl/broadphase/broadphase_SSaP.h" -#include "hpp/fcl/broadphase/broadphase_interval_tree.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h" -#include "hpp/fcl/broadphase/default_broadphase_callbacks.h" -#include "hpp/fcl/broadphase/detail/sparse_hash_table.h" -#include "hpp/fcl/broadphase/detail/spatial_hash.h" +#include "coal/broadphase/broadphase_bruteforce.h" +#include "coal/broadphase/broadphase_spatialhash.h" +#include "coal/broadphase/broadphase_SaP.h" +#include "coal/broadphase/broadphase_SSaP.h" +#include "coal/broadphase/broadphase_interval_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" +#include "coal/broadphase/default_broadphase_callbacks.h" +#include "coal/broadphase/detail/sparse_hash_table.h" +#include "coal/broadphase/detail/spatial_hash.h" #include "utility.h" #include <boost/math/constants/constants.hpp> diff --git a/test/broadphase_collision_2.cpp b/test/broadphase_collision_2.cpp index 8592061948772b37a5c9e1dacb1ef77b70077681..72f477422ff4daca4a834d29da72a9f4672e0eb8 100644 --- a/test/broadphase_collision_2.cpp +++ b/test/broadphase_collision_2.cpp @@ -38,16 +38,16 @@ #define BOOST_TEST_MODULE BROADPHASE_COLLISION_2 #include <boost/test/included/unit_test.hpp> -#include "hpp/fcl/broadphase/broadphase_bruteforce.h" -#include "hpp/fcl/broadphase/broadphase_spatialhash.h" -#include "hpp/fcl/broadphase/broadphase_SaP.h" -#include "hpp/fcl/broadphase/broadphase_SSaP.h" -#include "hpp/fcl/broadphase/broadphase_interval_tree.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h" -#include "hpp/fcl/broadphase/default_broadphase_callbacks.h" -#include "hpp/fcl/broadphase/detail/sparse_hash_table.h" -#include "hpp/fcl/broadphase/detail/spatial_hash.h" +#include "coal/broadphase/broadphase_bruteforce.h" +#include "coal/broadphase/broadphase_spatialhash.h" +#include "coal/broadphase/broadphase_SaP.h" +#include "coal/broadphase/broadphase_SSaP.h" +#include "coal/broadphase/broadphase_interval_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" +#include "coal/broadphase/default_broadphase_callbacks.h" +#include "coal/broadphase/detail/sparse_hash_table.h" +#include "coal/broadphase/detail/spatial_hash.h" #include "utility.h" #if USE_GOOGLEHASH diff --git a/test/broadphase_dynamic_AABB_tree.cpp b/test/broadphase_dynamic_AABB_tree.cpp index df225687fde3938b2acbbb39ce16bed23698e8aa..4db3537378cc6c629688c2c5e7c41534afc5cd62 100644 --- a/test/broadphase_dynamic_AABB_tree.cpp +++ b/test/broadphase_dynamic_AABB_tree.cpp @@ -36,15 +36,15 @@ /** Tests the dynamic axis-aligned bounding box tree.*/ -#include <iostream> -#include <memory> - #define BOOST_TEST_MODULE BROADPHASE_DYNAMIC_AABB_TREE #include <boost/test/included/unit_test.hpp> -// #include "hpp/fcl/data_types.h" -#include "hpp/fcl/shape/geometric_shapes.h" -#include "hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h" +// #include "coal/data_types.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/broadphase/broadphase_dynamic_AABB_tree.h" + +#include <iostream> +#include <memory> using namespace coal; diff --git a/test/bvh_models.cpp b/test/bvh_models.cpp index 92a715e413317d9cbd1c12f860769b3c709cd99b..b966e98c3c30bb460164ed0954aa7583dadbcc88 100644 --- a/test/bvh_models.cpp +++ b/test/bvh_models.cpp @@ -41,14 +41,14 @@ #include "fcl_resources/config.h" -#include <hpp/fcl/collision.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/BVH/BVH_utility.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> -#include <hpp/fcl/mesh_loader/assimp.h> -#include <hpp/fcl/mesh_loader/loader.h> +#include "coal/collision.h" +#include "coal/BVH/BVH_model.h" +#include "coal/BVH/BVH_utility.h" +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" +#include "coal/mesh_loader/assimp.h" +#include "coal/mesh_loader/loader.h" #include "utility.h" #include <iostream> diff --git a/test/capsule_box_1.cpp b/test/capsule_box_1.cpp index f34a20faa3b2ea236f091d53a3e1781548d77379..c3a0947359d24413943b308968ddf57a57cead63 100644 --- a/test/capsule_box_1.cpp +++ b/test/capsule_box_1.cpp @@ -40,11 +40,11 @@ #define CHECK_CLOSE_TO_0(x, eps) BOOST_CHECK_CLOSE((x + 1.0), (1.0), (eps)) #include <cmath> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/distance.h" +#include "coal/math/transform.h" +#include "coal/collision.h" +#include "coal/collision_object.h" +#include "coal/shape/geometric_shapes.h" #include "utility.h" diff --git a/test/capsule_box_2.cpp b/test/capsule_box_2.cpp index 6af75b959113f7f06b358b695e7a58e3638e540f..ed94fc22a3d438002e70e4567802d4d12d12c420 100644 --- a/test/capsule_box_2.cpp +++ b/test/capsule_box_2.cpp @@ -42,11 +42,11 @@ #include "utility.h" #include <cmath> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/distance.h" +#include "coal/math/transform.h" +#include "coal/collision.h" +#include "coal/collision_object.h" +#include "coal/shape/geometric_shapes.h" BOOST_AUTO_TEST_CASE(distance_capsule_box) { typedef coal::shared_ptr<coal::CollisionGeometry> CollisionGeometryPtr_t; diff --git a/test/capsule_capsule.cpp b/test/capsule_capsule.cpp index 593950fd940f92004a0832ab818e00d372815bbd..d7f8af59f80f81ef8f9ffce37ab67e82d1718e71 100644 --- a/test/capsule_capsule.cpp +++ b/test/capsule_capsule.cpp @@ -42,12 +42,12 @@ #include <cmath> #include <iostream> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/shape/geometric_shapes.h> +#include "coal/distance.h" +#include "coal/collision.h" +#include "coal/math/transform.h" +#include "coal/collision.h" +#include "coal/collision_object.h" +#include "coal/shape/geometric_shapes.h" #include "utility.h" diff --git a/test/collision.cpp b/test/collision.cpp index 115e50bbc20fc7382bcb7239b58a47cf34b05dae..6484d8765fef74ebed70bc2d44fc5e73eae84275 100644 --- a/test/collision.cpp +++ b/test/collision.cpp @@ -43,26 +43,26 @@ #include <fstream> #include <boost/assign/list_of.hpp> -#include <hpp/fcl/fwd.hh> +#include "coal/fwd.hh" -HPP_FCL_COMPILER_DIAGNOSTIC_PUSH -HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS +COAL_COMPILER_DIAGNOSTIC_PUSH +COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS -#include <hpp/fcl/collision.h> +#include "coal/collision.h" -HPP_FCL_COMPILER_DIAGNOSTIC_POP +COAL_COMPILER_DIAGNOSTIC_POP -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/mesh_loader/assimp.h> +#include "coal/BV/BV.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/mesh_loader/assimp.h" -#include <hpp/fcl/internal/traversal_node_bvhs.h> -#include <hpp/fcl/internal/traversal_node_setup.h> +#include "coal/internal/traversal_node_bvhs.h" +#include "coal/internal/traversal_node_setup.h" #include "../src/collision_node.h" -#include <hpp/fcl/internal/BV_splitter.h> +#include "coal/internal/BV_splitter.h" -#include <hpp/fcl/timings.h> +#include "coal/timings.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/collision_node_asserts.cpp b/test/collision_node_asserts.cpp index fb8b57f6255add6466c3c742d028ea47b9a4f9fe..e81d75b51e2685a0d3844e296c61e0f45d13142d 100644 --- a/test/collision_node_asserts.cpp +++ b/test/collision_node_asserts.cpp @@ -2,8 +2,8 @@ #include <boost/test/included/unit_test.hpp> #include <boost/math/constants/constants.hpp> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/collision.h> +#include "coal/BVH/BVH_model.h" +#include "coal/collision.h" using namespace coal; diff --git a/test/contact_patch.cpp b/test/contact_patch.cpp index 457f8be5a0f64b9a804766e93178e94f40ea2eff..fdc1a258dc0bcd32d6b028c5b288766d591a7146 100644 --- a/test/contact_patch.cpp +++ b/test/contact_patch.cpp @@ -37,7 +37,7 @@ #define BOOST_TEST_MODULE FCL_CONTACT_PATCH #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/contact_patch.h> +#include "coal/contact_patch.h" #include "utility.h" diff --git a/test/convex.cpp b/test/convex.cpp index ad6522029d9e55b9ada97af39a11b12854336df1..52043cf95fccd9015a7a8568cd269c59c5f10694 100644 --- a/test/convex.cpp +++ b/test/convex.cpp @@ -37,9 +37,9 @@ #define BOOST_TEST_MODULE FCL_GEOMETRIC_SHAPES #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/shape/convex.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/distance.h> +#include "coal/shape/convex.h" +#include "coal/collision.h" +#include "coal/distance.h" #include "utility.h" diff --git a/test/distance.cpp b/test/distance.cpp index 567e2109bd21acb1274b375996b712c6a4ec4e80..89db86065884cd71f416bfaa71b23a234aa10556 100644 --- a/test/distance.cpp +++ b/test/distance.cpp @@ -41,10 +41,10 @@ #include <boost/test/included/unit_test.hpp> #include <boost/filesystem.hpp> -#include <hpp/fcl/internal/traversal_node_bvhs.h> -#include <hpp/fcl/internal/traversal_node_setup.h> +#include "coal/internal/traversal_node_bvhs.h" +#include "coal/internal/traversal_node_setup.h" #include "../src/collision_node.h" -#include <hpp/fcl/internal/BV_splitter.h> +#include "coal/internal/BV_splitter.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/distance_lower_bound.cpp b/test/distance_lower_bound.cpp index 7442280e8f9d6ffa188ca96c114319ab76794624..598f1a33ee0cb0eb13bee7ff7ef397cd8881c4c6 100644 --- a/test/distance_lower_bound.cpp +++ b/test/distance_lower_bound.cpp @@ -36,13 +36,13 @@ #include <boost/test/included/unit_test.hpp> #include <boost/filesystem.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/data_types.h> -#include <hpp/fcl/BV/OBBRSS.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/distance.h> +#include "coal/fwd.hh" +#include "coal/data_types.h" +#include "coal/BV/OBBRSS.h" +#include "coal/BVH/BVH_model.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/collision.h" +#include "coal/distance.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/frontlist.cpp b/test/frontlist.cpp index f90634d5ec676f09c2b0fdc068b21159afaada6d..8c63fb1e2c50f2d7d726f259b639bee32c8cb794 100644 --- a/test/frontlist.cpp +++ b/test/frontlist.cpp @@ -38,10 +38,10 @@ #define BOOST_TEST_MODULE FCL_FRONT_LIST #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/internal/traversal_node_bvhs.h> -#include <hpp/fcl/internal/traversal_node_setup.h> +#include "coal/internal/traversal_node_bvhs.h" +#include "coal/internal/traversal_node_setup.h" #include <../src/collision_node.h> -#include <hpp/fcl/internal/BV_splitter.h> +#include "coal/internal/BV_splitter.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/geometric_shapes.cpp b/test/geometric_shapes.cpp index ba5114c3f7363cee978c033ece5d33aa6ac08490..150a43f30a1ec6ca94675bee349d8391fca26101 100644 --- a/test/geometric_shapes.cpp +++ b/test/geometric_shapes.cpp @@ -39,14 +39,14 @@ #define BOOST_TEST_MODULE FCL_GEOMETRIC_SHAPES #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/distance.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/collision.h" +#include "coal/distance.h" #include "utility.h" #include <iostream> -#include <hpp/fcl/internal/tools.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/tools.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" +#include "coal/internal/shape_shape_func.h" using namespace coal; diff --git a/test/gjk.cpp b/test/gjk.cpp index 1631a27772fdff99abcfcc23c354c44c805b88da..75c96efa1929a2339aef9266248334f0daa53d24 100644 --- a/test/gjk.cpp +++ b/test/gjk.cpp @@ -39,10 +39,10 @@ #include <boost/test/included/unit_test.hpp> #include <Eigen/Geometry> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/internal/tools.h> -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/tools.h" +#include "coal/internal/shape_shape_func.h" #include "utility.h" diff --git a/test/gjk_asserts.cpp b/test/gjk_asserts.cpp index afe6ae5de2dbf1eb6339ac826537dee04a20c80c..b65b5d111e9bdacdf49dafe9214cbc21313d2106 100644 --- a/test/gjk_asserts.cpp +++ b/test/gjk_asserts.cpp @@ -2,8 +2,8 @@ #include <boost/test/included/unit_test.hpp> #include <boost/math/constants/constants.hpp> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/collision.h> +#include "coal/BVH/BVH_model.h" +#include "coal/collision.h" using namespace coal; diff --git a/test/gjk_convergence_criterion.cpp b/test/gjk_convergence_criterion.cpp index bc331a7a7e55204d85600b6ad4e3e29448428410..2cbb124fb50d8b5fb915862cbb558626ac4d1b99 100644 --- a/test/gjk_convergence_criterion.cpp +++ b/test/gjk_convergence_criterion.cpp @@ -34,15 +34,15 @@ /** \author Louis Montaut */ -#include "hpp/fcl/data_types.h" -#include <boost/test/tools/old/interface.hpp> #define BOOST_TEST_MODULE FCL_NESTEROV_GJK #include <boost/test/included/unit_test.hpp> +#include <boost/test/tools/old/interface.hpp> #include <Eigen/Geometry> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/internal/tools.h> +#include "coal/data_types.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/internal/tools.h" #include "utility.h" diff --git a/test/hfields.cpp b/test/hfields.cpp index a28ea8052d737632861740b189134f426d693e42..92bd16f49172c36feb20f5467149d6787662bdb2 100644 --- a/test/hfields.cpp +++ b/test/hfields.cpp @@ -40,15 +40,15 @@ #include "fcl_resources/config.h" -#include <hpp/fcl/collision.h> -#include <hpp/fcl/hfield.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/mesh_loader/assimp.h> -#include <hpp/fcl/mesh_loader/loader.h> - -#include <hpp/fcl/collision.h> -#include <hpp/fcl/internal/traversal_node_hfield_shape.h> +#include "coal/collision.h" +#include "coal/hfield.h" +#include "coal/math/transform.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/mesh_loader/assimp.h" +#include "coal/mesh_loader/loader.h" + +#include "coal/collision.h" +#include "coal/internal/traversal_node_hfield_shape.h" #include "utility.h" #include <iostream> diff --git a/test/math.cpp b/test/math.cpp index 8a4edf638e08d59531b2c8388667881a8968b2ac..251f49873ee9320649c14b6e4df3c9c17d067619 100644 --- a/test/math.cpp +++ b/test/math.cpp @@ -39,11 +39,11 @@ #define BOOST_TEST_MODULE FCL_MATH #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/data_types.h> -#include <hpp/fcl/math/transform.h> +#include "coal/data_types.h" +#include "coal/math/transform.h" -#include <hpp/fcl/internal/intersect.h> -#include <hpp/fcl/internal/tools.h> +#include "coal/internal/intersect.h" +#include "coal/internal/tools.h" using namespace coal; diff --git a/test/normal_and_nearest_points.cpp b/test/normal_and_nearest_points.cpp index 41ac105ee3cff8f8e0b7878485f08cc2fe4e7ce6..5b31c7aeaa4f9ca81216237ee243872edf7cc809 100644 --- a/test/normal_and_nearest_points.cpp +++ b/test/normal_and_nearest_points.cpp @@ -37,12 +37,12 @@ #define BOOST_TEST_MODULE NORMAL_AND_NEAREST_POINTS #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/BV/OBBRSS.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> +#include "coal/fwd.hh" +#include "coal/shape/geometric_shapes.h" +#include "coal/collision_data.h" +#include "coal/BV/OBBRSS.h" +#include "coal/BVH/BVH_model.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" #include "utility.h" diff --git a/test/obb.cpp b/test/obb.cpp index bd94b94ed441d39dd01b0b83fd815933abdd128a..8405484b84bf1326874b93f40b4d94542793948e 100644 --- a/test/obb.cpp +++ b/test/obb.cpp @@ -40,10 +40,10 @@ #include <chrono> -#include <hpp/fcl/narrowphase/narrowphase.h> +#include "coal/narrowphase/narrowphase.h" #include "../src/BV/OBB.h" -#include <hpp/fcl/internal/shape_shape_func.h> +#include "coal/internal/shape_shape_func.h" #include "utility.h" using namespace coal; diff --git a/test/octree.cpp b/test/octree.cpp index 5b1100de5abbc076a906f0aaf80fe1770218bc47..4d51ad612665177755ac5c211e8b0f44d0a08bb5 100644 --- a/test/octree.cpp +++ b/test/octree.cpp @@ -40,13 +40,13 @@ #include <boost/test/included/unit_test.hpp> #include <boost/filesystem.hpp> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/hfield.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/internal/BV_splitter.h> +#include "coal/BVH/BVH_model.h" +#include "coal/collision.h" +#include "coal/distance.h" +#include "coal/hfield.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/internal/BV_splitter.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/profiling.cpp b/test/profiling.cpp index 2462cdf0b457824b2171ed606820f9ebb8be58cb..f755661496276c89a293b0b82c51af2108fa8c3b 100644 --- a/test/profiling.cpp +++ b/test/profiling.cpp @@ -16,14 +16,14 @@ #include <boost/filesystem.hpp> -#include <hpp/fcl/fwd.hh> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/collision_utility.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/collision_func_matrix.h> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/mesh_loader/assimp.h> +#include "coal/fwd.hh" +#include "coal/collision.h" +#include "coal/BVH/BVH_model.h" +#include "coal/collision_utility.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/collision_func_matrix.h" +#include "coal/narrowphase/narrowphase.h" +#include "coal/mesh_loader/assimp.h" #include "utility.h" #include "fcl_resources/config.h" diff --git a/test/security_margin.cpp b/test/security_margin.cpp index 9fe867be3e72567ce7f0bf54615f86399fd43e05..b9a82504586c217bc159d27b93bb59effe55a696 100644 --- a/test/security_margin.cpp +++ b/test/security_margin.cpp @@ -37,13 +37,13 @@ #include <cmath> #include <iostream> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> +#include "coal/distance.h" +#include "coal/math/transform.h" +#include "coal/collision.h" +#include "coal/collision_object.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/shape/geometric_shapes_utility.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" #include "utility.h" diff --git a/test/serialization.cpp b/test/serialization.cpp index 4f2bee37dcd28913c4c76d08ada9abf75b3646bd..7c46dcb54353653c3c375a42ad6559b2bc80af5d 100644 --- a/test/serialization.cpp +++ b/test/serialization.cpp @@ -36,30 +36,31 @@ #include <fstream> #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/fwd.hh> - -HPP_FCL_COMPILER_DIAGNOSTIC_PUSH -HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS - -#include <hpp/fcl/collision.h> -#include <hpp/fcl/contact_patch.h> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/BV/OBBRSS.h> -#include <hpp/fcl/BVH/BVH_model.h> - -#include <hpp/fcl/serialization/collision_data.h> -#include <hpp/fcl/serialization/contact_patch.h> -#include <hpp/fcl/serialization/AABB.h> -#include <hpp/fcl/serialization/BVH_model.h> -#include <hpp/fcl/serialization/hfield.h> -#include <hpp/fcl/serialization/transform.h> -#include <hpp/fcl/serialization/geometric_shapes.h> -#include <hpp/fcl/serialization/convex.h> -#include <hpp/fcl/serialization/archive.h> -#include <hpp/fcl/serialization/memory.h> +#include "coal/fwd.hh" + +COAL_COMPILER_DIAGNOSTIC_PUSH +COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS + +#include "coal/collision.h" + +#include "coal/contact_patch.h" +#include "coal/distance.h" +#include "coal/BV/OBBRSS.h" +#include "coal/BVH/BVH_model.h" + +#include "coal/serialization/collision_data.h" +#include "coal/serialization/contact_patch.h" +#include "coal/serialization/AABB.h" +#include "coal/serialization/BVH_model.h" +#include "coal/serialization/hfield.h" +#include "coal/serialization/transform.h" +#include "coal/serialization/geometric_shapes.h" +#include "coal/serialization/convex.h" +#include "coal/serialization/archive.h" +#include "coal/serialization/memory.h" #ifdef HPP_FCL_HAS_OCTOMAP -#include <hpp/fcl/serialization/octree.h> +#include "coal/serialization/octree.h" #endif #include "utility.h" @@ -590,4 +591,4 @@ BOOST_AUTO_TEST_CASE(test_memory_footprint) { computeMemoryFootprint(m1)); } -HPP_FCL_COMPILER_DIAGNOSTIC_POP +COAL_COMPILER_DIAGNOSTIC_POP diff --git a/test/shape_inflation.cpp b/test/shape_inflation.cpp index 323dc90bbe4f13c9db8536768cbe3f80139d547d..9c1abd985a0967bc690316ab8e92f7b34aee130e 100644 --- a/test/shape_inflation.cpp +++ b/test/shape_inflation.cpp @@ -37,12 +37,12 @@ #include <cmath> #include <iostream> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/shape/geometric_shapes.h> -#include <hpp/fcl/shape/geometric_shapes_utility.h> +#include "coal/distance.h" +#include "coal/math/transform.h" +#include "coal/collision.h" +#include "coal/collision_object.h" +#include "coal/shape/geometric_shapes.h" +#include "coal/shape/geometric_shapes_utility.h" #include "utility.h" diff --git a/test/shape_mesh_consistency.cpp b/test/shape_mesh_consistency.cpp index e84f179fc2bf4870ec5b577e456de77bf3946934..1e45c3451ebe1b4396f5bef4f440f29fe6862db5 100644 --- a/test/shape_mesh_consistency.cpp +++ b/test/shape_mesh_consistency.cpp @@ -38,10 +38,10 @@ #define BOOST_TEST_MODULE FCL_SHAPE_MESH_CONSISTENCY #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> -#include <hpp/fcl/distance.h> -#include <hpp/fcl/collision.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" +#include "coal/distance.h" +#include "coal/collision.h" #include "utility.h" using namespace coal; diff --git a/test/simple.cpp b/test/simple.cpp index b1582ef3a7a3ee96a70828c9b3c9457bb42c679e..4010537142df431121399225698f4de9941a965f 100644 --- a/test/simple.cpp +++ b/test/simple.cpp @@ -1,9 +1,9 @@ #define BOOST_TEST_MODULE FCL_SIMPLE #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/internal/intersect.h> -#include <hpp/fcl/collision.h> -#include <hpp/fcl/BVH/BVH_model.h> +#include "coal/internal/intersect.h" +#include "coal/collision.h" +#include "coal/BVH/BVH_model.h" #include "fcl_resources/config.h" #include <sstream> diff --git a/test/swept_sphere_radius.cpp b/test/swept_sphere_radius.cpp index b829fd7b9e1a7f46b2c67b5ac2459cef2ac6a0a4..df7974e28cb20df908a4cb47266789c0ba18442f 100644 --- a/test/swept_sphere_radius.cpp +++ b/test/swept_sphere_radius.cpp @@ -37,13 +37,13 @@ #define BOOST_TEST_MODULE SWEPT_SPHERE_RADIUS #include <boost/test/included/unit_test.hpp> -#include <hpp/fcl/narrowphase/narrowphase.h> -#include <hpp/fcl/collision_utility.h> +#include "coal/narrowphase/narrowphase.h" +#include "coal/collision_utility.h" -#include <hpp/fcl/serialization/geometric_shapes.h> -#include <hpp/fcl/serialization/convex.h> -#include <hpp/fcl/serialization/transform.h> -#include <hpp/fcl/serialization/archive.h> +#include "coal/serialization/geometric_shapes.h" +#include "coal/serialization/convex.h" +#include "coal/serialization/transform.h" +#include "coal/serialization/archive.h" #include "utility.h" diff --git a/test/utility.cpp b/test/utility.cpp index a17831eb95d4944c3e8611038ee193de415a4fd2..5efd2ca1e35dde0bc42e94172a986adc02556fff 100644 --- a/test/utility.cpp +++ b/test/utility.cpp @@ -1,13 +1,13 @@ #include "utility.h" -#include <hpp/fcl/BV/BV.h> -#include <hpp/fcl/BVH/BVH_model.h> -#include <hpp/fcl/shape/geometric_shape_to_BVH_model.h> -#include <hpp/fcl/collision_utility.h> -#include <hpp/fcl/fwd.hh> - -#include <hpp/fcl/collision.h> -#include <hpp/fcl/distance.h> +#include "coal/BV/BV.h" +#include "coal/BVH/BVH_model.h" +#include "coal/shape/geometric_shape_to_BVH_model.h" +#include "coal/collision_utility.h" +#include "coal/fwd.hh" + +#include "coal/collision.h" +#include "coal/distance.h" #include <cstdio> #include <cstddef> diff --git a/test/utility.h b/test/utility.h index 96b09c26d2c896db3f9c8b8f9c6402419bb78df6..444f8aa54df8e7a5fd89cc65b7dd5480482a4ef3 100644 --- a/test/utility.h +++ b/test/utility.h @@ -38,14 +38,14 @@ #ifndef TEST_HPP_FCL_UTILITY_H #define TEST_HPP_FCL_UTILITY_H -#include <hpp/fcl/math/transform.h> -#include <hpp/fcl/collision_data.h> -#include <hpp/fcl/collision_object.h> -#include <hpp/fcl/broadphase/default_broadphase_callbacks.h> -#include <hpp/fcl/shape/convex.h> +#include "coal/math/transform.h" +#include "coal/collision_data.h" +#include "coal/collision_object.h" +#include "coal/broadphase/default_broadphase_callbacks.h" +#include "coal/shape/convex.h" #ifdef HPP_FCL_HAS_OCTOMAP -#include <hpp/fcl/octree.h> +#include "coal/octree.h" #endif #ifdef _WIN32