39 #ifndef HPP_FCL_TRAVERSAL_NODE_OCTREE_H
40 #define HPP_FCL_TRAVERSAL_NODE_OCTREE_H
60 const GJKSolver* solver;
62 mutable const CollisionRequest* crequest;
63 mutable const DistanceRequest* drequest;
65 mutable CollisionResult* cresult;
66 mutable DistanceResult* dresult;
69 OcTreeSolver(
const GJKSolver* solver_)
77 void OcTreeIntersect(
const OcTree* tree1,
const OcTree* tree2,
78 const Transform3f& tf1,
const Transform3f& tf2,
79 const CollisionRequest& request_,
80 CollisionResult& result_)
const {
84 OcTreeIntersectRecurse(tree1, tree1->getRoot(), tree1->getRootBV(), tree2,
85 tree2->getRoot(), tree2->getRootBV(), tf1, tf2);
89 void OcTreeDistance(
const OcTree* tree1,
const OcTree* tree2,
90 const Transform3f& tf1,
const Transform3f& tf2,
91 const DistanceRequest& request_,
92 DistanceResult& result_)
const {
96 OcTreeDistanceRecurse(tree1, tree1->getRoot(), tree1->getRootBV(), tree2,
97 tree2->getRoot(), tree2->getRootBV(), tf1, tf2);
101 template <
typename BV>
102 void OcTreeMeshIntersect(
const OcTree* tree1,
const BVHModel<BV>* tree2,
103 const Transform3f& tf1,
const Transform3f& tf2,
104 const CollisionRequest& request_,
105 CollisionResult& result_)
const {
106 crequest = &request_;
109 OcTreeMeshIntersectRecurse(tree1, tree1->getRoot(), tree1->getRootBV(),
114 template <
typename BV>
115 void OcTreeMeshDistance(
const OcTree* tree1,
const BVHModel<BV>* tree2,
116 const Transform3f& tf1,
const Transform3f& tf2,
117 const DistanceRequest& request_,
118 DistanceResult& result_)
const {
119 drequest = &request_;
122 OcTreeMeshDistanceRecurse(tree1, tree1->getRoot(), tree1->getRootBV(),
127 template <
typename BV>
128 void MeshOcTreeIntersect(
const BVHModel<BV>* tree1,
const OcTree* tree2,
129 const Transform3f& tf1,
const Transform3f& tf2,
130 const CollisionRequest& request_,
131 CollisionResult& result_)
const
134 crequest = &request_;
137 OcTreeMeshIntersectRecurse(tree2, tree2->getRoot(), tree2->getRootBV(),
142 template <
typename BV>
143 void MeshOcTreeDistance(
const BVHModel<BV>* tree1,
const OcTree* tree2,
144 const Transform3f& tf1,
const Transform3f& tf2,
145 const DistanceRequest& request_,
146 DistanceResult& result_)
const {
147 drequest = &request_;
150 OcTreeMeshDistanceRecurse(tree1, 0, tree2, tree2->getRoot(),
151 tree2->getRootBV(), tf1, tf2);
154 template <
typename BV>
155 void OcTreeHeightFieldIntersect(
156 const OcTree* tree1,
const HeightField<BV>* tree2,
const Transform3f& tf1,
157 const Transform3f& tf2,
const CollisionRequest& request_,
158 CollisionResult& result_,
FCL_REAL& sqrDistLowerBound)
const {
159 crequest = &request_;
162 OcTreeHeightFieldIntersectRecurse(tree1, tree1->getRoot(),
163 tree1->getRootBV(), tree2, 0, tf1, tf2,
167 template <
typename BV>
168 void HeightFieldOcTreeIntersect(
const HeightField<BV>* tree1,
169 const OcTree* tree2,
const Transform3f& tf1,
170 const Transform3f& tf2,
171 const CollisionRequest& request_,
172 CollisionResult& result_,
173 FCL_REAL& sqrDistLowerBound)
const {
174 crequest = &request_;
177 HeightFieldOcTreeIntersectRecurse(tree1, 0, tree2, tree2->getRoot(),
178 tree2->getRootBV(), tf1, tf2,
183 template <
typename S>
184 void OcTreeShapeIntersect(
const OcTree* tree,
const S& s,
185 const Transform3f& tf1,
const Transform3f& tf2,
186 const CollisionRequest& request_,
187 CollisionResult& result_)
const {
188 crequest = &request_;
192 computeBV<AABB>(s, Transform3f(), bv2);
194 convertBV(bv2, tf2, obb2);
195 OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
200 template <
typename S>
201 void ShapeOcTreeIntersect(
const S& s,
const OcTree* tree,
202 const Transform3f& tf1,
const Transform3f& tf2,
203 const CollisionRequest& request_,
204 CollisionResult& result_)
const {
205 crequest = &request_;
209 computeBV<AABB>(s, Transform3f(), bv1);
211 convertBV(bv1, tf1, obb1);
212 OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
217 template <
typename S>
218 void OcTreeShapeDistance(
const OcTree* tree,
const S& s,
219 const Transform3f& tf1,
const Transform3f& tf2,
220 const DistanceRequest& request_,
221 DistanceResult& result_)
const {
222 drequest = &request_;
226 computeBV<AABB>(s, tf2, aabb2);
227 OcTreeShapeDistanceRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
232 template <
typename S>
233 void ShapeOcTreeDistance(
const S& s,
const OcTree* tree,
234 const Transform3f& tf1,
const Transform3f& tf2,
235 const DistanceRequest& request_,
236 DistanceResult& result_)
const {
237 drequest = &request_;
241 computeBV<AABB>(s, tf1, aabb1);
242 OcTreeShapeDistanceRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
247 template <
typename S>
248 bool OcTreeShapeDistanceRecurse(
const OcTree* tree1,
250 const AABB& bv1,
const S& s,
251 const AABB& aabb2,
const Transform3f& tf1,
252 const Transform3f& tf2)
const {
253 if (!tree1->nodeHasChildren(root1)) {
254 if (tree1->isNodeOccupied(root1)) {
260 box.computeLocalAABB();
263 Vec3f p1, p2, normal;
265 &box, box_tf, &s, tf2, this->solver,
266 this->drequest->enable_signed_distance, p1, p2, normal);
268 this->dresult->update(
distance, tree1, &s,
269 (
int)(root1 - tree1->getRoot()),
272 return drequest->isSatisfied(*dresult);
277 if (!tree1->isNodeOccupied(root1))
return false;
279 for (
unsigned int i = 0; i < 8; ++i) {
280 if (tree1->nodeChildExists(root1, i)) {
283 computeChildBV(bv1, i, child_bv);
286 convertBV(child_bv, tf1, aabb1);
288 if (d < dresult->min_distance) {
289 if (OcTreeShapeDistanceRecurse(tree1, child, child_bv, s, aabb2, tf1,
299 template <
typename S>
300 bool OcTreeShapeIntersectRecurse(
const OcTree* tree1,
302 const AABB& bv1,
const S& s,
const OBB& obb2,
303 const Transform3f& tf1,
304 const Transform3f& tf2)
const {
306 if (!root1)
return false;
312 if (tree1->isNodeFree(root1))
314 else if ((tree1->isNodeUncertain(root1) || s.isUncertain()))
318 convertBV(bv1, tf1, obb1);
320 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
327 if (!tree1->nodeHasChildren(root1)) {
328 assert(tree1->isNodeOccupied(root1));
334 box.computeLocalAABB();
337 bool contactNotAdded =
338 (cresult->numContacts() >= crequest->num_max_contacts);
339 std::size_t ncontact = ShapeShapeCollide<Box, S>(
340 &box, box_tf, &s, tf2, solver, *crequest, *cresult);
341 assert(ncontact == 0 || ncontact == 1);
342 if (!contactNotAdded && ncontact == 1) {
344 const Contact& c = cresult->getContact(cresult->numContacts() - 1);
346 cresult->numContacts() - 1,
347 Contact(tree1, c.o2,
static_cast<int>(root1 - tree1->getRoot()),
348 c.b2, c.pos, c.normal, c.penetration_depth));
353 return crequest->isSatisfied(*cresult);
356 for (
unsigned int i = 0; i < 8; ++i) {
357 if (tree1->nodeChildExists(root1, i)) {
360 computeChildBV(bv1, i, child_bv);
362 if (OcTreeShapeIntersectRecurse(tree1, child, child_bv, s, obb2, tf1,
371 template <
typename BV>
372 bool OcTreeMeshDistanceRecurse(
const OcTree* tree1,
374 const AABB& bv1,
const BVHModel<BV>* tree2,
375 unsigned int root2,
const Transform3f& tf1,
376 const Transform3f& tf2)
const {
377 if (!tree1->nodeHasChildren(root1) && tree2->getBV(root2).isLeaf()) {
378 if (tree1->isNodeOccupied(root1)) {
384 box.computeLocalAABB();
387 size_t primitive_id =
388 static_cast<size_t>(tree2->getBV(root2).primitiveId());
389 const Triangle& tri_id = (*(tree2->tri_indices))[primitive_id];
390 const TriangleP tri((*(tree2->vertices))[tri_id[0]],
391 (*(tree2->vertices))[tri_id[1]],
392 (*(tree2->vertices))[tri_id[2]]);
394 Vec3f p1, p2, normal;
396 &box, box_tf, &tri, tf2, this->solver,
397 this->drequest->enable_signed_distance, p1, p2, normal);
399 this->dresult->update(
distance, tree1, tree2,
400 (
int)(root1 - tree1->getRoot()),
401 static_cast<int>(primitive_id), p1, p2, normal);
403 return this->drequest->isSatisfied(*dresult);
408 if (!tree1->isNodeOccupied(root1))
return false;
410 if (tree2->getBV(root2).isLeaf() ||
411 (tree1->nodeHasChildren(root1) &&
412 (bv1.size() > tree2->getBV(root2).bv.size()))) {
413 for (
unsigned int i = 0; i < 8; ++i) {
414 if (tree1->nodeChildExists(root1, i)) {
417 computeChildBV(bv1, i, child_bv);
421 convertBV(child_bv, tf1, aabb1);
422 convertBV(tree2->getBV(root2).bv, tf2, aabb2);
423 d = aabb1.distance(aabb2);
425 if (d < dresult->min_distance) {
426 if (OcTreeMeshDistanceRecurse(tree1, child, child_bv, tree2, root2,
435 convertBV(bv1, tf1, aabb1);
436 unsigned int child = (
unsigned int)tree2->getBV(root2).leftChild();
437 convertBV(tree2->getBV(child).bv, tf2, aabb2);
438 d = aabb1.distance(aabb2);
440 if (d < dresult->min_distance) {
441 if (OcTreeMeshDistanceRecurse(tree1, root1, bv1, tree2, child, tf1,
446 child = (
unsigned int)tree2->getBV(root2).rightChild();
447 convertBV(tree2->getBV(child).bv, tf2, aabb2);
448 d = aabb1.distance(aabb2);
450 if (d < dresult->min_distance) {
451 if (OcTreeMeshDistanceRecurse(tree1, root1, bv1, tree2, child, tf1,
461 template <
typename BV>
462 bool OcTreeMeshIntersectRecurse(
const OcTree* tree1,
464 const AABB& bv1,
const BVHModel<BV>* tree2,
465 unsigned int root2,
const Transform3f& tf1,
466 const Transform3f& tf2)
const {
472 if (!root1)
return false;
473 BVNode<BV>
const& bvn2 = tree2->getBV(root2);
479 if (tree1->isNodeFree(root1))
481 else if ((tree1->isNodeUncertain(root1) || tree2->isUncertain()))
485 convertBV(bv1, tf1, obb1);
486 convertBV(bvn2.bv, tf2, obb2);
488 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
496 if (!tree1->nodeHasChildren(root1) && bvn2.isLeaf()) {
497 assert(tree1->isNodeOccupied(root1));
502 box.computeLocalAABB();
505 size_t primitive_id =
static_cast<size_t>(bvn2.primitiveId());
506 const Triangle& tri_id = (*(tree2->tri_indices))[primitive_id];
507 const TriangleP tri((*(tree2->vertices))[tri_id[0]],
508 (*(tree2->vertices))[tri_id[1]],
509 (*(tree2->vertices))[tri_id[2]]);
516 const bool compute_penetration = this->crequest->enable_contact ||
517 (this->crequest->security_margin < 0);
518 Vec3f c1, c2, normal;
520 &box, box_tf, &tri, tf2, this->solver, compute_penetration, c1, c2,
523 distance - this->crequest->security_margin;
526 *(this->crequest), *(this->cresult), distToCollision, c1, c2, normal);
528 if (cresult->numContacts() < crequest->num_max_contacts) {
529 if (distToCollision <= crequest->collision_distance_threshold) {
530 cresult->addContact(Contact(
531 tree1, tree2, (
int)(root1 - tree1->getRoot()),
532 static_cast<int>(primitive_id), c1, c2, normal,
distance));
535 return crequest->isSatisfied(*cresult);
540 (tree1->nodeHasChildren(root1) && (bv1.size() > bvn2.bv.size()))) {
541 for (
unsigned int i = 0; i < 8; ++i) {
542 if (tree1->nodeChildExists(root1, i)) {
545 computeChildBV(bv1, i, child_bv);
547 if (OcTreeMeshIntersectRecurse(tree1, child, child_bv, tree2, root2,
553 if (OcTreeMeshIntersectRecurse(tree1, root1, bv1, tree2,
554 (
unsigned int)bvn2.leftChild(), tf1, tf2))
557 if (OcTreeMeshIntersectRecurse(tree1, root1, bv1, tree2,
558 (
unsigned int)bvn2.rightChild(), tf1, tf2))
566 template <
typename BV>
567 bool OcTreeHeightFieldIntersectRecurse(
569 const HeightField<BV>* tree2,
unsigned int root2,
const Transform3f& tf1,
570 const Transform3f& tf2,
FCL_REAL& sqrDistLowerBound)
const {
576 if (!root1)
return false;
577 HFNode<BV>
const& bvn2 = tree2->getBV(root2);
583 if (tree1->isNodeFree(root1))
585 else if ((tree1->isNodeUncertain(root1) || tree2->isUncertain()))
589 convertBV(bv1, tf1, obb1);
590 convertBV(bvn2.bv, tf2, obb2);
592 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound_)) {
593 if (sqrDistLowerBound_ < sqrDistLowerBound)
594 sqrDistLowerBound = sqrDistLowerBound_;
602 if (!tree1->nodeHasChildren(root1) && bvn2.isLeaf()) {
603 assert(tree1->isNodeOccupied(root1));
608 box.computeLocalAABB();
611 typedef Convex<Triangle> ConvexTriangle;
612 ConvexTriangle convex1, convex2;
613 int convex1_active_faces, convex2_active_faces;
614 details::buildConvexTriangles(bvn2, *tree2, convex1, convex1_active_faces,
615 convex2, convex2_active_faces);
617 convex1.computeLocalAABB();
618 convex2.computeLocalAABB();
621 Vec3f c1, c2, normal, normal_top;
623 bool hfield_witness_is_on_bin_side;
625 bool collision = details::shapeDistance<Triangle, Box, 0>(
626 solver, *crequest, convex1, convex1_active_faces, convex2,
627 convex2_active_faces, tf2, box, box_tf,
distance, c2, c1, normal,
628 normal_top, hfield_witness_is_on_bin_side);
631 distance - crequest->security_margin * (normal_top.dot(normal));
633 if (distToCollision <= crequest->collision_distance_threshold) {
634 sqrDistLowerBound = 0;
635 if (crequest->num_max_contacts > cresult->numContacts()) {
636 if (normal_top.isApprox(normal) &&
637 (collision || !hfield_witness_is_on_bin_side)) {
639 Contact(tree1, tree2, (
int)(root1 - tree1->getRoot()),
644 sqrDistLowerBound = distToCollision * distToCollision;
649 *crequest, *cresult, distToCollision, c1, c2, -normal);
651 assert(cresult->isCollision() || sqrDistLowerBound > 0);
652 return crequest->isSatisfied(*cresult);
657 (tree1->nodeHasChildren(root1) && (bv1.size() > bvn2.bv.size()))) {
658 for (
unsigned int i = 0; i < 8; ++i) {
659 if (tree1->nodeChildExists(root1, i)) {
662 computeChildBV(bv1, i, child_bv);
664 if (OcTreeHeightFieldIntersectRecurse(tree1, child, child_bv, tree2,
671 if (OcTreeHeightFieldIntersectRecurse(tree1, root1, bv1, tree2,
672 (
unsigned int)bvn2.leftChild(), tf1,
673 tf2, sqrDistLowerBound))
676 if (OcTreeHeightFieldIntersectRecurse(tree1, root1, bv1, tree2,
677 (
unsigned int)bvn2.rightChild(),
678 tf1, tf2, sqrDistLowerBound))
686 template <
typename BV>
687 bool HeightFieldOcTreeIntersectRecurse(
688 const HeightField<BV>* tree1,
unsigned int root1,
const OcTree* tree2,
690 const Transform3f& tf2,
FCL_REAL& sqrDistLowerBound)
const {
696 if (!root2)
return false;
697 HFNode<BV>
const& bvn1 = tree1->getBV(root1);
703 if (tree2->isNodeFree(root2))
705 else if ((tree2->isNodeUncertain(root2) || tree1->isUncertain()))
709 convertBV(bvn1.bv, tf1, obb1);
710 convertBV(bv2, tf2, obb2);
712 if (!obb2.overlap(obb1, *crequest, sqrDistLowerBound_)) {
713 if (sqrDistLowerBound_ < sqrDistLowerBound)
714 sqrDistLowerBound = sqrDistLowerBound_;
722 if (!tree2->nodeHasChildren(root2) && bvn1.isLeaf()) {
723 assert(tree2->isNodeOccupied(root2));
728 box.computeLocalAABB();
731 typedef Convex<Triangle> ConvexTriangle;
732 ConvexTriangle convex1, convex2;
733 int convex1_active_faces, convex2_active_faces;
734 details::buildConvexTriangles(bvn1, *tree1, convex1, convex1_active_faces,
735 convex2, convex2_active_faces);
737 convex1.computeLocalAABB();
738 convex2.computeLocalAABB();
741 Vec3f c1, c2, normal, normal_top;
743 bool hfield_witness_is_on_bin_side;
745 bool collision = details::shapeDistance<Triangle, Box, 0>(
746 solver, *crequest, convex1, convex1_active_faces, convex2,
747 convex2_active_faces, tf1, box, box_tf,
distance, c1, c2, normal,
748 normal_top, hfield_witness_is_on_bin_side);
751 distance - crequest->security_margin * (normal_top.dot(normal));
753 if (distToCollision <= crequest->collision_distance_threshold) {
754 sqrDistLowerBound = 0;
755 if (crequest->num_max_contacts > cresult->numContacts()) {
756 if (normal_top.isApprox(normal) &&
757 (collision || !hfield_witness_is_on_bin_side)) {
758 cresult->addContact(Contact(tree1, tree2, (
int)
Contact::NONE,
759 (int)(root2 - tree2->getRoot()), c1, c2,
764 sqrDistLowerBound = distToCollision * distToCollision;
769 *crequest, *cresult, distToCollision, c1, c2, normal);
771 assert(cresult->isCollision() || sqrDistLowerBound > 0);
772 return crequest->isSatisfied(*cresult);
777 (tree2->nodeHasChildren(root2) && (bv2.size() > bvn1.bv.size()))) {
778 for (
unsigned int i = 0; i < 8; ++i) {
779 if (tree2->nodeChildExists(root2, i)) {
782 computeChildBV(bv2, i, child_bv);
784 if (HeightFieldOcTreeIntersectRecurse(tree1, root1, tree2, child,
791 if (HeightFieldOcTreeIntersectRecurse(
792 tree1, (
unsigned int)bvn1.leftChild(), tree2, root2, bv2, tf1,
793 tf2, sqrDistLowerBound))
796 if (HeightFieldOcTreeIntersectRecurse(
797 tree1, (
unsigned int)bvn1.rightChild(), tree2, root2, bv2, tf1,
798 tf2, sqrDistLowerBound))
805 bool OcTreeDistanceRecurse(
const OcTree* tree1,
809 const Transform3f& tf1,
810 const Transform3f& tf2)
const {
811 if (!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2)) {
812 if (tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2)) {
814 Transform3f box1_tf, box2_tf;
819 box1.computeLocalAABB();
820 box2.computeLocalAABB();
823 Vec3f p1, p2, normal;
825 &box1, box1_tf, &box2, box2_tf, this->solver,
826 this->drequest->enable_signed_distance, p1, p2, normal);
828 this->dresult->update(
distance, tree1, tree2,
829 (
int)(root1 - tree1->getRoot()),
830 (
int)(root2 - tree2->getRoot()), p1, p2, normal);
832 return drequest->isSatisfied(*dresult);
837 if (!tree1->isNodeOccupied(root1) || !tree2->isNodeOccupied(root2))
840 if (!tree2->nodeHasChildren(root2) ||
841 (tree1->nodeHasChildren(root1) && (bv1.size() > bv2.size()))) {
842 for (
unsigned int i = 0; i < 8; ++i) {
843 if (tree1->nodeChildExists(root1, i)) {
846 computeChildBV(bv1, i, child_bv);
850 convertBV(bv1, tf1, aabb1);
851 convertBV(bv2, tf2, aabb2);
852 d = aabb1.distance(aabb2);
854 if (d < dresult->min_distance) {
855 if (OcTreeDistanceRecurse(tree1, child, child_bv, tree2, root2, bv2,
862 for (
unsigned int i = 0; i < 8; ++i) {
863 if (tree2->nodeChildExists(root2, i)) {
866 computeChildBV(bv2, i, child_bv);
870 convertBV(bv1, tf1, aabb1);
871 convertBV(bv2, tf2, aabb2);
872 d = aabb1.distance(aabb2);
874 if (d < dresult->min_distance) {
875 if (OcTreeDistanceRecurse(tree1, root1, bv1, tree2, child, child_bv,
886 bool OcTreeIntersectRecurse(
const OcTree* tree1,
890 const Transform3f& tf1,
891 const Transform3f& tf2)
const {
893 if (!root1)
return false;
894 if (!root2)
return false;
900 if (tree1->isNodeFree(root1) || tree2->isNodeFree(root2))
902 else if ((tree1->isNodeUncertain(root1) || tree2->isNodeUncertain(root2)))
906 (!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2));
907 if (!bothAreLeaves || !crequest->enable_contact) {
909 convertBV(bv1, tf1, obb1);
910 convertBV(bv2, tf2, obb2);
912 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
913 if (cresult->distance_lower_bound > 0 &&
915 cresult->distance_lower_bound * cresult->distance_lower_bound)
916 cresult->distance_lower_bound =
917 sqrt(sqrDistLowerBound) - crequest->security_margin;
920 if (crequest->enable_contact) {
921 if (cresult->numContacts() < crequest->num_max_contacts)
923 Contact(tree1, tree2,
static_cast<int>(root1 - tree1->getRoot()),
924 static_cast<int>(root2 - tree2->getRoot())));
925 return crequest->isSatisfied(*cresult);
931 assert(tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2));
934 Transform3f box1_tf, box2_tf;
938 if (this->solver->gjk_initial_guess ==
940 box1.computeLocalAABB();
941 box2.computeLocalAABB();
949 const bool compute_penetration = (this->crequest->enable_contact ||
950 (this->crequest->security_margin < 0));
951 Vec3f c1, c2, normal;
953 &box1, box1_tf, &box2, box2_tf, this->solver, compute_penetration, c1,
957 distance - this->crequest->security_margin;
960 *(this->crequest), *(this->cresult), distToCollision, c1, c2, normal);
962 if (this->cresult->numContacts() < this->crequest->num_max_contacts) {
963 if (distToCollision <= this->crequest->collision_distance_threshold)
964 this->cresult->addContact(
965 Contact(tree1, tree2,
static_cast<int>(root1 - tree1->getRoot()),
966 static_cast<int>(root2 - tree2->getRoot()), c1, c2,
970 return crequest->isSatisfied(*cresult);
974 if (!tree2->nodeHasChildren(root2) ||
975 (tree1->nodeHasChildren(root1) && (bv1.size() > bv2.size()))) {
976 for (
unsigned int i = 0; i < 8; ++i) {
977 if (tree1->nodeChildExists(root1, i)) {
980 computeChildBV(bv1, i, child_bv);
982 if (OcTreeIntersectRecurse(tree1, child, child_bv, tree2, root2, bv2,
988 for (
unsigned int i = 0; i < 8; ++i) {
989 if (tree2->nodeChildExists(root2, i)) {
992 computeChildBV(bv2, i, child_bv);
994 if (OcTreeIntersectRecurse(tree1, root1, bv1, tree2, child, child_bv,
1010 :
public CollisionTraversalNodeBase {
1012 OcTreeCollisionTraversalNode(
const CollisionRequest& request)
1013 : CollisionTraversalNodeBase(request) {
1020 bool BVDisjoints(
unsigned,
unsigned,
FCL_REAL&)
const {
return false; }
1022 void leafCollides(
unsigned,
unsigned,
FCL_REAL& sqrDistLowerBound)
const {
1023 otsolver->OcTreeIntersect(model1, model2, tf1, tf2, request, *result);
1024 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
1025 sqrDistLowerBound *= sqrDistLowerBound;
1028 const OcTree* model1;
1029 const OcTree* model2;
1031 Transform3f tf1, tf2;
1033 const OcTreeSolver* otsolver;
1037 template <
typename S>
1039 :
public CollisionTraversalNodeBase {
1041 ShapeOcTreeCollisionTraversalNode(
const CollisionRequest& request)
1042 : CollisionTraversalNodeBase(request) {
1049 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
1053 void leafCollides(
unsigned int,
unsigned int,
1054 FCL_REAL& sqrDistLowerBound)
const {
1055 otsolver->OcTreeShapeIntersect(model2, *model1, tf2, tf1, request, *result);
1056 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
1057 sqrDistLowerBound *= sqrDistLowerBound;
1061 const OcTree* model2;
1063 Transform3f tf1, tf2;
1065 const OcTreeSolver* otsolver;
1070 template <
typename S>
1072 :
public CollisionTraversalNodeBase {
1074 OcTreeShapeCollisionTraversalNode(
const CollisionRequest& request)
1075 : CollisionTraversalNodeBase(request) {
1082 bool BVDisjoints(
unsigned int,
unsigned int,
fcl::FCL_REAL&)
const {
1086 void leafCollides(
unsigned int,
unsigned int,
1087 FCL_REAL& sqrDistLowerBound)
const {
1088 otsolver->OcTreeShapeIntersect(model1, *model2, tf1, tf2, request, *result);
1089 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
1090 sqrDistLowerBound *= sqrDistLowerBound;
1093 const OcTree* model1;
1096 Transform3f tf1, tf2;
1098 const OcTreeSolver* otsolver;
1102 template <
typename BV>
1104 :
public CollisionTraversalNodeBase {
1106 MeshOcTreeCollisionTraversalNode(
const CollisionRequest& request)
1107 : CollisionTraversalNodeBase(request) {
1114 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
1118 void leafCollides(
unsigned int,
unsigned int,
1119 FCL_REAL& sqrDistLowerBound)
const {
1120 otsolver->OcTreeMeshIntersect(model2, model1, tf2, tf1, request, *result);
1121 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
1122 sqrDistLowerBound *= sqrDistLowerBound;
1125 const BVHModel<BV>* model1;
1126 const OcTree* model2;
1128 Transform3f tf1, tf2;
1130 const OcTreeSolver* otsolver;
1134 template <
typename BV>
1136 :
public CollisionTraversalNodeBase {
1138 OcTreeMeshCollisionTraversalNode(
const CollisionRequest& request)
1139 : CollisionTraversalNodeBase(request) {
1146 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
1150 void leafCollides(
unsigned int,
unsigned int,
1151 FCL_REAL& sqrDistLowerBound)
const {
1152 otsolver->OcTreeMeshIntersect(model1, model2, tf1, tf2, request, *result);
1153 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
1154 sqrDistLowerBound *= sqrDistLowerBound;
1157 const OcTree* model1;
1158 const BVHModel<BV>* model2;
1160 Transform3f tf1, tf2;
1162 const OcTreeSolver* otsolver;
1166 template <
typename BV>
1168 :
public CollisionTraversalNodeBase {
1170 OcTreeHeightFieldCollisionTraversalNode(
const CollisionRequest& request)
1171 : CollisionTraversalNodeBase(request) {
1178 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
1182 void leafCollides(
unsigned int,
unsigned int,
1183 FCL_REAL& sqrDistLowerBound)
const {
1184 otsolver->OcTreeHeightFieldIntersect(model1, model2, tf1, tf2, request,
1185 *result, sqrDistLowerBound);
1188 const OcTree* model1;
1189 const HeightField<BV>* model2;
1191 Transform3f tf1, tf2;
1193 const OcTreeSolver* otsolver;
1197 template <
typename BV>
1199 :
public CollisionTraversalNodeBase {
1201 HeightFieldOcTreeCollisionTraversalNode(
const CollisionRequest& request)
1202 : CollisionTraversalNodeBase(request) {
1209 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
1213 void leafCollides(
unsigned int,
unsigned int,
1214 FCL_REAL& sqrDistLowerBound)
const {
1215 otsolver->HeightFieldOcTreeIntersect(model1, model2, tf1, tf2, request,
1216 *result, sqrDistLowerBound);
1219 const HeightField<BV>* model1;
1220 const OcTree* model2;
1222 Transform3f tf1, tf2;
1224 const OcTreeSolver* otsolver;
1234 :
public DistanceTraversalNodeBase {
1236 OcTreeDistanceTraversalNode() {
1243 FCL_REAL BVDistanceLowerBound(
unsigned,
unsigned)
const {
return -1; }
1245 bool BVDistanceLowerBound(
unsigned,
unsigned,
FCL_REAL&)
const {
1249 void leafComputeDistance(
unsigned,
unsigned int)
const {
1250 otsolver->OcTreeDistance(model1, model2, tf1, tf2, request, *result);
1253 const OcTree* model1;
1254 const OcTree* model2;
1256 const OcTreeSolver* otsolver;
1260 template <
typename Shape>
1262 :
public DistanceTraversalNodeBase {
1264 ShapeOcTreeDistanceTraversalNode() {
1271 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
1273 void leafComputeDistance(
unsigned int,
unsigned int)
const {
1274 otsolver->OcTreeShapeDistance(model2, *model1, tf2, tf1, request, *result);
1277 const Shape* model1;
1278 const OcTree* model2;
1280 const OcTreeSolver* otsolver;
1284 template <
typename Shape>
1286 :
public DistanceTraversalNodeBase {
1288 OcTreeShapeDistanceTraversalNode() {
1295 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
1297 void leafComputeDistance(
unsigned int,
unsigned int)
const {
1298 otsolver->OcTreeShapeDistance(model1, *model2, tf1, tf2, request, *result);
1301 const OcTree* model1;
1302 const Shape* model2;
1304 const OcTreeSolver* otsolver;
1308 template <
typename BV>
1310 :
public DistanceTraversalNodeBase {
1312 MeshOcTreeDistanceTraversalNode() {
1319 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
1321 void leafComputeDistance(
unsigned int,
unsigned int)
const {
1322 otsolver->OcTreeMeshDistance(model2, model1, tf2, tf1, request, *result);
1325 const BVHModel<BV>* model1;
1326 const OcTree* model2;
1328 const OcTreeSolver* otsolver;
1332 template <
typename BV>
1334 :
public DistanceTraversalNodeBase {
1336 OcTreeMeshDistanceTraversalNode() {
1343 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
1345 void leafComputeDistance(
unsigned int,
unsigned int)
const {
1346 otsolver->OcTreeMeshDistance(model1, model2, tf1, tf2, request, *result);
1349 const OcTree* model1;
1350 const BVHModel<BV>* model2;
1352 const OcTreeSolver* otsolver;
octomap::OcTreeNode OcTreeNode
Definition: octree.h:64
#define HPP_FCL_DLLAPI
Definition: config.hh:88
FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const FCL_REAL &distance, const Vec3f &p0, const Vec3f &p1, const Vec3f &normal)
Definition: collision_data.h:1186
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const FCL_REAL sqrDistLowerBound)
Definition: collision_data.h:1177
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
void constructBox(const AABB &bv, Box &box, Transform3f &tf)
construct a box shape (with a configuration) from a given bounding volume
@ BoundingVolumeGuess
Definition: data_types.h:85
double FCL_REAL
Definition: data_types.h:66
Main namespace.
Definition: broadphase_bruteforce.h:44
static const int NONE
invalid contact primitive information
Definition: collision_data.h:1088