38 #ifndef FCL_TRAVERSAL_OCTREE_OCTREESOLVER_INL_H 39 #define FCL_TRAVERSAL_OCTREE_OCTREESOLVER_INL_H 52 template <
typename NarrowPhaseSolver>
54 const NarrowPhaseSolver* solver_)
65 template <
typename NarrowPhaseSolver>
67 const OcTree<S>* tree1,
68 const OcTree<S>* tree2,
78 tree2, tree2->getRoot(), tree2->getRootBV(),
83 template <
typename NarrowPhaseSolver>
85 const OcTree<S>* tree1,
86 const OcTree<S>* tree2,
96 tree2, tree2->getRoot(), tree2->getRootBV(),
101 template <
typename NarrowPhaseSolver>
102 template <
typename BV>
104 const OcTree<S>* tree1,
120 template <
typename NarrowPhaseSolver>
121 template <
typename BV>
123 const OcTree<S>* tree1,
139 template <
typename NarrowPhaseSolver>
140 template <
typename BV>
143 const OcTree<S>* tree2,
160 template <
typename NarrowPhaseSolver>
161 template <
typename BV>
164 const OcTree<S>* tree2,
174 tree2, tree2->getRoot(), tree2->getRootBV(),
180 template <
typename NarrowPhaseSolver>
181 template <
typename Shape>
183 const OcTree<S>* tree,
205 template <
typename NarrowPhaseSolver>
206 template <
typename Shape>
209 const OcTree<S>* tree,
229 template <
typename NarrowPhaseSolver>
230 template <
typename Shape>
232 const OcTree<S>* tree,
251 template <
typename NarrowPhaseSolver>
252 template <
typename Shape>
255 const OcTree<S>* tree,
272 template <
typename NarrowPhaseSolver>
273 template <
typename Shape>
275 const Shape& s,
const AABB<S>& aabb2,
278 if(!tree1->nodeHasChildren(root1))
280 if(tree1->isNodeOccupied(root1))
295 solver->shapeDistance(box, box_tf, s, tf2, &dist, &closest_p1, &closest_p2);
305 if(!tree1->isNodeOccupied(root1))
return false;
307 for(
unsigned int i = 0; i < 8; ++i)
309 if(tree1->nodeChildExists(root1, i))
311 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
313 computeChildBV(bv1, i, child_bv);
318 if(d < dresult->min_distance)
330 template <
typename NarrowPhaseSolver>
331 template <
typename Shape>
333 const Shape& s,
const OBB<S>& obb2,
346 if(
solver->shapeIntersect(box, box_tf, s, tf2,
nullptr))
352 aabb1.
overlap(aabb2, overlap_part);
359 else if(!tree1->nodeHasChildren(root1))
361 if(tree1->isNodeOccupied(root1) && s.isOccupied())
371 bool is_intersect =
false;
374 if(
solver->shapeIntersect(box, box_tf, s, tf2,
nullptr))
383 std::vector<ContactPoint<S>> contacts;
384 if(
solver->shapeIntersect(box, box_tf, s, tf2, &contacts))
389 const size_t free_space =
crequest->num_max_contacts -
cresult->numContacts();
390 size_t num_adding_contacts;
393 if (free_space < contacts.size())
395 std::partial_sort(contacts.begin(), contacts.begin() + free_space, contacts.end(), std::bind(comparePenDepth<S>, std::placeholders::_2, std::placeholders::_1));
396 num_adding_contacts = free_space;
400 num_adding_contacts = contacts.size();
403 for(
size_t i = 0; i < num_adding_contacts; ++i)
409 if(is_intersect &&
crequest->enable_cost)
415 aabb1.
overlap(aabb2, overlap_part);
422 else if(!tree1->isNodeFree(root1) && !s.isFree() &&
crequest->enable_cost)
432 if(
solver->shapeIntersect(box, box_tf, s, tf2,
nullptr))
438 aabb1.
overlap(aabb2, overlap_part);
451 if(tree1->isNodeFree(root1) || s.isFree())
return false;
452 else if((tree1->isNodeUncertain(root1) || s.isUncertain()) && !
crequest->enable_cost)
return false;
457 if(!obb1.
overlap(obb2))
return false;
460 for(
unsigned int i = 0; i < 8; ++i)
462 if(tree1->nodeChildExists(root1, i))
464 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
466 computeChildBV(bv1, i, child_bv);
471 else if(!s.isFree() &&
crequest->enable_cost)
474 computeChildBV(bv1, i, child_bv);
485 template <
typename NarrowPhaseSolver>
486 template <
typename BV>
491 if(!tree1->nodeHasChildren(root1) && tree2->
getBV(root2).isLeaf())
493 if(tree1->isNodeOccupied(root1))
499 int primitive_id = tree2->
getBV(root2).primitiveId();
507 solver->shapeTriangleDistance(box, box_tf, p1, p2, p3, tf2, &dist, &closest_p1, &closest_p2);
509 dresult->update(dist, tree1, tree2, root1 - tree1->getRoot(), primitive_id, closest_p1, closest_p2);
517 if(!tree1->isNodeOccupied(root1))
return false;
519 if(tree2->
getBV(root2).isLeaf() || (tree1->nodeHasChildren(root1) && (bv1.
size() > tree2->
getBV(root2).bv.size())))
521 for(
unsigned int i = 0; i < 8; ++i)
523 if(tree1->nodeChildExists(root1, i))
525 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
527 computeChildBV(bv1, i, child_bv);
535 if(d < dresult->min_distance)
548 int child = tree2->
getBV(root2).leftChild();
552 if(d < dresult->min_distance)
558 child = tree2->
getBV(root2).rightChild();
562 if(d < dresult->min_distance)
573 template <
typename NarrowPhaseSolver>
574 template <
typename BV>
581 if(tree2->
getBV(root2).isLeaf())
592 int primitive_id = tree2->
getBV(root2).primitiveId();
598 if(
solver->shapeTriangleIntersect(box, box_tf, p1, p2, p3, tf2,
nullptr,
nullptr,
nullptr))
603 AABB<S> aabb2(tf2 * p1, tf2 * p2, tf2 * p3);
604 aabb1.
overlap(aabb2, overlap_part);
622 else if(!tree1->nodeHasChildren(root1) && tree2->
getBV(root2).isLeaf())
624 if(tree1->isNodeOccupied(root1) && tree2->
isOccupied())
635 int primitive_id = tree2->
getBV(root2).primitiveId();
641 bool is_intersect =
false;
644 if(
solver->shapeTriangleIntersect(box, box_tf, p1, p2, p3, tf2,
nullptr,
nullptr,
nullptr))
648 cresult->addContact(
Contact<S>(tree1, tree2, root1 - tree1->getRoot(), primitive_id));
657 if(
solver->shapeTriangleIntersect(box, box_tf, p1, p2, p3, tf2, &contact, &depth, &normal))
661 cresult->addContact(
Contact<S>(tree1, tree2, root1 - tree1->getRoot(), primitive_id, contact, normal, depth));
665 if(is_intersect &&
crequest->enable_cost)
670 AABB<S> aabb2(tf2 * p1, tf2 * p2, tf2 * p3);
671 aabb1.
overlap(aabb2, overlap_part);
680 else if(!tree1->isNodeFree(root1) && !tree2->
isFree() &&
crequest->enable_cost)
691 int primitive_id = tree2->
getBV(root2).primitiveId();
697 if(
solver->shapeTriangleIntersect(box, box_tf, p1, p2, p3, tf2,
nullptr,
nullptr,
nullptr))
702 AABB<S> aabb2(tf2 * p1, tf2 * p2, tf2 * p3);
703 aabb1.
overlap(aabb2, overlap_part);
717 if(tree1->isNodeFree(root1) || tree2->
isFree())
return false;
718 else if((tree1->isNodeUncertain(root1) || tree2->
isUncertain()) && !
crequest->enable_cost)
return false;
724 if(!obb1.
overlap(obb2))
return false;
727 if(tree2->
getBV(root2).isLeaf() || (tree1->nodeHasChildren(root1) && (bv1.
size() > tree2->
getBV(root2).bv.size())))
729 for(
unsigned int i = 0; i < 8; ++i)
731 if(tree1->nodeChildExists(root1, i))
733 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
735 computeChildBV(bv1, i, child_bv);
743 computeChildBV(bv1, i, child_bv);
764 template <
typename NarrowPhaseSolver>
767 if(!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2))
769 if(tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2))
785 solver->shapeDistance(box1, box1_tf, box2, box2_tf, &dist, &closest_p1, &closest_p2);
787 dresult->update(dist, tree1, tree2, root1 - tree1->getRoot(), root2 - tree2->getRoot(), closest_p1, closest_p2);
795 if(!tree1->isNodeOccupied(root1) || !tree2->isNodeOccupied(root2))
return false;
797 if(!tree2->nodeHasChildren(root2) || (tree1->nodeHasChildren(root1) && (bv1.
size() > bv2.
size())))
799 for(
unsigned int i = 0; i < 8; ++i)
801 if(tree1->nodeChildExists(root1, i))
803 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
805 computeChildBV(bv1, i, child_bv);
813 if(d < dresult->min_distance)
824 for(
unsigned int i = 0; i < 8; ++i)
826 if(tree2->nodeChildExists(root2, i))
828 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
830 computeChildBV(bv2, i, child_bv);
838 if(d < dresult->min_distance)
851 template <
typename NarrowPhaseSolver>
871 aabb1.
overlap(aabb2, overlap_part);
872 cresult->addCostSource(
CostSource<S>(overlap_part, tree1->getOccupancyThres() * tree2->getOccupancyThres()),
crequest->num_max_cost_sources);
877 else if(!root1 && root2)
879 if(tree2->nodeHasChildren(root2))
881 for(
unsigned int i = 0; i < 8; ++i)
883 if(tree2->nodeChildExists(root2, i))
885 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
887 computeChildBV(bv2, i, child_bv);
894 computeChildBV(bv2, i, child_bv);
908 else if(root1 && !root2)
910 if(tree1->nodeHasChildren(root1))
912 for(
unsigned int i = 0; i < 8; ++i)
914 if(tree1->nodeChildExists(root1, i))
916 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
918 computeChildBV(bv1, i, child_bv);
925 computeChildBV(bv1, i, child_bv);
939 else if(!tree1->nodeHasChildren(root1) && !tree2->nodeHasChildren(root2))
941 if(tree1->isNodeOccupied(root1) && tree2->isNodeOccupied(root2))
943 bool is_intersect =
false;
954 cresult->addContact(
Contact<S>(tree1, tree2, root1 - tree1->getRoot(), root2 - tree2->getRoot()));
964 std::vector<ContactPoint<S>> contacts;
965 if(
solver->shapeIntersect(box1, box1_tf, box2, box2_tf, &contacts))
970 const size_t free_space =
crequest->num_max_contacts -
cresult->numContacts();
971 size_t num_adding_contacts;
974 if (free_space < contacts.size())
976 std::partial_sort(contacts.begin(), contacts.begin() + free_space, contacts.end(), std::bind(comparePenDepth<S>, std::placeholders::_2, std::placeholders::_1));
977 num_adding_contacts = free_space;
981 num_adding_contacts = contacts.size();
984 for(
size_t i = 0; i < num_adding_contacts; ++i)
985 cresult->addContact(
Contact<S>(tree1, tree2, root1 - tree1->getRoot(), root2 - tree2->getRoot(), contacts[i].pos, contacts[i].normal, contacts[i].penetration_depth));
990 if(is_intersect &&
crequest->enable_cost)
1001 aabb1.
overlap(aabb2, overlap_part);
1007 else if(!tree1->isNodeFree(root1) && !tree2->isNodeFree(root2) &&
crequest->enable_cost)
1024 aabb1.
overlap(aabb2, overlap_part);
1037 if(tree1->isNodeFree(root1) || tree2->isNodeFree(root2))
return false;
1038 else if((tree1->isNodeUncertain(root1) || tree2->isNodeUncertain(root2)) && !
crequest->enable_cost)
return false;
1044 if(!obb1.
overlap(obb2))
return false;
1047 if(!tree2->nodeHasChildren(root2) || (tree1->nodeHasChildren(root1) && (bv1.
size() > bv2.
size())))
1049 for(
unsigned int i = 0; i < 8; ++i)
1051 if(tree1->nodeChildExists(root1, i))
1053 const typename OcTree<S>::OcTreeNode* child = tree1->getNodeChild(root1, i);
1055 computeChildBV(bv1, i, child_bv);
1062 else if(!tree2->isNodeFree(root2) &&
crequest->enable_cost)
1065 computeChildBV(bv1, i, child_bv);
1076 for(
unsigned int i = 0; i < 8; ++i)
1078 if(tree2->nodeChildExists(root2, i))
1080 const typename OcTree<S>::OcTreeNode* child = tree2->getNodeChild(root2, i);
1082 computeChildBV(bv2, i, child_bv);
1085 tree2, child, child_bv,
1089 else if(!tree1->isNodeFree(root1) &&
crequest->enable_cost)
1092 computeChildBV(bv2, i, child_bv);
1095 tree2,
nullptr, child_bv,
FCL_EXPORT void convertBV(const BV1 &bv1, const Transform3< typename BV1::S > &tf1, BV2 &bv2)
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity...
void MeshOcTreeDistance(const BVHModel< BV > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
distance between mesh and octree
bool OcTreeMeshDistanceRecurse(const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const BVHModel< BV > *tree2, int root2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
void MeshOcTreeIntersect(const BVHModel< BV > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
collision between mesh and octree
void OcTreeMeshDistance(const OcTree< S > *tree1, const BVHModel< BV > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
distance between octree and mesh
OcTreeSolver(const NarrowPhaseSolver *solver_)
bool OcTreeShapeIntersectRecurse(const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const Shape &s, const OBB< S > &obb2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
void OcTreeDistance(const OcTree< S > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
distance between two octrees
bool OcTreeIntersectRecurse(const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const OcTree< S > *tree2, const typename OcTree< S >::OcTreeNode *root2, const AABB< S > &bv2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
DistanceResult< S > * dresult
Vector3< S > * vertices
Geometry point data.
bool isFree() const
whether the object is completely free
Eigen::Matrix< S, 3, 1 > Vector3
bool isUncertain() const
whether the object has some uncertainty
bool OcTreeMeshIntersectRecurse(const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const BVHModel< BV > *tree2, int root2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
FCL_EXPORT void computeBV(const Shape &s, const Transform3< typename BV::S > &tf, BV &bv)
calculate a bounding volume for a shape in a specific configuration
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
void OcTreeIntersect(const OcTree< S > *tree1, const OcTree< S > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
collision between two octrees
void OcTreeShapeDistance(const OcTree< S > *tree, const Shape &s, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
distance between octree and shape
void OcTreeShapeIntersect(const OcTree< S > *tree, const Shape &s, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
collision between octree and shape
void ShapeOcTreeIntersect(const Shape &s, const OcTree< S > *tree, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
collision between shape and octree
Parameters for performing collision request.
bool overlap(const OBB< S > &other) const
Check collision between two OBB, return true if collision happens.
void OcTreeMeshIntersect(const OcTree< S > *tree1, const BVHModel< BV > *tree2, const Transform3< S > &tf1, const Transform3< S > &tf2, const CollisionRequest< S > &request_, CollisionResult< S > &result_) const
collision between octree and mesh
const DistanceRequest< S > * drequest
bool isOccupied() const
whether the object is completely occupied
Center at zero point, axis aligned box.
void ShapeOcTreeDistance(const Shape &s, const OcTree< S > *tree, const Transform3< S > &tf1, const Transform3< S > &tf2, const DistanceRequest< S > &request_, DistanceResult< S > &result_) const
distance between shape and octree
const NarrowPhaseSolver * solver
template void constructBox(const OBB< double > &bv, Box< double > &box, Transform3< double > &tf)
bool OcTreeShapeDistanceRecurse(const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const Shape &s, const AABB< S > &aabb2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
S distance(const AABB< S > &other, Vector3< S > *P, Vector3< S > *Q) const
Distance between two AABBs; P and Q, should not be nullptr, return the nearest points.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
BV::S cost_density
collision cost for unit volume
bool overlap(const AABB< S > &other) const
Check whether two AABB are overlap.
Cost source describes an area with a cost. The area is described by an AABB<S> region.
bool OcTreeDistanceRecurse(const OcTree< S > *tree1, const typename OcTree< S >::OcTreeNode *root1, const AABB< S > &bv1, const OcTree< S > *tree2, const typename OcTree< S >::OcTreeNode *root2, const AABB< S > &bv2, const Transform3< S > &tf1, const Transform3< S > &tf2) const
const CollisionRequest< S > * crequest
S size() const
Size of the AABB (used in BV_Splitter to order two AABBs)
CollisionResult< S > * cresult
request to the distance computation
typename NarrowPhaseSolver::S S