42 #if HPP_FCL_HAVE_OCTOMAP 53 namespace dynamic_AABB_tree {
55 #if HPP_FCL_HAVE_OCTOMAP 59 const AABB& root2_bv,
const Transform3f&
tf2,
62 if (root1->isLeaf()) {
63 CollisionObject* obj1 =
static_cast<CollisionObject*
>(root1->data);
65 if (!obj1->collisionGeometry()->isFree()) {
70 if (obb1.overlap(obb2)) {
75 box->cost_density = tree2->getDefaultOccupancy();
77 CollisionObject obj2(shared_ptr<CollisionGeometry>(box), box_tf);
78 return (*callback)(obj1, &obj2);
82 if (collisionRecurse_(root1->children[0], tree2,
nullptr, root2_bv, tf2,
85 if (collisionRecurse_(root1->children[1], tree2,
nullptr, root2_bv, tf2,
91 }
else if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
92 CollisionObject* obj1 =
static_cast<CollisionObject*
>(root1->data);
94 if (!tree2->isNodeFree(root2) && !obj1->collisionGeometry()->isFree()) {
99 if (obb1.overlap(obb2)) {
100 Box* box =
new Box();
104 box->cost_density = root2->getOccupancy();
105 box->threshold_occupied = tree2->getOccupancyThres();
107 CollisionObject obj2(shared_ptr<CollisionGeometry>(box), box_tf);
108 return (*callback)(obj1, &obj2);
119 if (tree2->isNodeFree(root2) || !obb1.overlap(obb2))
return false;
121 if (!tree2->nodeHasChildren(root2) ||
122 (!root1->isLeaf() && (root1->bv.size() > root2_bv.size()))) {
123 if (collisionRecurse_(root1->children[0], tree2, root2, root2_bv, tf2,
126 if (collisionRecurse_(root1->children[1], tree2, root2, root2_bv, tf2,
130 for (
unsigned int i = 0; i < 8; ++i) {
131 if (tree2->nodeChildExists(root2, i)) {
136 if (collisionRecurse_(root1, tree2, child, child_bv, tf2, callback))
141 if (collisionRecurse_(root1, tree2,
nullptr, child_bv, tf2, callback))
152 const AABB& root2_bv,
const Transform3f& tf2,
153 DistanceCallBackBase* callback,
FCL_REAL& min_dist) {
154 if (root1->isLeaf() && !tree2->nodeHasChildren(root2)) {
155 if (tree2->isNodeOccupied(root2)) {
156 Box* box =
new Box();
159 CollisionObject obj(shared_ptr<CollisionGeometry>(box), box_tf);
160 return (*callback)(
static_cast<CollisionObject*
>(root1->data), &obj,
166 if (!tree2->isNodeOccupied(root2))
return false;
168 if (!tree2->nodeHasChildren(root2) ||
169 (!root1->isLeaf() && (root1->bv.size() > root2_bv.size()))) {
173 FCL_REAL d1 = aabb2.distance(root1->children[0]->bv);
174 FCL_REAL d2 = aabb2.distance(root1->children[1]->bv);
178 if (distanceRecurse_(root1->children[1], tree2, root2, root2_bv, tf2,
184 if (distanceRecurse_(root1->children[0], tree2, root2, root2_bv, tf2,
190 if (distanceRecurse_(root1->children[0], tree2, root2, root2_bv, tf2,
196 if (distanceRecurse_(root1->children[1], tree2, root2, root2_bv, tf2,
202 for (
unsigned int i = 0; i < 8; ++i) {
203 if (tree2->nodeChildExists(root2, i)) {
210 FCL_REAL d = root1->bv.distance(aabb2);
213 if (distanceRecurse_(root1, tree2, child, child_bv, tf2, callback,
227 const AABB& root2_bv,
const Transform3f& tf2,
228 CollisionCallBackBase* callback) {
229 if (tf2.rotation().isIdentity())
230 return collisionRecurse_(root1, tree2, root2, root2_bv, tf2.translation(),
233 return collisionRecurse_(root1, tree2, root2, root2_bv, tf2, callback);
239 const AABB& root2_bv,
const Transform3f& tf2,
240 DistanceCallBackBase* callback,
FCL_REAL& min_dist) {
241 if (tf2.rotation().isIdentity())
242 return distanceRecurse_(root1, tree2, root2, root2_bv, tf2.translation(),
245 return distanceRecurse_(root1, tree2, root2, root2_bv, tf2, callback,
256 if (!root1->
bv.overlap(root2->
bv))
return false;
258 static_cast<CollisionObject*>(root2->
data));
261 if (!root1->
bv.overlap(root2->
bv))
return false;
264 (!root1->
isLeaf() && (root1->
bv.size() > root2->
bv.size()))) {
278 if (!root->
bv.overlap(query->
getAABB()))
return false;
282 if (!root->
bv.overlap(query->
getAABB()))
return false;
300 if (root->
isLeaf())
return false;
319 return (*callback)(root1_obj, root2_obj, min_dist);
323 (!root1->
isLeaf() && (root1->
bv.size() > root2->
bv.size()))) {
384 return (*callback)(root_obj, query, min_dist);
418 if (root->
isLeaf())
return false;
436 tree_topdown_balance_threshold = &dtree.bu_threshold;
437 tree_topdown_level = &dtree.topdown_level;
438 max_tree_nonbalanced_level = 10;
439 tree_incremental_balance_pass = 10;
440 *tree_topdown_balance_threshold = 2;
441 *tree_topdown_level = 0;
446 octree_as_geometry_collide =
true;
447 octree_as_geometry_distance =
false;
452 const std::vector<CollisionObject*>& other_objs) {
453 if (other_objs.empty())
return;
458 std::vector<DynamicAABBNode*> leaves(other_objs.size());
459 table.rehash(other_objs.size());
460 for (
size_t i = 0, size = other_objs.size(); i < size; ++i) {
463 node->
bv = other_objs[i]->getAABB();
466 node->
data = other_objs[i];
467 table[other_objs[i]] = node;
471 dtree.init(leaves, tree_init_level);
493 size_t num = dtree.size();
499 size_t height = dtree.getMaxHeight();
502 max_tree_nonbalanced_level)
503 dtree.balanceIncremental(tree_incremental_balance_pass);
505 dtree.balanceTopdown();
513 for (
auto it = table.cbegin(); it != table.cend(); ++it) {
517 if (node->
bv.volume() <= 0.)
518 throw std::invalid_argument(
"The bounding volume has a negative volume.");
529 const auto it = table.find(updated_obj);
530 if (it != table.end()) {
532 if (!(node->
bv == updated_obj->
getAABB()))
533 dtree.update(node, updated_obj->
getAABB());
540 update_(updated_obj);
546 const std::vector<CollisionObject*>& updated_objs) {
547 for (
size_t i = 0, size = updated_objs.size(); i < size; ++i)
548 update_(updated_objs[i]);
560 std::vector<CollisionObject*>& objs)
const {
561 objs.resize(this->size());
563 table.begin(), table.end(), objs.begin(),
564 std::bind(&DynamicAABBTable::value_type::first, std::placeholders::_1));
571 if (size() == 0)
return;
573 #if HPP_FCL_HAVE_OCTOMAP 575 if (!octree_as_geometry_collide) {
596 if (size() == 0)
return;
597 FCL_REAL min_dist = (std::numeric_limits<FCL_REAL>::max)();
599 #if HPP_FCL_HAVE_OCTOMAP 601 if (!octree_as_geometry_distance) {
622 if (size() == 0)
return;
630 if (size() == 0)
return;
631 FCL_REAL min_dist = (std::numeric_limits<FCL_REAL>::max)();
643 if ((size() == 0) || (other_manager->
size() == 0))
return;
655 if ((size() == 0) || (other_manager->
size() == 0))
return;
656 FCL_REAL min_dist = (std::numeric_limits<FCL_REAL>::max)();
658 dtree.getRoot(), other_manager->
dtree.getRoot(),
callback, min_dist);
virtual void init()
Initialization of the callback before running the collision broadphase manager.
OcTreeNode * getRoot() const
get the root node of the octree
const detail::HierarchyTree< AABB > & getTree() const
returns the AABB tree structure.
void clear()
clear the manager
DynamicAABBTreeCollisionManager()
Base class for broad phase collision. It helps to accelerate the collision/distance between N objects...
bool isLeaf() const
whether is a leaf
bool distanceRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode *root1, DynamicAABBTreeCollisionManager::DynamicAABBNode *root2, DistanceCallBackBase *callback, FCL_REAL &min_dist)
virtual void registerObjects(const std::vector< CollisionObject *> &other_objs)
add objects to the manager
Base callback class for collision queries. This class can be supersed by child classes to provide des...
AABB getRootBV() const
get the bounding volume for the root
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
virtual void init()
Initialization of the callback before running the collision broadphase manager.
void update_(CollisionObject *updated_obj)
NodeBase< BV > * parent
pointer to parent node
void distance(CollisionObject *obj, DistanceCallBackBase *callback) const
perform distance computation between one object and all the objects belonging to the manager ...
detail::NodeBase< AABB > DynamicAABBNode
const Transform3f & getTransform() const
get object's transform
Octree is one type of collision geometry which can encode uncertainty information in the sensor data...
octomap::OcTreeNode OcTreeNode
NodeBase< BV > * children[2]
for leaf node, children nodes
Class for hierarchy tree structure.
virtual std::vector< CollisionObject * > getObjects() const
return the objects managed by the manager
void collide(CollisionObject *obj, CollisionCallBackBase *callback) const
perform collision test between one object and all the objects belonging to the manager ...
void setup()
initialize the manager, related with the specific type of manager
bool empty() const
whether the manager is empty
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get geometry from the object instance
virtual void update()
update the condition of manager
bool collisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode *root1, DynamicAABBTreeCollisionManager::DynamicAABBNode *root2, CollisionCallBackBase *callback)
size_t select(const NodeBase< BV > &query, const NodeBase< BV > &node1, const NodeBase< BV > &node2)
select from node1 and node2 which is close to a given query. 0 for node1 and 1 for node2 ...
FCL_REAL distance(const AABB &other) const
Distance between two AABBs.
void registerObject(CollisionObject *obj)
add one object to the manager
detail::HierarchyTree< AABB > dtree
bool selfCollisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode *root, CollisionCallBackBase *callback)
const AABB & getAABB() const
get the AABB in world space
void unregisterObject(CollisionObject *obj)
remove one object from the manager
BV bv
the bounding volume for the node
the object for collision or distance computation, contains the geometry and the transform information...
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
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
size_t size() const
the number of objects managed by the manager
Base callback class for distance queries. This class can be supersed by child classes to provide desi...
void registerObjects(const std::vector< CollisionObject *> &other_objs)
add objects to the manager
bool selfDistanceRecurse(DynamicAABBTreeCollisionManager::DynamicAABBNode *root, DistanceCallBackBase *callback, FCL_REAL &min_dist)