39 #ifndef COAL_TRAVERSAL_NODE_OCTREE_H 
   40 #define COAL_TRAVERSAL_NODE_OCTREE_H 
   57 class COAL_DLLAPI OcTreeSolver {
 
   59   const GJKSolver* solver;
 
   61   mutable const CollisionRequest* crequest;
 
   62   mutable const DistanceRequest* drequest;
 
   64   mutable CollisionResult* cresult;
 
   65   mutable DistanceResult* dresult;
 
   68   OcTreeSolver(
const GJKSolver* solver_)
 
   76   void OcTreeIntersect(
const OcTree* tree1, 
const OcTree* tree2,
 
   77                        const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
   78                        const CollisionRequest& request_,
 
   79                        CollisionResult& result_)
 const {
 
   83     OcTreeIntersectRecurse(tree1, tree1->getRoot(), tree1->getRootBV(), tree2,
 
   84                            tree2->getRoot(), tree2->getRootBV(), 
tf1, 
tf2);
 
   88   void OcTreeDistance(
const OcTree* tree1, 
const OcTree* tree2,
 
   89                       const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
   90                       const DistanceRequest& request_,
 
   91                       DistanceResult& result_)
 const {
 
   95     OcTreeDistanceRecurse(tree1, tree1->getRoot(), tree1->getRootBV(), tree2,
 
   96                           tree2->getRoot(), tree2->getRootBV(), 
tf1, 
tf2);
 
  100   template <
typename BV>
 
  101   void OcTreeMeshIntersect(
const OcTree* tree1, 
const BVHModel<BV>* tree2,
 
  102                            const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  103                            const CollisionRequest& request_,
 
  104                            CollisionResult& result_)
 const {
 
  105     crequest = &request_;
 
  108     OcTreeMeshIntersectRecurse(tree1, tree1->getRoot(), tree1->getRootBV(),
 
  113   template <
typename BV>
 
  114   void OcTreeMeshDistance(
const OcTree* tree1, 
const BVHModel<BV>* tree2,
 
  115                           const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  116                           const DistanceRequest& request_,
 
  117                           DistanceResult& result_)
 const {
 
  118     drequest = &request_;
 
  121     OcTreeMeshDistanceRecurse(tree1, tree1->getRoot(), tree1->getRootBV(),
 
  126   template <
typename BV>
 
  127   void MeshOcTreeIntersect(
const BVHModel<BV>* tree1, 
const OcTree* tree2,
 
  128                            const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  129                            const CollisionRequest& request_,
 
  130                            CollisionResult& result_)
 const 
  133     crequest = &request_;
 
  136     OcTreeMeshIntersectRecurse(tree2, tree2->getRoot(), tree2->getRootBV(),
 
  141   template <
typename BV>
 
  142   void MeshOcTreeDistance(
const BVHModel<BV>* tree1, 
const OcTree* tree2,
 
  143                           const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  144                           const DistanceRequest& request_,
 
  145                           DistanceResult& result_)
 const {
 
  146     drequest = &request_;
 
  149     OcTreeMeshDistanceRecurse(tree1, 0, tree2, tree2->getRoot(),
 
  150                               tree2->getRootBV(), 
tf1, 
tf2);
 
  153   template <
typename BV>
 
  154   void OcTreeHeightFieldIntersect(
 
  155       const OcTree* tree1, 
const HeightField<BV>* tree2, 
const Transform3s& 
tf1,
 
  156       const Transform3s& 
tf2, 
const CollisionRequest& request_,
 
  157       CollisionResult& result_, 
CoalScalar& sqrDistLowerBound)
 const {
 
  158     crequest = &request_;
 
  161     OcTreeHeightFieldIntersectRecurse(tree1, tree1->getRoot(),
 
  162                                       tree1->getRootBV(), tree2, 0, 
tf1, 
tf2,
 
  166   template <
typename BV>
 
  167   void HeightFieldOcTreeIntersect(
const HeightField<BV>* tree1,
 
  168                                   const OcTree* tree2, 
const Transform3s& 
tf1,
 
  169                                   const Transform3s& 
tf2,
 
  170                                   const CollisionRequest& request_,
 
  171                                   CollisionResult& result_,
 
  173     crequest = &request_;
 
  176     HeightFieldOcTreeIntersectRecurse(tree1, 0, tree2, tree2->getRoot(),
 
  177                                       tree2->getRootBV(), 
tf1, 
tf2,
 
  182   template <
typename S>
 
  183   void OcTreeShapeIntersect(
const OcTree* tree, 
const S& s,
 
  184                             const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  185                             const CollisionRequest& request_,
 
  186                             CollisionResult& result_)
 const {
 
  187     crequest = &request_;
 
  191     computeBV<AABB>(s, Transform3s(), bv2);
 
  194     OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
 
  199   template <
typename S>
 
  200   void ShapeOcTreeIntersect(
const S& s, 
const OcTree* tree,
 
  201                             const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  202                             const CollisionRequest& request_,
 
  203                             CollisionResult& result_)
 const {
 
  204     crequest = &request_;
 
  208     computeBV<AABB>(s, Transform3s(), bv1);
 
  211     OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
 
  216   template <
typename S>
 
  217   void OcTreeShapeDistance(
const OcTree* tree, 
const S& s,
 
  218                            const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  219                            const DistanceRequest& request_,
 
  220                            DistanceResult& result_)
 const {
 
  221     drequest = &request_;
 
  225     computeBV<AABB>(s, 
tf2, aabb2);
 
  226     OcTreeShapeDistanceRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
 
  231   template <
typename S>
 
  232   void ShapeOcTreeDistance(
const S& s, 
const OcTree* tree,
 
  233                            const Transform3s& 
tf1, 
const Transform3s& 
tf2,
 
  234                            const DistanceRequest& request_,
 
  235                            DistanceResult& result_)
 const {
 
  236     drequest = &request_;
 
  240     computeBV<AABB>(s, 
tf1, aabb1);
 
  241     OcTreeShapeDistanceRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
 
  246   template <
typename S>
 
  247   bool OcTreeShapeDistanceRecurse(
const OcTree* tree1,
 
  249                                   const AABB& bv1, 
const S& s,
 
  250                                   const AABB& aabb2, 
const Transform3s& 
tf1,
 
  251                                   const Transform3s& 
tf2)
 const {
 
  252     if (!tree1->nodeHasChildren(root1)) {
 
  253       if (tree1->isNodeOccupied(root1)) {
 
  259           box.computeLocalAABB();
 
  264             &
box, box_tf, &s, 
tf2, this->solver,
 
  265             this->drequest->enable_signed_distance, 
p1, p2, normal);
 
  267         this->dresult->update(
distance, tree1, &s,
 
  268                               (
int)(root1 - tree1->getRoot()),
 
  271         return drequest->isSatisfied(*dresult);
 
  276     if (!tree1->isNodeOccupied(root1)) 
return false;
 
  278     for (
unsigned int i = 0; i < 8; ++i) {
 
  279       if (tree1->nodeChildExists(root1, i)) {
 
  287         if (d < dresult->min_distance) {
 
  288           if (OcTreeShapeDistanceRecurse(tree1, child, child_bv, s, aabb2, 
tf1,
 
  298   template <
typename S>
 
  299   bool OcTreeShapeIntersectRecurse(
const OcTree* tree1,
 
  301                                    const AABB& bv1, 
const S& s, 
const OBB& obb2,
 
  302                                    const Transform3s& 
tf1,
 
  303                                    const Transform3s& 
tf2)
 const {
 
  305     if (!root1) 
return false;
 
  311     if (tree1->isNodeFree(root1))
 
  313     else if ((tree1->isNodeUncertain(root1) || s.isUncertain()))
 
  319       if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
 
  326     if (!tree1->nodeHasChildren(root1)) {
 
  327       assert(tree1->isNodeOccupied(root1));  
 
  333         box.computeLocalAABB();
 
  336       bool contactNotAdded =
 
  337           (cresult->numContacts() >= crequest->num_max_contacts);
 
  338       std::size_t ncontact = ShapeShapeCollide<Box, S>(
 
  339           &
box, box_tf, &s, 
tf2, solver, *crequest, *cresult);
 
  340       assert(ncontact == 0 || ncontact == 1);
 
  341       if (!contactNotAdded && ncontact == 1) {
 
  343         const Contact& 
c = cresult->getContact(cresult->numContacts() - 1);
 
  345             cresult->numContacts() - 1,
 
  346             Contact(tree1, 
c.o2, 
static_cast<int>(root1 - tree1->getRoot()),
 
  347                     c.b2, 
c.pos, 
c.normal, 
c.penetration_depth));
 
  352       return crequest->isSatisfied(*cresult);
 
  355     for (
unsigned int i = 0; i < 8; ++i) {
 
  356       if (tree1->nodeChildExists(root1, i)) {
 
  361         if (OcTreeShapeIntersectRecurse(tree1, child, child_bv, s, obb2, 
tf1,
 
  370   template <
typename BV>
 
  371   bool OcTreeMeshDistanceRecurse(
const OcTree* tree1,
 
  373                                  const AABB& bv1, 
const BVHModel<BV>* tree2,
 
  374                                  unsigned int root2, 
const Transform3s& 
tf1,
 
  375                                  const Transform3s& 
tf2)
 const {
 
  376     if (!tree1->nodeHasChildren(root1) && tree2->getBV(root2).isLeaf()) {
 
  377       if (tree1->isNodeOccupied(root1)) {
 
  383           box.computeLocalAABB();
 
  386         size_t primitive_id =
 
  387             static_cast<size_t>(tree2->getBV(root2).primitiveId());
 
  388         const Triangle& tri_id = (*(tree2->tri_indices))[primitive_id];
 
  389         const TriangleP tri((*(tree2->vertices))[tri_id[0]],
 
  390                             (*(tree2->vertices))[tri_id[1]],
 
  391                             (*(tree2->vertices))[tri_id[2]]);
 
  395             internal::ShapeShapeDistance<Box, TriangleP>(
 
  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)) {
 
  423           d = aabb1.distance(aabb2);
 
  425           if (d < dresult->min_distance) {
 
  426             if (OcTreeMeshDistanceRecurse(tree1, child, child_bv, tree2, root2,
 
  436       unsigned int child = (
unsigned int)tree2->getBV(root2).leftChild();
 
  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();
 
  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 Transform3s& 
tf1,
 
  466                                   const Transform3s& 
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()))
 
  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);
 
  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)) {
 
  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 Transform3s& 
tf1,
 
  570       const Transform3s& 
tf2, 
CoalScalar& 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()))
 
  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       Vec3s 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,
 
  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)) {
 
  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 Transform3s& 
tf2, 
CoalScalar& 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()))
 
  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       Vec3s 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,
 
  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)) {
 
  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 Transform3s& 
tf1,
 
  810                              const Transform3s& 
tf2)
 const {
 
  811     if (!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2)) {
 
  812       if (tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2)) {
 
  814         Transform3s box1_tf, box2_tf;
 
  819           box1.computeLocalAABB();
 
  820           box2.computeLocalAABB();
 
  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)) {
 
  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)) {
 
  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 Transform3s& 
tf1,
 
  891                               const Transform3s& 
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) {
 
  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       Transform3s 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));
 
  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)) {
 
  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)) {
 
  994           if (OcTreeIntersectRecurse(tree1, root1, bv1, tree2, child, child_bv,
 
 1009 class COAL_DLLAPI OcTreeCollisionTraversalNode
 
 1010     : 
public CollisionTraversalNodeBase {
 
 1012   OcTreeCollisionTraversalNode(
const CollisionRequest& request)
 
 1013       : CollisionTraversalNodeBase(request) {
 
 1020   bool BVDisjoints(
unsigned, 
unsigned, 
CoalScalar&)
 const { 
return false; }
 
 1022   void leafCollides(
unsigned, 
unsigned, 
CoalScalar& sqrDistLowerBound)
 const {
 
 1023     otsolver->OcTreeIntersect(model1, model2, 
tf1, 
tf2, request, *result);
 
 1024     sqrDistLowerBound = std::max((
CoalScalar)0, result->distance_lower_bound);
 
 1025     sqrDistLowerBound *= sqrDistLowerBound;
 
 1028   const OcTree* model1;
 
 1029   const OcTree* model2;
 
 1033   const OcTreeSolver* otsolver;
 
 1037 template <
typename S>
 
 1038 class COAL_DLLAPI ShapeOcTreeCollisionTraversalNode
 
 1039     : 
public CollisionTraversalNodeBase {
 
 1041   ShapeOcTreeCollisionTraversalNode(
const CollisionRequest& request)
 
 1042       : CollisionTraversalNodeBase(request) {
 
 1049   bool BVDisjoints(
unsigned int, 
unsigned int, 
CoalScalar&)
 const {
 
 1053   void leafCollides(
unsigned int, 
unsigned int,
 
 1055     otsolver->OcTreeShapeIntersect(model2, *model1, 
tf2, 
tf1, request, *result);
 
 1056     sqrDistLowerBound = std::max((
CoalScalar)0, result->distance_lower_bound);
 
 1057     sqrDistLowerBound *= sqrDistLowerBound;
 
 1061   const OcTree* model2;
 
 1065   const OcTreeSolver* otsolver;
 
 1070 template <
typename S>
 
 1071 class COAL_DLLAPI OcTreeShapeCollisionTraversalNode
 
 1072     : 
public CollisionTraversalNodeBase {
 
 1074   OcTreeShapeCollisionTraversalNode(
const CollisionRequest& request)
 
 1075       : CollisionTraversalNodeBase(request) {
 
 1086   void leafCollides(
unsigned int, 
unsigned int,
 
 1088     otsolver->OcTreeShapeIntersect(model1, *model2, 
tf1, 
tf2, request, *result);
 
 1089     sqrDistLowerBound = std::max((
CoalScalar)0, result->distance_lower_bound);
 
 1090     sqrDistLowerBound *= sqrDistLowerBound;
 
 1093   const OcTree* model1;
 
 1098   const OcTreeSolver* otsolver;
 
 1102 template <
typename BV>
 
 1103 class COAL_DLLAPI MeshOcTreeCollisionTraversalNode
 
 1104     : 
public CollisionTraversalNodeBase {
 
 1106   MeshOcTreeCollisionTraversalNode(
const CollisionRequest& request)
 
 1107       : CollisionTraversalNodeBase(request) {
 
 1114   bool BVDisjoints(
unsigned int, 
unsigned int, 
CoalScalar&)
 const {
 
 1118   void leafCollides(
unsigned int, 
unsigned int,
 
 1120     otsolver->OcTreeMeshIntersect(model2, model1, 
tf2, 
tf1, request, *result);
 
 1121     sqrDistLowerBound = std::max((
CoalScalar)0, result->distance_lower_bound);
 
 1122     sqrDistLowerBound *= sqrDistLowerBound;
 
 1125   const BVHModel<BV>* model1;
 
 1126   const OcTree* model2;
 
 1130   const OcTreeSolver* otsolver;
 
 1134 template <
typename BV>
 
 1135 class COAL_DLLAPI OcTreeMeshCollisionTraversalNode
 
 1136     : 
public CollisionTraversalNodeBase {
 
 1138   OcTreeMeshCollisionTraversalNode(
const CollisionRequest& request)
 
 1139       : CollisionTraversalNodeBase(request) {
 
 1146   bool BVDisjoints(
unsigned int, 
unsigned int, 
CoalScalar&)
 const {
 
 1150   void leafCollides(
unsigned int, 
unsigned int,
 
 1152     otsolver->OcTreeMeshIntersect(model1, model2, 
tf1, 
tf2, request, *result);
 
 1153     sqrDistLowerBound = std::max((
CoalScalar)0, result->distance_lower_bound);
 
 1154     sqrDistLowerBound *= sqrDistLowerBound;
 
 1157   const OcTree* model1;
 
 1158   const BVHModel<BV>* model2;
 
 1162   const OcTreeSolver* otsolver;
 
 1166 template <
typename BV>
 
 1167 class COAL_DLLAPI OcTreeHeightFieldCollisionTraversalNode
 
 1168     : 
public CollisionTraversalNodeBase {
 
 1170   OcTreeHeightFieldCollisionTraversalNode(
const CollisionRequest& request)
 
 1171       : CollisionTraversalNodeBase(request) {
 
 1178   bool BVDisjoints(
unsigned int, 
unsigned int, 
CoalScalar&)
 const {
 
 1182   void leafCollides(
unsigned int, 
unsigned int,
 
 1184     otsolver->OcTreeHeightFieldIntersect(model1, model2, 
tf1, 
tf2, request,
 
 1185                                          *result, sqrDistLowerBound);
 
 1188   const OcTree* model1;
 
 1189   const HeightField<BV>* model2;
 
 1193   const OcTreeSolver* otsolver;
 
 1197 template <
typename BV>
 
 1198 class COAL_DLLAPI HeightFieldOcTreeCollisionTraversalNode
 
 1199     : 
public CollisionTraversalNodeBase {
 
 1201   HeightFieldOcTreeCollisionTraversalNode(
const CollisionRequest& request)
 
 1202       : CollisionTraversalNodeBase(request) {
 
 1209   bool BVDisjoints(
unsigned int, 
unsigned int, 
CoalScalar&)
 const {
 
 1213   void leafCollides(
unsigned int, 
unsigned int,
 
 1215     otsolver->HeightFieldOcTreeIntersect(model1, model2, 
tf1, 
tf2, request,
 
 1216                                          *result, sqrDistLowerBound);
 
 1219   const HeightField<BV>* model1;
 
 1220   const OcTree* model2;
 
 1224   const OcTreeSolver* otsolver;
 
 1233 class COAL_DLLAPI OcTreeDistanceTraversalNode
 
 1234     : 
public DistanceTraversalNodeBase {
 
 1236   OcTreeDistanceTraversalNode() {
 
 1243   CoalScalar BVDistanceLowerBound(
unsigned, 
unsigned)
 const { 
return -1; }
 
 1245   bool BVDistanceLowerBound(
unsigned, 
unsigned, 
CoalScalar&)
 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>
 
 1261 class COAL_DLLAPI ShapeOcTreeDistanceTraversalNode
 
 1262     : 
public DistanceTraversalNodeBase {
 
 1264   ShapeOcTreeDistanceTraversalNode() {
 
 1271   CoalScalar BVDistanceLowerBound(
unsigned int, 
unsigned int)
 const {
 
 1275   void leafComputeDistance(
unsigned int, 
unsigned int)
 const {
 
 1276     otsolver->OcTreeShapeDistance(model2, *model1, 
tf2, 
tf1, request, *result);
 
 1279   const Shape* model1;
 
 1280   const OcTree* model2;
 
 1282   const OcTreeSolver* otsolver;
 
 1286 template <
typename Shape>
 
 1287 class COAL_DLLAPI OcTreeShapeDistanceTraversalNode
 
 1288     : 
public DistanceTraversalNodeBase {
 
 1290   OcTreeShapeDistanceTraversalNode() {
 
 1297   CoalScalar BVDistanceLowerBound(
unsigned int, 
unsigned int)
 const {
 
 1301   void leafComputeDistance(
unsigned int, 
unsigned int)
 const {
 
 1302     otsolver->OcTreeShapeDistance(model1, *model2, 
tf1, 
tf2, request, *result);
 
 1305   const OcTree* model1;
 
 1306   const Shape* model2;
 
 1308   const OcTreeSolver* otsolver;
 
 1312 template <
typename BV>
 
 1313 class COAL_DLLAPI MeshOcTreeDistanceTraversalNode
 
 1314     : 
public DistanceTraversalNodeBase {
 
 1316   MeshOcTreeDistanceTraversalNode() {
 
 1323   CoalScalar BVDistanceLowerBound(
unsigned int, 
unsigned int)
 const {
 
 1327   void leafComputeDistance(
unsigned int, 
unsigned int)
 const {
 
 1328     otsolver->OcTreeMeshDistance(model2, model1, 
tf2, 
tf1, request, *result);
 
 1331   const BVHModel<BV>* model1;
 
 1332   const OcTree* model2;
 
 1334   const OcTreeSolver* otsolver;
 
 1338 template <
typename BV>
 
 1339 class COAL_DLLAPI OcTreeMeshDistanceTraversalNode
 
 1340     : 
public DistanceTraversalNodeBase {
 
 1342   OcTreeMeshDistanceTraversalNode() {
 
 1349   CoalScalar BVDistanceLowerBound(
unsigned int, 
unsigned int)
 const {
 
 1353   void leafComputeDistance(
unsigned int, 
unsigned int)
 const {
 
 1354     otsolver->OcTreeMeshDistance(model1, model2, 
tf1, 
tf2, request, *result);
 
 1357   const OcTree* model1;
 
 1358   const BVHModel<BV>* model2;
 
 1360   const OcTreeSolver* otsolver;