38 #ifndef HPP_FCL_TRAVERSAL_NODE_OCTREE_H 39 #define HPP_FCL_TRAVERSAL_NODE_OCTREE_H 55 class HPP_FCL_DLLAPI OcTreeSolver {
57 const GJKSolver* solver;
59 mutable const CollisionRequest* crequest;
60 mutable const DistanceRequest* drequest;
62 mutable CollisionResult* cresult;
63 mutable DistanceResult* dresult;
66 OcTreeSolver(
const GJKSolver* solver_)
74 void OcTreeIntersect(
const OcTree* tree1,
const OcTree* tree2,
75 const Transform3f&
tf1,
const Transform3f&
tf2,
76 const CollisionRequest& request_,
77 CollisionResult& result_)
const {
81 OcTreeIntersectRecurse(tree1, tree1->getRoot(), tree1->getRootBV(), tree2,
82 tree2->getRoot(), tree2->getRootBV(),
tf1,
tf2);
86 void OcTreeDistance(
const OcTree* tree1,
const OcTree* tree2,
87 const Transform3f& tf1,
const Transform3f& tf2,
88 const DistanceRequest& request_,
89 DistanceResult& result_)
const {
93 OcTreeDistanceRecurse(tree1, tree1->getRoot(), tree1->getRootBV(), tree2,
94 tree2->getRoot(), tree2->getRootBV(),
tf1,
tf2);
98 template <
typename BV>
99 void OcTreeMeshIntersect(
const OcTree* tree1,
const BVHModel<BV>* tree2,
100 const Transform3f& tf1,
const Transform3f& tf2,
101 const CollisionRequest& request_,
102 CollisionResult& result_)
const {
103 crequest = &request_;
106 OcTreeMeshIntersectRecurse(tree1, tree1->getRoot(), tree1->getRootBV(),
111 template <
typename BV>
112 void OcTreeMeshDistance(
const OcTree* tree1,
const BVHModel<BV>* tree2,
113 const Transform3f& tf1,
const Transform3f& tf2,
114 const DistanceRequest& request_,
115 DistanceResult& result_)
const {
116 drequest = &request_;
119 OcTreeMeshDistanceRecurse(tree1, tree1->getRoot(), tree1->getRootBV(),
124 template <
typename BV>
125 void MeshOcTreeIntersect(
const BVHModel<BV>* tree1,
const OcTree* tree2,
126 const Transform3f& tf1,
const Transform3f& tf2,
127 const CollisionRequest& request_,
128 CollisionResult& result_)
const 131 crequest = &request_;
134 OcTreeMeshIntersectRecurse(tree2, tree2->getRoot(), tree2->getRootBV(),
139 template <
typename BV>
140 void MeshOcTreeDistance(
const BVHModel<BV>* tree1,
const OcTree* tree2,
141 const Transform3f& tf1,
const Transform3f& tf2,
142 const DistanceRequest& request_,
143 DistanceResult& result_)
const {
144 drequest = &request_;
147 OcTreeMeshDistanceRecurse(tree1, 0, tree2, tree2->getRoot(),
148 tree2->getRootBV(),
tf1,
tf2);
152 template <
typename S>
153 void OcTreeShapeIntersect(
const OcTree* tree,
const S& s,
154 const Transform3f& tf1,
const Transform3f& tf2,
155 const CollisionRequest& request_,
156 CollisionResult& result_)
const {
157 crequest = &request_;
161 computeBV<AABB>(s, Transform3f(), bv2);
164 OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
169 template <
typename S>
170 void ShapeOcTreeIntersect(
const S& s,
const OcTree* tree,
171 const Transform3f& tf1,
const Transform3f& tf2,
172 const CollisionRequest& request_,
173 CollisionResult& result_)
const {
174 crequest = &request_;
178 computeBV<AABB>(s, Transform3f(), bv1);
181 OcTreeShapeIntersectRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
186 template <
typename S>
187 void OcTreeShapeDistance(
const OcTree* tree,
const S& s,
188 const Transform3f& tf1,
const Transform3f& tf2,
189 const DistanceRequest& request_,
190 DistanceResult& result_)
const {
191 drequest = &request_;
195 computeBV<AABB>(s,
tf2, aabb2);
196 OcTreeShapeDistanceRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
201 template <
typename S>
202 void ShapeOcTreeDistance(
const S& s,
const OcTree* tree,
203 const Transform3f& tf1,
const Transform3f& tf2,
204 const DistanceRequest& request_,
205 DistanceResult& result_)
const {
206 drequest = &request_;
210 computeBV<AABB>(s,
tf1, aabb1);
211 OcTreeShapeDistanceRecurse(tree, tree->getRoot(), tree->getRootBV(), s,
216 template <
typename S>
217 bool OcTreeShapeDistanceRecurse(
const OcTree* tree1,
219 const AABB& bv1,
const S& s,
220 const AABB& aabb2,
const Transform3f& tf1,
221 const Transform3f& tf2)
const {
222 if (!tree1->nodeHasChildren(root1)) {
223 if (tree1->isNodeOccupied(root1)) {
229 Vec3f closest_p1, closest_p2, normal;
230 solver->shapeDistance(box, box_tf, s, tf2, dist, closest_p1, closest_p2,
233 dresult->update(dist, tree1, &s, (
int)(root1 - tree1->getRoot()),
236 return drequest->isSatisfied(*dresult);
241 if (!tree1->isNodeOccupied(root1))
return false;
243 for (
unsigned int i = 0; i < 8; ++i) {
244 if (tree1->nodeChildExists(root1, i)) {
252 if (d < dresult->min_distance) {
253 if (OcTreeShapeDistanceRecurse(tree1, child, child_bv, s, aabb2, tf1,
263 template <
typename S>
264 bool OcTreeShapeIntersectRecurse(
const OcTree* tree1,
266 const AABB& bv1,
const S& s,
const OBB& obb2,
267 const Transform3f& tf1,
268 const Transform3f& tf2)
const {
270 if (!root1)
return false;
276 if (tree1->isNodeFree(root1))
278 else if ((tree1->isNodeUncertain(root1) || s.isUncertain()))
284 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
291 if (!tree1->nodeHasChildren(root1)) {
292 assert(tree1->isNodeOccupied(root1));
298 bool contactNotAdded =
299 (cresult->numContacts() >= crequest->num_max_contacts);
300 std::size_t ncontact = ShapeShapeCollide<Box, S>(
301 &
box, box_tf, &s,
tf2, solver, *crequest, *cresult);
302 assert(ncontact == 0 || ncontact == 1);
303 if (!contactNotAdded && ncontact == 1) {
305 const Contact&
c = cresult->getContact(cresult->numContacts() - 1);
307 cresult->numContacts() - 1,
308 Contact(tree1, c.o2, static_cast<int>(root1 - tree1->getRoot()),
309 c.b2, c.pos, c.normal, c.penetration_depth));
312 return crequest->isSatisfied(*cresult);
315 for (
unsigned int i = 0; i < 8; ++i) {
316 if (tree1->nodeChildExists(root1, i)) {
321 if (OcTreeShapeIntersectRecurse(tree1, child, child_bv, s, obb2, tf1,
330 template <
typename BV>
331 bool OcTreeMeshDistanceRecurse(
const OcTree* tree1,
333 const AABB& bv1,
const BVHModel<BV>* tree2,
334 unsigned int root2,
const Transform3f& tf1,
335 const Transform3f& tf2)
const {
336 if (!tree1->nodeHasChildren(root1) && tree2->getBV(root2).isLeaf()) {
337 if (tree1->isNodeOccupied(root1)) {
342 int primitive_id = tree2->getBV(root2).primitiveId();
343 const Triangle& tri_id = tree2->tri_indices[primitive_id];
344 const Vec3f&
p1 = tree2->vertices[tri_id[0]];
345 const Vec3f& p2 = tree2->vertices[tri_id[1]];
346 const Vec3f& p3 = tree2->vertices[tri_id[2]];
349 Vec3f closest_p1, closest_p2, normal;
350 solver->shapeTriangleInteraction(box, box_tf, p1, p2, p3, tf2, dist,
351 closest_p1, closest_p2, normal);
353 dresult->update(dist, tree1, tree2, (
int)(root1 - tree1->getRoot()),
354 primitive_id, closest_p1, closest_p2, normal);
356 return drequest->isSatisfied(*dresult);
361 if (!tree1->isNodeOccupied(root1))
return false;
363 if (tree2->getBV(root2).isLeaf() ||
364 (tree1->nodeHasChildren(root1) &&
365 (bv1.size() > tree2->getBV(root2).bv.size()))) {
366 for (
unsigned int i = 0; i < 8; ++i) {
367 if (tree1->nodeChildExists(root1, i)) {
376 d = aabb1.distance(aabb2);
378 if (d < dresult->min_distance) {
379 if (OcTreeMeshDistanceRecurse(tree1, child, child_bv, tree2, root2,
389 unsigned int child = (
unsigned int)tree2->getBV(root2).leftChild();
391 d = aabb1.distance(aabb2);
393 if (d < dresult->min_distance) {
394 if (OcTreeMeshDistanceRecurse(tree1, root1, bv1, tree2, child, tf1,
399 child = (
unsigned int)tree2->getBV(root2).rightChild();
401 d = aabb1.distance(aabb2);
403 if (d < dresult->min_distance) {
404 if (OcTreeMeshDistanceRecurse(tree1, root1, bv1, tree2, child, tf1,
414 template <
typename BV>
415 bool OcTreeMeshIntersectRecurse(
const OcTree* tree1,
417 const AABB& bv1,
const BVHModel<BV>* tree2,
418 unsigned int root2,
const Transform3f& tf1,
419 const Transform3f& tf2)
const {
425 if (!root1)
return false;
426 BVNode<BV>
const& bvn2 = tree2->getBV(root2);
432 if (tree1->isNodeFree(root1))
434 else if ((tree1->isNodeUncertain(root1) || tree2->isUncertain()))
441 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
449 if (!tree1->nodeHasChildren(root1) && bvn2.isLeaf()) {
450 assert(tree1->isNodeOccupied(root1));
455 int primitive_id = bvn2.primitiveId();
456 const Triangle& tri_id = tree2->tri_indices[primitive_id];
457 const Vec3f& p1 = tree2->vertices[tri_id[0]];
458 const Vec3f& p2 = tree2->vertices[tri_id[1]];
459 const Vec3f& p3 = tree2->vertices[tri_id[2]];
464 bool collision = solver->shapeTriangleInteraction(
465 box, box_tf, p1, p2, p3, tf2, distance, c1, c2, normal);
466 FCL_REAL distToCollision = distance - crequest->security_margin;
468 if (cresult->numContacts() < crequest->num_max_contacts) {
470 cresult->addContact(Contact(tree1, tree2,
471 (
int)(root1 - tree1->getRoot()),
472 primitive_id, c1, normal, -distance));
473 }
else if (distToCollision < 0) {
474 cresult->addContact(Contact(
475 tree1, tree2, (
int)(root1 - tree1->getRoot()), primitive_id,
476 .5 * (c1 + c2), (c2 - c1).normalized(), -
distance));
480 distToCollision, c1, c2);
482 return crequest->isSatisfied(*cresult);
487 (tree1->nodeHasChildren(root1) && (bv1.size() > bvn2.bv.size()))) {
488 for (
unsigned int i = 0; i < 8; ++i) {
489 if (tree1->nodeChildExists(root1, i)) {
494 if (OcTreeMeshIntersectRecurse(tree1, child, child_bv, tree2, root2,
500 if (OcTreeMeshIntersectRecurse(tree1, root1, bv1, tree2,
501 (
unsigned int)bvn2.leftChild(),
tf1,
tf2))
504 if (OcTreeMeshIntersectRecurse(tree1, root1, bv1, tree2,
505 (
unsigned int)bvn2.rightChild(),
tf1,
tf2))
512 bool OcTreeDistanceRecurse(
const OcTree* tree1,
516 const Transform3f& tf1,
517 const Transform3f& tf2)
const {
518 if (!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2)) {
519 if (tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2)) {
521 Transform3f box1_tf, box2_tf;
526 Vec3f closest_p1, closest_p2, normal;
527 solver->shapeDistance(box1, box1_tf, box2, box2_tf, dist, closest_p1,
530 dresult->update(dist, tree1, tree2, (
int)(root1 - tree1->getRoot()),
531 (
int)(root2 - tree2->getRoot()), closest_p1, closest_p2,
534 return drequest->isSatisfied(*dresult);
539 if (!tree1->isNodeOccupied(root1) || !tree2->isNodeOccupied(root2))
542 if (!tree2->nodeHasChildren(root2) ||
543 (tree1->nodeHasChildren(root1) && (bv1.size() > bv2.size()))) {
544 for (
unsigned int i = 0; i < 8; ++i) {
545 if (tree1->nodeChildExists(root1, i)) {
554 d = aabb1.distance(aabb2);
556 if (d < dresult->min_distance) {
557 if (OcTreeDistanceRecurse(tree1, child, child_bv, tree2, root2, bv2,
564 for (
unsigned int i = 0; i < 8; ++i) {
565 if (tree2->nodeChildExists(root2, i)) {
574 d = aabb1.distance(aabb2);
576 if (d < dresult->min_distance) {
577 if (OcTreeDistanceRecurse(tree1, root1, bv1, tree2, child, child_bv,
588 bool OcTreeIntersectRecurse(
const OcTree* tree1,
592 const Transform3f& tf1,
593 const Transform3f& tf2)
const {
595 if (!root1)
return false;
596 if (!root2)
return false;
602 if (tree1->isNodeFree(root1) || tree2->isNodeFree(root2))
604 else if ((tree1->isNodeUncertain(root1) || tree2->isNodeUncertain(root2)))
608 (!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2));
609 if (!bothAreLeaves || !crequest->enable_contact) {
614 if (!obb1.overlap(obb2, *crequest, sqrDistLowerBound)) {
615 if (cresult->distance_lower_bound > 0 &&
617 cresult->distance_lower_bound * cresult->distance_lower_bound)
618 cresult->distance_lower_bound =
619 sqrt(sqrDistLowerBound) - crequest->security_margin;
622 if (!crequest->enable_contact) {
623 if (cresult->numContacts() < crequest->num_max_contacts)
625 Contact(tree1, tree2, static_cast<int>(root1 - tree1->getRoot()),
626 static_cast<int>(root2 - tree2->getRoot())));
627 return crequest->isSatisfied(*cresult);
633 assert(tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2));
636 Transform3f box1_tf, box2_tf;
641 Vec3f c1, c2, normal;
642 bool collision = solver->shapeDistance(box1, box1_tf, box2, box2_tf,
643 distance, c1, c2, normal);
644 FCL_REAL distToCollision = distance - crequest->security_margin;
646 if (cresult->numContacts() < crequest->num_max_contacts) {
649 Contact(tree1, tree2, static_cast<int>(root1 - tree1->getRoot()),
650 static_cast<int>(root2 - tree2->getRoot()), c1, normal,
652 else if (distToCollision <= 0)
654 Contact(tree1, tree2, static_cast<int>(root1 - tree1->getRoot()),
655 static_cast<int>(root2 - tree2->getRoot()),
656 .5 * (c1 + c2), (c2 - c1).normalized(), -
distance));
659 distToCollision, c1, c2);
661 return crequest->isSatisfied(*cresult);
665 if (!tree2->nodeHasChildren(root2) ||
666 (tree1->nodeHasChildren(root1) && (bv1.size() > bv2.size()))) {
667 for (
unsigned int i = 0; i < 8; ++i) {
668 if (tree1->nodeChildExists(root1, i)) {
673 if (OcTreeIntersectRecurse(tree1, child, child_bv, tree2, root2, bv2,
679 for (
unsigned int i = 0; i < 8; ++i) {
680 if (tree2->nodeChildExists(root2, i)) {
685 if (OcTreeIntersectRecurse(tree1, root1, bv1, tree2, child, child_bv,
700 class HPP_FCL_DLLAPI OcTreeCollisionTraversalNode
701 :
public CollisionTraversalNodeBase {
703 OcTreeCollisionTraversalNode(
const CollisionRequest& request)
704 : CollisionTraversalNodeBase(request) {
711 bool BVDisjoints(
unsigned,
unsigned,
FCL_REAL&)
const {
return false; }
713 void leafCollides(
unsigned,
unsigned,
FCL_REAL& sqrDistLowerBound)
const {
714 otsolver->OcTreeIntersect(model1, model2, tf1, tf2, request, *result);
715 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
716 sqrDistLowerBound *= sqrDistLowerBound;
719 const OcTree* model1;
720 const OcTree* model2;
724 const OcTreeSolver* otsolver;
728 template <
typename S>
729 class HPP_FCL_DLLAPI ShapeOcTreeCollisionTraversalNode
730 :
public CollisionTraversalNodeBase {
732 ShapeOcTreeCollisionTraversalNode(
const CollisionRequest& request)
733 : CollisionTraversalNodeBase(request) {
740 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
744 void leafCollides(
unsigned int,
unsigned int,
745 FCL_REAL& sqrDistLowerBound)
const {
746 otsolver->OcTreeShapeIntersect(model2, *model1, tf2, tf1, request, *result);
747 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
748 sqrDistLowerBound *= sqrDistLowerBound;
752 const OcTree* model2;
756 const OcTreeSolver* otsolver;
761 template <
typename S>
762 class HPP_FCL_DLLAPI OcTreeShapeCollisionTraversalNode
763 :
public CollisionTraversalNodeBase {
765 OcTreeShapeCollisionTraversalNode(
const CollisionRequest& request)
766 : CollisionTraversalNodeBase(request) {
773 bool BVDisjoints(
unsigned int,
unsigned int,
fcl::FCL_REAL&)
const {
777 void leafCollides(
unsigned int,
unsigned int,
778 FCL_REAL& sqrDistLowerBound)
const {
779 otsolver->OcTreeShapeIntersect(model1, *model2, tf1, tf2, request, *result);
780 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
781 sqrDistLowerBound *= sqrDistLowerBound;
784 const OcTree* model1;
789 const OcTreeSolver* otsolver;
793 template <
typename BV>
794 class HPP_FCL_DLLAPI MeshOcTreeCollisionTraversalNode
795 :
public CollisionTraversalNodeBase {
797 MeshOcTreeCollisionTraversalNode(
const CollisionRequest& request)
798 : CollisionTraversalNodeBase(request) {
805 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
809 void leafCollides(
unsigned int,
unsigned int,
810 FCL_REAL& sqrDistLowerBound)
const {
811 otsolver->OcTreeMeshIntersect(model2, model1, tf2, tf1, request, *result);
812 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
813 sqrDistLowerBound *= sqrDistLowerBound;
816 const BVHModel<BV>* model1;
817 const OcTree* model2;
821 const OcTreeSolver* otsolver;
825 template <
typename BV>
826 class HPP_FCL_DLLAPI OcTreeMeshCollisionTraversalNode
827 :
public CollisionTraversalNodeBase {
829 OcTreeMeshCollisionTraversalNode(
const CollisionRequest& request)
830 : CollisionTraversalNodeBase(request) {
837 bool BVDisjoints(
unsigned int,
unsigned int,
FCL_REAL&)
const {
841 void leafCollides(
unsigned int,
unsigned int,
842 FCL_REAL& sqrDistLowerBound)
const {
843 std::cout <<
"leafCollides" << std::endl;
844 otsolver->OcTreeMeshIntersect(model1, model2, tf1, tf2, request, *result);
845 sqrDistLowerBound = std::max((
FCL_REAL)0, result->distance_lower_bound);
846 sqrDistLowerBound *= sqrDistLowerBound;
849 const OcTree* model1;
850 const BVHModel<BV>* model2;
854 const OcTreeSolver* otsolver;
863 class HPP_FCL_DLLAPI OcTreeDistanceTraversalNode
864 :
public DistanceTraversalNodeBase {
866 OcTreeDistanceTraversalNode() {
873 FCL_REAL BVDistanceLowerBound(
unsigned,
unsigned)
const {
return -1; }
875 bool BVDistanceLowerBound(
unsigned,
unsigned,
FCL_REAL&)
const {
879 void leafComputeDistance(
unsigned,
unsigned int)
const {
880 otsolver->OcTreeDistance(model1, model2, tf1, tf2, request, *result);
883 const OcTree* model1;
884 const OcTree* model2;
886 const OcTreeSolver* otsolver;
890 template <
typename Shape>
891 class HPP_FCL_DLLAPI ShapeOcTreeDistanceTraversalNode
892 :
public DistanceTraversalNodeBase {
894 ShapeOcTreeDistanceTraversalNode() {
901 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
903 void leafComputeDistance(
unsigned int,
unsigned int)
const {
904 otsolver->OcTreeShapeDistance(model2, *model1, tf2, tf1, request, *result);
908 const OcTree* model2;
910 const OcTreeSolver* otsolver;
914 template <
typename Shape>
915 class HPP_FCL_DLLAPI OcTreeShapeDistanceTraversalNode
916 :
public DistanceTraversalNodeBase {
918 OcTreeShapeDistanceTraversalNode() {
925 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
927 void leafComputeDistance(
unsigned int,
unsigned int)
const {
928 otsolver->OcTreeShapeDistance(model1, *model2, tf1, tf2, request, *result);
931 const OcTree* model1;
934 const OcTreeSolver* otsolver;
938 template <
typename BV>
939 class HPP_FCL_DLLAPI MeshOcTreeDistanceTraversalNode
940 :
public DistanceTraversalNodeBase {
942 MeshOcTreeDistanceTraversalNode() {
949 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
951 void leafComputeDistance(
unsigned int,
unsigned int)
const {
952 otsolver->OcTreeMeshDistance(model2, model1, tf2, tf1, request, *result);
955 const BVHModel<BV>* model1;
956 const OcTree* model2;
958 const OcTreeSolver* otsolver;
962 template <
typename BV>
963 class HPP_FCL_DLLAPI OcTreeMeshDistanceTraversalNode
964 :
public DistanceTraversalNodeBase {
966 OcTreeMeshDistanceTraversalNode() {
973 FCL_REAL BVDistanceLowerBound(
unsigned int,
unsigned int)
const {
return -1; }
975 void leafComputeDistance(
unsigned int,
unsigned int)
const {
976 otsolver->OcTreeMeshDistance(model1, model2, tf1, tf2, request, *result);
979 const OcTree* model1;
980 const BVHModel<BV>* model2;
982 const OcTreeSolver* otsolver;
static void computeChildBV(const AABB &root_bv, unsigned int i, AABB &child_bv)
compute the bounding volume of an octree node's i-th child
octomap::OcTreeNode OcTreeNode
HPP_FCL_DLLAPI 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)
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const FCL_REAL &sqrDistLowerBound)
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
static void convertBV(const BV1 &bv1, const Transform3f &tf1, BV2 &bv2)
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity...
HPP_FCL_DLLAPI void constructBox(const AABB &bv, Box &box, Transform3f &tf)
construct a box shape (with a configuration) from a given bounding volume
static const int NONE
invalid contact primitive information