shape_mesh_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_SHAPEMESHDISTANCETRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_SHAPEMESHDISTANCETRAVERSALNODE_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  : ShapeBVHDistanceTraversalNode<Shape, BV>()
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 Shape, typename BV, typename NarrowPhaseSolver>
69 {
70  FCL_UNUSED(b1);
71 
72  using S = typename BV::S;
73 
74  if(this->enable_statistics) this->num_leaf_tests++;
75 
76  const BVNode<BV>& node = this->model2->getBV(b2);
77 
78  int primitive_id = node.primitiveId();
79 
80  const Triangle& tri_id = tri_indices[primitive_id];
81 
82  const Vector3<S>& p1 = vertices[tri_id[0]];
83  const Vector3<S>& p2 = vertices[tri_id[1]];
84  const Vector3<S>& p3 = vertices[tri_id[2]];
85 
86  S distance;
87  Vector3<S> closest_p1, closest_p2;
88  nsolver->shapeTriangleDistance(*(this->model1), this->tf1, p1, p2, p3, &distance, &closest_p1, &closest_p2);
89 
90  this->result->update(
91  distance,
92  this->model1,
93  this->model2,
95  primitive_id,
96  closest_p1,
97  closest_p2);
98 }
99 
100 //==============================================================================
101 template <typename Shape, typename BV, typename NarrowPhaseSolver>
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 Shape, typename BV, typename NarrowPhaseSolver>
111 FCL_EXPORT
114  const Shape& model1,
115  const Transform3<typename BV::S>& tf1,
116  BVHModel<BV>& model2,
118  const NarrowPhaseSolver* nsolver,
119  const DistanceRequest<typename BV::S>& request,
121  bool use_refit,
122  bool refit_bottomup)
123 {
124  using S = typename BV::S;
125 
126  if(model2.getModelType() != BVH_MODEL_TRIANGLES)
127  return false;
128 
129  if(!tf2.matrix().isIdentity())
130  {
131  std::vector<Vector3<S>> vertices_transformed(model2.num_vertices);
132  for(int i = 0; i < model2.num_vertices; ++i)
133  {
134  Vector3<S>& p = model2.vertices[i];
135  Vector3<S> new_v = tf2 * p;
136  vertices_transformed[i] = new_v;
137  }
138 
139  model2.beginReplaceModel();
140  model2.replaceSubModel(vertices_transformed);
141  model2.endReplaceModel(use_refit, refit_bottomup);
142 
143  tf2.setIdentity();
144  }
145 
146  node.request = request;
147  node.result = &result;
148 
149  node.model1 = &model1;
150  node.tf1 = tf1;
151  node.model2 = &model2;
152  node.tf2 = tf2;
153  node.nsolver = nsolver;
154 
155  node.vertices = model2.vertices;
156  node.tri_indices = model2.tri_indices;
157 
158  computeBV(model1, tf1, node.model1_bv);
159 
160  return true;
161 }
162 
163 //==============================================================================
164 template <typename Shape, typename NarrowPhaseSolver>
166  : ShapeMeshDistanceTraversalNode<Shape, RSS<S>, NarrowPhaseSolver>()
167 {
168 }
169 
170 //==============================================================================
171 template <typename Shape, typename NarrowPhaseSolver>
173 {
175  this->model2, this->vertices, this->tri_indices, 0,
176  *(this->model1), this->tf2, this->tf1, this->nsolver, this->request, *(this->result));
177 }
178 
179 //==============================================================================
180 template <typename Shape, typename NarrowPhaseSolver>
182 {
183 }
184 
185 //==============================================================================
186 template <typename Shape, typename NarrowPhaseSolver>
187 typename Shape::S
189 BVTesting(int b1, int b2) const
190 {
191  FCL_UNUSED(b1);
192 
193  if(this->enable_statistics) this->num_bv_tests++;
194  return distance(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
195 }
196 
197 //==============================================================================
198 template <typename Shape, typename NarrowPhaseSolver>
200 leafTesting(int b1, int b2) const
201 {
203  this->tf2, this->tf1, this->nsolver, this->enable_statistics, this->num_leaf_tests, this->request, *(this->result));
204 }
205 
206 //==============================================================================
207 template <typename Shape, typename NarrowPhaseSolver>
210  : ShapeMeshDistanceTraversalNode<Shape, kIOS<S>, NarrowPhaseSolver>()
211 {
212 }
213 
214 //==============================================================================
215 template <typename Shape, typename NarrowPhaseSolver>
217 {
219  this->model2,
220  this->vertices,
221  this->tri_indices,
222  0,
223  *(this->model1),
224  this->tf2,
225  this->tf1,
226  this->nsolver,
227  *(this->result));
228 }
229 
230 //==============================================================================
231 template <typename Shape, typename NarrowPhaseSolver>
233 {
234 }
235 
236 //==============================================================================
237 template <typename Shape, typename NarrowPhaseSolver>
238 typename Shape::S
240 BVTesting(int b1, int b2) const
241 {
242  FCL_UNUSED(b1);
243 
244  if(this->enable_statistics) this->num_bv_tests++;
245  return distance(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
246 }
247 
248 //==============================================================================
249 template <typename Shape, typename NarrowPhaseSolver>
251 leafTesting(int b1, int b2) const
252 {
254  this->tf2, this->tf1, this->nsolver, this->enable_statistics, this->num_leaf_tests, this->request, *(this->result));
255 }
256 
257 //==============================================================================
258 template <typename Shape, typename NarrowPhaseSolver>
261 {
262 }
263 
264 //==============================================================================
265 template <typename Shape, typename NarrowPhaseSolver>
267 {
269  this->model2,
270  this->vertices,
271  this->tri_indices,
272  0,
273  *(this->model1),
274  this->tf2,
275  this->tf1,
276  this->nsolver,
277  *(this->result));
278 }
279 
280 //==============================================================================
281 template <typename Shape, typename NarrowPhaseSolver>
284 {
285 }
286 
287 //==============================================================================
288 template <typename Shape, typename NarrowPhaseSolver>
289 typename Shape::S
291 BVTesting(int b1, int b2) const
292 {
293  FCL_UNUSED(b1);
294 
295  if(this->enable_statistics) this->num_bv_tests++;
296  return distance(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
297 }
298 
299 //==============================================================================
300 template <typename Shape, typename NarrowPhaseSolver>
302 leafTesting(int b1, int b2) const
303 {
305  b2,
306  b1,
307  this->model2,
308  *(this->model1),
309  this->vertices,
310  this->tri_indices,
311  this->tf2,
312  this->tf1,
313  this->nsolver,
314  this->enable_statistics,
315  this->num_leaf_tests,
316  this->request,
317  *(this->result));
318 }
319 
320 template <typename Shape, typename BV, typename NarrowPhaseSolver, template <typename, typename> class OrientedNode>
321 static bool setupShapeMeshDistanceOrientedNode(OrientedNode<Shape, NarrowPhaseSolver>& node,
322  const Shape& model1, const Transform3<typename BV::S>& tf1,
324  const NarrowPhaseSolver* nsolver,
327 {
328  if(model2.getModelType() != BVH_MODEL_TRIANGLES)
329  return false;
330 
331  node.request = request;
332  node.result = &result;
333 
334  node.model1 = &model1;
335  node.tf1 = tf1;
336  node.model2 = &model2;
337  node.tf2 = tf2;
338  node.nsolver = nsolver;
339 
340  computeBV(model1, tf1, node.model1_bv);
341 
342  node.vertices = model2.vertices;
343  node.tri_indices = model2.tri_indices;
344  node.R = tf2.linear();
345  node.T = tf2.translation();
346 
347  return true;
348 }
349 
350 //==============================================================================
351 template <typename Shape, typename NarrowPhaseSolver>
352 FCL_EXPORT
354  const Shape& model1, const Transform3<typename Shape::S>& tf1,
356  const NarrowPhaseSolver* nsolver,
359 {
360  return detail::setupShapeMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, nsolver, request, result);
361 }
362 
363 //==============================================================================
364 template <typename Shape, typename NarrowPhaseSolver>
365 FCL_EXPORT
367  const Shape& model1, const Transform3<typename Shape::S>& tf1,
369  const NarrowPhaseSolver* nsolver,
372 {
373  return detail::setupShapeMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, nsolver, request, result);
374 }
375 
376 //==============================================================================
377 template <typename Shape, typename NarrowPhaseSolver>
378 FCL_EXPORT
380  const Shape& model1, const Transform3<typename Shape::S>& tf1,
382  const NarrowPhaseSolver* nsolver,
385 {
386  return detail::setupShapeMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, nsolver, request, result);
387 }
388 
389 } // namespace detail
390 } // namespace fcl
391 
392 #endif
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Traversal node for distance between shape and mesh.
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
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
static bool setupShapeMeshDistanceOrientedNode(OrientedNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
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...
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 shape and BVH.
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
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 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)
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
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_EXPORT bool initialize(ShapeMeshDistanceTraversalNodeOBBRSS< 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, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result)
Initialize traversal node for distance computation between one shape and one mesh, specialized for OBBRSS type.
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
DistanceRequest< BV::S > request
request setting for distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
#define FCL_UNUSED(x)
Definition: unused.h:39
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
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
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


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