shape_mesh_collision_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_SHAPEMESHCOLLISIONTRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_SHAPEMESHCOLLISIONTRAVERSALNODE_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>
53 FCL_EXPORT
55  : ShapeBVHCollisionTraversalNode<Shape, BV>()
56 {
57  vertices = nullptr;
58  tri_indices = nullptr;
59 
60  nsolver = nullptr;
61 }
62 
63 //==============================================================================
64 template <typename Shape, typename BV, typename NarrowPhaseSolver>
65 FCL_EXPORT
67 {
68  FCL_UNUSED(b1);
69 
70  using S = typename BV::S;
71 
72  if(this->enable_statistics) this->num_leaf_tests++;
73  const BVNode<BV>& node = this->model2->getBV(b2);
74 
75  int primitive_id = node.primitiveId();
76 
77  const Triangle& tri_id = tri_indices[primitive_id];
78 
79  const Vector3<S>& p1 = vertices[tri_id[0]];
80  const Vector3<S>& p2 = vertices[tri_id[1]];
81  const Vector3<S>& p3 = vertices[tri_id[2]];
82 
83  if(this->model1->isOccupied() && this->model2->isOccupied())
84  {
85  bool is_intersect = false;
86 
87  if(!this->request.enable_contact)
88  {
89  if(nsolver->shapeTriangleIntersect(*(this->model1), this->tf1, p1, p2, p3, nullptr, nullptr, nullptr))
90  {
91  is_intersect = true;
92  if(this->request.num_max_contacts > this->result->numContacts())
93  this->result->addContact(Contact<S>(this->model1, this->model2, Contact<S>::NONE, primitive_id));
94  }
95  }
96  else
97  {
98  S penetration;
99  Vector3<S> normal;
100  Vector3<S> contactp;
101 
102  if(nsolver->shapeTriangleIntersect(*(this->model1), this->tf1, p1, p2, p3, &contactp, &penetration, &normal))
103  {
104  is_intersect = true;
105  if(this->request.num_max_contacts > this->result->numContacts())
106  this->result->addContact(Contact<S>(this->model1, this->model2, Contact<S>::NONE, primitive_id, contactp, normal, penetration));
107  }
108  }
109 
110  if(is_intersect && this->request.enable_cost)
111  {
112  AABB<S> overlap_part;
113  AABB<S> shape_aabb;
114  computeBV(*(this->model1), this->tf1, shape_aabb);
115  AABB<S>(p1, p2, p3).overlap(shape_aabb, overlap_part);
116  this->result->addCostSource(CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
117  }
118  }
119  else if((!this->model1->isFree() && !this->model2->isFree()) && this->request.enable_cost)
120  {
121  if(nsolver->shapeTriangleIntersect(*(this->model1), this->tf1, p1, p2, p3, nullptr, nullptr, nullptr))
122  {
123  AABB<S> overlap_part;
124  AABB<S> shape_aabb;
125  computeBV(*(this->model1), this->tf1, shape_aabb);
126  AABB<S>(p1, p2, p3).overlap(shape_aabb, overlap_part);
127  this->result->addCostSource(CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
128  }
129  }
130 }
131 
132 //==============================================================================
133 template <typename Shape, typename BV, typename NarrowPhaseSolver>
134 FCL_EXPORT
136 {
137  return this->request.isSatisfied(*(this->result));
138 }
139 
140 //==============================================================================
141 template <typename Shape, typename BV, typename NarrowPhaseSolver>
142 FCL_EXPORT
145  const Shape& model1,
146  const Transform3<typename BV::S>& tf1,
147  BVHModel<BV>& model2,
149  const NarrowPhaseSolver* nsolver,
150  const CollisionRequest<typename BV::S>& request,
152  bool use_refit,
153  bool refit_bottomup)
154 {
155  using S = typename BV::S;
156 
157  if(model2.getModelType() != BVH_MODEL_TRIANGLES)
158  return false;
159 
160  if(!tf2.matrix().isIdentity())
161  {
162  std::vector<Vector3<S>> vertices_transformed(model2.num_vertices);
163  for(int i = 0; i < model2.num_vertices; ++i)
164  {
165  Vector3<S>& p = model2.vertices[i];
166  Vector3<S> new_v = tf2 * p;
167  vertices_transformed[i] = new_v;
168  }
169 
170  model2.beginReplaceModel();
171  model2.replaceSubModel(vertices_transformed);
172  model2.endReplaceModel(use_refit, refit_bottomup);
173 
174  tf2.setIdentity();
175  }
176 
177  node.model1 = &model1;
178  node.tf1 = tf1;
179  node.model2 = &model2;
180  node.tf2 = tf2;
181  node.nsolver = nsolver;
182 
183  computeBV(model1, tf1, node.model1_bv);
184 
185  node.vertices = model2.vertices;
186  node.tri_indices = model2.tri_indices;
187 
188  node.request = request;
189  node.result = &result;
190 
191  node.cost_density = model1.cost_density * model2.cost_density;
192 
193  return true;
194 }
195 
196 //==============================================================================
197 template <typename Shape, typename NarrowPhaseSolver>
198 FCL_EXPORT
200 {
201 }
202 
203 //==============================================================================
204 template <typename Shape, typename NarrowPhaseSolver>
205 FCL_EXPORT
207 {
208  FCL_UNUSED(b1);
209 
210  if(this->enable_statistics) this->num_bv_tests++;
211  return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
212 }
213 
214 //==============================================================================
215 template <typename Shape, typename NarrowPhaseSolver>
216 FCL_EXPORT
218 {
220  this->tf2, this->tf1, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->request));
221 
222  // may need to change the order in pairs
223 }
224 
225 //==============================================================================
226 template <typename Shape, typename NarrowPhaseSolver>
227 FCL_EXPORT
229 {
230 }
231 
232 //==============================================================================
233 template <typename Shape, typename NarrowPhaseSolver>
234 FCL_EXPORT
236 {
237  FCL_UNUSED(b1);
238 
239  if(this->enable_statistics) this->num_bv_tests++;
240  return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
241 }
242 
243 //==============================================================================
244 template <typename Shape, typename NarrowPhaseSolver>
245 FCL_EXPORT
247 {
249  this->tf2, this->tf1, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->request));
250 
251  // may need to change the order in pairs
252 }
253 
254 //==============================================================================
255 template <typename Shape, typename NarrowPhaseSolver>
256 FCL_EXPORT
258 {
259 }
260 
261 //==============================================================================
262 template <typename Shape, typename NarrowPhaseSolver>
263 FCL_EXPORT
265 {
266  FCL_UNUSED(b1);
267 
268  if(this->enable_statistics) this->num_bv_tests++;
269  return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
270 }
271 
272 //==============================================================================
273 template <typename Shape, typename NarrowPhaseSolver>
274 FCL_EXPORT
276 {
278  this->tf2, this->tf1, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->request));
279 
280  // may need to change the order in pairs
281 }
282 
283 //==============================================================================
284 template <typename Shape, typename NarrowPhaseSolver>
285 FCL_EXPORT
287 {
288 }
289 
290 //==============================================================================
291 template <typename Shape, typename NarrowPhaseSolver>
292 FCL_EXPORT
294 {
295  FCL_UNUSED(b1);
296 
297  if(this->enable_statistics) this->num_bv_tests++;
298  return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv);
299 }
300 
301 //==============================================================================
302 template <typename Shape, typename NarrowPhaseSolver>
303 FCL_EXPORT
305 {
307  this->tf2, this->tf1, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->request));
308 
309  // may need to change the order in pairs
310 }
311 
312 template <typename Shape, typename BV, typename NarrowPhaseSolver, template <typename, typename> class OrientedNode>
313 static bool setupShapeMeshCollisionOrientedNode(OrientedNode<Shape, NarrowPhaseSolver>& node,
314  const Shape& model1, const Transform3<typename BV::S>& tf1,
316  const NarrowPhaseSolver* nsolver,
319 {
320  if(model2.getModelType() != BVH_MODEL_TRIANGLES)
321  return false;
322 
323  node.model1 = &model1;
324  node.tf1 = tf1;
325  node.model2 = &model2;
326  node.tf2 = tf2;
327  node.nsolver = nsolver;
328 
329  computeBV(model1, tf1, node.model1_bv);
330 
331  node.vertices = model2.vertices;
332  node.tri_indices = model2.tri_indices;
333 
334  node.request = request;
335  node.result = &result;
336 
337  node.cost_density = model1.cost_density * model2.cost_density;
338 
339  return true;
340 }
341 
342 //==============================================================================
343 template <typename Shape, typename NarrowPhaseSolver>
344 FCL_EXPORT
347  const Shape& model1,
351  const NarrowPhaseSolver* nsolver,
354 {
356  node, model1, tf1, model2, tf2, nsolver, request, result);
357 }
358 
359 //==============================================================================
360 template <typename Shape, typename NarrowPhaseSolver>
361 FCL_EXPORT
364  const Shape& model1,
368  const NarrowPhaseSolver* nsolver,
371 {
373  node, model1, tf1, model2, tf2, nsolver, request, result);
374 }
375 
376 //==============================================================================
377 template <typename Shape, typename NarrowPhaseSolver>
378 FCL_EXPORT
381  const Shape& model1,
385  const NarrowPhaseSolver* nsolver,
388 {
390  node, model1, tf1, model2, tf2, nsolver, request, result);
391 }
392 
393 //==============================================================================
394 template <typename Shape, typename NarrowPhaseSolver>
395 FCL_EXPORT
398  const Shape& model1,
402  const NarrowPhaseSolver* nsolver,
405 {
407  node, model1, tf1, model2, tf2, nsolver, request, result);
408 }
409 
410 } // namespace detail
411 } // namespace fcl
412 
413 #endif
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Main namespace.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
collision result
Traversal node for collision between shape and BVH.
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
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...
Transform3< BV::S > tf2
configuration of second object
Contact information returned by collision.
Definition: contact.h:48
bool overlap(S a1, S a2, S b1, S b2)
returns 1 if the intervals overlap, and 0 otherwise
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
CollisionRequest< BV::S > request
request setting for collision
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
unknown model type
Definition: BVH_internal.h:78
Traversal node for collision between shape and mesh.
static bool setupShapeMeshCollisionOrientedNode(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 CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
Parameters for performing collision request.
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)
bool 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 meshShapeCollisionOrientedNodeLeafTesting(int b1, int b2, 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, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
FCL_EXPORT bool initialize(ShapeMeshCollisionTraversalNodeOBBRSS< 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 CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result)
Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS ty...
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
BV::S cost_density
collision cost for unit volume
CollisionResult< BV::S > * result
collision 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
Cost source describes an area with a cost. The area is described by an AABB<S> region.
Definition: cost_source.h:49
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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.
A class describing the kIOS collision structure, which is a set of spheres.
Definition: kIOS.h:48
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Oriented bounding box class.
Definition: OBB.h:51
Traversal node for shape and mesh, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)


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