From 887fd0cdba32d96deaec125b90810e77ee1a4a8a Mon Sep 17 00:00:00 2001 From: Lucile Remigy <lremigy@laas.fr> Date: Mon, 19 Aug 2019 15:40:10 +0200 Subject: [PATCH] delete useless methods in includes --- include/hpp/fcl/BV/AABB.h | 37 ++++--------------- include/hpp/fcl/BV/BV.h | 38 +------------------- include/hpp/fcl/BV/OBB.h | 7 ---- include/hpp/fcl/BV/OBBRSS.h | 11 +----- include/hpp/fcl/BV/RSS.h | 4 --- include/hpp/fcl/BV/kDOP.h | 9 +++-- include/hpp/fcl/BV/kIOS.h | 8 ----- include/hpp/fcl/BVH/BVH_model.h | 54 +++++++++++++--------------- include/hpp/fcl/BVH/BVH_utility.h | 34 ------------------ include/hpp/fcl/math/matrix_3f.h | 36 ------------------- include/hpp/fcl/math/tools.h | 32 +---------------- include/hpp/fcl/math/transform.h | 21 +---------- include/hpp/fcl/math/vec_3f.h | 6 ++-- include/hpp/fcl/mesh_loader/assimp.h | 1 - include/hpp/fcl/mesh_loader/loader.h | 14 ++------ test/test_fcl_eigen.cpp | 4 +-- test/test_fcl_geometric_shapes.cpp | 8 ++--- test/test_fcl_gjk.cpp | 4 +-- 18 files changed, 53 insertions(+), 275 deletions(-) diff --git a/include/hpp/fcl/BV/AABB.h b/include/hpp/fcl/BV/AABB.h index 0b93c48a..49dcaadf 100644 --- a/include/hpp/fcl/BV/AABB.h +++ b/include/hpp/fcl/BV/AABB.h @@ -104,23 +104,12 @@ public: return overlap (other); } - /// @brief Check whether the AABB contains another AABB + /// @brief Check whether the AABB contains another AABB inline bool contain(const AABB& other) const { return (other.min_[0] >= min_[0]) && (other.max_[0] <= max_[0]) && (other.min_[1] >= min_[1]) && (other.max_[1] <= max_[1]) && (other.min_[2] >= min_[2]) && (other.max_[2] <= max_[2]); } - - /// @brief Check whether two AABB are overlapped along specific axis - inline bool axisOverlap(const AABB& other, int axis_id) const - { - if(min_[axis_id] > other.max_[axis_id]) return false; - - if(max_[axis_id] < other.min_[axis_id]) return false; - - return true; - } - /// @brief Check whether two AABB are overlap and return the overlap part inline bool overlap(const AABB& other, AABB& overlap_part) const { @@ -145,6 +134,12 @@ public: return true; } + /// @brief Volume of the AABB + inline FCL_REAL volume() const + { + return width() * height() * depth(); + } + /// @brief Merge the AABB and a point inline AABB& operator += (const Vec3f& p) { @@ -186,24 +181,12 @@ public: return max_[2] - min_[2]; } - /// @brief Volume of the AABB - inline FCL_REAL volume() const - { - return width() * height() * depth(); - } - /// @brief Size of the AABB (used in BV_Splitter to order two AABBs) inline FCL_REAL size() const { return (max_ - min_).squaredNorm(); } - /// @brief Radius of the AABB - inline FCL_REAL radius() const - { - return (max_ - min_).norm() / 2; - } - /// @brief Center of the AABB inline Vec3f center() const { @@ -216,12 +199,6 @@ public: /// @brief Distance between two AABBs FCL_REAL distance(const AABB& other) const; - /// @brief whether two AABB are equal - inline bool equal(const AABB& other) const - { - return isEqual(min_, other.min_) && isEqual(max_, other.max_); - } - /// @brief expand the half size of the AABB by delta, and keep the center unchanged. inline AABB& expand(const Vec3f& delta) { diff --git a/include/hpp/fcl/BV/BV.h b/include/hpp/fcl/BV/BV.h index d88aa1fc..bb42f7fb 100644 --- a/include/hpp/fcl/BV/BV.h +++ b/include/hpp/fcl/BV/BV.h @@ -90,43 +90,7 @@ class Converter<AABB, OBB> { public: static void convert(const AABB& bv1, const Transform3f& tf1, OBB& bv2) - { - /* - bv2.To = tf1.transform(bv1.center()); - - /// Sort the AABB edges so that AABB extents are ordered. - FCL_REAL d[3] = {bv1.width(), bv1.height(), bv1.depth() }; - std::size_t id[3] = {0, 1, 2}; - - for(std::size_t i = 1; i < 3; ++i) - { - for(std::size_t j = i; j > 0; --j) - { - if(d[j] > d[j-1]) - { - { - FCL_REAL tmp = d[j]; - d[j] = d[j-1]; - d[j-1] = tmp; - } - { - std::size_t tmp = id[j]; - id[j] = id[j-1]; - id[j-1] = tmp; - } - } - } - } - - Vec3f extent = (bv1.max_ - bv1.min_) * 0.5; - bv2.extent = Vec3f(extent[id[0]], extent[id[1]], extent[id[2]]); - const Matrix3f& R = tf1.getRotation(); - bool left_hand = (id[0] == (id[1] + 1) % 3); - bv2.axis[0] = left_hand ? -R.col(id[0]) : R.col(id[0]); - bv2.axis[1] = R.col(id[1]); - bv2.axis[2] = R.col(id[2]); - */ - + { bv2.To.noalias() = tf1.transform(bv1.center()); bv2.extent.noalias() = (bv1.max_ - bv1.min_) * 0.5; bv2.axes.noalias() = tf1.getRotation(); diff --git a/include/hpp/fcl/BV/OBB.h b/include/hpp/fcl/BV/OBB.h index f3897cf3..028f011e 100644 --- a/include/hpp/fcl/BV/OBB.h +++ b/include/hpp/fcl/BV/OBB.h @@ -73,13 +73,6 @@ public: bool overlap(const OBB& other, const CollisionRequest& request, FCL_REAL& sqrDistLowerBound) const; - - /// @brief Check collision between two OBB and return the overlap part. For OBB, the overlap_part return value is NOT used as the overlap part of two obbs usually is not an obb. - bool overlap(const OBB& other, OBB& /*overlap_part*/) const - { - return overlap(other); - } - /// @brief Check whether the OBB contains a point. bool contain(const Vec3f& p) const; diff --git a/include/hpp/fcl/BV/OBBRSS.h b/include/hpp/fcl/BV/OBBRSS.h index bc8d715c..dbd7ff1f 100644 --- a/include/hpp/fcl/BV/OBBRSS.h +++ b/include/hpp/fcl/BV/OBBRSS.h @@ -74,13 +74,7 @@ public: return obb.overlap(other.obb, request, sqrDistLowerBound); } - /// @brief Check collision between two OBBRSS and return the overlap part. - bool overlap(const OBBRSS& other, OBBRSS& /*overlap_part*/) const - { - return overlap(other); - } - - /// @brief Check whether the OBBRSS contains a point +/// @brief Check whether the OBBRSS contains a point inline bool contain(const Vec3f& p) const { return obb.contain(p); @@ -153,9 +147,6 @@ public: } }; -/// @brief Translate the OBBRSS bv -OBBRSS translate(const OBBRSS& bv, const Vec3f& t); - /// @brief Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity bool overlap(const Matrix3f& R0, const Vec3f& T0, const OBBRSS& b1, const OBBRSS& b2); diff --git a/include/hpp/fcl/BV/RSS.h b/include/hpp/fcl/BV/RSS.h index 6822e97e..53d3ca3c 100644 --- a/include/hpp/fcl/BV/RSS.h +++ b/include/hpp/fcl/BV/RSS.h @@ -142,10 +142,6 @@ public: }; - -/// @brief Translate the RSS bv -RSS translate(const RSS& bv, const Vec3f& t); - /// @brief distance between two RSS bounding volumes /// P and Q (optional return values) are the closest points in the rectangles, 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) diff --git a/include/hpp/fcl/BV/kDOP.h b/include/hpp/fcl/BV/kDOP.h index da590162..80f8d211 100644 --- a/include/hpp/fcl/BV/kDOP.h +++ b/include/hpp/fcl/BV/kDOP.h @@ -85,6 +85,10 @@ namespace fcl template<size_t N> class KDOP { +private: + /// @brief Origin's distances to N KDOP planes + FCL_REAL dist_[N]; + public: /// @brief Creating kDOP containing nothing @@ -158,11 +162,6 @@ public: /// @brief The distance between two KDOP<N>. Not implemented. FCL_REAL distance(const KDOP<N>& other, Vec3f* P = NULL, Vec3f* Q = NULL) const; -private: - /// @brief Origin's distances to N KDOP planes - FCL_REAL dist_[N]; - -public: inline FCL_REAL dist(std::size_t i) const { return dist_[i]; diff --git a/include/hpp/fcl/BV/kIOS.h b/include/hpp/fcl/BV/kIOS.h index a7228168..77ab3e45 100644 --- a/include/hpp/fcl/BV/kIOS.h +++ b/include/hpp/fcl/BV/kIOS.h @@ -100,14 +100,6 @@ public: bool overlap(const kIOS& other, const CollisionRequest&, FCL_REAL& sqrDistLowerBound) const; - /// @brief Check collision between two kIOS and return the overlap part. - /// For kIOS, we return nothing, as the overlappart of two kIOS usually is not an kIOS - /// @todo Not efficient. It first checks the sphere collisions and then use OBB for further culling. - bool overlap(const kIOS& other, kIOS& /*overlap_part*/) const - { - return overlap(other); - } - /// @brief Check whether the kIOS contains a point inline bool contain(const Vec3f& p) const; diff --git a/include/hpp/fcl/BVH/BVH_model.h b/include/hpp/fcl/BVH/BVH_model.h index 1f29a9bb..031942f1 100644 --- a/include/hpp/fcl/BVH/BVH_model.h +++ b/include/hpp/fcl/BVH/BVH_model.h @@ -59,6 +59,30 @@ class BVHModel : public CollisionGeometry, { public: + /// @brief Geometry point data + Vec3f* vertices; + + /// @brief Geometry triangle index data, will be NULL for point clouds + Triangle* tri_indices; + + /// @brief Geometry point data in previous frame + Vec3f* prev_vertices; + + /// @brief Number of triangles + int num_tris; + + /// @brief Number of points + int num_vertices; + + /// @brief The state of BVH building process + BVHBuildState build_state; + + /// @brief Split rule to split one BV node into two children + boost::shared_ptr<BVSplitterBase<BV> > bv_splitter; + + /// @brief Fitting rule to fit a BV node to a set of geometry primitives + boost::shared_ptr<BVFitterBase<BV> > bv_fitter; + /// @brief Model type described by the instance BVHModelType getModelType() const { @@ -150,7 +174,6 @@ public: /// @brief End BVH model construction, will build the bounding volume hierarchy int endModel(); - /// @brief Replace the geometry information of current frame (i.e. should have the same mesh topology with the previous frame) int beginReplaceModel(); @@ -166,7 +189,6 @@ public: /// @brief End BVH model replacement, will also refit or rebuild the bounding volume hierarchy int endReplaceModel(bool refit = true, bool bottomup = true); - /// @brief Replace the geometry information of current frame (i.e. should have the same mesh topology with the previous frame). /// The current frame will be saved as the previous frame in prev_vertices. int beginUpdateModel(); @@ -186,7 +208,7 @@ public: /// @brief Check the number of memory used int memUsage(int msg) const; - /// @brief This is a special acceleration: BVH_model default stores the BV's transform in world coordinate. However, we can also store each BV's transform related to its parent +/// @brief This is a special acceleration: BVH_model default stores the BV's transform in world coordinate. However, we can also store each BV's transform related to its parent /// BV node. When traversing the BVH, this can save one matrix transformation. void makeParentRelative() { @@ -244,32 +266,6 @@ public: return C.trace() * Matrix3f::Identity() - C; } -public: - /// @brief Geometry point data - Vec3f* vertices; - - /// @brief Geometry triangle index data, will be NULL for point clouds - Triangle* tri_indices; - - /// @brief Geometry point data in previous frame - Vec3f* prev_vertices; - - /// @brief Number of triangles - int num_tris; - - /// @brief Number of points - int num_vertices; - - /// @brief The state of BVH building process - BVHBuildState build_state; - - /// @brief Split rule to split one BV node into two children - boost::shared_ptr<BVSplitterBase<BV> > bv_splitter; - - /// @brief Fitting rule to fit a BV node to a set of geometry primitives - boost::shared_ptr<BVFitterBase<BV> > bv_fitter; - - private: int num_tris_allocated; diff --git a/include/hpp/fcl/BVH/BVH_utility.h b/include/hpp/fcl/BVH/BVH_utility.h index 85110c26..e87cf918 100644 --- a/include/hpp/fcl/BVH/BVH_utility.h +++ b/include/hpp/fcl/BVH/BVH_utility.h @@ -46,39 +46,6 @@ namespace hpp { namespace fcl { -/// @brief Expand the BVH bounding boxes according to the variance matrix corresponding to the data stored within each BV node -template<typename BV> -void BVHExpand(BVHModel<BV>& model, const Variance3f* ucs, FCL_REAL r) -{ - for(int i = 0; i < model.num_bvs; ++i) - { - BVNode<BV>& bvnode = model.getBV(i); - - BV bv; - for(int j = 0; j < bvnode.num_primitives; ++j) - { - int v_id = bvnode.first_primitive + j; - const Variance3f& uc = ucs[v_id]; - - Vec3f& v = model.vertices[bvnode.first_primitive + j]; - - for(int k = 0; k < 3; ++k) - { - bv += (v + uc.axis[k] * (r * uc.sigma[k])); - bv += (v - uc.axis[k] * (r * uc.sigma[k])); - } - } - - bvnode.bv = bv; - } -} - -/// @brief Expand the BVH bounding boxes according to the corresponding variance information, for OBB -void BVHExpand(BVHModel<OBB>& model, const Variance3f* ucs, FCL_REAL r); - -/// @brief Expand the BVH bounding boxes according to the corresponding variance information, for RSS -void BVHExpand(BVHModel<RSS>& model, const Variance3f* ucs, FCL_REAL r); - /// @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> @@ -99,7 +66,6 @@ void circumCircleComputation(const Vec3f& a, const Vec3f& b, const Vec3f& c, Vec /// @brief Compute the maximum distance from a given center point to a point cloud FCL_REAL maximumDistance(Vec3f* ps, Vec3f* ps2, Triangle* ts, unsigned int* indices, int n, const Vec3f& query); - } } // namespace hpp diff --git a/include/hpp/fcl/math/matrix_3f.h b/include/hpp/fcl/math/matrix_3f.h index 122f3291..9026a222 100644 --- a/include/hpp/fcl/math/matrix_3f.h +++ b/include/hpp/fcl/math/matrix_3f.h @@ -60,42 +60,6 @@ public: /// @brief Eigen axes of the variation matrix Vec3f axis[3]; - Variance3f() {} - - Variance3f(const Matrix3f& S) : Sigma(S) - { - init(); - } - - /// @brief init the Variance - void init() - { - eigen(Sigma, sigma, axis); - } - - /// @brief Compute the sqrt of Sigma matrix based on the eigen decomposition result, this is useful when the uncertainty matrix is initialized as a square variation matrix - Variance3f& sqrt() - { - for(std::size_t i = 0; i < 3; ++i) - { - if(sigma[i] < 0) sigma[i] = 0; - sigma[i] = std::sqrt(sigma[i]); - } - - - Sigma.setZero(); - for(std::size_t i = 0; i < 3; ++i) - { - for(std::size_t j = 0; j < 3; ++j) - { - Sigma(i, j) += sigma[0] * axis[0][i] * axis[0][j]; - Sigma(i, j) += sigma[1] * axis[1][i] * axis[1][j]; - Sigma(i, j) += sigma[2] * axis[2][i] * axis[2][j]; - } - } - - return *this; - } }; } diff --git a/include/hpp/fcl/math/tools.h b/include/hpp/fcl/math/tools.h index cfc19640..f1778661 100644 --- a/include/hpp/fcl/math/tools.h +++ b/include/hpp/fcl/math/tools.h @@ -98,14 +98,6 @@ void generateCoordinateSystem( } /* ----- Start Matrices ------ */ -template<typename Derived, typename OtherDerived> -void hat(const Eigen::MatrixBase<Derived>& mat, const Eigen::MatrixBase<OtherDerived>& vec) -{ - EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived, 3, 3); - EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(OtherDerived, 3, 1); - const_cast< Eigen::MatrixBase<Derived>& >(mat) << 0, -vec[2], vec[1], vec[2], 0, -vec[0], -vec[1], vec[0], 0; -} - template<typename Derived, typename OtherDerived> void relativeTransform(const Eigen::MatrixBase<Derived>& R1, const Eigen::MatrixBase<OtherDerived>& t1, const Eigen::MatrixBase<Derived>& R2, const Eigen::MatrixBase<OtherDerived>& t2, @@ -205,11 +197,7 @@ void eigen(const Eigen::MatrixBase<Derived>& m, typename Derived::Scalar dout[3] return; } -template<typename Derived, typename OtherDerived> -typename Derived::Scalar quadraticForm(const Eigen::MatrixBase<Derived>& R, const Eigen::MatrixBase<OtherDerived>& v) -{ - return v.dot(R * v); -} + template<typename Derived, typename OtherDerived> bool isEqual(const Eigen::MatrixBase<Derived>& lhs, const Eigen::MatrixBase<OtherDerived>& rhs, const FCL_REAL tol = std::numeric_limits<FCL_REAL>::epsilon()*100) @@ -217,26 +205,8 @@ bool isEqual(const Eigen::MatrixBase<Derived>& lhs, const Eigen::MatrixBase<Othe return ((lhs - rhs).array().abs() < tol).all(); } -template <typename Derived> -inline Derived& setEulerZYX(const Eigen::MatrixBase<Derived>& R, FCL_REAL eulerX, FCL_REAL eulerY, FCL_REAL eulerZ) -{ - const_cast< Eigen::MatrixBase<Derived>& >(R).noalias() = ( - Eigen::AngleAxisd (eulerZ, Eigen::Vector3d::UnitZ()) * - Eigen::AngleAxisd (eulerY, Eigen::Vector3d::UnitY()) * - Eigen::AngleAxisd (eulerX, Eigen::Vector3d::UnitX()) - ).toRotationMatrix(); - return const_cast< Eigen::MatrixBase<Derived>& >(R).derived(); -} - -template <typename Derived> -inline Derived& setEulerYPR(const Eigen::MatrixBase<Derived>& R, FCL_REAL yaw, FCL_REAL pitch, FCL_REAL roll) -{ - return setEulerZYX(R, roll, pitch, yaw); } -} - - } // namespace hpp #endif diff --git a/include/hpp/fcl/math/transform.h b/include/hpp/fcl/math/transform.h index 69c12043..1787918d 100644 --- a/include/hpp/fcl/math/transform.h +++ b/include/hpp/fcl/math/transform.h @@ -126,13 +126,7 @@ public: R.setIdentity(); } - /// @brief Construct transform from another transform - Transform3f(const Transform3f& tf) : matrix_set(tf.matrix_set), - R(tf.R), - T(tf.T), - q(tf.q) - { - } + /// @brief operator = Transform3f& operator = (const Transform3f& tf) @@ -268,19 +262,6 @@ public: } }; - -/// @brief inverse the transform -Transform3f inverse(const Transform3f& tf); - -/// @brief compute the relative transform between two transforms: tf2 = tf1 * tf (relative to the local coordinate system in tf1) -void relativeTransform(const Transform3f& tf1, const Transform3f& tf2, - Transform3f& tf); - -/// @brief compute the relative transform between two transforms: tf2 = tf * tf1 (relative to the global coordinate system) -void relativeTransform2(const Transform3f& tf1, const Transform3f& tf2, - Transform3f& tf); - - } } // namespace hpp diff --git a/include/hpp/fcl/math/vec_3f.h b/include/hpp/fcl/math/vec_3f.h index b7fcef9d..a45a9202 100644 --- a/include/hpp/fcl/math/vec_3f.h +++ b/include/hpp/fcl/math/vec_3f.h @@ -57,6 +57,9 @@ namespace fcl } + +} // namespace hpp + #ifdef HPP_FCL_HAVE_OCTOMAP #define OCTOMAP_VERSION_AT_LEAST(x,y,z) \ (OCTOMAP_MAJOR_VERSION > x || (OCTOMAP_MAJOR_VERSION >= x && \ @@ -68,7 +71,4 @@ namespace fcl (OCTOMAP_MINOR_VERSION < y || (OCTOMAP_MINOR_VERSION <= y && \ OCTOMAP_PATCH_VERSION <= z)))) #endif // HPP_FCL_HAVE_OCTOMAP - -} // namespace hpp - #endif diff --git a/include/hpp/fcl/mesh_loader/assimp.h b/include/hpp/fcl/mesh_loader/assimp.h index 2b3078d4..3abcf0ae 100644 --- a/include/hpp/fcl/mesh_loader/assimp.h +++ b/include/hpp/fcl/mesh_loader/assimp.h @@ -60,7 +60,6 @@ namespace hpp { namespace fcl { - struct TriangleAndVertices { diff --git a/include/hpp/fcl/mesh_loader/loader.h b/include/hpp/fcl/mesh_loader/loader.h index ce8a30af..01ba842b 100644 --- a/include/hpp/fcl/mesh_loader/loader.h +++ b/include/hpp/fcl/mesh_loader/loader.h @@ -53,7 +53,7 @@ namespace fcl { public: virtual ~MeshLoader() {} - /// \param bvType ignored + /// \param bvType ignored /// \deprecated Use MeshLoader::load(const std::string&, const Vec3f&) CollisionGeometryPtr_t load (const std::string& filename, const Vec3f& scale, @@ -83,16 +83,6 @@ namespace fcl { CachedMeshLoader (const NODE_TYPE& bvType = BV_OBBRSS) : MeshLoader (bvType) {} - /// \param bvType ignored - /// \deprecated Use MeshLoader::load(const std::string&, const Vec3f&) - CollisionGeometryPtr_t load (const std::string& filename, - const Vec3f& scale, - const NODE_TYPE& bvType) HPP_FCL_DEPRECATED - { - (void) bvType; - return load(filename, scale); - } - virtual CollisionGeometryPtr_t load (const std::string& filename, const Vec3f& scale); @@ -107,7 +97,7 @@ namespace fcl { }; typedef std::map <Key, CollisionGeometryPtr_t> Cache_t; - const Cache_t cache () const { return cache_; } + private: Cache_t cache_; }; diff --git a/test/test_fcl_eigen.cpp b/test/test_fcl_eigen.cpp index a1bcb12f..5b50dce7 100644 --- a/test/test_fcl_eigen.cpp +++ b/test/test_fcl_eigen.cpp @@ -102,11 +102,11 @@ BOOST_AUTO_TEST_CASE(fcl_eigen_matrix3fx) a *= a; PRINT_MATRIX(a); - Matrix3fX b = inverse(a); + Matrix3fX b = a.inverse(); a += a + a * b; PRINT_MATRIX(a); - b = inverse(a); + b = a.inverse(); a.transpose (); PRINT_MATRIX(a); PRINT_MATRIX(a.transposeTimes (b)); diff --git a/test/test_fcl_geometric_shapes.cpp b/test/test_fcl_geometric_shapes.cpp index 60df213b..a2cdacc9 100644 --- a/test/test_fcl_geometric_shapes.cpp +++ b/test/test_fcl_geometric_shapes.cpp @@ -291,11 +291,11 @@ BOOST_AUTO_TEST_CASE (shapeIntersection_cylinderbox) BOOST_CHECK ((res && distance > 0) || (!res && distance <= 0)); // If objects are not colliding, p2 should be outside the cylinder and // p1 should be outside the box - Vec3f p2Loc (inverse (tf1).transform (p2)); + Vec3f p2Loc (tf1.inverse().transform (p2)); bool p2_in_cylinder ((fabs (p2Loc [2]) <= .5*s1.lz) && (p2Loc [0] * p2Loc [0] + p2Loc [1] * p2Loc [1] <= s1.radius)); - Vec3f p1Loc (inverse (tf2).transform (p1)); + Vec3f p1Loc (tf2.inverse().transform (p1)); bool p1_in_box ((fabs (p1Loc [0]) <= .5 * s2.side [0]) && (fabs (p1Loc [1]) <= .5 * s2.side [1]) && (fabs (p1Loc [2]) <= .5 * s2.side [2])); @@ -310,11 +310,11 @@ BOOST_AUTO_TEST_CASE (shapeIntersection_cylinderbox) // If objects are not colliding, p2 should be outside the cylinder and // p1 should be outside the box - p2Loc = inverse (tf1).transform (p2); + p2Loc = tf1.inverse().transform (p2); p2_in_cylinder = (fabs (p2Loc [2]) <= .5*s1.lz) && (p2Loc [0] * p2Loc [0] + p2Loc [1] * p2Loc [1] <= s1.radius); - p1Loc = inverse (tf2).transform (p1); + p1Loc = tf2.inverse().transform (p1); p1_in_box = (fabs (p1Loc [0]) <= .5 * s2.side [0]) && (fabs (p1Loc [1]) <= .5 * s2.side [1]) && (fabs (p1Loc [2]) <= .5 * s2.side [2]); diff --git a/test/test_fcl_gjk.cpp b/test/test_fcl_gjk.cpp index 3bb9b907..52a5cfdd 100644 --- a/test/test_fcl_gjk.cpp +++ b/test/test_fcl_gjk.cpp @@ -183,11 +183,11 @@ BOOST_AUTO_TEST_CASE(distance_triangle_triangle_1) BOOST_CHECK (w1.squaredNorm () > eps*eps); M.col (0) = u1; M.col (1) = v1; M.col (2) = w1; // Compute a1 such that p1 = P1 + a11 u1 + a12 v1 + a13 u1 x v1 - a1 = M.inverse () * (p1 - P1); + a1 = M.inverse() * (p1 - P1); BOOST_CHECK (w2.squaredNorm () > eps*eps); // Compute a2 such that p2 = Q1 + a21 u2 + a22 v2 + a23 u2 x v2 M.col (0) = u2; M.col (1) = v2; M.col (2) = w2; - a2 = M.inverse () * (p2 - Q1); + a2 = M.inverse() * (p2 - Q1); // minimal distance and closest points can be considered as a constrained // optimisation problem: -- GitLab