shape_inflation.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 
35 #define BOOST_TEST_MODULE FCL_SECURITY_MARGIN
36 #include <boost/test/included/unit_test.hpp>
37 
38 #include <cmath>
39 #include <iostream>
40 #include <hpp/fcl/distance.h>
41 #include <hpp/fcl/math/transform.h>
42 #include <hpp/fcl/collision.h>
46 
47 #include "utility.h"
48 
49 using namespace hpp::fcl;
57 using hpp::fcl::Vec3f;
58 
59 #define MATH_SQUARED(x) (x * x)
60 
61 template <typename Shape>
62 bool isApprox(const Shape &s1, const Shape &s2, const FCL_REAL tol);
63 
64 bool isApprox(const FCL_REAL &v1, const FCL_REAL &v2, const FCL_REAL tol) {
65  typedef Eigen::Matrix<FCL_REAL, 1, 1> ScalarMatrix;
66  ScalarMatrix m1;
67  m1 << v1;
68  ScalarMatrix m2;
69  m2 << v2;
70  return m1.isApprox(m2, tol);
71 }
72 
73 bool isApprox(const Box &s1, const Box &s2, const FCL_REAL tol) {
74  return s1.halfSide.isApprox(s2.halfSide, tol);
75 }
76 
77 bool isApprox(const Sphere &s1, const Sphere &s2, const FCL_REAL tol) {
78  return isApprox(s1.radius, s2.radius, tol);
79 }
80 
81 bool isApprox(const Ellipsoid &s1, const Ellipsoid &s2, const FCL_REAL tol) {
82  return s1.radii.isApprox(s2.radii, tol);
83 }
84 
85 bool isApprox(const Capsule &s1, const Capsule &s2, const FCL_REAL tol) {
86  return isApprox(s1.radius, s2.radius, tol) &&
87  isApprox(s1.halfLength, s2.halfLength, tol);
88 }
89 
90 bool isApprox(const Cylinder &s1, const Cylinder &s2, const FCL_REAL tol) {
91  return isApprox(s1.radius, s2.radius, tol) &&
92  isApprox(s1.halfLength, s2.halfLength, tol);
93 }
94 
95 bool isApprox(const Cone &s1, const Cone &s2, const FCL_REAL tol) {
96  return isApprox(s1.radius, s2.radius, tol) &&
97  isApprox(s1.halfLength, s2.halfLength, tol);
98 }
99 
100 bool isApprox(const TriangleP &s1, const TriangleP &s2, const FCL_REAL tol) {
101  return s1.a.isApprox(s2.a, tol) && s1.b.isApprox(s2.b, tol) &&
102  s1.c.isApprox(s2.c, tol);
103 }
104 
105 bool isApprox(const Halfspace &s1, const Halfspace &s2, const FCL_REAL tol) {
106  return isApprox(s1.d, s2.d, tol) && s1.n.isApprox(s2.n, tol);
107 }
108 
109 template <typename Shape>
110 void test(const Shape &original_shape, const FCL_REAL inflation,
111  const FCL_REAL tol = 1e-8) {
112  // Zero inflation
113  {
114  const FCL_REAL inflation = 0.;
115  const auto &inflation_result = original_shape.inflated(inflation);
116  const Transform3f &shift = inflation_result.second;
117  const Shape &inflated_shape = inflation_result.first;
118 
119  BOOST_CHECK(isApprox(original_shape, inflated_shape, tol));
120  BOOST_CHECK(shift.isIdentity(tol));
121  }
122 
123  // Positive inflation
124  {
125  const auto &inflation_result = original_shape.inflated(inflation);
126  const Shape &inflated_shape = inflation_result.first;
127  const Transform3f &inflation_shift = inflation_result.second;
128 
129  BOOST_CHECK(!isApprox(original_shape, inflated_shape, tol));
130 
131  const auto &deflation_result = inflated_shape.inflated(-inflation);
132  const Shape &deflated_shape = deflation_result.first;
133  const Transform3f &deflation_shift = deflation_result.second;
134 
135  BOOST_CHECK(isApprox(original_shape, deflated_shape, tol));
136  BOOST_CHECK((inflation_shift * deflation_shift).isIdentity(tol));
137  }
138 
139  // Negative inflation
140  {
141  const auto &inflation_result = original_shape.inflated(-inflation);
142  const Shape &inflated_shape = inflation_result.first;
143  const Transform3f &inflation_shift = inflation_result.second;
144 
145  BOOST_CHECK(!isApprox(original_shape, inflated_shape, tol));
146 
147  const auto &deflation_result = inflated_shape.inflated(+inflation);
148  const Shape &deflated_shape = deflation_result.first;
149  const Transform3f &deflation_shift = deflation_result.second;
150 
151  BOOST_CHECK(isApprox(original_shape, deflated_shape, tol));
152  BOOST_CHECK((inflation_shift * deflation_shift).isIdentity(tol));
153  }
154 }
155 
156 template <typename Shape>
157 void test_throw(const Shape &shape, const FCL_REAL inflation) {
158  BOOST_REQUIRE_THROW(shape.inflated(inflation), std::invalid_argument);
159 }
160 
161 template <typename Shape>
162 void test_no_throw(const Shape &shape, const FCL_REAL inflation) {
163  BOOST_REQUIRE_NO_THROW(shape.inflated(inflation));
164 }
165 
166 BOOST_AUTO_TEST_CASE(test_inflate) {
167  const hpp::fcl::Sphere sphere(1);
168  test(sphere, 0.01, 1e-8);
169  test_throw(sphere, -1.1);
170  test_no_throw(sphere, 1.);
171 
172  const hpp::fcl::Box box(1, 1, 1);
173  test(box, 0.01, 1e-8);
174  test_throw(box, -0.6);
175 
176  const hpp::fcl::Ellipsoid ellipsoid(1, 2, 3);
177  test(ellipsoid, 0.01, 1e-8);
178  test_throw(ellipsoid, -1.1);
179 
180  const hpp::fcl::Capsule capsule(1., 2.);
181  test(capsule, 0.01, 1e-8);
182  test_throw(capsule, -1.1);
183 
184  const hpp::fcl::Cylinder cylinder(1., 2.);
185  test(cylinder, 0.01, 1e-8);
186  test_throw(cylinder, -1.1);
187 
188  const hpp::fcl::Cone cone(1., 4.);
189  test(cone, 0.01, 1e-8);
190  test_throw(cone, -1.1);
191 
192  const hpp::fcl::Halfspace halfspace(Vec3f::UnitZ(), 0.);
193  test(halfspace, 0.01, 1e-8);
194 
195  // const hpp::fcl::TriangleP triangle(Vec3f::UnitX(), Vec3f::UnitY(),
196  // Vec3f::UnitZ());
197  // test(triangle, 0.01, 1e-8);
198 }
hpp::fcl::Cylinder::radius
FCL_REAL radius
Radius of the cylinder.
Definition: shape/geometric_shapes.h:522
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
test_throw
void test_throw(const Shape &shape, const FCL_REAL inflation)
Definition: shape_inflation.cpp:157
collision_object.h
collision_manager.box
box
Definition: collision_manager.py:11
test
void test(const Shape &original_shape, const FCL_REAL inflation, const FCL_REAL tol=1e-8)
Definition: shape_inflation.cpp:110
hpp::fcl::TriangleP::c
Vec3f c
Definition: shape/geometric_shapes.h:109
collision_manager.sphere
sphere
Definition: collision_manager.py:4
hpp::fcl::Sphere
Center at zero point sphere.
Definition: shape/geometric_shapes.h:196
hpp::fcl::Capsule::radius
FCL_REAL radius
Radius of capsule.
Definition: shape/geometric_shapes.h:346
utility.h
isApprox
bool isApprox(const Shape &s1, const Shape &s2, const FCL_REAL tol)
hpp::fcl::CollisionGeometryPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: include/hpp/fcl/fwd.hh:96
hpp::fcl::Box::halfSide
Vec3f halfSide
box side half-length
Definition: shape/geometric_shapes.h:148
hpp::fcl::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: shape/geometric_shapes.h:501
hpp::fcl::Capsule::halfLength
FCL_REAL halfLength
Half Length along z axis.
Definition: shape/geometric_shapes.h:352
hpp::fcl::TriangleP::b
Vec3f b
Definition: shape/geometric_shapes.h:109
geometric_shapes_utility.h
hpp::fcl::Cylinder::halfLength
FCL_REAL halfLength
Half Length along z axis.
Definition: shape/geometric_shapes.h:528
hpp::fcl::Ellipsoid
Ellipsoid centered at point zero.
Definition: shape/geometric_shapes.h:258
distance.h
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::Sphere::radius
FCL_REAL radius
Radius of the sphere.
Definition: shape/geometric_shapes.h:206
hpp::fcl::Transform3f::isIdentity
bool isIdentity(const FCL_REAL &prec=Eigen::NumTraits< FCL_REAL >::dummy_precision()) const
check whether the transform is identity
Definition: transform.h:187
hpp::fcl::CollisionRequest
request to the collision algorithm
Definition: collision_data.h:235
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
hpp::fcl::CollisionResult
collision result
Definition: collision_data.h:302
hpp::fcl::Cone
Cone The base of the cone is at and the top is at .
Definition: shape/geometric_shapes.h:414
test_no_throw
void test_no_throw(const Shape &shape, const FCL_REAL inflation)
Definition: shape_inflation.cpp:162
hpp::fcl::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: shape/geometric_shapes.h:333
hpp::fcl::Cone::radius
FCL_REAL radius
Radius of the cone.
Definition: shape/geometric_shapes.h:427
hpp::fcl
Definition: broadphase_bruteforce.h:45
hpp::fcl::TriangleP::a
Vec3f a
Definition: shape/geometric_shapes.h:109
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::Halfspace
Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Poi...
Definition: shape/geometric_shapes.h:729
hpp::fcl::DistanceRequest
request to the distance computation
Definition: collision_data.h:392
hpp::fcl::DistanceResult
distance result
Definition: collision_data.h:420
hpp::fcl::UnitZ
const Vec3f UnitZ
Definition: utility.cpp:89
transform.h
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_inflate)
Definition: shape_inflation.cpp:166
hpp::fcl::TriangleP
Triangle stores the points instead of only indices of points.
Definition: shape/geometric_shapes.h:71
hpp::fcl::Cone::halfLength
FCL_REAL halfLength
Half Length along z axis.
Definition: shape/geometric_shapes.h:433
geometric_shapes.h
hpp::fcl::Halfspace::d
FCL_REAL d
Plane offset.
Definition: shape/geometric_shapes.h:790
hpp::fcl::Halfspace::n
Vec3f n
Plane normal.
Definition: shape/geometric_shapes.h:787
collision.h
hpp::fcl::Ellipsoid::radii
Vec3f radii
Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2.
Definition: shape/geometric_shapes.h:271
hpp::fcl::Box
Center at zero point, axis aligned box.
Definition: shape/geometric_shapes.h:125


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:15