test_fcl_sphere_sphere.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018. Toyota Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of CNRS-LAAS and AIST nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #include <memory>
38 #include <utility>
39 #include <vector>
40 
41 #include <gtest/gtest.h>
42 #include <Eigen/Dense>
43 
44 #include "eigen_matrix_compare.h"
49 
50 // For two spheres 1, 2, sphere 1 has radius1, and is centered at point A, with
51 // coordinate p_FA in some frame F; sphere 2 has radius2, and is centered at
52 // point B, with coordinate p_FB in the same frame F. Compute the (optionally
53 // signed) distance between the two spheres.
54 template <typename S>
55 S ComputeSphereSphereDistance(S radius1, S radius2, const fcl::Vector3<S>& p_FA,
56  const fcl::Vector3<S>& p_FB,
57  fcl::GJKSolverType solver_type,
58  bool enable_nearest_points,
59  bool enable_signed_distance,
60  fcl::DistanceResult<S>* result) {
61  // Pose of the sphere expressed in the frame F. X_FA is the pose of sphere 1
62  // in frame F, while X_FB is the pose of sphere 2 in frame F.
63  // We use monogram notation as in Drake, explained in
64  // http://drake.mit.edu/doxygen_cxx/group__multibody__spatial__pose.html
65  fcl::Transform3<S> X_FA, X_FB;
66  X_FA.setIdentity();
67  X_FB.setIdentity();
68  X_FA.translation() = p_FA;
69  X_FB.translation() = p_FB;
70 
72  request.enable_nearest_points = enable_nearest_points;
73  request.enable_signed_distance = enable_signed_distance;
74  request.gjk_solver_type = solver_type;
75 
76  using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometry<S>>;
77  CollisionGeometryPtr_t sphere_geometry_1(new fcl::Sphere<S>(radius1));
78  CollisionGeometryPtr_t sphere_geometry_2(new fcl::Sphere<S>(radius2));
79 
80  fcl::CollisionObject<S> sphere_1(sphere_geometry_1, X_FA);
81  fcl::CollisionObject<S> sphere_2(sphere_geometry_2, X_FB);
82  const S min_distance = fcl::distance(&sphere_1, &sphere_2, request, *result);
83  return min_distance;
84 }
85 
86 template <typename S>
88  // @param p_FC_ the center of the sphere C measured and expressed in a frame F
89  SphereSpecification(S m_radius, const fcl::Vector3<S>& p_FC_)
90  : radius(m_radius), p_FC(p_FC_) {}
91  S radius;
93 };
94 
95 template <typename S>
97  const SphereSpecification<S>& sphere2,
98  fcl::GJKSolverType solver_type,
99  bool enable_nearest_points,
100  bool enable_signed_distance,
101  S min_distance_expected,
102  const fcl::Vector3<S>& p1_expected,
103  const fcl::Vector3<S>& p2_expected, S tol) {
104  fcl::DistanceResult<S> result;
105  const S min_distance = ComputeSphereSphereDistance<S>(
106  sphere1.radius, sphere2.radius, sphere1.p_FC, sphere2.p_FC, solver_type,
107  enable_nearest_points, enable_signed_distance, &result);
108  EXPECT_NEAR(min_distance, min_distance_expected, tol);
109  EXPECT_NEAR(result.min_distance, min_distance_expected, tol);
110  EXPECT_TRUE(fcl::CompareMatrices(result.nearest_points[0], p1_expected, tol));
111  EXPECT_TRUE(fcl::CompareMatrices(result.nearest_points[1], p2_expected, tol));
112 }
113 
114 template <typename S>
117  const SphereSpecification<S>& m_sphere2)
118  : sphere1(m_sphere1), sphere2(m_sphere2) {
119  min_distance =
120  (sphere1.p_FC - sphere2.p_FC).norm() - sphere1.radius - sphere2.radius;
121  const fcl::Vector3<S> AB = (sphere1.p_FC - sphere2.p_FC).normalized();
122  p_WP1 = sphere1.p_FC + AB * -sphere1.radius;
123  p_WP2 = sphere2.p_FC + AB * sphere2.radius;
124  }
128  // The closest point P1 on sphere 1 is expressed in the world frame W.
130  // The closest point P2 on sphere 2 is expressed in the world frame W.
132 };
133 
134 template <typename S>
135 void TestSeparatingSpheres(S tol, fcl::GJKSolverType solver_type) {
136  std::vector<SphereSpecification<S>> spheres;
137  spheres.emplace_back(0.5, fcl::Vector3<S>(0, 0, -1)); // sphere 1
138  spheres.emplace_back(0.6, fcl::Vector3<S>(1.2, 0, 0)); // sphere 2
139  spheres.emplace_back(0.4, fcl::Vector3<S>(-0.3, 0, 0)); // sphere 3
140  spheres.emplace_back(0.3, fcl::Vector3<S>(0, 0, 1)); // sphere 4
141 
142  for (int i = 0; i < static_cast<int>(spheres.size()); ++i) {
143  for (int j = i + 1; j < static_cast<int>(spheres.size()); ++j) {
144  SphereSphereDistance<S> sphere_sphere_distance(spheres[i], spheres[j]);
145  bool enable_signed_distance = true;
146  CheckSphereToSphereDistance<S>(
147  spheres[i], spheres[j], solver_type, true, enable_signed_distance,
148  sphere_sphere_distance.min_distance, sphere_sphere_distance.p_WP1,
149  sphere_sphere_distance.p_WP2, tol);
150 
151  // Now switch the order of sphere 1 with sphere 2 in calling
152  // fcl::distance function, and test again.
153  CheckSphereToSphereDistance<S>(
154  spheres[j], spheres[i], solver_type, true, enable_signed_distance,
155  sphere_sphere_distance.min_distance, sphere_sphere_distance.p_WP2,
156  sphere_sphere_distance.p_WP1, tol);
157 
158  enable_signed_distance = false;
159  CheckSphereToSphereDistance<S>(
160  spheres[i], spheres[j], solver_type, true, enable_signed_distance,
161  sphere_sphere_distance.min_distance, sphere_sphere_distance.p_WP1,
162  sphere_sphere_distance.p_WP2, tol);
163 
164  // Now switch the order of sphere 1 with sphere 2 in calling
165  // fcl::distance function, and test again.
166  CheckSphereToSphereDistance<S>(
167  spheres[j], spheres[i], solver_type, true, enable_signed_distance,
168  sphere_sphere_distance.min_distance, sphere_sphere_distance.p_WP2,
169  sphere_sphere_distance.p_WP1, tol);
170 
171  // TODO (hongkai.dai@tri.global): Test enable_nearest_points=false.
172  }
173  }
174 }
175 
176 GTEST_TEST(FCL_SPHERE_SPHERE, Separating_Spheres_INDEP) {
177  TestSeparatingSpheres<double>(1E-14, fcl::GJKSolverType::GST_INDEP);
178 }
179 
180 GTEST_TEST(FCL_SPHERE_SPHERE, Separating_Spheres_LIBCCD) {
181  // TODO(hongkai.dai@tri.global): The accuracy of the closest point is only up
182  // to 1E-3, although gjkSolver::distance_tolerance is 1E-6. We should
183  // investigate the accuracy issue.
184  // Specifically, when setting `enable_signed_distance = true`, then except for
185  // the the pair of spheres (2, 3), the closest point between all other pairs
186  // fail to achieve tolerance 1E-6. When `enable_signed_distance = false`, then
187  // all pairs achieve tolerance 1E-6.
188  TestSeparatingSpheres<double>(1E-3, fcl::GJKSolverType::GST_LIBCCD);
189 }
190 //==============================================================================
191 int main(int argc, char* argv[]) {
192  ::testing::InitGoogleTest(&argc, argv);
193  return RUN_ALL_TESTS();
194 }
SphereSphereDistance::sphere2
SphereSpecification< S > sphere2
Definition: test_fcl_sphere_sphere.cpp:126
fcl::DistanceRequest
request to the distance computation
Definition: distance_request.h:52
distance_result.h
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::GJKSolverType
GJKSolverType
Type of narrow phase GJK solver.
Definition: gjk_solver_type.h:45
SphereSphereDistance::p_WP1
fcl::Vector3< S > p_WP1
Definition: test_fcl_sphere_sphere.cpp:129
collision_object.h
eigen_matrix_compare.h
fcl::distance
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS-inl.h:266
SphereSphereDistance
Definition: test_fcl_sphere_sphere.cpp:115
main
int main(int argc, char *argv[])
Definition: test_fcl_sphere_sphere.cpp:191
fcl::CompareMatrices
::testing::AssertionResult CompareMatrices(const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute)
Definition: eigen_matrix_compare.h:63
CheckSphereToSphereDistance
void CheckSphereToSphereDistance(const SphereSpecification< S > &sphere1, const SphereSpecification< S > &sphere2, fcl::GJKSolverType solver_type, bool enable_nearest_points, bool enable_signed_distance, S min_distance_expected, const fcl::Vector3< S > &p1_expected, const fcl::Vector3< S > &p2_expected, S tol)
Definition: test_fcl_sphere_sphere.cpp:96
GTEST_TEST
GTEST_TEST(FCL_SPHERE_SPHERE, Separating_Spheres_INDEP)
Definition: test_fcl_sphere_sphere.cpp:176
fcl::DistanceResult::nearest_points
Vector3< S > nearest_points[2]
Nearest points in the world coordinates.
Definition: distance_result.h:69
SphereSphereDistance::sphere1
SphereSpecification< S > sphere1
Definition: test_fcl_sphere_sphere.cpp:125
SphereSphereDistance::min_distance
S min_distance
Definition: test_fcl_sphere_sphere.cpp:127
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::DistanceResult
distance result
Definition: distance_request.h:48
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
distance.h
ComputeSphereSphereDistance
S ComputeSphereSphereDistance(S radius1, S radius2, const fcl::Vector3< S > &p_FA, const fcl::Vector3< S > &p_FB, fcl::GJKSolverType solver_type, bool enable_nearest_points, bool enable_signed_distance, fcl::DistanceResult< S > *result)
Definition: test_fcl_sphere_sphere.cpp:55
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
SphereSpecification::radius
S radius
Definition: test_fcl_sphere_sphere.cpp:91
fcl::DistanceRequest::gjk_solver_type
GJKSolverType gjk_solver_type
narrow phase solver type
Definition: distance_request.h:102
fcl::GST_LIBCCD
@ GST_LIBCCD
Definition: gjk_solver_type.h:45
distance_request.h
fcl::DistanceRequest::enable_nearest_points
bool enable_nearest_points
whether to return the nearest points
Definition: distance_request.h:55
fcl::DistanceResult::min_distance
S min_distance
Minimum distance between two objects.
Definition: distance_result.h:64
SphereSpecification::SphereSpecification
SphereSpecification(S m_radius, const fcl::Vector3< S > &p_FC_)
Definition: test_fcl_sphere_sphere.cpp:89
fcl::DistanceRequest::enable_signed_distance
bool enable_signed_distance
Whether to compute exact negative distance.
Definition: distance_request.h:92
SphereSpecification::p_FC
fcl::Vector3< S > p_FC
Definition: test_fcl_sphere_sphere.cpp:92
fcl::Sphere
Center at zero point sphere.
Definition: sphere.h:51
SphereSpecification
Definition: test_fcl_sphere_sphere.cpp:87
fcl::GST_INDEP
@ GST_INDEP
Definition: gjk_solver_type.h:45
fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:51
SphereSphereDistance::SphereSphereDistance
SphereSphereDistance(const SphereSpecification< S > &m_sphere1, const SphereSpecification< S > &m_sphere2)
Definition: test_fcl_sphere_sphere.cpp:116
SphereSphereDistance::p_WP2
fcl::Vector3< S > p_WP2
Definition: test_fcl_sphere_sphere.cpp:131
TestSeparatingSpheres
void TestSeparatingSpheres(S tol, fcl::GJKSolverType solver_type)
Definition: test_fcl_sphere_sphere.cpp:135


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49