shape_mesh_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_SHAPEMESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_SHAPEMESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_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 Shape, typename BV, typename NarrowPhaseSolver>
55  : ShapeMeshDistanceTraversalNode<Shape, BV, 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 Shape, typename BV, 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->model1_bv.distance(this->model2->getBV(b2).bv, &P1, &P2);
76 
77  stack.emplace_back(P1, P2, b1, b2, d);
78 
79  return d;
80 }
81 
82 //==============================================================================
83 template <typename Shape, typename BV, typename NarrowPhaseSolver>
85 {
86  FCL_UNUSED(b1);
87 
88  if(this->enable_statistics) this->num_leaf_tests++;
89 
90  const BVNode<BV>& node = this->model2->getBV(b2);
91 
92  int primitive_id = node.primitiveId();
93 
94  const Triangle& tri_id = this->tri_indices[primitive_id];
95 
96  const Vector3<S>& p1 = this->vertices[tri_id[0]];
97  const Vector3<S>& p2 = this->vertices[tri_id[1]];
98  const Vector3<S>& p3 = this->vertices[tri_id[2]];
99 
100  S d;
101  Vector3<S> P1, P2;
102  this->nsolver->shapeTriangleDistance(*(this->model1), this->tf1, p1, p2, p3, &d, &P1, &P2);
103 
104  if(d < this->min_distance)
105  {
106  this->min_distance = d;
107 
108  closest_p1 = P1;
109  closest_p2 = P2;
110 
111  last_tri_id = primitive_id;
112  }
113 
114  Vector3<S> n = P2 - this->tf1 * p1; n.normalize();
115  // here n should be in global frame
116  TBVMotionBoundVisitor<BV> mb_visitor1(this->model1_bv, n);
117  TriangleMotionBoundVisitor<S> mb_visitor2(p1, p2, p3, -n);
118  S bound1 = motion1->computeMotionBound(mb_visitor1);
119  S bound2 = motion2->computeMotionBound(mb_visitor2);
120 
121  S bound = bound1 + bound2;
122 
123  S cur_delta_t;
124  if(bound <= d) cur_delta_t = 1;
125  else cur_delta_t = d / bound;
126 
127  if(cur_delta_t < delta_t)
128  delta_t = cur_delta_t;
129 }
130 
131 //==============================================================================
132 template <typename Shape, typename BV, typename NarrowPhaseSolver>
134 canStop(S c) const
135 {
136  if((c >= w * (this->min_distance - this->abs_err)) && (c * (1 + this->rel_err) >= w * this->min_distance))
137  {
138  const auto& data = stack.back();
139 
140  Vector3<S> n = data.P2 - this->tf1 * data.P1; n.normalize();
141  int c2 = data.c2;
142 
143  TBVMotionBoundVisitor<BV> mb_visitor1(this->model1_bv, n);
144  TBVMotionBoundVisitor<BV> mb_visitor2(this->model2->getBV(c2).bv, -n);
145  S bound1 = motion1->computeMotionBound(mb_visitor1);
146  S bound2 = motion2->computeMotionBound(mb_visitor2);
147 
148  S bound = bound1 + bound2;
149 
150  S cur_delta_t;
151  if(bound < c) cur_delta_t = 1;
152  else cur_delta_t = c / bound;
153 
154  if(cur_delta_t < delta_t)
155  delta_t = cur_delta_t;
156 
157  stack.pop_back();
158 
159  return true;
160  }
161  else
162  {
163  stack.pop_back();
164 
165  return false;
166  }
167 }
168 
169 //==============================================================================
170 template <typename Shape, typename BV, typename NarrowPhaseSolver>
173  const Shape& model1,
174  const Transform3<typename BV::S>& tf1,
175  BVHModel<BV>& model2,
176  const Transform3<typename BV::S>& tf2,
177  const NarrowPhaseSolver* nsolver,
178  typename BV::S w,
179  bool use_refit,
180  bool refit_bottomup)
181 {
182  using S = typename BV::S;
183 
184  std::vector<Vector3<S>> vertices_transformed(model2.num_vertices);
185  for(int i = 0; i < model2.num_vertices; ++i)
186  {
187  Vector3<S>& p = model2.vertices[i];
188  Vector3<S> new_v = tf2 * p;
189  vertices_transformed[i] = new_v;
190  }
191 
192  model2.beginReplaceModel();
193  model2.replaceSubModel(vertices_transformed);
194  model2.endReplaceModel(use_refit, refit_bottomup);
195 
196  node.model1 = &model1;
197  node.model2 = &model2;
198 
199  node.vertices = model2.vertices;
200  node.tri_indices = model2.tri_indices;
201 
202  node.tf1 = tf1;
203  node.tf2 = tf2;
204 
205  node.nsolver = nsolver;
206  node.w = w;
207 
209 
210  return true;
211 }
212 
213 //==============================================================================
214 template <typename Shape, typename NarrowPhaseSolver>
215 ShapeMeshConservativeAdvancementTraversalNodeRSS<Shape, NarrowPhaseSolver>::
216 ShapeMeshConservativeAdvancementTraversalNodeRSS(
217  typename Shape::S w_)
219  Shape, RSS<typename Shape::S>, NarrowPhaseSolver>(w_)
220 {
221  // Do nothing
222 }
223 
224 //==============================================================================
225 template <typename Shape, typename NarrowPhaseSolver>
226 typename Shape::S
228 BVTesting(int b1, int b2) const
229 {
230  using S = typename Shape::S;
231 
232  if(this->enable_statistics) this->num_bv_tests++;
233  Vector3<S> P1, P2;
234  S d = distance(this->tf2.linear(), this->tf2.translation(), this->model2->getBV(b2).bv, this->model1_bv, &P2, &P1);
235 
236  this->stack.emplace_back(P1, P2, b1, b2, d);
237 
238  return d;
239 }
240 
241 //==============================================================================
242 template <typename Shape, typename NarrowPhaseSolver>
244 leafTesting(int b1, int b2) const
245 {
247  b2,
248  b1,
249  this->model2,
250  *(this->model1),
251  this->model1_bv,
252  this->vertices,
253  this->tri_indices,
254  this->tf2,
255  this->tf1,
256  this->motion2,
257  this->motion1,
258  this->nsolver,
259  this->enable_statistics,
260  this->min_distance,
261  this->closest_p2,
262  this->closest_p1,
263  this->last_tri_id,
264  this->delta_t,
265  this->num_leaf_tests);
266 }
267 
268 //==============================================================================
269 template <typename Shape, typename NarrowPhaseSolver>
271 canStop(typename Shape::S c) const
272 {
274  c,
275  this->min_distance,
276  this->abs_err,
277  this->rel_err,
278  this->w,
279  this->model2,
280  *(this->model1),
281  this->model1_bv,
282  this->motion2,
283  this->motion1,
284  this->stack,
285  this->delta_t);
286 }
287 
288 //==============================================================================
289 template <typename Shape, typename NarrowPhaseSolver>
292  const Shape& model1,
294  const BVHModel<RSS<typename Shape::S>>& model2,
296  const NarrowPhaseSolver* nsolver,
297  typename Shape::S w)
298 {
299  using S = typename Shape::S;
300 
301  node.model1 = &model1;
302  node.tf1 = tf1;
303  node.model2 = &model2;
304  node.tf2 = tf2;
305  node.nsolver = nsolver;
306 
307  node.w = w;
308 
310 
311  return true;
312 }
313 
314 //==============================================================================
315 template <typename Shape, typename NarrowPhaseSolver>
318  typename Shape::S w_)
320  Shape, OBBRSS<typename Shape::S>, NarrowPhaseSolver>(w_)
321 {
322 }
323 
324 //==============================================================================
325 template <typename Shape, typename NarrowPhaseSolver>
326 typename Shape::S
328 BVTesting(int b1, int b2) const
329 {
330  using S = typename Shape::S;
331 
332  if(this->enable_statistics) this->num_bv_tests++;
333  Vector3<S> P1, P2;
334  S d = distance(this->tf2.linear(), this->tf2.translation(), this->model2->getBV(b2).bv, this->model1_bv, &P2, &P1);
335 
336  this->stack.emplace_back(P1, P2, b1, b2, d);
337 
338  return d;
339 }
340 
341 //==============================================================================
342 template <typename Shape, typename NarrowPhaseSolver>
344 leafTesting(int b1, int b2) const
345 {
347  b2,
348  b1,
349  this->model2,
350  *(this->model1),
351  this->model1_bv,
352  this->vertices,
353  this->tri_indices,
354  this->tf2,
355  this->tf1,
356  this->motion2,
357  this->motion1,
358  this->nsolver,
359  this->enable_statistics,
360  this->min_distance,
361  this->closest_p2,
362  this->closest_p1,
363  this->last_tri_id,
364  this->delta_t,
365  this->num_leaf_tests);
366 }
367 
368 //==============================================================================
369 template <typename Shape, typename NarrowPhaseSolver>
371 canStop(typename Shape::S c) const
372 {
374  c,
375  this->min_distance,
376  this->abs_err,
377  this->rel_err,
378  this->w,
379  this->model2,
380  *(this->model1),
381  this->model1_bv,
382  this->motion2,
383  this->motion1,
384  this->stack,
385  this->delta_t);
386 }
387 
388 //==============================================================================
389 template <typename Shape, typename NarrowPhaseSolver>
392  const Shape& model1,
394  const BVHModel<OBBRSS<typename Shape::S>>& model2,
396  const NarrowPhaseSolver* nsolver,
397  typename Shape::S w)
398 {
399  using S = typename Shape::S;
400 
401  node.model1 = &model1;
402  node.tf1 = tf1;
403  node.model2 = &model2;
404  node.tf2 = tf2;
405  node.nsolver = nsolver;
406 
407  node.w = w;
408 
410 
411  return true;
412 }
413 
414 } // namespace detail
415 } // namespace fcl
416 
417 #endif
fcl::detail::ShapeMeshConservativeAdvancementTraversalNode::w
S w
CA controlling variable: early stop for the early iterations of CA.
Definition: shape_mesh_conservative_advancement_traversal_node.h:77
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS::BVTesting
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:328
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeRSS
Definition: shape_mesh_conservative_advancement_traversal_node.h:106
fcl::TriangleMotionBoundVisitor
Definition: motion_base.h:52
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS::canStop
bool canStop(S c) const
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:371
fcl::detail::ShapeBVHDistanceTraversalNode::model1
const Shape * model1
Definition: shape_bvh_distance_traversal_node.h:74
fcl::BVHModel::vertices
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
fcl::detail::meshShapeConservativeAdvancementOrientedNodeLeafTesting
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)
Definition: mesh_shape_conservative_advancement_traversal_node-inl.h:217
fcl::detail::TraversalNodeBase< BV::S >::tf1
Transform3< BV::S > tf1
configuation of first object
Definition: traversal_node_base.h:85
fcl::computeBV
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
Definition: geometry/shape/utility-inl.h:1056
unused.h
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS::leafTesting
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:344
shape_mesh_conservative_advancement_traversal_node.h
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeRSS::leafTesting
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:244
fcl::RSS
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
fcl::Triangle
Triangle with 3 indices for points.
Definition: triangle.h:48
fcl::detail::ShapeMeshDistanceTraversalNode::vertices
Vector3< S > * vertices
Definition: shape_mesh_distance_traversal_node.h:67
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS
Definition: shape_mesh_conservative_advancement_traversal_node.h:133
fcl::detail::initialize
bool initialize(ShapeMeshConservativeAdvancementTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w)
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:390
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::detail::ShapeMeshConservativeAdvancementTraversalNodeRSS::canStop
bool canStop(S c) const
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:271
fcl::BVHModel::tri_indices
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Definition: BVH_model.h:165
fcl::detail::ShapeMeshConservativeAdvancementTraversalNode
Definition: shape_mesh_conservative_advancement_traversal_node.h:52
fcl::detail::meshShapeConservativeAdvancementOrientedNodeCanStop
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)
Definition: mesh_shape_conservative_advancement_traversal_node-inl.h:285
fcl::BVNode
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: BV_node.h:52
fcl::detail::ShapeMeshDistanceTraversalNode
Traversal node for distance between shape and mesh.
Definition: shape_mesh_distance_traversal_node.h:52
fcl::detail::ShapeBVHDistanceTraversalNode::model1_bv
BV model1_bv
Definition: shape_bvh_distance_traversal_node.h:76
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::detail::ShapeMeshDistanceTraversalNode::nsolver
const NarrowPhaseSolver * nsolver
Definition: shape_mesh_distance_traversal_node.h:73
fcl::detail::ShapeBVHDistanceTraversalNode::model2
const BVHModel< BV > * model2
Definition: shape_bvh_distance_traversal_node.h:75
fcl::bound
template Interval< double > bound(const Interval< double > &i, double v)
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS
ShapeMeshConservativeAdvancementTraversalNodeOBBRSS(S w_=1)
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:317
fcl::detail::distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
fcl::OBBRSS
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: OBBRSS.h:50
fcl::TBVMotionBoundVisitor
Definition: tbv_motion_bound_visitor.h:65
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
fcl::BVHModel::num_vertices
int num_vertices
Number of points.
Definition: BVH_model.h:174
FCL_UNUSED
#define FCL_UNUSED(x)
Definition: unused.h:39
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeOBBRSS::S
typename Shape::S S
Definition: shape_mesh_conservative_advancement_traversal_node.h:138
fcl::detail::TraversalNodeBase< BV::S >::tf2
Transform3< BV::S > tf2
configuration of second object
Definition: traversal_node_base.h:88
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeRSS::BVTesting
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:228
fcl::detail::ShapeMeshConservativeAdvancementTraversalNode::ShapeMeshConservativeAdvancementTraversalNode
ShapeMeshConservativeAdvancementTraversalNode(S w_=1)
Definition: shape_mesh_conservative_advancement_traversal_node-inl.h:54
fcl::detail::ShapeMeshConservativeAdvancementTraversalNodeRSS::S
typename Shape::S S
Definition: shape_mesh_conservative_advancement_traversal_node.h:111
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::detail::ShapeMeshDistanceTraversalNode::tri_indices
Triangle * tri_indices
Definition: shape_mesh_distance_traversal_node.h:68
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::BVNodeBase::primitiveId
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
Definition: BV_node_base.cpp:50
fcl::detail::ShapeBVHDistanceTraversalNode< Shape, OBBRSS< Shape::S > >::S
typename OBBRSS< Shape::S > ::S S
Definition: shape_bvh_distance_traversal_node.h:58
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


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