test_fcl_octomap_collision.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #include <gtest/gtest.h>
39 
40 #include "fcl/config.h"
52 #include "test_fcl_utility.h"
53 #include "fcl_resources/config.h"
54 
55 using namespace fcl;
56 
58 template <typename S>
59 void octomap_collision_test(S env_scale, std::size_t env_size, bool exhaustive, std::size_t num_max_contacts, bool use_mesh, bool use_mesh_octomap, double resolution = 0.1);
60 
63 template <typename S>
65  S env_scale,
66  std::size_t env_size,
67  std::size_t num_max_contacts,
68  double resolution = 0.1);
69 
70 template<typename BV>
71 void octomap_collision_test_BVH(std::size_t n, bool exhaustive, double resolution = 0.1);
72 
73 template <typename S>
75 {
76 #ifdef NDEBUG
77  octomap_collision_test<S>(200, 100, false, 10, false, false);
78  octomap_collision_test<S>(200, 1000, false, 10, false, false);
79  octomap_collision_test<S>(200, 100, true, 1, false, false);
80  octomap_collision_test<S>(200, 1000, true, 1, false, false);
81 #else
82  octomap_collision_test<S>(200, 10, false, 10, false, false, 0.1);
83  octomap_collision_test<S>(200, 100, false, 10, false, false, 0.1);
84  octomap_collision_test<S>(200, 10, true, 1, false, false, 0.1);
85  octomap_collision_test<S>(200, 100, true, 1, false, false, 0.1);
86 #endif
87 }
88 
90 {
91 // test_octomap_collision<float>();
92  test_octomap_collision<double>();
93 }
94 
95 template <typename S>
97 {
98 #ifdef NDEBUG
99  octomap_collision_test<S>(200, 100, false, 10, true, true);
100  octomap_collision_test<S>(200, 1000, false, 10, true, true);
101  octomap_collision_test<S>(200, 100, true, 1, true, true);
102  octomap_collision_test<S>(200, 1000, true, 1, true, true);
103 #else
104  octomap_collision_test<S>(200, 4, false, 1, true, true, 1.0);
105  octomap_collision_test<S>(200, 4, true, 1, true, true, 1.0);
106 #endif
107 }
108 
110 {
111 // test_octomap_collision_mesh<float>();
112  test_octomap_collision_mesh<double>();
113 }
114 
115 template <typename S>
117 {
118 #ifdef NDEBUG
119  octomap_collision_test_contact_primitive_id<S>(1, 30, 100000);
120 #else
121  octomap_collision_test_contact_primitive_id<S>(1, 10, 10000, 1.0);
122 #endif
123 }
124 
126 {
127 // test_octomap_collision_contact_primitive_id<float>();
128  test_octomap_collision_contact_primitive_id<double>();
129 }
130 
131 template <typename S>
133 {
134 #ifdef NDEBUG
135  octomap_collision_test<S>(200, 100, false, 10, true, false);
136  octomap_collision_test<S>(200, 1000, false, 10, true, false);
137  octomap_collision_test<S>(200, 100, true, 1, true, false);
138  octomap_collision_test<S>(200, 1000, true, 1, true, false);
139 #else
140  octomap_collision_test<S>(200, 4, false, 4, true, false, 1.0);
141  octomap_collision_test<S>(200, 4, true, 1, true, false, 1.0);
142 #endif
143 }
144 
146 {
147 // test_octomap_collision_mesh_octomap_box<float>();
148  test_octomap_collision_mesh_octomap_box<double>();
149 }
150 
151 template <typename S>
153 {
154 #ifdef NDEBUG
155  octomap_collision_test_BVH<OBB<S>>(5, false);
156  octomap_collision_test_BVH<OBB<S>>(5, true);
157 #else
158  octomap_collision_test_BVH<OBB<S>>(1, false, 1.0);
159  octomap_collision_test_BVH<OBB<S>>(1, true, 1.0);
160 #endif
161 }
162 
164 {
165 // test_octomap_bvh_obb_collision_obb<float>();
166  test_octomap_bvh_obb_collision_obb<double>();
167 }
168 
169 template<typename BV>
170 void octomap_collision_test_BVH(std::size_t n, bool exhaustive, double resolution)
171 {
172  using S = typename BV::S;
173 
174  std::vector<Vector3<S>> p1;
175  std::vector<Triangle> t1;
176 
177  test::loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1);
178 
179  BVHModel<BV>* m1 = new BVHModel<BV>();
180  std::shared_ptr<CollisionGeometry<S>> m1_ptr(m1);
181 
182  m1->beginModel();
183  m1->addSubModel(p1, t1);
184  m1->endModel();
185 
186  auto octree = std::shared_ptr<const octomap::OcTree>(
187  test::generateOcTree(resolution));
188  OcTree<S>* tree = new OcTree<S>(octree);
189  std::shared_ptr<CollisionGeometry<S>> tree_ptr(tree);
190 
191  // Check and make sure that the generated tree contains both free and
192  // occupied space. There was a time when it was impossible to represent free
193  // space, this part of the collision tests that both free and occupied space
194  // are correctly represented.
195  size_t free_nodes = 0;
196  size_t occupied_nodes = 0;
197  for (auto it = octree->begin(), end = octree->end(); it != end; ++it)
198  {
199  if (tree->isNodeFree(&*it))
200  ++free_nodes;
201  if (tree->isNodeOccupied(&*it))
202  ++occupied_nodes;
203  }
204  EXPECT_GT(free_nodes, 0UL);
205  EXPECT_GT(occupied_nodes, 0UL);
206 
207  aligned_vector<Transform3<S>> transforms;
208  S extents[] = {-10, -10, 10, 10, 10, 10};
209 
210  test::generateRandomTransforms(extents, transforms, n);
211 
212  for(std::size_t i = 0; i < n; ++i)
213  {
214  Transform3<S> tf(transforms[i]);
215 
216  CollisionObject<S> obj1(m1_ptr, tf);
217  CollisionObject<S> obj2(tree_ptr, tf);
219  if(exhaustive) cdata.request.num_max_contacts = 100000;
220 
221  DefaultCollisionFunction(&obj1, &obj2, &cdata);
222 
223 
224  std::vector<CollisionObject<S>*> boxes;
225  test::generateBoxesFromOctomap(boxes, *tree);
226  for(std::size_t j = 0; j < boxes.size(); ++j)
227  boxes[j]->setTransform(tf * boxes[j]->getTransform());
228 
230  manager->registerObjects(boxes);
231  manager->setup();
232 
234  if(exhaustive) cdata2.request.num_max_contacts = 100000;
235  manager->collide(&obj1, &cdata2, DefaultCollisionFunction);
236 
237  for(std::size_t j = 0; j < boxes.size(); ++j)
238  delete boxes[j];
239  delete manager;
240 
241  if(exhaustive)
242  {
243  std::cout << cdata.result.numContacts() << " " << cdata2.result.numContacts() << std::endl;
244  EXPECT_TRUE(cdata.result.numContacts() == cdata2.result.numContacts());
245  }
246  else
247  {
248  std::cout << (cdata.result.numContacts() > 0) << " " << (cdata2.result.numContacts() > 0) << std::endl;
249  EXPECT_TRUE((cdata.result.numContacts() > 0) == (cdata2.result.numContacts() > 0));
250  }
251  }
252 }
253 
254 template <typename S>
255 void octomap_collision_test(S env_scale, std::size_t env_size, bool exhaustive, std::size_t num_max_contacts, bool use_mesh, bool use_mesh_octomap, double resolution)
256 {
257  // srand(1);
258  std::vector<CollisionObject<S>*> env;
259  if(use_mesh)
260  test::generateEnvironmentsMesh(env, env_scale, env_size);
261  else
262  test::generateEnvironments(env, env_scale, env_size);
263 
264  OcTree<S>* tree = new OcTree<S>(std::shared_ptr<const octomap::OcTree>(test::generateOcTree(resolution)));
265  CollisionObject<S> tree_obj((std::shared_ptr<CollisionGeometry<S>>(tree)));
266 
268  manager->registerObjects(env);
269  manager->setup();
270 
272  if(exhaustive) cdata.request.num_max_contacts = 100000;
273  else cdata.request.num_max_contacts = num_max_contacts;
274 
275  test::TStruct t1;
276  test::Timer timer1;
277  timer1.start();
278  manager->octree_as_geometry_collide = false;
279  manager->octree_as_geometry_distance = false;
280  manager->collide(&tree_obj, &cdata, DefaultCollisionFunction);
281  timer1.stop();
282  t1.push_back(timer1.getElapsedTime());
283 
285  if(exhaustive) cdata3.request.num_max_contacts = 100000;
286  else cdata3.request.num_max_contacts = num_max_contacts;
287 
288  test::TStruct t3;
289  test::Timer timer3;
290  timer3.start();
291  manager->octree_as_geometry_collide = true;
292  manager->octree_as_geometry_distance = true;
293  manager->collide(&tree_obj, &cdata3, DefaultCollisionFunction);
294  timer3.stop();
295  t3.push_back(timer3.getElapsedTime());
296 
297  test::TStruct t2;
298  test::Timer timer2;
299  timer2.start();
300  std::vector<CollisionObject<S>*> boxes;
301  if(use_mesh_octomap)
302  test::generateBoxesFromOctomapMesh(boxes, *tree);
303  else
304  test::generateBoxesFromOctomap(boxes, *tree);
305  timer2.stop();
306  t2.push_back(timer2.getElapsedTime());
307 
308  timer2.start();
310  manager2->registerObjects(boxes);
311  manager2->setup();
312  timer2.stop();
313  t2.push_back(timer2.getElapsedTime());
314 
315 
317  if(exhaustive) cdata2.request.num_max_contacts = 100000;
318  else cdata2.request.num_max_contacts = num_max_contacts;
319 
320  timer2.start();
321  manager->collide(manager2, &cdata2, DefaultCollisionFunction);
322  timer2.stop();
323  t2.push_back(timer2.getElapsedTime());
324 
325  std::cout << cdata.result.numContacts() << " " << cdata3.result.numContacts() << " " << cdata2.result.numContacts() << std::endl;
326  if(exhaustive)
327  {
328  if(use_mesh) EXPECT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0));
329  else EXPECT_TRUE(cdata.result.numContacts() == cdata2.result.numContacts());
330  }
331  else
332  {
333  if(use_mesh) EXPECT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0));
334  else EXPECT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); // because AABB<S> return collision when two boxes contact
335  }
336 
337  delete manager;
338  delete manager2;
339  for(size_t i = 0; i < boxes.size(); ++i)
340  delete boxes[i];
341 
342  if(exhaustive) std::cout << "exhaustive collision" << std::endl;
343  else std::cout << "non exhaustive collision" << std::endl;
344  std::cout << "1) octomap overall time: " << t1.overall_time << std::endl;
345  std::cout << "1') octomap overall time (as geometry): " << t3.overall_time << std::endl;
346  std::cout << "2) boxes overall time: " << t2.overall_time << std::endl;
347  std::cout << " a) to boxes: " << t2.records[0] << std::endl;
348  std::cout << " b) structure init: " << t2.records[1] << std::endl;
349  std::cout << " c) collision: " << t2.records[2] << std::endl;
350  std::cout << "Note: octomap may need more collides when using mesh, because octomap collision uses box primitive inside" << std::endl;
351 }
352 
353 template <typename S>
355  S env_scale,
356  std::size_t env_size,
357  std::size_t num_max_contacts,
358  double resolution)
359 {
360  std::vector<CollisionObject<S>*> env;
361  test::generateEnvironmentsMesh(env, env_scale, env_size);
362  // An epsilon which scales with the domain of the of the octree.
363  // TODO(SeanCurtis-TRI): Figure out why this needs to be float
364  // tolerance, even for S = double (note previous spellings also used
365  // float tolerance).
366  const S kEps = env_scale * std::numeric_limits<float>::epsilon();
367 
368  std::shared_ptr<const octomap::OcTree> octree(
369  test::generateOcTree(resolution));
370  OcTree<S>* tree = new OcTree<S>(octree);
371  CollisionObject<S> tree_obj((std::shared_ptr<CollisionGeometry<S>>(tree)));
372 
373  std::vector<CollisionObject<S>*> boxes;
374  test::generateBoxesFromOctomap(boxes, *tree);
375  for(typename std::vector<CollisionObject<S>*>::const_iterator cit = env.begin();
376  cit != env.end(); ++cit)
377  {
378  fcl::CollisionRequest<S> req(num_max_contacts, true);
379  fcl::CollisionResult<S> cResult;
380  fcl::collide(&tree_obj, *cit, req, cResult);
381  for(std::size_t index=0; index<cResult.numContacts(); ++index)
382  {
383  const Contact<S>& contact = cResult.getContact(index);
384 
385  const fcl::OcTree<S>* contact_tree = static_cast<const fcl::OcTree<S>*>(
386  contact.o1);
388  octomap::OcTreeKey key;
389  unsigned int depth;
390  auto get_node_rv = contact_tree->getNodeByQueryCellId(
391  contact.b1,
392  contact.pos,
393  &aabb,
394  &key,
395  &depth);
396  EXPECT_TRUE(get_node_rv != nullptr);
397  auto center_octomap_point = octree->keyToCoord(key);
398  double cell_size = octree->getNodeSize(depth);
399  for (unsigned i = 0; i < 3; ++i)
400  {
401  EXPECT_NEAR(aabb.min_[i], center_octomap_point(i) - cell_size / 2.0,
402  kEps);
403  EXPECT_NEAR(aabb.max_[i], center_octomap_point(i) + cell_size / 2.0,
404  kEps);
405  }
406  auto octree_node = octree->search(key, depth);
407  EXPECT_TRUE(octree_node == get_node_rv);
408 
409  const fcl::BVHModel<fcl::OBBRSS<S>>* surface = static_cast<const fcl::BVHModel<fcl::OBBRSS<S>>*> (contact.o2);
410  EXPECT_TRUE(surface->num_tris > contact.b2);
411  }
412  }
413 }
414 
415 //==============================================================================
416 int main(int argc, char* argv[])
417 {
418  ::testing::InitGoogleTest(&argc, argv);
419  return RUN_ALL_TESTS();
420 }
void test_octomap_collision_mesh()
void generateEnvironmentsMesh(std::vector< CollisionObject< S > *> &env, S env_scale, std::size_t n)
Generate environment with 3 * n objects, but all in meshes.
int beginModel(int num_tris=0, int num_vertices=0)
Begin a new BVH model.
size_t numContacts() const
number of contacts found
std::array< S, 6 > & extents()
double getElapsedTime()
get elapsed time in milli-second
void octomap_collision_test_BVH(std::size_t n, bool exhaustive, double resolution=0.1)
void test_octomap_bvh_obb_collision_obb()
Main namespace.
collision result
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
intptr_t b1
contact primitive in object 1 if object 1 is mesh or point cloud, it is the triangle or point id if o...
Definition: contact.h:61
std::vector< double > records
CollisionObject< S > * obj1
void stop()
stop the timer
void octomap_collision_test_contact_primitive_id(S env_scale, std::size_t env_size, std::size_t num_max_contacts, double resolution=0.1)
Octomap collision with an environment mesh with 3 * env_size objects, asserting that correct triangle...
const Contact< S > & getContact(size_t i) const
get the i-th contact calculated
void octomap_collision_test(S env_scale, std::size_t env_size, bool exhaustive, std::size_t num_max_contacts, bool use_mesh, bool use_mesh_octomap, double resolution=0.1)
Octomap collision with an environment with 3 * env_size objects.
S epsilon()
void start()
start timer
Contact information returned by collision.
Definition: contact.h:48
#define EXPECT_NEAR(a, b, prec)
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
void test_octomap_collision_contact_primitive_id()
int addSubModel(const std::vector< Vector3< S >> &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
The geometry for the object for collision or distance computation.
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
int num_tris
Number of triangles.
Definition: BVH_model.h:171
void collide(CollisionObject< S > *obj, void *cdata, CollisionCallBack< S > callback) const
perform collision test between one object and all the objects belonging to the manager ...
Vector3< S > pos
contact position, in world space
Definition: contact.h:74
void setup()
initialize the manager, related with the specific type of manager
Parameters for performing collision request.
void generateEnvironments(std::vector< CollisionObject< S > *> &env, S env_scale, std::size_t n)
Generate environment with 3 * n objects: n boxes, n spheres and n cylinders.
int main(int argc, char *argv[])
GTEST_TEST(FCL_OCTOMAP, test_octomap_collision)
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
the object for collision or distance computation, contains the geometry and the transform information...
Collision data for use with the DefaultCollisionFunction. It stores the collision request and the res...
int num_max_contacts
CollisionObject< S > * obj2
void generateRandomTransforms(S extents[6], aligned_vector< Transform3< S >> &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
bool DefaultCollisionFunction(CollisionObject< S > *o1, CollisionObject< S > *o2, void *data)
Provides a simple callback for the collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DefaultCollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data&#39;s CollisionResult instance.
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
void push_back(double t)
void test_octomap_collision_mesh_octomap_box()
void loadOBJFile(const char *filename, std::vector< Vector3< S >> &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
static const double kEps
#define EXPECT_TRUE(args)
void registerObjects(const std::vector< CollisionObject< S > *> &other_objs)
add objects to the manager
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
Definition: types.h:122
intptr_t b2
contact primitive in object 2 if object 2 is mesh or point cloud, it is the triangle or point id if o...
Definition: contact.h:68
const CollisionGeometry< S > * o2
collision object 2
Definition: contact.h:54
void test_octomap_collision()
const CollisionGeometry< S > * o1
collision object 1
Definition: contact.h:51


fcl_catkin
Author(s):
autogenerated on Thu Mar 23 2023 03:00:19