mesh_shape_distance_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_MESHSHAPEDISTANCETRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_MESHSHAPEDISTANCETRAVERSALNODE_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  : BVHShapeDistanceTraversalNode<BV, Shape>()
56 {
57  vertices = nullptr;
58  tri_indices = nullptr;
59 
60  rel_err = 0;
61  abs_err = 0;
62 
63  nsolver = nullptr;
64 }
65 
66 //==============================================================================
67 template <typename BV, typename Shape, typename NarrowPhaseSolver>
69 leafTesting(int b1, int b2) const
70 {
71  FCL_UNUSED(b2);
72 
73  if(this->enable_statistics) this->num_leaf_tests++;
74 
75  const BVNode<BV>& node = this->model1->getBV(b1);
76 
77  int primitive_id = node.primitiveId();
78 
79  const Triangle& tri_id = tri_indices[primitive_id];
80 
81  const Vector3<S>& p1 = vertices[tri_id[0]];
82  const Vector3<S>& p2 = vertices[tri_id[1]];
83  const Vector3<S>& p3 = vertices[tri_id[2]];
84 
85  S d;
86  Vector3<S> closest_p1, closest_p2;
87  nsolver->shapeTriangleDistance(*(this->model2), this->tf2, p1, p2, p3, &d, &closest_p2, &closest_p1);
88 
89  this->result->update(
90  d,
91  this->model1,
92  this->model2,
93  primitive_id,
95  closest_p1,
96  closest_p2);
97 }
98 
99 //==============================================================================
100 template <typename BV, typename Shape, typename NarrowPhaseSolver>
102 canStop(S c) const
103 {
104  if((c >= this->result->min_distance - abs_err) && (c * (1 + rel_err) >= this->result->min_distance))
105  return true;
106  return false;
107 }
108 
109 //==============================================================================
110 template <typename BV, typename Shape, typename NarrowPhaseSolver>
113  BVHModel<BV>& model1,
115  const Shape& model2,
116  const Transform3<typename BV::S>& tf2,
117  const NarrowPhaseSolver* nsolver,
118  const DistanceRequest<typename BV::S>& request,
120  bool use_refit,
121  bool refit_bottomup)
122 {
123  using S = typename BV::S;
124 
125  if(model1.getModelType() != BVH_MODEL_TRIANGLES)
126  return false;
127 
128  if(!tf1.matrix().isIdentity())
129  {
130  std::vector<Vector3<S>> vertices_transformed1(model1.num_vertices);
131  for(int i = 0; i < model1.num_vertices; ++i)
132  {
133  Vector3<S>& p = model1.vertices[i];
134  Vector3<S> new_v = tf1 * p;
135  vertices_transformed1[i] = new_v;
136  }
137 
138  model1.beginReplaceModel();
139  model1.replaceSubModel(vertices_transformed1);
140  model1.endReplaceModel(use_refit, refit_bottomup);
141 
142  tf1.setIdentity();
143  }
144 
145  node.request = request;
146  node.result = &result;
147 
148  node.model1 = &model1;
149  node.tf1 = tf1;
150  node.model2 = &model2;
151  node.tf2 = tf2;
152  node.nsolver = nsolver;
153 
154  node.vertices = model1.vertices;
155  node.tri_indices = model1.tri_indices;
156 
157  computeBV(model2, tf2, node.model2_bv);
158 
159  return true;
160 }
161 
162 //==============================================================================
163 template <typename BV, typename Shape, typename NarrowPhaseSolver>
165  int b1, int /* b2 */,
166  const BVHModel<BV>* model1, const Shape& model2,
167  Vector3<typename BV::S>* vertices, Triangle* tri_indices,
168  const Transform3<typename BV::S>& tf1,
169  const Transform3<typename BV::S>& tf2,
170  const NarrowPhaseSolver* nsolver,
171  bool enable_statistics,
172  int & num_leaf_tests,
173  const DistanceRequest<typename BV::S>& /* request */,
175 {
176  using S = typename BV::S;
177 
178  if(enable_statistics) num_leaf_tests++;
179 
180  const BVNode<BV>& node = model1->getBV(b1);
181  int primitive_id = node.primitiveId();
182 
183  const Triangle& tri_id = tri_indices[primitive_id];
184  const Vector3<S>& p1 = vertices[tri_id[0]];
185  const Vector3<S>& p2 = vertices[tri_id[1]];
186  const Vector3<S>& p3 = vertices[tri_id[2]];
187 
188  S distance;
189  Vector3<S> closest_p1, closest_p2;
190  nsolver->shapeTriangleDistance(model2, tf2, p1, p2, p3, tf1, &distance, &closest_p2, &closest_p1);
191 
192  result.update(
193  distance,
194  model1,
195  &model2,
196  primitive_id,
198  closest_p1,
199  closest_p2);
200 }
201 
202 //==============================================================================
203 template <typename BV, typename Shape, typename NarrowPhaseSolver>
205  const BVHModel<BV>* model1,
206  Vector3<typename BV::S>* vertices,
207  Triangle* tri_indices,
208  int init_tri_id,
209  const Shape& model2,
210  const Transform3<typename BV::S>& tf1,
211  const Transform3<typename BV::S>& tf2,
212  const NarrowPhaseSolver* nsolver,
213  const DistanceRequest<typename BV::S>& /* request */,
215 {
216  using S = typename BV::S;
217 
218  const Triangle& init_tri = tri_indices[init_tri_id];
219 
220  const Vector3<S>& p1 = vertices[init_tri[0]];
221  const Vector3<S>& p2 = vertices[init_tri[1]];
222  const Vector3<S>& p3 = vertices[init_tri[2]];
223 
224  S distance;
225  Vector3<S> closest_p1, closest_p2;
226  nsolver->shapeTriangleDistance(model2, tf2, p1, p2, p3, tf1, &distance, &closest_p2, &closest_p1);
227 
228  result.update(
229  distance,
230  model1,
231  &model2,
232  init_tri_id,
234  closest_p1,
235  closest_p2);
236 }
237 
238 //==============================================================================
239 template <typename Shape, typename NarrowPhaseSolver>
243  RSS<typename Shape::S>, Shape, NarrowPhaseSolver>()
244 {
245 }
246 
247 //==============================================================================
248 template <typename Shape, typename NarrowPhaseSolver>
250 {
252  this->model1,
253  this->vertices,
254  this->tri_indices,
255  0,
256  *(this->model2),
257  this->tf1,
258  this->tf2,
259  this->nsolver,
260  this->request,
261  *(this->result));
262 }
263 
264 //==============================================================================
265 template <typename Shape, typename NarrowPhaseSolver>
267 {
268 }
269 
270 //==============================================================================
271 template <typename Shape, typename NarrowPhaseSolver>
272 typename Shape::S
274  int b1, int b2) const
275 {
276  FCL_UNUSED(b2);
277 
278  if(this->enable_statistics) this->num_bv_tests++;
279 
280  return distance(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
281 }
282 
283 //==============================================================================
284 template <typename Shape, typename NarrowPhaseSolver>
286 leafTesting(int b1, int b2) const
287 {
289  b1,
290  b2,
291  this->model1,
292  *(this->model2),
293  this->vertices,
294  this->tri_indices,
295  this->tf1,
296  this->tf2,
297  this->nsolver,
298  this->enable_statistics,
299  this->num_leaf_tests,
300  this->request,
301  *(this->result));
302 }
303 
304 //==============================================================================
305 template <typename Shape, typename NarrowPhaseSolver>
307 {
308 }
309 
310 //==============================================================================
311 template <typename Shape, typename NarrowPhaseSolver>
313 {
315  *(this->model2), this->tf1, this->tf2, this->nsolver, this->request, *(this->result));
316 }
317 
318 //==============================================================================
319 template <typename Shape, typename NarrowPhaseSolver>
321 {
322 }
323 
324 //==============================================================================
325 template <typename Shape, typename NarrowPhaseSolver>
327 {
328  FCL_UNUSED(b2);
329 
330  if(this->enable_statistics) this->num_bv_tests++;
331 
332  return distance(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
333 }
334 
335 //==============================================================================
336 template <typename Shape, typename NarrowPhaseSolver>
338 {
340  this->tf1, this->tf2, this->nsolver, this->enable_statistics, this->num_leaf_tests, this->request, *(this->result));
341 }
342 
343 //==============================================================================
344 template <typename Shape, typename NarrowPhaseSolver>
346 {
347 }
348 
349 //==============================================================================
350 template <typename Shape, typename NarrowPhaseSolver>
352 {
354  *(this->model2), this->tf1, this->tf2, this->nsolver, this->request, *(this->result));
355 }
356 
357 //==============================================================================
358 template <typename Shape, typename NarrowPhaseSolver>
360 {
361 
362 }
363 
364 //==============================================================================
365 template <typename Shape, typename NarrowPhaseSolver>
366 typename Shape::S
368 BVTesting(int b1, int b2) const
369 {
370  FCL_UNUSED(b2);
371 
372  if(this->enable_statistics) this->num_bv_tests++;
373 
374  return distance(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
375 }
376 
377 //==============================================================================
378 template <typename Shape, typename NarrowPhaseSolver>
380 {
382  this->tf1, this->tf2, this->nsolver, this->enable_statistics, this->num_leaf_tests, this->request, *(this->result));
383 }
384 
385 template <typename BV, typename Shape, typename NarrowPhaseSolver, template <typename, typename> class OrientedNode>
386 static bool setupMeshShapeDistanceOrientedNode(OrientedNode<Shape, NarrowPhaseSolver>& node,
388  const Shape& model2, const Transform3<typename BV::S>& tf2,
389  const NarrowPhaseSolver* nsolver,
392 {
393  if(model1.getModelType() != BVH_MODEL_TRIANGLES)
394  return false;
395 
396  node.request = request;
397  node.result = &result;
398 
399  node.model1 = &model1;
400  node.tf1 = tf1;
401  node.model2 = &model2;
402  node.tf2 = tf2;
403  node.nsolver = nsolver;
404 
405  computeBV(model2, tf2, node.model2_bv);
406 
407  node.vertices = model1.vertices;
408  node.tri_indices = model1.tri_indices;
409 
410  return true;
411 }
412 
413 //==============================================================================
414 template <typename Shape, typename NarrowPhaseSolver>
418  const Shape& model2, const Transform3<typename Shape::S>& tf2,
419  const NarrowPhaseSolver* nsolver,
422 {
423  return detail::setupMeshShapeDistanceOrientedNode(node, model1, tf1, model2, tf2, nsolver, request, result);
424 }
425 
426 //==============================================================================
427 template <typename Shape, typename NarrowPhaseSolver>
431  const Shape& model2, const Transform3<typename Shape::S>& tf2,
432  const NarrowPhaseSolver* nsolver,
435 {
436  return detail::setupMeshShapeDistanceOrientedNode(node, model1, tf1, model2, tf2, nsolver, request, result);
437 }
438 
439 //==============================================================================
440 template <typename Shape, typename NarrowPhaseSolver>
444  const Shape& model2, const Transform3<typename Shape::S>& tf2,
445  const NarrowPhaseSolver* nsolver,
448 {
449  return detail::setupMeshShapeDistanceOrientedNode(node, model1, tf1, model2, tf2, nsolver, request, result);
450 }
451 
452 } // namespace detail
453 } // namespace fcl
454 
455 #endif
Main namespace.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
Traversal node for distance between mesh and shape.
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
BVHModelType getModelType() const
Model type described by the instance.
Definition: BVH_model-inl.h:50
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.
static bool setupMeshShapeDistanceOrientedNode(OrientedNode< Shape, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
distance result
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)...
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
Traversal node for distance computation between BVH and shape.
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
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
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
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
void distancePreprocessOrientedNode(const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
unknown model type
Definition: BVH_internal.h:78
void meshShapeDistanceOrientedNodeLeafTesting(int b1, int, const BVHModel< BV > *model1, const Shape &model2, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &, DistanceResult< typename BV::S > &result)
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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)
DistanceRequest< BV::S > request
request setting for distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
Traversal node for distance between mesh and shape, when mesh BVH is one of the oriented node (RSS...
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
#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
bool initialize(MeshShapeDistanceTraversalNodeOBBRSS< 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, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result)
Initialize traversal node for distance computation between one mesh and one shape, specialized for OBBRSS type.
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
void distancePreprocessOrientedNode(const BVHModel< BV > *model1, Vector3< typename BV::S > *vertices, Triangle *tri_indices, int init_tri_id, const Shape &model2, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &, DistanceResult< typename BV::S > &result)
DistanceResult< BV::S > * result
distance result kept during the traversal iteration
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
void update(S distance, const CollisionGeometry< S > *o1_, const CollisionGeometry< S > *o2_, int b1_, int b2_)
add distance information into the result
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: OBBRSS.h:50
request to the distance computation
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
A class describing the kIOS collision structure, which is a set of spheres.
Definition: kIOS.h:48
S BVTesting(int b1, int b2) const
BV test between b1 and b2.


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