coal 3.0.1
Coal, The Collision Detection Library. Previously known as HPP-FCL, fork of FCL -- The Flexible Collision Library
Loading...
Searching...
No Matches
traversal_node_bvh_shape.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-2015, 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 COAL_TRAVERSAL_NODE_MESH_SHAPE_H
39#define COAL_TRAVERSAL_NODE_MESH_SHAPE_H
40
42
43#include "coal/collision_data.h"
49#include "coal/BVH/BVH_model.h"
51
52namespace coal {
53
56
58template <typename BV, typename S>
59class BVHShapeCollisionTraversalNode : public CollisionTraversalNodeBase {
60 public:
61 BVHShapeCollisionTraversalNode(const CollisionRequest& request)
62 : CollisionTraversalNodeBase(request) {
63 model1 = NULL;
64 model2 = NULL;
65
66 num_bv_tests = 0;
67 num_leaf_tests = 0;
68 query_time_seconds = 0.0;
69 }
70
72 bool isFirstNodeLeaf(unsigned int b) const {
73 return model1->getBV(b).isLeaf();
74 }
75
77 int getFirstLeftChild(unsigned int b) const {
78 return model1->getBV(b).leftChild();
79 }
80
82 int getFirstRightChild(unsigned int b) const {
83 return model1->getBV(b).rightChild();
84 }
85
86 const BVHModel<BV>* model1;
87 const S* model2;
88 BV model2_bv;
89
90 mutable int num_bv_tests;
91 mutable int num_leaf_tests;
92 mutable Scalar query_time_seconds;
93};
94
96template <typename BV, typename S,
97 int _Options = RelativeTransformationIsIdentity>
98class MeshShapeCollisionTraversalNode
99 : public BVHShapeCollisionTraversalNode<BV, S> {
100 public:
101 enum {
102 Options = _Options,
103 RTIsIdentity = _Options & RelativeTransformationIsIdentity
104 };
105
106 MeshShapeCollisionTraversalNode(const CollisionRequest& request)
107 : BVHShapeCollisionTraversalNode<BV, S>(request) {
108 vertices = NULL;
109 tri_indices = NULL;
110
111 nsolver = NULL;
112 }
113
119 bool BVDisjoints(unsigned int b1, unsigned int /*b2*/,
120 Scalar& sqrDistLowerBound) const {
121 if (this->enable_statistics) this->num_bv_tests++;
122 bool disjoint;
123 if (RTIsIdentity)
124 disjoint = !this->model1->getBV(b1).bv.overlap(
125 this->model2_bv, this->request, sqrDistLowerBound);
126 else
127 disjoint = !overlap(this->tf1.getRotation(), this->tf1.getTranslation(),
128 this->model1->getBV(b1).bv, this->model2_bv,
129 this->request, sqrDistLowerBound);
130 if (disjoint)
131 internal::updateDistanceLowerBoundFromBV(this->request, *this->result,
132 sqrDistLowerBound);
133 assert(!disjoint || sqrDistLowerBound > 0);
134 return disjoint;
135 }
136
138 void leafCollides(unsigned int b1, unsigned int /*b2*/,
139 Scalar& sqrDistLowerBound) const {
140 if (this->enable_statistics) this->num_leaf_tests++;
141 const BVNode<BV>& node = this->model1->getBV(b1);
142
143 int primitive_id = node.primitiveId();
144
145 const Triangle32& tri_id = this->tri_indices[primitive_id];
146 const TriangleP tri(this->vertices[tri_id[0]], this->vertices[tri_id[1]],
147 this->vertices[tri_id[2]]);
148
149 // When reaching this point, `this->solver` has already been set up
150 // by the CollisionRequest `this->request`.
151 // The only thing we need to (and can) pass to `ShapeShapeDistance` is
152 // whether or not penetration information is should be computed in case of
153 // collision.
154 const bool compute_penetration =
155 this->request.enable_contact || (this->request.security_margin < 0);
156 Vec3s c1, c2, normal;
158
159 if (RTIsIdentity) {
160 static const Transform3s Id;
161 distance = internal::ShapeShapeDistance<TriangleP, S>(
162 &tri, Id, this->model2, this->tf2, this->nsolver, compute_penetration,
163 c1, c2, normal);
164 } else {
165 distance = internal::ShapeShapeDistance<TriangleP, S>(
166 &tri, this->tf1, this->model2, this->tf2, this->nsolver,
167 compute_penetration, c1, c2, normal);
168 }
169 const Scalar distToCollision = distance - this->request.security_margin;
170
171 internal::updateDistanceLowerBoundFromLeaf(this->request, *(this->result),
172 distToCollision, c1, c2, normal);
173
174 if (distToCollision <= this->request.collision_distance_threshold) {
175 sqrDistLowerBound = 0;
176 if (this->result->numContacts() < this->request.num_max_contacts) {
177 this->result->addContact(Contact(this->model1, this->model2,
178 primitive_id, Contact::NONE, c1, c2,
179 normal, distance));
180 assert(this->result->isCollision());
181 }
182 } else {
183 sqrDistLowerBound = distToCollision * distToCollision;
184 }
185
186 assert(this->result->isCollision() || sqrDistLowerBound > 0);
187 } // leafCollides
188
189 Vec3s* vertices;
190 Triangle32* tri_indices;
191
192 const GJKSolver* nsolver;
193};
194
196
199
201template <typename BV, typename S>
202class BVHShapeDistanceTraversalNode : public DistanceTraversalNodeBase {
203 public:
204 BVHShapeDistanceTraversalNode() : DistanceTraversalNodeBase() {
205 model1 = NULL;
206 model2 = NULL;
207
208 num_bv_tests = 0;
209 num_leaf_tests = 0;
210 query_time_seconds = 0.0;
211 }
212
214 bool isFirstNodeLeaf(unsigned int b) const {
215 return model1->getBV(b).isLeaf();
216 }
217
219 int getFirstLeftChild(unsigned int b) const {
220 return model1->getBV(b).leftChild();
221 }
222
224 int getFirstRightChild(unsigned int b) const {
225 return model1->getBV(b).rightChild();
226 }
227
229 Scalar BVDistanceLowerBound(unsigned int b1, unsigned int /*b2*/) const {
230 return model1->getBV(b1).bv.distance(model2_bv);
231 }
232
233 const BVHModel<BV>* model1;
234 const S* model2;
235 BV model2_bv;
236
237 mutable int num_bv_tests;
238 mutable int num_leaf_tests;
239 mutable Scalar query_time_seconds;
240};
241
243template <typename S, typename BV>
244class ShapeBVHDistanceTraversalNode : public DistanceTraversalNodeBase {
245 public:
246 ShapeBVHDistanceTraversalNode() : DistanceTraversalNodeBase() {
247 model1 = NULL;
248 model2 = NULL;
249
250 num_bv_tests = 0;
251 num_leaf_tests = 0;
252 query_time_seconds = 0.0;
253 }
254
256 bool isSecondNodeLeaf(unsigned int b) const {
257 return model2->getBV(b).isLeaf();
258 }
259
261 int getSecondLeftChild(unsigned int b) const {
262 return model2->getBV(b).leftChild();
263 }
264
266 int getSecondRightChild(unsigned int b) const {
267 return model2->getBV(b).rightChild();
268 }
269
271 Scalar BVDistanceLowerBound(unsigned int /*b1*/, unsigned int b2) const {
272 return model1_bv.distance(model2->getBV(b2).bv);
273 }
274
275 const S* model1;
276 const BVHModel<BV>* model2;
277 BV model1_bv;
278
279 mutable int num_bv_tests;
280 mutable int num_leaf_tests;
281 mutable Scalar query_time_seconds;
282};
283
285template <typename BV, typename S>
286class MeshShapeDistanceTraversalNode
287 : public BVHShapeDistanceTraversalNode<BV, S> {
288 public:
289 MeshShapeDistanceTraversalNode() : BVHShapeDistanceTraversalNode<BV, S>() {
290 vertices = NULL;
291 tri_indices = NULL;
292
293 rel_err = 0;
294 abs_err = 0;
295
296 nsolver = NULL;
297 }
298
300 void leafComputeDistance(unsigned int b1, unsigned int /*b2*/) const {
301 if (this->enable_statistics) this->num_leaf_tests++;
302
303 const BVNode<BV>& node = this->model1->getBV(b1);
304
305 int primitive_id = node.primitiveId();
306
307 const Triangle32& tri_id = tri_indices[primitive_id];
308 const TriangleP tri(this->vertices[tri_id[0]], this->vertices[tri_id[1]],
309 this->vertices[tri_id[2]]);
310
311 Vec3s p1, p2, normal;
312 const Scalar distance = internal::ShapeShapeDistance<TriangleP, S>(
313 &tri, this->tf1, this->model2, this->tf2, this->nsolver,
314 this->request.enable_signed_distance, p1, p2, normal);
315
316 this->result->update(distance, this->model1, this->model2, primitive_id,
317 DistanceResult::NONE, p1, p2, normal);
318 }
319
321 bool canStop(Scalar c) const {
322 if ((c >= this->result->min_distance - abs_err) &&
323 (c * (1 + rel_err) >= this->result->min_distance))
324 return true;
325 return false;
326 }
327
328 Vec3s* vertices;
329 Triangle32* tri_indices;
330
331 Scalar rel_err;
332 Scalar abs_err;
333
334 const GJKSolver* nsolver;
335};
336
338namespace details {
339
340template <typename BV, typename S>
341void meshShapeDistanceOrientedNodeleafComputeDistance(
342 unsigned int b1, unsigned int /* b2 */, const BVHModel<BV>* model1,
343 const S& model2, Vec3s* vertices, Triangle32* tri_indices,
344 const Transform3s& tf1, const Transform3s& tf2, const GJKSolver* nsolver,
345 bool enable_statistics, int& num_leaf_tests, const DistanceRequest& request,
346 DistanceResult& result) {
347 if (enable_statistics) num_leaf_tests++;
348
349 const BVNode<BV>& node = model1->getBV(b1);
350 int primitive_id = node.primitiveId();
351
352 const Triangle32& tri_id = tri_indices[primitive_id];
353 const TriangleP tri(vertices[tri_id[0]], vertices[tri_id[1]],
354 vertices[tri_id[2]]);
355
356 Vec3s p1, p2, normal;
357 const Scalar distance = internal::ShapeShapeDistance<TriangleP, S>(
358 &tri, tf1, &model2, tf2, nsolver, request.enable_signed_distance, p1, p2,
359 normal);
360
361 result.update(distance, model1, &model2, primitive_id, DistanceResult::NONE,
362 p1, p2, normal);
363}
364
365template <typename BV, typename S>
366static inline void distancePreprocessOrientedNode(
367 const BVHModel<BV>* model1, Vec3s* vertices, Triangle32* tri_indices,
368 int init_tri_id, const S& model2, const Transform3s& tf1,
369 const Transform3s& tf2, const GJKSolver* nsolver,
370 const DistanceRequest& request, DistanceResult& result) {
371 const Triangle32& tri_id = tri_indices[init_tri_id];
372 const TriangleP tri(vertices[tri_id[0]], vertices[tri_id[1]],
373 vertices[tri_id[2]]);
374
375 Vec3s p1, p2, normal;
376 const Scalar distance = internal::ShapeShapeDistance<TriangleP, S>(
377 &tri, tf1, &model2, tf2, nsolver, request.enable_signed_distance, p1, p2,
378 normal);
379 result.update(distance, model1, &model2, init_tri_id, DistanceResult::NONE,
380 p1, p2, normal);
381}
382
383} // namespace details
384
386
389template <typename S>
390class MeshShapeDistanceTraversalNodeRSS
391 : public MeshShapeDistanceTraversalNode<RSS, S> {
392 public:
393 MeshShapeDistanceTraversalNodeRSS()
394 : MeshShapeDistanceTraversalNode<RSS, S>() {}
395
396 void preprocess() {
397 details::distancePreprocessOrientedNode(
398 this->model1, this->vertices, this->tri_indices, 0, *(this->model2),
399 this->tf1, this->tf2, this->nsolver, this->request, *(this->result));
400 }
401
402 void postprocess() {}
403
404 Scalar BVDistanceLowerBound(unsigned int b1, unsigned int /*b2*/) const {
405 if (this->enable_statistics) this->num_bv_tests++;
406 return distance(this->tf1.getRotation(), this->tf1.getTranslation(),
407 this->model2_bv, this->model1->getBV(b1).bv);
408 }
409
410 void leafComputeDistance(unsigned int b1, unsigned int b2) const {
411 details::meshShapeDistanceOrientedNodeleafComputeDistance(
412 b1, b2, this->model1, *(this->model2), this->vertices,
413 this->tri_indices, this->tf1, this->tf2, this->nsolver,
414 this->enable_statistics, this->num_leaf_tests, this->request,
415 *(this->result));
416 }
417};
418
419template <typename S>
420class MeshShapeDistanceTraversalNodekIOS
421 : public MeshShapeDistanceTraversalNode<kIOS, S> {
422 public:
423 MeshShapeDistanceTraversalNodekIOS()
424 : MeshShapeDistanceTraversalNode<kIOS, S>() {}
425
426 void preprocess() {
427 details::distancePreprocessOrientedNode(
428 this->model1, this->vertices, this->tri_indices, 0, *(this->model2),
429 this->tf1, this->tf2, this->nsolver, this->request, *(this->result));
430 }
431
432 void postprocess() {}
433
434 Scalar BVDistanceLowerBound(unsigned int b1, unsigned int /*b2*/) const {
435 if (this->enable_statistics) this->num_bv_tests++;
436 return distance(this->tf1.getRotation(), this->tf1.getTranslation(),
437 this->model2_bv, this->model1->getBV(b1).bv);
438 }
439
440 void leafComputeDistance(unsigned int b1, unsigned int b2) const {
441 details::meshShapeDistanceOrientedNodeleafComputeDistance(
442 b1, b2, this->model1, *(this->model2), this->vertices,
443 this->tri_indices, this->tf1, this->tf2, this->nsolver,
444 this->enable_statistics, this->num_leaf_tests, this->request,
445 *(this->result));
446 }
447};
448
449template <typename S>
450class MeshShapeDistanceTraversalNodeOBBRSS
451 : public MeshShapeDistanceTraversalNode<OBBRSS, S> {
452 public:
453 MeshShapeDistanceTraversalNodeOBBRSS()
454 : MeshShapeDistanceTraversalNode<OBBRSS, S>() {}
455
456 void preprocess() {
457 details::distancePreprocessOrientedNode(
458 this->model1, this->vertices, this->tri_indices, 0, *(this->model2),
459 this->tf1, this->tf2, this->nsolver, this->request, *(this->result));
460 }
461
462 void postprocess() {}
463
464 Scalar BVDistanceLowerBound(unsigned int b1, unsigned int /*b2*/) const {
465 if (this->enable_statistics) this->num_bv_tests++;
466 return distance(this->tf1.getRotation(), this->tf1.getTranslation(),
467 this->model2_bv, this->model1->getBV(b1).bv);
468 }
469
470 void leafComputeDistance(unsigned int b1, unsigned int b2) const {
471 details::meshShapeDistanceOrientedNodeleafComputeDistance(
472 b1, b2, this->model1, *(this->model2), this->vertices,
473 this->tri_indices, this->tf1, this->tf2, this->nsolver,
474 this->enable_statistics, this->num_leaf_tests, this->request,
475 *(this->result));
476 }
477};
478
480
481} // namespace coal
482
484
485#endif
Main namespace.
Definition broadphase_bruteforce.h:44
Scalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
bool overlap(const Matrix3s &R0, const Vec3s &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
Eigen::Matrix< Scalar, 3, 1 > Vec3s
Definition data_types.h:70
double Scalar
Definition data_types.h:68
TriangleTpl< std::uint32_t > Triangle32
Definition data_types.h:205
static const int NONE
invalid contact primitive information
Definition collision_data.h:1085