distance_lower_bound.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014-2016, CNRS-LAAS
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 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 COAL_DISTANCE_LOWER_BOUND
36 #include <boost/test/included/unit_test.hpp>
37 #include <boost/filesystem.hpp>
38 
39 #include "coal/fwd.hh"
40 #include "coal/data_types.h"
41 #include "coal/BV/OBBRSS.h"
42 #include "coal/BVH/BVH_model.h"
44 #include "coal/collision.h"
45 #include "coal/distance.h"
46 #include "utility.h"
47 #include "fcl_resources/config.h"
48 
49 using coal::BVHModel;
50 using coal::CoalScalar;
57 using coal::OBBRSS;
58 using coal::shared_ptr;
59 using coal::Transform3s;
60 using coal::Triangle;
61 using coal::Vec3s;
62 
64  const CollisionGeometryPtr_t& m1,
65  const CollisionGeometryPtr_t& m2,
67  Transform3s pose1(tf), pose2;
68 
69  CollisionRequest request;
70 
71  CollisionResult result;
72  CollisionObject co1(m1, pose1);
73  CollisionObject co2(m2, pose2);
74 
75  coal::collide(&co1, &co2, request, result);
77 
78  return result.isCollision();
79 }
80 
82  const CollisionGeometryPtr_t& m2) {
83  Transform3s pose1(tf), pose2;
84 
86  request.enable_distance_lower_bound = false;
87 
88  CollisionResult result;
89  CollisionObject co1(m1, pose1);
90  CollisionObject co2(m2, pose2);
91 
92  coal::collide(&co1, &co2, request, result);
93  return result.isCollision();
94 }
95 
98  Transform3s pose1(tf), pose2;
99 
100  DistanceRequest request;
101  DistanceResult result;
102  CollisionObject co1(m1, pose1);
103  CollisionObject co2(m2, pose2);
104 
105  coal::distance(&co1, &co2, request, result);
106  distance = result.min_distance;
107 
108  if (result.min_distance <= 0) {
109  return true;
110  } else {
111  return false;
112  }
113 }
114 
116  std::vector<Vec3s> p1, p2;
117  std::vector<Triangle> t1, t2;
118  boost::filesystem::path path(TEST_RESOURCES_DIR);
119 
120  loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
121  loadOBJFile((path / "rob.obj").string().c_str(), p2, t2);
122 
123  shared_ptr<BVHModel<OBBRSS> > m1(new BVHModel<OBBRSS>);
124  shared_ptr<BVHModel<OBBRSS> > m2(new BVHModel<OBBRSS>);
125 
126  m1->beginModel();
127  m1->addSubModel(p1, t1);
128  m1->endModel();
129 
130  m2->beginModel();
131  m2->addSubModel(p2, t2);
132  m2->endModel();
133 
134  std::vector<Transform3s> transforms;
135  CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
136  std::size_t n = 100;
137 
138  generateRandomTransforms(extents, transforms, n);
139 
140  // collision
141  for (std::size_t i = 0; i < transforms.size(); ++i) {
142  CoalScalar distanceLowerBound, distance;
143  bool col1, col2, col3;
144  col1 = testDistanceLowerBound(transforms[i], m1, m2, distanceLowerBound);
145  col2 = testDistance(transforms[i], m1, m2, distance);
146  col3 = testCollide(transforms[i], m1, m2);
147  std::cout << "col1 = " << col1 << ", col2 = " << col2 << ", col3 = " << col3
148  << std::endl;
149  std::cout << "distance lower bound = " << distanceLowerBound << std::endl;
150  std::cout << "distance = " << distance << std::endl;
151  BOOST_CHECK(col1 == col3);
152  if (!col1) {
153  BOOST_CHECK_MESSAGE(distanceLowerBound <= distance,
154  "distance = " << distance << ", lower bound = "
155  << distanceLowerBound);
156  }
157  }
158 }
159 
160 BOOST_AUTO_TEST_CASE(box_sphere) {
161  shared_ptr<coal::Sphere> sphere(new coal::Sphere(0.5));
162  shared_ptr<coal::Box> box(new coal::Box(1., 1., 1.));
163 
164  Transform3s M1;
165  M1.setIdentity();
166  Transform3s M2;
167  M2.setIdentity();
168 
169  std::vector<Transform3s> transforms;
170  CoalScalar extents[] = {-2., -2., -2., 2., 2., 2.};
171  const std::size_t n = 1000;
172 
173  generateRandomTransforms(extents, transforms, n);
174 
175  CoalScalar distanceLowerBound, distance;
176  bool col1, col2;
177  col1 = testDistanceLowerBound(M1, sphere, box, distanceLowerBound);
178  col2 = testDistance(M1, sphere, box, distance);
179  BOOST_CHECK(col1 == col2);
180  BOOST_CHECK(distanceLowerBound <= distance);
181 
182  for (std::size_t i = 0; i < transforms.size(); ++i) {
183  CoalScalar distanceLowerBound, distance;
184  bool col1, col2;
185  col1 =
186  testDistanceLowerBound(transforms[i], sphere, box, distanceLowerBound);
187  col2 = testDistance(transforms[i], sphere, box, distance);
188  BOOST_CHECK(col1 == col2);
189  if (!col1) {
190  BOOST_CHECK_MESSAGE(distanceLowerBound <= distance,
191  "distance = " << distance << ", lower bound = "
192  << distanceLowerBound);
193  }
194  }
195 }
196 
197 BOOST_AUTO_TEST_CASE(sphere_sphere) {
198  shared_ptr<coal::Sphere> sphere1(new coal::Sphere(0.5));
199  shared_ptr<coal::Sphere> sphere2(new coal::Sphere(1.));
200 
201  Transform3s M1;
202  M1.setIdentity();
203  Transform3s M2;
204  M2.setIdentity();
205 
206  std::vector<Transform3s> transforms;
207  CoalScalar extents[] = {-2., -2., -2., 2., 2., 2.};
208  const std::size_t n = 1000;
209 
210  generateRandomTransforms(extents, transforms, n);
211 
212  CoalScalar distanceLowerBound, distance;
213  bool col1, col2;
214  col1 = testDistanceLowerBound(M1, sphere1, sphere2, distanceLowerBound);
215  col2 = testDistance(M1, sphere1, sphere2, distance);
216  BOOST_CHECK(col1 == col2);
217  BOOST_CHECK(distanceLowerBound <= distance);
218 
219  for (std::size_t i = 0; i < transforms.size(); ++i) {
220  CoalScalar distanceLowerBound, distance;
221  bool col1, col2;
222  col1 = testDistanceLowerBound(transforms[i], sphere1, sphere2,
223  distanceLowerBound);
224  col2 = testDistance(transforms[i], sphere1, sphere2, distance);
225  BOOST_CHECK(col1 == col2);
226  if (!col1) {
227  BOOST_CHECK_MESSAGE(distanceLowerBound <= distance,
228  "distance = " << distance << ", lower bound = "
229  << distanceLowerBound);
230  }
231  }
232 }
233 
235  std::vector<Vec3s> p1;
236  std::vector<Triangle> t1;
237  boost::filesystem::path path(TEST_RESOURCES_DIR);
238 
239  loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
240 
241  shared_ptr<BVHModel<OBBRSS> > m1(new BVHModel<OBBRSS>);
242  shared_ptr<coal::Box> m2(new coal::Box(500, 200, 150));
243 
244  m1->beginModel();
245  m1->addSubModel(p1, t1);
246  m1->endModel();
247 
248  std::vector<Transform3s> transforms;
249  CoalScalar extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
250  std::size_t n = 100;
251 
252  generateRandomTransforms(extents, transforms, n);
253 
254  // collision
255  for (std::size_t i = 0; i < transforms.size(); ++i) {
256  CoalScalar distanceLowerBound, distance;
257  bool col1, col2;
258  col1 = testDistanceLowerBound(transforms[i], m1, m2, distanceLowerBound);
259  col2 = testDistance(transforms[i], m1, m2, distance);
260  BOOST_CHECK(col1 == col2);
261  if (!col1) {
262  BOOST_CHECK_MESSAGE(distanceLowerBound <= distance,
263  "distance = " << distance << ", lower bound = "
264  << distanceLowerBound);
265  }
266  }
267 }
collision.h
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
testDistance
bool testDistance(const Transform3s &tf, const CollisionGeometryPtr_t &m1, const CollisionGeometryPtr_t &m2, CoalScalar &distance)
Definition: distance_lower_bound.cpp:96
collision_manager.box
box
Definition: collision_manager.py:11
coal::CollisionResult::isCollision
bool isCollision() const
return binary collision result
Definition: coal/collision_data.h:443
collision_manager.sphere
sphere
Definition: collision_manager.py:4
testCollide
bool testCollide(const Transform3s &tf, const CollisionGeometryPtr_t &m1, const CollisionGeometryPtr_t &m2)
Definition: distance_lower_bound.cpp:81
coal::CollisionRequest::enable_distance_lower_bound
bool enable_distance_lower_bound
Whether a lower bound on distance is returned when objects are disjoint.
Definition: coal/collision_data.h:321
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(mesh_mesh)
Definition: distance_lower_bound.cpp:115
distance
double distance(const std::vector< Transform3s > &tf, const BVHModel< BV > &m1, const BVHModel< BV > &m2, bool verbose)
Definition: benchmark.cpp:93
narrowphase.h
utility.h
coal::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
coal::NO_REQUEST
@ NO_REQUEST
Definition: coal/collision_data.h:307
coal::CollisionResult::distance_lower_bound
CoalScalar distance_lower_bound
Definition: coal/collision_data.h:401
coal::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::Sphere
Center at zero point sphere.
Definition: coal/shape/geometric_shapes.h:240
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::DistanceResult::min_distance
CoalScalar min_distance
minimum distance between two objects. If two objects are in collision and DistanceRequest::enable_sig...
Definition: coal/collision_data.h:1058
BVH_model.h
coal::OBBRSS
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: coal/BV/OBBRSS.h:53
coal::DistanceRequest
request to the distance computation
Definition: coal/collision_data.h:985
t2
dictionary t2
fwd.hh
coal::CollisionResult
collision result
Definition: coal/collision_data.h:390
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
distance.h
coal::DistanceResult
distance result
Definition: coal/collision_data.h:1051
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
coal::Transform3s::setIdentity
void setIdentity()
set the transform to be identity transform
Definition: coal/math/transform.h:199
collision.path
path
Definition: scripts/collision.py:6
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
octree.p1
tuple p1
Definition: octree.py:54
coal::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: coal/BVH/BVH_model.h:314
OBBRSS.h
coal::collide
COAL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts,...
Definition: src/collision.cpp:61
coal::Triangle
Triangle with 3 indices for points.
Definition: coal/data_types.h:111
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::CollisionGeometryPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: include/coal/fwd.hh:134
coal::loadOBJFile
void loadOBJFile(const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
Definition: utility.cpp:97
testDistanceLowerBound
bool testDistanceLowerBound(const Transform3s &tf, const CollisionGeometryPtr_t &m1, const CollisionGeometryPtr_t &m2, CoalScalar &distance)
Definition: distance_lower_bound.cpp:63


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