mesh_shape_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_MESHSHAPECOLLISIONTRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_MESHSHAPECOLLISIONTRAVERSALNODE_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>
54  : BVHShapeCollisionTraversalNode<BV, Shape>()
55 {
56  vertices = nullptr;
57  tri_indices = nullptr;
58 
59  nsolver = nullptr;
60 }
61 
62 //==============================================================================
63 template <typename BV, typename Shape, typename NarrowPhaseSolver>
65 {
66  FCL_UNUSED(b2);
67 
68  if(this->enable_statistics) this->num_leaf_tests++;
69  const BVNode<BV>& node = this->model1->getBV(b1);
70 
71  int primitive_id = node.primitiveId();
72 
73  const Triangle& tri_id = tri_indices[primitive_id];
74 
75  const Vector3<S>& p1 = vertices[tri_id[0]];
76  const Vector3<S>& p2 = vertices[tri_id[1]];
77  const Vector3<S>& p3 = vertices[tri_id[2]];
78 
79  if(this->model1->isOccupied() && this->model2->isOccupied())
80  {
81  bool is_intersect = false;
82 
83  if(!this->request.enable_contact)
84  {
85  if(nsolver->shapeTriangleIntersect(*(this->model2), this->tf2, p1, p2, p3, nullptr, nullptr, nullptr))
86  {
87  is_intersect = true;
88  if(this->request.num_max_contacts > this->result->numContacts())
89  this->result->addContact(Contact<S>(this->model1, this->model2, primitive_id, Contact<S>::NONE));
90  }
91  }
92  else
93  {
94  S penetration;
95  Vector3<S> normal;
96  Vector3<S> contactp;
97 
98  if(nsolver->shapeTriangleIntersect(*(this->model2), this->tf2, p1, p2, p3, &contactp, &penetration, &normal))
99  {
100  is_intersect = true;
101  if(this->request.num_max_contacts > this->result->numContacts())
102  this->result->addContact(Contact<S>(this->model1, this->model2, primitive_id, Contact<S>::NONE, contactp, -normal, penetration));
103  }
104  }
105 
106  if(is_intersect && this->request.enable_cost)
107  {
108  AABB<S> overlap_part;
109  AABB<S> shape_aabb;
110  computeBV(*(this->model2), this->tf2, shape_aabb);
111  AABB<S>(p1, p2, p3).overlap(shape_aabb, overlap_part);
112  this->result->addCostSource(CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
113  }
114  }
115  if((!this->model1->isFree() && !this->model2->isFree()) && this->request.enable_cost)
116  {
117  if(nsolver->shapeTriangleIntersect(*(this->model2), this->tf2, p1, p2, p3, nullptr, nullptr, nullptr))
118  {
119  AABB<S> overlap_part;
120  AABB<S> shape_aabb;
121  computeBV(*(this->model2), this->tf2, shape_aabb);
122  AABB<S>(p1, p2, p3).overlap(shape_aabb, overlap_part);
123  this->result->addCostSource(CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
124  }
125  }
126 }
127 
128 //==============================================================================
129 template <typename BV, typename Shape, typename NarrowPhaseSolver>
131 {
132  return this->request.isSatisfied(*(this->result));
133 }
134 
135 //==============================================================================
136 template <typename BV, typename Shape, typename NarrowPhaseSolver>
139  BVHModel<BV>& model1,
141  const Shape& model2,
142  const Transform3<typename BV::S>& tf2,
143  const NarrowPhaseSolver* nsolver,
144  const CollisionRequest<typename BV::S>& request,
146  bool use_refit,
147  bool refit_bottomup)
148 {
149  using S = typename BV::S;
150 
151  if(model1.getModelType() != BVH_MODEL_TRIANGLES)
152  return false;
153 
154  if(!tf1.matrix().isIdentity())
155  {
156  std::vector<Vector3<S>> vertices_transformed(model1.num_vertices);
157  for(int i = 0; i < model1.num_vertices; ++i)
158  {
159  Vector3<S>& p = model1.vertices[i];
160  Vector3<S> new_v = tf1 * p;
161  vertices_transformed[i] = new_v;
162  }
163 
164  model1.beginReplaceModel();
165  model1.replaceSubModel(vertices_transformed);
166  model1.endReplaceModel(use_refit, refit_bottomup);
167 
168  tf1.setIdentity();
169  }
170 
171  node.model1 = &model1;
172  node.tf1 = tf1;
173  node.model2 = &model2;
174  node.tf2 = tf2;
175  node.nsolver = nsolver;
176 
177  computeBV(model2, tf2, node.model2_bv);
178 
179  node.vertices = model1.vertices;
180  node.tri_indices = model1.tri_indices;
181 
182  node.request = request;
183  node.result = &result;
184 
185  node.cost_density = model1.cost_density * model2.cost_density;
186 
187  return true;
188 }
189 
190 //==============================================================================
191 template <typename BV, typename Shape, typename NarrowPhaseSolver>
193  int b1, int b2,
194  const BVHModel<BV>* model1, const Shape& model2,
195  Vector3<typename BV::S>* vertices, Triangle* tri_indices,
196  const Transform3<typename BV::S>& tf1,
197  const Transform3<typename BV::S>& tf2,
198  const NarrowPhaseSolver* nsolver,
199  bool enable_statistics,
200  typename BV::S cost_density,
201  int& num_leaf_tests,
202  const CollisionRequest<typename BV::S>& request,
204 {
205  FCL_UNUSED(b2);
206 
207  using S = typename BV::S;
208 
209  if(enable_statistics) num_leaf_tests++;
210  const BVNode<BV>& node = model1->getBV(b1);
211 
212  int primitive_id = node.primitiveId();
213 
214  const Triangle& tri_id = tri_indices[primitive_id];
215 
216  const Vector3<S>& p1 = vertices[tri_id[0]];
217  const Vector3<S>& p2 = vertices[tri_id[1]];
218  const Vector3<S>& p3 = vertices[tri_id[2]];
219 
220  if(model1->isOccupied() && model2.isOccupied())
221  {
222  bool is_intersect = false;
223 
224  if(!request.enable_contact) // only interested in collision or not
225  {
226  if(nsolver->shapeTriangleIntersect(model2, tf2, p1, p2, p3, tf1, nullptr, nullptr, nullptr))
227  {
228  is_intersect = true;
229  if(request.num_max_contacts > result.numContacts())
230  result.addContact(Contact<S>(model1, &model2, primitive_id, Contact<S>::NONE));
231  }
232  }
233  else
234  {
235  S penetration;
236  Vector3<S> normal;
237  Vector3<S> contactp;
238 
239  if(nsolver->shapeTriangleIntersect(model2, tf2, p1, p2, p3, tf1, &contactp, &penetration, &normal))
240  {
241  is_intersect = true;
242  if(request.num_max_contacts > result.numContacts())
243  result.addContact(Contact<S>(model1, &model2, primitive_id, Contact<S>::NONE, contactp, -normal, penetration));
244  }
245  }
246 
247  if(is_intersect && request.enable_cost)
248  {
249  AABB<S> overlap_part;
250  AABB<S> shape_aabb;
251  computeBV(model2, tf2, shape_aabb);
252  /* bool res = */ AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).overlap(shape_aabb, overlap_part);
253  result.addCostSource(CostSource<S>(overlap_part, cost_density), request.num_max_cost_sources);
254  }
255  }
256  else if((!model1->isFree() || model2.isFree()) && request.enable_cost)
257  {
258  if(nsolver->shapeTriangleIntersect(model2, tf2, p1, p2, p3, tf1, nullptr, nullptr, nullptr))
259  {
260  AABB<S> overlap_part;
261  AABB<S> shape_aabb;
262  computeBV(model2, tf2, shape_aabb);
263  /* bool res = */ AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).overlap(shape_aabb, overlap_part);
264  result.addCostSource(CostSource<S>(overlap_part, cost_density), request.num_max_cost_sources);
265  }
266  }
267 }
268 
269 //==============================================================================
270 template <typename Shape, typename NarrowPhaseSolver>
273  : MeshShapeCollisionTraversalNode<OBB<typename Shape::S>, Shape, NarrowPhaseSolver>()
274 {
275 }
276 
277 //==============================================================================
278 template <typename Shape, typename NarrowPhaseSolver>
280 {
281  FCL_UNUSED(b2);
282 
283  if(this->enable_statistics) this->num_bv_tests++;
284 
285  return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
286 }
287 
288 //==============================================================================
289 template <typename Shape, typename NarrowPhaseSolver>
291 {
293  this->tf1, this->tf2, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->result));
294 }
295 
296 //==============================================================================
297 template <typename Shape, typename NarrowPhaseSolver>
299  : MeshShapeCollisionTraversalNode<RSS<typename Shape::S>, Shape, NarrowPhaseSolver>()
300 {
301 }
302 
303 //==============================================================================
304 template <typename Shape, typename NarrowPhaseSolver>
306 {
307  FCL_UNUSED(b2);
308 
309  if(this->enable_statistics) this->num_bv_tests++;
310 
311  return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
312 }
313 
314 //==============================================================================
315 template <typename Shape, typename NarrowPhaseSolver>
317 {
319  this->tf1, this->tf2, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->result));
320 }
321 
322 //==============================================================================
323 template <typename Shape, typename NarrowPhaseSolver>
326  : MeshShapeCollisionTraversalNode<kIOS<typename Shape::S>, Shape, NarrowPhaseSolver>()
327 {
328 }
329 
330 //==============================================================================
331 template <typename Shape, typename NarrowPhaseSolver>
333 {
334  FCL_UNUSED(b2);
335 
336  if(this->enable_statistics) this->num_bv_tests++;
337 
338  return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
339 }
340 
341 //==============================================================================
342 template <typename Shape, typename NarrowPhaseSolver>
344 {
346  this->tf1, this->tf2, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->result));
347 }
348 
349 //==============================================================================
350 template <typename Shape, typename NarrowPhaseSolver>
353  : MeshShapeCollisionTraversalNode<OBBRSS<typename Shape::S>, Shape, NarrowPhaseSolver>()
354 {
355 }
356 
357 //==============================================================================
358 template <typename Shape, typename NarrowPhaseSolver>
360 {
361  FCL_UNUSED(b2);
362 
363  if(this->enable_statistics) this->num_bv_tests++;
364  return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv);
365 }
366 
367 //==============================================================================
368 template <typename Shape, typename NarrowPhaseSolver>
370 {
372  this->tf1, this->tf2, this->nsolver, this->enable_statistics, this->cost_density, this->num_leaf_tests, this->request, *(this->result));
373 }
374 
375 template <typename BV, typename Shape, typename NarrowPhaseSolver,
376  template <typename, typename> class OrientedNode>
378  OrientedNode<Shape, NarrowPhaseSolver>& node,
379  const BVHModel<BV>& model1,
381  const Shape& model2, const Transform3<typename BV::S>& tf2,
382  const NarrowPhaseSolver* nsolver,
385 {
386  if(model1.getModelType() != BVH_MODEL_TRIANGLES)
387  return false;
388 
389  node.model1 = &model1;
390  node.tf1 = tf1;
391  node.model2 = &model2;
392  node.tf2 = tf2;
393  node.nsolver = nsolver;
394 
395  computeBV(model2, tf2, node.model2_bv);
396 
397  node.vertices = model1.vertices;
398  node.tri_indices = model1.tri_indices;
399 
400  node.request = request;
401  node.result = &result;
402 
403  node.cost_density = model1.cost_density * model2.cost_density;
404 
405  return true;
406 }
407 
408 //==============================================================================
409 template <typename Shape, typename NarrowPhaseSolver>
414  const Shape& model2,
416  const NarrowPhaseSolver* nsolver,
419 {
421  node, model1, tf1, model2, tf2, nsolver, request, result);
422 }
423 
424 //==============================================================================
425 template <typename Shape, typename NarrowPhaseSolver>
430  const Shape& model2,
432  const NarrowPhaseSolver* nsolver,
435 {
437  node, model1, tf1, model2, tf2, nsolver, request, result);
438 }
439 
440 //==============================================================================
441 template <typename Shape, typename NarrowPhaseSolver>
446  const Shape& model2,
448  const NarrowPhaseSolver* nsolver,
451 {
453  node, model1, tf1, model2, tf2, nsolver, request, result);
454 }
455 
456 //==============================================================================
457 template <typename Shape, typename NarrowPhaseSolver>
462  const Shape& model2,
464  const NarrowPhaseSolver* nsolver,
467 {
469  node, model1, tf1, model2, tf2, nsolver, request, result);
470 }
471 
472 } // namespace detail
473 } // namespace fcl
474 
475 #endif
Traversal node for collision between mesh and shape.
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
size_t numContacts() const
number of contacts found
bool enable_cost
If true, the cost sources will be computed.
void addCostSource(const CostSource< S > &c, std::size_t num_max_cost_sources)
add one cost source into result structure
size_t num_max_contacts
The maximum number of contacts that can be returned.
Main namespace.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
collision result
bool setupMeshShapeCollisionOrientedNode(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 CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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.
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)...
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
bool isFree() const
whether the object is completely free
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
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
Traversal node for collision 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
unknown model type
Definition: BVH_internal.h:78
bool enable_contact
If true, contact information (e.g., normal, penetration depth, and contact position) will be returned...
Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
Parameters for performing collision request.
size_t num_max_cost_sources
The maximum number of cost sources that can be returned.
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 isOccupied() const
whether the object is completely occupied
#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
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)
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
bool initialize(MeshShapeCollisionTraversalNodeOBBRSS< 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 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...
Cost source describes an area with a cost. The area is described by an AABB<S> region.
Definition: cost_source.h:49
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: OBBRSS.h:50
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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
Oriented bounding box class.
Definition: OBB.h:51
void addContact(const Contact< S > &c)
add one contact into result structure


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