gjk_convergence_criterion.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 #include <boost/test/tools/old/interface.hpp>
40 
41 #include <Eigen/Geometry>
42 #include "coal/data_types.h"
45 #include "coal/internal/tools.h"
46 
47 #include "utility.h"
48 
49 using coal::Box;
50 using coal::CoalScalar;
53 using coal::GJKSolver;
54 using coal::ShapeBase;
56 using coal::Transform3s;
57 using coal::Vec3s;
58 using coal::details::GJK;
60 using std::size_t;
61 
62 BOOST_AUTO_TEST_CASE(set_cv_criterion) {
63  GJKSolver solver;
64  GJK gjk(128, 1e-6);
65 
66  // Checking defaults
67  BOOST_CHECK(solver.gjk.convergence_criterion ==
69  BOOST_CHECK(solver.gjk.convergence_criterion_type ==
71 
72  BOOST_CHECK(gjk.convergence_criterion == GJKConvergenceCriterion::Default);
73  BOOST_CHECK(gjk.convergence_criterion_type ==
75 
76  // Checking set
78  gjk.convergence_criterion = GJKConvergenceCriterion::DualityGap;
80  gjk.convergence_criterion_type = GJKConvergenceCriterionType::Absolute;
81 
82  BOOST_CHECK(solver.gjk.convergence_criterion ==
84  BOOST_CHECK(solver.gjk.convergence_criterion_type ==
86 
87  BOOST_CHECK(gjk.convergence_criterion == GJKConvergenceCriterion::DualityGap);
88  BOOST_CHECK(gjk.convergence_criterion_type ==
90 }
91 
92 void test_gjk_cv_criterion(const ShapeBase& shape0, const ShapeBase& shape1,
93  const GJKConvergenceCriterionType cv_type) {
94  // Solvers
95  unsigned int max_iterations = 128;
96  // by default GJK uses the VDB convergence criterion, which is relative.
97  GJK gjk1(max_iterations, 1e-6);
98 
99  CoalScalar tol;
100  switch (cv_type) {
101  // need to lower the tolerance when absolute
103  tol = 1e-8;
104  break;
106  tol = 1e-6;
107  break;
108  default:
109  throw std::logic_error("Wrong convergence criterion type");
110  }
111 
112  GJK gjk2(max_iterations, tol);
114  gjk2.convergence_criterion_type = cv_type;
115 
116  GJK gjk3(max_iterations, tol);
118  gjk3.convergence_criterion_type = cv_type;
119 
120  // Minkowski difference
121  MinkowskiDiff mink_diff;
122 
123  // Generate random transforms
124  size_t n = 1000;
125  CoalScalar extents[] = {-3., -3., 0, 3., 3., 3.};
126  std::vector<Transform3s> transforms;
127  generateRandomTransforms(extents, transforms, n);
128  Transform3s identity = Transform3s::Identity();
129 
130  // Same init for both solvers
131  Vec3s init_guess = Vec3s(1, 0, 0);
132  support_func_guess_t init_support_guess;
133  init_support_guess.setZero();
134 
135  // Run for 3 different cv criterions
136  for (size_t i = 0; i < n; ++i) {
137  mink_diff.set<false>(&shape0, &shape1, identity, transforms[i]);
138 
139  GJK::Status res1 = gjk1.evaluate(mink_diff, init_guess, init_support_guess);
140  BOOST_CHECK(gjk1.getNumIterations() <= max_iterations);
141  Vec3s ray1 = gjk1.ray;
142  res1 = gjk1.evaluate(mink_diff, init_guess, init_support_guess);
143  BOOST_CHECK(res1 != GJK::Status::Failed);
144  EIGEN_VECTOR_IS_APPROX(gjk1.ray, ray1, 1e-8);
145 
146  GJK::Status res2 = gjk2.evaluate(mink_diff, init_guess, init_support_guess);
147  BOOST_CHECK(gjk2.getNumIterations() <= max_iterations);
148  Vec3s ray2 = gjk2.ray;
149  res2 = gjk2.evaluate(mink_diff, init_guess, init_support_guess);
150  BOOST_CHECK(res2 != GJK::Status::Failed);
151  EIGEN_VECTOR_IS_APPROX(gjk2.ray, ray2, 1e-8);
152 
153  GJK::Status res3 = gjk3.evaluate(mink_diff, init_guess, init_support_guess);
154  BOOST_CHECK(gjk3.getNumIterations() <= max_iterations);
155  Vec3s ray3 = gjk3.ray;
156  res3 = gjk3.evaluate(mink_diff, init_guess, init_support_guess);
157  BOOST_CHECK(res3 != GJK::Status::Failed);
158  EIGEN_VECTOR_IS_APPROX(gjk3.ray, ray3, 1e-8);
159 
160  // check that solutions are close enough
161  EIGEN_VECTOR_IS_APPROX(gjk1.ray, gjk2.ray, 1e-4);
162  EIGEN_VECTOR_IS_APPROX(gjk1.ray, gjk3.ray, 1e-4);
163  }
164 }
165 
166 BOOST_AUTO_TEST_CASE(cv_criterion_same_solution) {
167  Box box0 = Box(0.1, 0.2, 0.3);
168  Box box1 = Box(1.1, 1.2, 1.3);
171 }
coal::GJKConvergenceCriterion
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
Definition: coal/data_types.h:104
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::Hybrid
@ Hybrid
Definition: coal/data_types.h:104
coal::details::GJK::ray
Vec3s ray
Definition: coal/narrowphase/gjk.h:111
coal::details::MinkowskiDiff
Minkowski difference class of two shapes.
Definition: coal/narrowphase/minkowski_difference.h:53
coal::GJKConvergenceCriterionType
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
Definition: coal/data_types.h:108
coal::Relative
@ Relative
Definition: coal/data_types.h:108
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::GJK::convergence_criterion
GJKConvergenceCriterion convergence_criterion
Definition: coal/narrowphase/gjk.h:107
coal::Default
@ Default
Definition: coal/data_types.h:104
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::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
test_gjk_cv_criterion
void test_gjk_cv_criterion(const ShapeBase &shape0, const ShapeBase &shape1, const GJKConvergenceCriterionType cv_type)
Definition: gjk_convergence_criterion.cpp:92
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::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::details::GJK::convergence_criterion_type
GJKConvergenceCriterionType convergence_criterion_type
Definition: coal/narrowphase/gjk.h:108
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
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(set_cv_criterion)
Definition: gjk_convergence_criterion.cpp:62
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
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::DualityGap
@ DualityGap
Definition: coal/data_types.h:104
coal::details::GJK
class for GJK algorithm
Definition: coal/narrowphase/gjk.h:53
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
gjk
Definition: doc/gjk.py:1
coal::Absolute
@ Absolute
Definition: coal/data_types.h:108


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