test_fcl_frontlist.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 
41 #include "test_fcl_utility.h"
42 
43 #include "fcl_resources/config.h"
44 
45 using namespace fcl;
46 
47 template<typename BV>
49  const std::vector<Vector3<typename BV::S>>& vertices1, const std::vector<Triangle>& triangles1,
50  const std::vector<Vector3<typename BV::S>>& vertices2, const std::vector<Triangle>& triangles2,
51  detail::SplitMethodType split_method,
52  bool refit_bottomup, bool verbose);
53 
54 template<typename BV, typename TraversalNode>
56  const std::vector<Vector3<typename BV::S>>& vertices1, const std::vector<Triangle>& triangles1,
57  const std::vector<Vector3<typename BV::S>>& vertices2, const std::vector<Triangle>& triangles2,
58  detail::SplitMethodType split_method, bool verbose);
59 
60 
61 template<typename BV>
63  const std::vector<Vector3<typename BV::S>>& vertices1, const std::vector<Triangle>& triangles1,
64  const std::vector<Vector3<typename BV::S>>& vertices2, const std::vector<Triangle>& triangles2, detail::SplitMethodType split_method, bool verbose);
65 
66 // TODO: randomly still have some runtime error
67 template <typename S>
69 {
70  std::vector<Vector3<S>> p1, p2;
71  std::vector<Triangle> t1, t2;
72 
73  test::loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1);
74  test::loadOBJFile(TEST_RESOURCES_DIR"/rob.obj", p2, t2);
75 
76  aligned_vector<Transform3<S>> transforms; // t0
77  aligned_vector<Transform3<S>> transforms2; // t1
78  S extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
79  S delta_trans[] = {1, 1, 1};
80 #ifdef NDEBUG
81  std::size_t n = 10;
82 #else
83  std::size_t n = 1;
84 #endif
85  bool verbose = false;
86 
87  test::generateRandomTransforms<S>(extents, delta_trans, 0.005 * 2 * 3.1415, transforms, transforms2, n);
88 
89  bool res, res2;
90 
91  for(std::size_t i = 0; i < transforms.size(); ++i)
92  {
93  res = collide_Test<AABB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
94  res2 = collide_front_list_Test<AABB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, false, verbose);
95  EXPECT_TRUE(res == res2);
96  res = collide_Test<AABB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
97  res2 = collide_front_list_Test<AABB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, false, verbose);
98  EXPECT_TRUE(res == res2);
99  res = collide_Test<AABB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
100  res2 = collide_front_list_Test<AABB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, false, verbose);
101  EXPECT_TRUE(res == res2);
102  }
103 
104  for(std::size_t i = 0; i < transforms.size(); ++i)
105  {
106  res = collide_Test<OBB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
107  res2 = collide_front_list_Test<OBB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, false, verbose);
108  EXPECT_TRUE(res == res2);
109  res = collide_Test<OBB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
110  res2 = collide_front_list_Test<OBB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, false, verbose);
111  EXPECT_TRUE(res == res2);
112  res = collide_Test<OBB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
113  res2 = collide_front_list_Test<OBB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, false, verbose);
114  EXPECT_TRUE(res == res2);
115  }
116 
117  for(std::size_t i = 0; i < transforms.size(); ++i)
118  {
119  // Disabled broken test lines. Please see #25.
120  // res = collide_Test<RSS<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
121  // res2 = collide_front_list_Test<RSS<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, false, verbose);
122  // EXPECT_TRUE(res == res2);
123  res = collide_Test<RSS<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
124  res2 = collide_front_list_Test<RSS<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, false, verbose);
125  EXPECT_TRUE(res == res2);
126  res = collide_Test<RSS<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
127  res2 = collide_front_list_Test<RSS<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, false, verbose);
128  EXPECT_TRUE(res == res2);
129  }
130 
131  for(std::size_t i = 0; i < transforms.size(); ++i)
132  {
133  res = collide_Test<KDOP<S, 16> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
134  res2 = collide_front_list_Test<KDOP<S, 16> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, false, verbose);
135  EXPECT_TRUE(res == res2);
136  res = collide_Test<KDOP<S, 16> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
137  res2 = collide_front_list_Test<KDOP<S, 16> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, false, verbose);
138  EXPECT_TRUE(res == res2);
139  res = collide_Test<KDOP<S, 16> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
140  res2 = collide_front_list_Test<KDOP<S, 16> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, false, verbose);
141  EXPECT_TRUE(res == res2);
142  }
143 
144  for(std::size_t i = 0; i < transforms.size(); ++i)
145  {
146  res = collide_Test<KDOP<S, 18> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
147  res2 = collide_front_list_Test<KDOP<S, 18> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, false, verbose);
148  EXPECT_TRUE(res == res2);
149  res = collide_Test<KDOP<S, 18> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
150  res2 = collide_front_list_Test<KDOP<S, 18> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, false, verbose);
151  EXPECT_TRUE(res == res2);
152  res = collide_Test<KDOP<S, 18> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
153  res2 = collide_front_list_Test<KDOP<S, 18> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, false, verbose);
154  EXPECT_TRUE(res == res2);
155  }
156 
157  for(std::size_t i = 0; i < transforms.size(); ++i)
158  {
159  res = collide_Test<KDOP<S, 24> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
160  res2 = collide_front_list_Test<KDOP<S, 24> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, false, verbose);
161  EXPECT_TRUE(res == res2);
162  res = collide_Test<KDOP<S, 24> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
163  res2 = collide_front_list_Test<KDOP<S, 24> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, false, verbose);
164  EXPECT_TRUE(res == res2);
165  res = collide_Test<KDOP<S, 24> >(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
166  res2 = collide_front_list_Test<KDOP<S, 24> >(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, false, verbose);
167  EXPECT_TRUE(res == res2);
168  }
169 
170  for(std::size_t i = 0; i < transforms.size(); ++i)
171  {
172  res = collide_Test<RSS<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
173  res2 = collide_front_list_Test_Oriented<RSS<S>, detail::MeshCollisionTraversalNodeRSS<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
174  EXPECT_TRUE(res == res2);
175  res = collide_Test<RSS<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
176  res2 = collide_front_list_Test_Oriented<RSS<S>, detail::MeshCollisionTraversalNodeRSS<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
177  EXPECT_TRUE(res == res2);
178  res = collide_Test<RSS<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
179  res2 = collide_front_list_Test_Oriented<RSS<S>, detail::MeshCollisionTraversalNodeRSS<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
180  EXPECT_TRUE(res == res2);
181  }
182 
183  for(std::size_t i = 0; i < transforms.size(); ++i)
184  {
185  res = collide_Test<OBB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
186  res2 = collide_front_list_Test_Oriented<OBB<S>, detail::MeshCollisionTraversalNodeOBB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEDIAN, verbose);
187  EXPECT_TRUE(res == res2);
188  res = collide_Test<OBB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
189  res2 = collide_front_list_Test_Oriented<OBB<S>, detail::MeshCollisionTraversalNodeOBB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_MEAN, verbose);
190  EXPECT_TRUE(res == res2);
191  res = collide_Test<OBB<S>>(transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
192  res2 = collide_front_list_Test_Oriented<OBB<S>, detail::MeshCollisionTraversalNodeOBB<S>>(transforms[i], transforms2[i], p1, t1, p2, t2, detail::SPLIT_METHOD_BV_CENTER, verbose);
193  EXPECT_TRUE(res == res2);
194  }
195 
196 }
197 
198 GTEST_TEST(FCL_FRONT_LIST, front_list)
199 {
200 // test_front_list<float>();
201  test_front_list<double>();
202 }
203 
204 template<typename BV>
206  const std::vector<Vector3<typename BV::S>>& vertices1, const std::vector<Triangle>& triangles1,
207  const std::vector<Vector3<typename BV::S>>& vertices2, const std::vector<Triangle>& triangles2,
208  detail::SplitMethodType split_method,
209  bool refit_bottomup, bool verbose)
210 {
211  using S = typename BV::S;
212 
213  BVHModel<BV> m1;
214  BVHModel<BV> m2;
215  m1.bv_splitter.reset(new detail::BVSplitter<BV>(split_method));
216  m2.bv_splitter.reset(new detail::BVSplitter<BV>(split_method));
217 
218  detail::BVHFrontList front_list;
219 
220 
221  std::vector<Vector3<S>> vertices1_new(vertices1.size());
222  for(std::size_t i = 0; i < vertices1_new.size(); ++i)
223  {
224  vertices1_new[i] = tf1 * vertices1[i];
225  }
226 
227  m1.beginModel();
228  m1.addSubModel(vertices1_new, triangles1);
229  m1.endModel();
230 
231  m2.beginModel();
232  m2.addSubModel(vertices2, triangles2);
233  m2.endModel();
234 
237 
238  CollisionResult<S> local_result;
240 
241  if(!detail::initialize<BV>(node, m1, pose1, m2, pose2,
242  CollisionRequest<S>(std::numeric_limits<int>::max(), false), local_result))
243  std::cout << "initialize error" << std::endl;
244 
245  node.enable_statistics = verbose;
246 
247  collide(&node, &front_list);
248 
249  if(verbose) std::cout << "front list size " << front_list.size() << std::endl;
250 
251 
252  // update the mesh
253  for(std::size_t i = 0; i < vertices1.size(); ++i)
254  {
255  vertices1_new[i] = tf2 * vertices1[i];
256  }
257 
258  m1.beginReplaceModel();
259  m1.replaceSubModel(vertices1_new);
260  m1.endReplaceModel(true, refit_bottomup);
261 
262  m2.beginReplaceModel();
263  m2.replaceSubModel(vertices2);
264  m2.endReplaceModel(true, refit_bottomup);
265 
266  local_result.clear();
267  collide(&node, &front_list);
268 
269  if(local_result.numContacts() > 0)
270  return true;
271  else
272  return false;
273 }
274 
275 
276 
277 
278 template<typename BV, typename TraversalNode>
280  const std::vector<Vector3<typename BV::S>>& vertices1, const std::vector<Triangle>& triangles1,
281  const std::vector<Vector3<typename BV::S>>& vertices2, const std::vector<Triangle>& triangles2,
282  detail::SplitMethodType split_method, bool verbose)
283 {
284  using S = typename BV::S;
285 
286  BVHModel<BV> m1;
287  BVHModel<BV> m2;
288  m1.bv_splitter.reset(new detail::BVSplitter<BV>(split_method));
289  m2.bv_splitter.reset(new detail::BVSplitter<BV>(split_method));
290 
291  detail::BVHFrontList front_list;
292 
293  m1.beginModel();
294  m1.addSubModel(vertices1, triangles1);
295  m1.endModel();
296 
297  m2.beginModel();
298  m2.addSubModel(vertices2, triangles2);
299  m2.endModel();
300 
301  Transform3<S> pose1(tf1);
303 
304  CollisionResult<S> local_result;
305  TraversalNode node;
306 
307  if(!initialize(node, (const BVHModel<BV>&)m1, pose1, (const BVHModel<BV>&)m2, pose2,
308  CollisionRequest<S>(std::numeric_limits<int>::max(), false), local_result))
309  std::cout << "initialize error" << std::endl;
310 
311  node.enable_statistics = verbose;
312 
313  collide(&node, &front_list);
314 
315  if(verbose) std::cout << "front list size " << front_list.size() << std::endl;
316 
317 
318  // update the mesh
319  pose1 = tf2;
320  if(!initialize(node, (const BVHModel<BV>&)m1, pose1, (const BVHModel<BV>&)m2, pose2, CollisionRequest<S>(), local_result))
321  std::cout << "initialize error" << std::endl;
322 
323  local_result.clear();
324  collide(&node, &front_list);
325 
326  if(local_result.numContacts() > 0)
327  return true;
328  else
329  return false;
330 }
331 
332 
333 template<typename BV>
335  const std::vector<Vector3<typename BV::S>>& vertices1, const std::vector<Triangle>& triangles1,
336  const std::vector<Vector3<typename BV::S>>& vertices2, const std::vector<Triangle>& triangles2, detail::SplitMethodType split_method, bool verbose)
337 {
338  using S = typename BV::S;
339 
340  BVHModel<BV> m1;
341  BVHModel<BV> m2;
342  m1.bv_splitter.reset(new detail::BVSplitter<BV>(split_method));
343  m2.bv_splitter.reset(new detail::BVSplitter<BV>(split_method));
344 
345  m1.beginModel();
346  m1.addSubModel(vertices1, triangles1);
347  m1.endModel();
348 
349  m2.beginModel();
350  m2.addSubModel(vertices2, triangles2);
351  m2.endModel();
352 
353  Transform3<S> pose1(tf);
355 
356  CollisionResult<S> local_result;
358 
359  if(!detail::initialize<BV>(node, m1, pose1, m2, pose2,
360  CollisionRequest<S>(std::numeric_limits<int>::max(), false), local_result))
361  std::cout << "initialize error" << std::endl;
362 
363  node.enable_statistics = verbose;
364 
365  collide(&node);
366 
367 
368  if(local_result.numContacts() > 0)
369  return true;
370  else
371  return false;
372 }
373 
374 //==============================================================================
375 int main(int argc, char* argv[])
376 {
377  ::testing::InitGoogleTest(&argc, argv);
378  return RUN_ALL_TESTS();
379 }
fcl::BVHModel::bv_splitter
std::shared_ptr< detail::BVSplitterBase< BV > > bv_splitter
Split rule to split one BV node into two children.
Definition: BVH_model.h:180
GTEST_TEST
GTEST_TEST(FCL_FRONT_LIST, front_list)
Definition: test_fcl_frontlist.cpp:198
fcl::detail::SPLIT_METHOD_MEDIAN
@ SPLIT_METHOD_MEDIAN
Definition: BV_splitter.h:59
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::test::loadOBJFile
void loadOBJFile(const char *filename, std::vector< Vector3< S >> &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
Definition: test_fcl_utility.h:194
collide_front_list_Test
bool collide_front_list_Test(const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const std::vector< Vector3< typename BV::S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< typename BV::S >> &vertices2, const std::vector< Triangle > &triangles2, detail::SplitMethodType split_method, bool refit_bottomup, bool verbose)
Definition: test_fcl_frontlist.cpp:205
fcl::detail::MeshCollisionTraversalNode
Traversal node for collision between two meshes.
Definition: mesh_collision_traversal_node.h:58
collide_front_list_Test_Oriented
bool collide_front_list_Test_Oriented(const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const std::vector< Vector3< typename BV::S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< typename BV::S >> &vertices2, const std::vector< Triangle > &triangles2, detail::SplitMethodType split_method, bool verbose)
Definition: test_fcl_frontlist.cpp:279
max
static T max(T x, T y)
Definition: svm.cpp:52
fcl::detail::SplitMethodType
SplitMethodType
Three types of split algorithms are provided in FCL as default.
Definition: BV_splitter.h:56
fcl::CollisionResult::clear
void clear()
clear the results obtained
Definition: collision_result-inl.h:125
fcl::BVHModel::endModel
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
Definition: BVH_model-inl.h:450
test_fcl_utility.h
fcl::CollisionResult
collision result
Definition: collision_request.h:48
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::detail::CollisionTraversalNodeBase< BV::S >::enable_statistics
bool enable_statistics
Whether stores statistics.
Definition: collision_traversal_node_base.h:78
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::BVHModel::beginReplaceModel
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
Definition: BVH_model-inl.h:521
fcl::CollisionRequest
Parameters for performing collision request.
Definition: collision_request.h:52
fcl::CollisionResult::numContacts
size_t numContacts() const
number of contacts found
Definition: collision_result-inl.h:83
fcl::detail::initialize
template bool initialize(MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result)
fcl::collide
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
test_front_list
void test_front_list()
Definition: test_fcl_frontlist.cpp:68
fcl::detail::SPLIT_METHOD_MEAN
@ SPLIT_METHOD_MEAN
Definition: BV_splitter.h:58
fcl::detail::SPLIT_METHOD_BV_CENTER
@ SPLIT_METHOD_BV_CENTER
Definition: BV_splitter.h:60
fcl::BVHModel::beginModel
int beginModel(int num_tris=0, int num_vertices=0)
Begin a new BVH model.
Definition: BVH_model-inl.h:207
fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
collide_Test
bool collide_Test(const Transform3< typename BV::S > &tf, const std::vector< Vector3< typename BV::S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< typename BV::S >> &vertices2, const std::vector< Triangle > &triangles2, detail::SplitMethodType split_method, bool verbose)
Definition: test_fcl_frontlist.cpp:334
fcl::detail::BVSplitter
A class describing the split rule that splits each BV node.
Definition: BV_splitter.h:65
fcl::BVHModel::addSubModel
int addSubModel(const std::vector< Vector3< S >> &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
Definition: BVH_model-inl.h:383
collision_node.h
extents
std::array< S, 6 > & extents()
Definition: test_fcl_geometric_shapes.cpp:63
fcl::detail::BVHFrontList
std::list< BVHFrontNode > BVHFrontList
BVH front list is a list of front nodes.
Definition: BVH_front.h:69
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::detail::MeshCollisionTraversalNodeRSS
Definition: mesh_collision_traversal_node.h:139
fcl::detail::MeshCollisionTraversalNodeOBB
Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB,...
Definition: mesh_collision_traversal_node.h:99
fcl::BVHModel::endReplaceModel
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
Definition: BVH_model-inl.h:594
fcl::aligned_vector
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
Definition: types.h:122
fcl::BVHModel::replaceSubModel
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
Definition: BVH_model-inl.h:576
main
int main(int argc, char *argv[])
Definition: test_fcl_frontlist.cpp:375
verbose
bool verbose
Definition: test_fcl_distance.cpp:50


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49