mesh_shape_conservative_advancement_traversal_node-inl.h
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 #ifndef FCL_TRAVERSAL_MESHSHAPECONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_MESHSHAPECONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H
40 
42 
43 #include "fcl/common/unused.h"
44 
45 namespace fcl
46 {
47 
48 namespace detail
49 {
50 
51 //==============================================================================
52 template <typename BV, typename Shape, typename NarrowPhaseSolver>
55  MeshShapeDistanceTraversalNode<BV, Shape, NarrowPhaseSolver>()
56 {
57  delta_t = 1;
58  toc = 0;
59  t_err = (S)0.0001;
60 
61  w = w_;
62 
63  motion1 = nullptr;
64  motion2 = nullptr;
65 }
66 
67 //==============================================================================
68 template <typename BV, typename Shape, typename NarrowPhaseSolver>
69 typename BV::S
71 BVTesting(int b1, int b2) const
72 {
73  if(this->enable_statistics) this->num_bv_tests++;
74  Vector3<S> P1, P2;
75  S d = this->model2_bv.distance(this->model1->getBV(b1).bv, &P2, &P1);
76 
77  stack.emplace_back(P1, P2, b1, b2, d);
78 
79  return d;
80 }
81 
82 //==============================================================================
83 template <typename BV, typename Shape, typename NarrowPhaseSolver>
85 leafTesting(int b1, int b2) const
86 {
87  FCL_UNUSED(b2);
88 
89  if(this->enable_statistics) this->num_leaf_tests++;
90 
91  const BVNode<BV>& node = this->model1->getBV(b1);
92 
93  int primitive_id = node.primitiveId();
94 
95  const Triangle& tri_id = this->tri_indices[primitive_id];
96 
97  const Vector3<S>& p1 = this->vertices[tri_id[0]];
98  const Vector3<S>& p2 = this->vertices[tri_id[1]];
99  const Vector3<S>& p3 = this->vertices[tri_id[2]];
100 
101  S d;
102  Vector3<S> P1, P2;
103  this->nsolver->shapeTriangleDistance(*(this->model2), this->tf2, p1, p2, p3, &d, &P2, &P1);
104 
105  if(d < this->min_distance)
106  {
107  this->min_distance = d;
108 
109  closest_p1 = P1;
110  closest_p2 = P2;
111 
112  last_tri_id = primitive_id;
113  }
114 
115  Vector3<S> n = this->tf2 * p2 - P1; n.normalize();
116  // here n should be in global frame
117  TriangleMotionBoundVisitor<S> mb_visitor1(p1, p2, p3, n);
118  TBVMotionBoundVisitor<BV> mb_visitor2(this->model2_bv, -n);
119  S bound1 = motion1->computeMotionBound(mb_visitor1);
120  S bound2 = motion2->computeMotionBound(mb_visitor2);
121 
122  S bound = bound1 + bound2;
123 
124  S cur_delta_t;
125  if(bound <= d) cur_delta_t = 1;
126  else cur_delta_t = d / bound;
127 
128  if(cur_delta_t < delta_t)
129  delta_t = cur_delta_t;
130 }
131 
132 //==============================================================================
133 template <typename BV, typename Shape, typename NarrowPhaseSolver>
135 canStop(S c) const
136 {
137  if((c >= w * (this->min_distance - this->abs_err))
138  && (c * (1 + this->rel_err) >= w * this->min_distance))
139  {
140  const auto& data = stack.back();
141 
142  Vector3<S> n = this->tf2 * data.P2 - data.P1; n.normalize();
143  int c1 = data.c1;
144 
145  TBVMotionBoundVisitor<BV> mb_visitor1(this->model1->getBV(c1).bv, n);
146  TBVMotionBoundVisitor<BV> mb_visitor2(this->model2_bv, -n);
147  S bound1 = motion1->computeMotionBound(mb_visitor1);
148  S bound2 = motion2->computeMotionBound(mb_visitor2);
149 
150  S bound = bound1 + bound2;
151 
152  S cur_delta_t;
153  if(bound < c) cur_delta_t = 1;
154  else cur_delta_t = c / bound;
155 
156  if(cur_delta_t < delta_t)
157  delta_t = cur_delta_t;
158 
159  stack.pop_back();
160 
161  return true;
162  }
163  else
164  {
165  stack.pop_back();
166 
167  return false;
168  }
169 }
170 
171 //==============================================================================
172 template <typename BV, typename Shape, typename NarrowPhaseSolver>
175  BVHModel<BV>& model1,
176  const Transform3<typename BV::S>& tf1,
177  const Shape& model2,
178  const Transform3<typename BV::S>& tf2,
179  const NarrowPhaseSolver* nsolver,
180  typename BV::S w,
181  bool use_refit,
182  bool refit_bottomup)
183 {
184  using S = typename BV::S;
185 
186  std::vector<Vector3<S>> vertices_transformed(model1.num_vertices);
187  for(int i = 0; i < model1.num_vertices; ++i)
188  {
189  Vector3<S>& p = model1.vertices[i];
190  Vector3<S> new_v = tf1 * p;
191  vertices_transformed[i] = new_v;
192  }
193 
194  model1.beginReplaceModel();
195  model1.replaceSubModel(vertices_transformed);
196  model1.endReplaceModel(use_refit, refit_bottomup);
197 
198  node.model1 = &model1;
199  node.model2 = &model2;
200 
201  node.vertices = model1.vertices;
202  node.tri_indices = model1.tri_indices;
203 
204  node.tf1 = tf1;
205  node.tf2 = tf2;
206 
207  node.nsolver = nsolver;
208  node.w = w;
209 
211 
212  return true;
213 }
214 
215 //==============================================================================
216 template <typename BV, typename Shape, typename NarrowPhaseSolver>
218  int b1,
219  int /* b2 */,
220  const BVHModel<BV>* model1,
221  const Shape& model2,
222  const BV& model2_bv,
223  Vector3<typename BV::S>* vertices,
224  Triangle* tri_indices,
225  const Transform3<typename BV::S>& tf1,
226  const Transform3<typename BV::S>& tf2,
227  const MotionBase<typename BV::S>* motion1,
228  const MotionBase<typename BV::S>* motion2,
229  const NarrowPhaseSolver* nsolver,
230  bool enable_statistics,
231  typename BV::S& min_distance,
234  int& last_tri_id,
235  typename BV::S& delta_t,
236  int& num_leaf_tests)
237 {
238  using S = typename BV::S;
239 
240  if(enable_statistics) num_leaf_tests++;
241 
242  const BVNode<BV>& node = model1->getBV(b1);
243  int primitive_id = node.primitiveId();
244 
245  const Triangle& tri_id = tri_indices[primitive_id];
246  const Vector3<S>& t1 = vertices[tri_id[0]];
247  const Vector3<S>& t2 = vertices[tri_id[1]];
248  const Vector3<S>& t3 = vertices[tri_id[2]];
249 
250  S distance;
253  nsolver->shapeTriangleDistance(model2, tf2, t1, t2, t3, tf1, &distance, &P2, &P1);
254 
255  if(distance < min_distance)
256  {
257  min_distance = distance;
258 
259  p1 = P1;
260  p2 = P2;
261 
262  last_tri_id = primitive_id;
263  }
264 
265  // n is in global frame
266  Vector3<S> n = P2 - P1; n.normalize();
267 
268  TriangleMotionBoundVisitor<S> mb_visitor1(t1, t2, t3, n);
269  TBVMotionBoundVisitor<BV> mb_visitor2(model2_bv, -n);
270  S bound1 = motion1->computeMotionBound(mb_visitor1);
271  S bound2 = motion2->computeMotionBound(mb_visitor2);
272 
273  S bound = bound1 + bound2;
274 
275  S cur_delta_t;
276  if(bound <= distance) cur_delta_t = 1;
277  else cur_delta_t = distance / bound;
278 
279  if(cur_delta_t < delta_t)
280  delta_t = cur_delta_t;
281 }
282 
283 //==============================================================================
284 template <typename BV, typename Shape>
286  typename BV::S c,
287  typename BV::S min_distance,
288  typename BV::S abs_err,
289  typename BV::S rel_err,
290  typename BV::S w,
291  const BVHModel<BV>* model1,
292  const Shape& model2,
293  const BV& model2_bv,
294  const MotionBase<typename BV::S>* motion1,
295  const MotionBase<typename BV::S>* motion2,
297  typename BV::S& delta_t)
298 {
299  FCL_UNUSED(model2);
300 
301  using S = typename BV::S;
302 
303  if((c >= w * (min_distance - abs_err)) && (c * (1 + rel_err) >= w * min_distance))
304  {
305  const auto& data = stack.back();
306  Vector3<S> n = data.P2 - data.P1; n.normalize();
307  int c1 = data.c1;
308 
309  TBVMotionBoundVisitor<BV> mb_visitor1(model1->getBV(c1).bv, n);
310  TBVMotionBoundVisitor<BV> mb_visitor2(model2_bv, -n);
311 
312  S bound1 = motion1->computeMotionBound(mb_visitor1);
313  S bound2 = motion2->computeMotionBound(mb_visitor2);
314 
315  S bound = bound1 + bound2;
316 
317  S cur_delta_t;
318  if(bound <= c) cur_delta_t = 1;
319  else cur_delta_t = c / bound;
320 
321  if(cur_delta_t < delta_t)
322  delta_t = cur_delta_t;
323 
324  stack.pop_back();
325 
326  return true;
327  }
328  else
329  {
330  stack.pop_back();
331  return false;
332  }
333 }
334 
335 //==============================================================================
336 template <typename Shape, typename NarrowPhaseSolver>
340  RSS<S>, Shape, NarrowPhaseSolver>(w_)
341 {
342  // Do nothing
343 }
344 
345 //==============================================================================
346 template <typename Shape, typename NarrowPhaseSolver>
347 typename Shape::S
349 BVTesting(int b1, int b2) const
350 {
351  if(this->enable_statistics) this->num_bv_tests++;
352  Vector3<S> P1, P2;
353  S d = distance(this->tf1.linear(), this->tf1.translation(), this->model1->getBV(b1).bv, this->model2_bv, &P1, &P2);
354 
355  this->stack.emplace_back(P1, P2, b1, b2, d);
356 
357  return d;
358 }
359 
360 //==============================================================================
361 template <typename Shape, typename NarrowPhaseSolver>
362 void
364 leafTesting(int b1, int b2) const
365 {
367  b1,
368  b2,
369  this->model1,
370  *(this->model2),
371  this->model2_bv,
372  this->vertices,
373  this->tri_indices,
374  this->tf1,
375  this->tf2,
376  this->motion1,
377  this->motion2,
378  this->nsolver,
379  this->enable_statistics,
380  this->min_distance,
381  this->closest_p1,
382  this->closest_p2,
383  this->last_tri_id,
384  this->delta_t,
385  this->num_leaf_tests);
386 }
387 
388 //==============================================================================
389 template <typename Shape, typename NarrowPhaseSolver>
390 bool
392 canStop(typename Shape::S c) const
393 {
395  c,
396  this->min_distance,
397  this->abs_err,
398  this->rel_err,
399  this->w,
400  this->model1,
401  *(this->model2),
402  this->model2_bv,
403  this->motion1,
404  this->motion2,
405  this->stack,
406  this->delta_t);
407 }
408 
409 //==============================================================================
410 template <typename Shape, typename NarrowPhaseSolver>
415  const Shape& model2,
417  const NarrowPhaseSolver* nsolver,
418  typename Shape::S w)
419 {
420  using S = typename Shape::S;
421 
422  node.model1 = &model1;
423  node.tf1 = tf1;
424  node.model2 = &model2;
425  node.tf2 = tf2;
426  node.nsolver = nsolver;
427 
428  node.w = w;
429 
431 
432  return true;
433 }
434 
435 //==============================================================================
436 template <typename Shape, typename NarrowPhaseSolver>
439  typename Shape::S w_)
441  OBBRSS<S>, Shape, NarrowPhaseSolver>(w_)
442 {
443  // Do nothing
444 }
445 
446 //==============================================================================
447 template <typename Shape, typename NarrowPhaseSolver>
448 typename Shape::S
450 BVTesting(int b1, int b2) const
451 {
452  if(this->enable_statistics) this->num_bv_tests++;
453  Vector3<S> P1, P2;
454  S d = distance(this->tf1.linear(), this->tf1.translation(), this->model1->getBV(b1).bv, this->model2_bv, &P1, &P2);
455 
456  this->stack.emplace_back(P1, P2, b1, b2, d);
457 
458  return d;
459 }
460 
461 //==============================================================================
462 template <typename Shape, typename NarrowPhaseSolver>
463 void
465 leafTesting(int b1, int b2) const
466 {
468  b1,
469  b2,
470  this->model1,
471  *(this->model2),
472  this->model2_bv,
473  this->vertices,
474  this->tri_indices,
475  this->tf1,
476  this->tf2,
477  this->motion1,
478  this->motion2,
479  this->nsolver,
480  this->enable_statistics,
481  this->min_distance,
482  this->closest_p1,
483  this->closest_p2,
484  this->last_tri_id,
485  this->delta_t,
486  this->num_leaf_tests);
487 }
488 
489 //==============================================================================
490 template <typename Shape, typename NarrowPhaseSolver>
491 bool
493 canStop(typename Shape::S c) const
494 {
496  c,
497  this->min_distance,
498  this->abs_err,
499  this->rel_err,
500  this->w,
501  this->model1,
502  *(this->model2),
503  this->model2_bv,
504  this->motion1,
505  this->motion2,
506  this->stack,
507  this->delta_t);
508 }
509 
510 //==============================================================================
511 template <typename Shape, typename NarrowPhaseSolver>
516  const Shape& model2,
518  const NarrowPhaseSolver* nsolver,
519  typename Shape::S w)
520 {
521  using S = typename Shape::S;
522 
523  node.model1 = &model1;
524  node.tf1 = tf1;
525  node.model2 = &model2;
526  node.tf2 = tf2;
527  node.nsolver = nsolver;
528 
529  node.w = w;
530 
532 
533  return true;
534 }
535 
536 } // namespace detail
537 } // namespace fcl
538 
539 #endif
Main namespace.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
Traversal node for distance between mesh and shape.
virtual S computeMotionBound(const BVMotionBoundVisitor< S > &mb_visitor) const =0
Compute the motion bound for a bounding volume, given the closest direction n between two query objec...
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
void meshShapeConservativeAdvancementOrientedNodeLeafTesting(int b1, int, const BVHModel< BV > *model1, const Shape &model2, const BV &model2_bv, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, bool enable_statistics, typename BV::S &min_distance, Vector3< typename BV::S > &p1, Vector3< typename BV::S > &p2, int &last_tri_id, typename BV::S &delta_t, int &num_leaf_tests)
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Transform3< BV::S > tf2
configuration of second object
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS-inl.h:266
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
bool initialize(MeshShapeConservativeAdvancementTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w)
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
int num_vertices
Number of points.
Definition: BVH_model.h:174
FCL_EXPORT void computeBV(const Shape &s, const Transform3< typename BV::S > &tf, BV &bv)
calculate a bounding volume for a shape in a specific configuration
Traversal node for conservative advancement computation between BVH and shape.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Definition: BVH_model.h:165
Triangle with 3 indices for points.
Definition: triangle.h:48
bool meshShapeConservativeAdvancementOrientedNodeCanStop(typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const Shape &model2, const BV &model2_bv, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t)
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)
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
#define FCL_UNUSED(x)
Definition: unused.h:39
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
BV bv
bounding volume storing the geometry
Definition: BV_node.h:57
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
template Interval< double > bound(const Interval< double > &i, double v)
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: BV_node.h:52
Transform3< BV::S > tf1
configuation of first object
S w
CA controlling variable: early stop for the early iterations of CA.
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: OBBRSS.h:50
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.


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