accelerated_gjk.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, INRIA
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 Willow Garage, Inc. 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 #define BOOST_TEST_MODULE COAL_NESTEROV_GJK
38 #include <boost/test/included/unit_test.hpp>
39 
40 #include <Eigen/Geometry>
43 #include "coal/internal/tools.h"
44 
45 #include "utility.h"
46 
47 using coal::Box;
48 using coal::Capsule;
49 using coal::CoalScalar;
51 using coal::Convex;
52 using coal::Ellipsoid;
53 using coal::GJKSolver;
54 using coal::GJKVariant;
55 using coal::ShapeBase;
57 using coal::Transform3s;
58 using coal::Triangle;
59 using coal::Vec3s;
60 using coal::details::GJK;
63 using std::size_t;
64 
65 BOOST_AUTO_TEST_CASE(set_gjk_variant) {
66  GJKSolver solver;
67  GJK gjk(128, 1e-6);
68  MinkowskiDiff shape;
69 
70  // Checking defaults
71  BOOST_CHECK(solver.gjk.gjk_variant == GJKVariant::DefaultGJK);
72  BOOST_CHECK(gjk.gjk_variant == GJKVariant::DefaultGJK);
73  BOOST_CHECK(shape.normalize_support_direction == false);
74 
75  // Checking set
78 
79  BOOST_CHECK(solver.gjk.gjk_variant == GJKVariant::NesterovAcceleration);
80  BOOST_CHECK(gjk.gjk_variant == GJKVariant::NesterovAcceleration);
81 
83  gjk.gjk_variant = GJKVariant::PolyakAcceleration;
84 
85  BOOST_CHECK(solver.gjk.gjk_variant == GJKVariant::PolyakAcceleration);
86  BOOST_CHECK(gjk.gjk_variant == GJKVariant::PolyakAcceleration);
87 }
88 
89 BOOST_AUTO_TEST_CASE(need_nesterov_normalize_support_direction) {
90  Ellipsoid ellipsoid = Ellipsoid(1, 1, 1);
91  Box box = Box(1, 1, 1);
92  Convex<Triangle> cvx;
93 
94  MinkowskiDiff mink_diff1;
95  mink_diff1.set<SupportOptions::NoSweptSphere>(&ellipsoid, &ellipsoid);
96  BOOST_CHECK(mink_diff1.normalize_support_direction == false);
97 
98  MinkowskiDiff mink_diff2;
99  mink_diff2.set<SupportOptions::NoSweptSphere>(&ellipsoid, &box);
100  BOOST_CHECK(mink_diff2.normalize_support_direction == false);
101 
102  MinkowskiDiff mink_diff3;
103  mink_diff3.set<SupportOptions::NoSweptSphere>(&cvx, &cvx);
104  BOOST_CHECK(mink_diff3.normalize_support_direction == true);
105 }
106 
107 void test_accelerated_gjk(const ShapeBase& shape0, const ShapeBase& shape1) {
108  // Solvers
109  unsigned int max_iterations = 128;
110  CoalScalar tolerance = 1e-6;
111  GJK gjk(max_iterations, tolerance);
112  GJK gjk_nesterov(max_iterations, tolerance);
114  GJK gjk_polyak(max_iterations, tolerance);
116 
117  // Minkowski difference
118  MinkowskiDiff mink_diff;
119 
120  // Generate random transforms
121  size_t n = 1000;
122  CoalScalar extents[] = {-3., -3., 0, 3., 3., 3.};
123  std::vector<Transform3s> transforms;
124  generateRandomTransforms(extents, transforms, n);
125  Transform3s identity = Transform3s::Identity();
126 
127  // Same init for both solvers
128  Vec3s init_guess = Vec3s(1, 0, 0);
129  support_func_guess_t init_support_guess;
130  init_support_guess.setZero();
131 
132  for (size_t i = 0; i < n; ++i) {
133  // No need to take into account swept-sphere radius in supports computation
134  // when using GJK/EPA; after they have converged, these algos will correctly
135  // handle the swept-sphere radius of the shapes.
136  mink_diff.set<SupportOptions::NoSweptSphere>(&shape0, &shape1, identity,
137  transforms[i]);
138 
139  // Evaluate both solvers twice, make sure they give the same solution
140  GJK::Status res_gjk_1 =
141  gjk.evaluate(mink_diff, init_guess, init_support_guess);
142  Vec3s ray_gjk = gjk.ray;
143  GJK::Status res_gjk_2 =
144  gjk.evaluate(mink_diff, init_guess, init_support_guess);
145  BOOST_CHECK(res_gjk_1 == res_gjk_2);
146  EIGEN_VECTOR_IS_APPROX(ray_gjk, gjk.ray, 1e-8);
147 
148  // --------------
149  // -- Nesterov --
150  // --------------
151  GJK::Status res_nesterov_gjk_1 =
152  gjk_nesterov.evaluate(mink_diff, init_guess, init_support_guess);
153  Vec3s ray_nesterov = gjk_nesterov.ray;
154  GJK::Status res_nesterov_gjk_2 =
155  gjk_nesterov.evaluate(mink_diff, init_guess, init_support_guess);
156  BOOST_CHECK(res_nesterov_gjk_1 == res_nesterov_gjk_2);
157  EIGEN_VECTOR_IS_APPROX(ray_nesterov, gjk_nesterov.ray, 1e-8);
158 
159  // Make sure GJK and Nesterov accelerated GJK find the same distance between
160  // the shapes
161  BOOST_CHECK(res_nesterov_gjk_1 == res_gjk_1);
162  BOOST_CHECK_SMALL(fabs(ray_gjk.norm() - ray_nesterov.norm()), 1e-4);
163 
164  // Make sure GJK and Nesterov accelerated GJK converges in a reasonable
165  // amount of iterations
166  BOOST_CHECK(gjk.getNumIterations() < max_iterations);
167  BOOST_CHECK(gjk_nesterov.getNumIterations() < max_iterations);
168 
169  // ------------
170  // -- Polyak --
171  // ------------
172  GJK::Status res_polyak_gjk_1 =
173  gjk_polyak.evaluate(mink_diff, init_guess, init_support_guess);
174  Vec3s ray_polyak = gjk_polyak.ray;
175  GJK::Status res_polyak_gjk_2 =
176  gjk_polyak.evaluate(mink_diff, init_guess, init_support_guess);
177  BOOST_CHECK(res_polyak_gjk_1 == res_polyak_gjk_2);
178  EIGEN_VECTOR_IS_APPROX(ray_polyak, gjk_polyak.ray, 1e-8);
179 
180  // Make sure GJK and Polyak accelerated GJK find the same distance between
181  // the shapes
182  BOOST_CHECK(res_polyak_gjk_1 == res_gjk_1);
183  BOOST_CHECK_SMALL(fabs(ray_gjk.norm() - ray_polyak.norm()), 1e-4);
184 
185  // Make sure GJK and Polyak accelerated GJK converges in a reasonable
186  // amount of iterations
187  BOOST_CHECK(gjk.getNumIterations() < max_iterations);
188  BOOST_CHECK(gjk_polyak.getNumIterations() < max_iterations);
189  }
190 }
191 
192 BOOST_AUTO_TEST_CASE(ellipsoid_ellipsoid) {
193  Ellipsoid ellipsoid0 = Ellipsoid(0.3, 0.4, 0.5);
194  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
195 
196  test_accelerated_gjk(ellipsoid0, ellipsoid1);
197  test_accelerated_gjk(ellipsoid0, ellipsoid1);
198 }
199 
200 BOOST_AUTO_TEST_CASE(ellipsoid_capsule) {
201  Ellipsoid ellipsoid0 = Ellipsoid(0.5, 0.4, 0.3);
202  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
203  Capsule capsule0 = Capsule(0.1, 0.3);
204  Capsule capsule1 = Capsule(1.1, 1.3);
205 
206  test_accelerated_gjk(ellipsoid0, capsule0);
207  test_accelerated_gjk(ellipsoid0, capsule1);
208  test_accelerated_gjk(ellipsoid1, capsule0);
209  test_accelerated_gjk(ellipsoid1, capsule1);
210 }
211 
212 BOOST_AUTO_TEST_CASE(ellipsoid_box) {
213  Ellipsoid ellipsoid0 = Ellipsoid(0.5, 0.4, 0.3);
214  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
215  Box box0 = Box(0.1, 0.2, 0.3);
216  Box box1 = Box(1.1, 1.2, 1.3);
217 
218  test_accelerated_gjk(ellipsoid0, box0);
219  test_accelerated_gjk(ellipsoid0, box1);
220  test_accelerated_gjk(ellipsoid1, box0);
221  test_accelerated_gjk(ellipsoid1, box1);
222 }
223 
224 BOOST_AUTO_TEST_CASE(ellipsoid_mesh) {
225  Ellipsoid ellipsoid0 = Ellipsoid(0.5, 0.4, 0.3);
226  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
229 
230  test_accelerated_gjk(ellipsoid0, cvx0);
231  test_accelerated_gjk(ellipsoid0, cvx1);
232  test_accelerated_gjk(ellipsoid1, cvx0);
233  test_accelerated_gjk(ellipsoid1, cvx1);
234 }
235 
236 BOOST_AUTO_TEST_CASE(capsule_mesh) {
237  Ellipsoid ellipsoid0 = Ellipsoid(0.5, 0.4, 0.3);
238  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
241  Capsule capsule0 = Capsule(0.1, 0.3);
242  Capsule capsule1 = Capsule(1.1, 1.3);
243 
244  test_accelerated_gjk(capsule0, cvx0);
245  test_accelerated_gjk(capsule0, cvx1);
246  test_accelerated_gjk(capsule1, cvx0);
247  test_accelerated_gjk(capsule1, cvx1);
248 }
249 
250 BOOST_AUTO_TEST_CASE(capsule_capsule) {
251  Capsule capsule0 = Capsule(0.1, 0.3);
252  Capsule capsule1 = Capsule(1.1, 1.3);
253 
254  test_accelerated_gjk(capsule0, capsule0);
255  test_accelerated_gjk(capsule1, capsule1);
256  test_accelerated_gjk(capsule0, capsule1);
257 }
258 
260  Box box0 = Box(0.1, 0.2, 0.3);
261  Box box1 = Box(1.1, 1.2, 1.3);
262  test_accelerated_gjk(box0, box0);
263  test_accelerated_gjk(box0, box1);
264  test_accelerated_gjk(box1, box1);
265 }
266 
268  Box box0 = Box(0.1, 0.2, 0.3);
269  Box box1 = Box(1.1, 1.2, 1.3);
270  Ellipsoid ellipsoid0 = Ellipsoid(0.5, 0.4, 0.3);
271  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
274 
275  test_accelerated_gjk(box0, cvx0);
276  test_accelerated_gjk(box0, cvx1);
277  test_accelerated_gjk(box1, cvx0);
278  test_accelerated_gjk(box1, cvx1);
279 }
280 
282  Ellipsoid ellipsoid0 = Ellipsoid(0.5, 0.4, 0.3);
283  Ellipsoid ellipsoid1 = Ellipsoid(1.5, 1.4, 1.3);
286 
287  test_accelerated_gjk(cvx0, cvx0);
288  test_accelerated_gjk(cvx0, cvx1);
289  test_accelerated_gjk(cvx1, cvx1);
290 }
coal::GJKSolver::gjk
EIGEN_MAKE_ALIGNED_OPERATOR_NEW details::GJK gjk
GJK algorithm.
Definition: coal/narrowphase/narrowphase.h:62
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::details::MinkowskiDiff::normalize_support_direction
bool normalize_support_direction
Wether or not to use the normalize heuristic in the GJK Nesterov acceleration. This setting is only a...
Definition: coal/narrowphase/minkowski_difference.h:79
collision_manager.box
box
Definition: collision_manager.py:11
coal::details::GJK::ray
Vec3s ray
Definition: coal/narrowphase/gjk.h:111
test_accelerated_gjk
void test_accelerated_gjk(const ShapeBase &shape0, const ShapeBase &shape1)
Definition: accelerated_gjk.cpp:107
coal::details::MinkowskiDiff
Minkowski difference class of two shapes.
Definition: coal/narrowphase/minkowski_difference.h:53
coal::details::GJK::gjk_variant
GJKVariant gjk_variant
Definition: coal/narrowphase/gjk.h:106
coal::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: coal/shape/geometric_shapes.h:383
coal::details::GJK::getNumIterations
size_t getNumIterations() const
Get the number of iterations of the last run of GJK.
Definition: coal/narrowphase/gjk.h:210
narrowphase.h
utility.h
coal::details::NoSweptSphere
@ NoSweptSphere
Definition: coal/narrowphase/support_functions.h:59
coal::GJKSolver
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were imple...
Definition: coal/narrowphase/narrowphase.h:57
coal::Ellipsoid
Ellipsoid centered at point zero.
Definition: coal/shape/geometric_shapes.h:305
coal::DefaultGJK
@ DefaultGJK
Definition: coal/data_types.h:98
coal::GJKVariant
GJKVariant
Variant to use for the GJK algorithm.
Definition: coal/data_types.h:98
coal::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::constructPolytopeFromEllipsoid
Convex< Triangle > constructPolytopeFromEllipsoid(const Ellipsoid &ellipsoid)
We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the origina...
Definition: utility.cpp:501
EIGEN_VECTOR_IS_APPROX
#define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision)
Definition: utility.h:59
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::NesterovAcceleration
@ NesterovAcceleration
Definition: coal/data_types.h:98
coal::support_func_guess_t
Eigen::Vector2i support_func_guess_t
Definition: coal/data_types.h:87
coal::ShapeBase
Base class for all basic geometric shapes.
Definition: coal/shape/geometric_shapes.h:58
coal::Convex
Convex polytope.
Definition: coal/serialization/collision_object.h:51
coal::PolyakAcceleration
@ PolyakAcceleration
Definition: coal/data_types.h:98
tools.h
coal::generateRandomTransforms
void generateRandomTransforms(CoalScalar extents[6], std::vector< Transform3s > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
Definition: utility.cpp:226
extents
CoalScalar extents[6]
Definition: test/geometric_shapes.cpp:53
coal::details::MinkowskiDiff::set
void set(const ShapeBase *shape0, const ShapeBase *shape1)
Set the two shapes, assuming the relative transformation between them is identity....
Definition: minkowski_difference.cpp:293
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(set_gjk_variant)
Definition: accelerated_gjk.cpp:65
coal::details::GJK::evaluate
Status evaluate(const MinkowskiDiff &shape, const Vec3s &guess, const support_func_guess_t &supportHint=support_func_guess_t::Zero())
GJK algorithm, given the initial value guess.
Definition: src/narrowphase/gjk.cpp:187
geometric_shapes.h
coal::details::GJK
class for GJK algorithm
Definition: coal/narrowphase/gjk.h:53
coal::Triangle
Triangle with 3 indices for points.
Definition: coal/data_types.h:111
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::details::SupportOptions
SupportOptions
Options for the computation of support points. NoSweptSphere option is used when the support function...
Definition: coal/narrowphase/support_functions.h:58
gjk
Definition: doc/gjk.py:1


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57