38 #ifndef FCL_BROAD_PHASE_INTERVAL_TREE_INL_H 39 #define FCL_BROAD_PHASE_INTERVAL_TREE_INL_H 58 p.value = obj->getAABB().min_[0];
60 p.value = obj->getAABB().max_[0];
61 auto end1 = std::upper_bound(start1,
endpoints[0].end(), p);
65 unsigned int start_id = start1 -
endpoints[0].begin();
66 unsigned int end_id = end1 -
endpoints[0].begin();
67 unsigned int cur_id = start_id;
68 for(
unsigned int i = start_id; i < end_id; ++i)
72 if(i == cur_id) cur_id++;
84 p.value = obj->getAABB().min_[1];
86 p.value = obj->getAABB().max_[1];
87 auto end2 = std::upper_bound(start2,
endpoints[1].end(), p);
91 unsigned int start_id = start2 -
endpoints[1].begin();
92 unsigned int end_id = end2 -
endpoints[1].begin();
93 unsigned int cur_id = start_id;
94 for(
unsigned int i = start_id; i < end_id; ++i)
98 if(i == cur_id) cur_id++;
111 p.value = obj->getAABB().min_[2];
113 p.value = obj->getAABB().max_[2];
114 auto end3 = std::upper_bound(start3,
endpoints[2].end(), p);
118 unsigned int start_id = start3 -
endpoints[2].begin();
119 unsigned int end_id = end3 -
endpoints[2].begin();
120 unsigned int cur_id = start_id;
121 for(
unsigned int i = start_id; i < end_id; ++i)
125 if(i == cur_id) cur_id++;
159 template <
typename S>
162 for(
int i = 0; i < 3; ++i)
163 interval_trees[i] =
nullptr;
167 template <
typename S>
174 template <
typename S>
183 p.value = obj->getAABB().min_[0];
184 q.value = obj->getAABB().max_[0];
188 p.value = obj->getAABB().min_[1];
189 q.value = obj->getAABB().max_[1];
193 p.value = obj->getAABB().min_[2];
194 q.value = obj->getAABB().max_[2];
201 template <
typename S>
210 for(
int i = 0; i < 3; ++i)
213 for(
int i = 0; i < 3; ++i)
219 CollisionObject<S>* obj = p.obj;
222 SAPInterval* ivl1 =
new SAPInterval(obj->getAABB().min_[0], obj->getAABB().max_[0],
obj);
223 SAPInterval* ivl2 =
new SAPInterval(obj->getAABB().min_[1], obj->getAABB().max_[1],
obj);
224 SAPInterval* ivl3 =
new SAPInterval(obj->getAABB().min_[2], obj->getAABB().max_[2],
obj);
241 template <
typename S>
275 template <
typename S>
279 const AABB<S>& new_aabb = updated_obj->getAABB();
280 for(
int i = 0; i < 3; ++i)
284 old_aabb.min_[i] = it->second->low;
285 old_aabb.max_[i] = it->second->high;
286 it->second->low = new_aabb.min_[i];
287 it->second->high = new_aabb.max_[i];
292 typename std::vector<EndPoint>::iterator it;
293 for(
int i = 0; i < 3; ++i)
295 dummy.value = old_aabb.min_[i];
299 if(it->obj == updated_obj && it->minmax == 0)
301 it->value = new_aabb.min_[i];
306 dummy.value = old_aabb.max_[i];
310 if(it->obj == updated_obj && it->minmax == 0)
312 it->value = new_aabb.max_[i];
322 template <
typename S>
325 for(
size_t i = 0; i < updated_objs.size(); ++i)
330 template <
typename S>
341 for(
int i = 0; i < 3; ++i)
350 for(
int i = 0; i < 3; ++i)
357 template <
typename S>
372 template <
typename S>
375 if(
size() == 0)
return;
380 template <
typename S>
383 static const unsigned int CUTOFF = 100;
385 std::deque<detail::SimpleInterval<S>*> results0, results1, results2;
387 results0 =
interval_trees[0]->query(obj->getAABB().min_[0], obj->getAABB().max_[0]);
388 if(results0.size() > CUTOFF)
390 results1 =
interval_trees[1]->query(obj->getAABB().min_[1], obj->getAABB().max_[1]);
391 if(results1.size() > CUTOFF)
393 results2 =
interval_trees[2]->query(obj->getAABB().min_[2], obj->getAABB().max_[2]);
394 if(results2.size() > CUTOFF)
396 int d1 = results0.size();
397 int d2 = results1.size();
398 int d3 = results2.size();
400 if(d1 >= d2 && d1 >= d3)
401 return checkColl(results0.begin(), results0.end(),
obj, cdata, callback);
402 else if(d2 >= d1 && d2 >= d3)
403 return checkColl(results1.begin(), results1.end(),
obj, cdata, callback);
405 return checkColl(results2.begin(), results2.end(),
obj, cdata, callback);
408 return checkColl(results2.begin(), results2.end(),
obj, cdata, callback);
411 return checkColl(results1.begin(), results1.end(),
obj, cdata, callback);
414 return checkColl(results0.begin(), results0.end(),
obj, cdata, callback);
418 template <
typename S>
421 if(
size() == 0)
return;
423 distance_(obj, cdata, callback, min_dist);
427 template <
typename S>
430 static const unsigned int CUTOFF = 100;
432 Vector3<S> delta = (obj->getAABB().max_ - obj->getAABB().min_) * 0.5;
433 AABB<S>
aabb = obj->getAABB();
436 Vector3<S> min_dist_delta(min_dist, min_dist, min_dist);
437 aabb.expand(min_dist_delta);
445 bool dist_res =
false;
447 old_min_distance = min_dist;
449 std::deque<detail::SimpleInterval<S>*> results0, results1, results2;
452 if(results0.size() > CUTOFF)
455 if(results1.size() > CUTOFF)
458 if(results2.size() > CUTOFF)
460 int d1 = results0.size();
461 int d2 = results1.size();
462 int d3 = results2.size();
464 if(d1 >= d2 && d1 >= d3)
465 dist_res =
checkDist(results0.begin(), results0.end(),
obj, cdata, callback, min_dist);
466 else if(d2 >= d1 && d2 >= d3)
467 dist_res =
checkDist(results1.begin(), results1.end(),
obj, cdata, callback, min_dist);
469 dist_res =
checkDist(results2.begin(), results2.end(),
obj, cdata, callback, min_dist);
472 dist_res =
checkDist(results2.begin(), results2.end(),
obj, cdata, callback, min_dist);
475 dist_res =
checkDist(results1.begin(), results1.end(),
obj, cdata, callback, min_dist);
478 dist_res =
checkDist(results0.begin(), results0.end(),
obj, cdata, callback, min_dist);
480 if(dist_res)
return true;
492 if(min_dist < old_min_distance)
494 Vector3<S> min_dist_delta(min_dist, min_dist, min_dist);
495 aabb = AABB<S>(obj->getAABB(), min_dist_delta);
500 if(aabb.equal(obj->getAABB()))
503 aabb.expand(obj->getAABB(), 2.0);
515 template <
typename S>
518 if(
size() == 0)
return;
520 std::set<CollisionObject<S>*> active;
521 std::set<std::pair<CollisionObject<S>*, CollisionObject<S>*> >
overlap;
528 if(diff_y > diff_x && diff_y > diff_z)
530 else if(diff_z > diff_y && diff_z > diff_x)
533 for(
unsigned int i = 0; i < n; ++i)
535 const EndPoint& endpoint =
endpoints[axis][i];
536 CollisionObject<S>* index = endpoint.obj;
537 if(endpoint.minmax == 0)
539 auto iter = active.begin();
540 auto end = active.end();
541 for(; iter != end; ++iter)
543 CollisionObject<S>* active_index = *iter;
544 const AABB<S>& b0 = active_index->getAABB();
545 const AABB<S>& b1 = index->getAABB();
547 int axis2 = (axis + 1) % 3;
548 int axis3 = (axis + 2) % 3;
550 if(b0.axisOverlap(b1, axis2) && b0.axisOverlap(b1, axis3))
552 std::pair<typename std::set<std::pair<CollisionObject<S>*, CollisionObject<S>*> >::iterator,
bool> insert_res;
553 if(active_index < index)
554 insert_res = overlap.insert(std::make_pair(active_index, index));
556 insert_res = overlap.insert(std::make_pair(index, active_index));
558 if(insert_res.second)
560 if(callback(active_index, index, cdata))
565 active.insert(index);
574 template <
typename S>
577 if(
size() == 0)
return;
583 for(
size_t i = 0; i <
endpoints[0].size(); ++i)
591 template <
typename S>
596 if((
size() == 0) || (other_manager->size() == 0))
return;
598 if(
this == other_manager)
604 if(this->
size() < other_manager->size())
607 if(other_manager->collide_(
endpoints[0][i].obj, cdata, callback))
return;
611 for(
size_t i = 0, size = other_manager->endpoints[0].size(); i <
size; ++i)
612 if(
collide_(other_manager->endpoints[0][i].obj, cdata, callback))
return;
617 template <
typename S>
622 if((
size() == 0) || (other_manager->size() == 0))
return;
624 if(
this == other_manager)
632 if(this->
size() < other_manager->size())
635 if(other_manager->distance_(
endpoints[0][i].obj, cdata, callback, min_dist))
return;
639 for(
size_t i = 0, size = other_manager->endpoints[0].size(); i <
size; ++i)
640 if(
distance_(other_manager->endpoints[0][i].obj, cdata, callback, min_dist))
return;
645 template <
typename S>
652 template <
typename S>
659 template <
typename S>
661 typename std::deque<detail::SimpleInterval<S>*>::const_iterator pos_start,
662 typename std::deque<detail::SimpleInterval<S>*>::const_iterator pos_end,
663 CollisionObject<S>* obj,
665 CollisionCallBack<S> callback)
const 667 while(pos_start < pos_end)
669 SAPInterval* ivl =
static_cast<SAPInterval*
>(*pos_start);
672 if(ivl->obj->getAABB().overlap(obj->getAABB()))
674 if(callback(ivl->obj, obj, cdata))
686 template <
typename S>
688 typename std::deque<detail::SimpleInterval<S>*>::const_iterator pos_start,
689 typename std::deque<detail::SimpleInterval<S>*>::const_iterator pos_end,
690 CollisionObject<S>* obj,
692 DistanceCallBack<S> callback,
695 while(pos_start < pos_end)
697 SAPInterval* ivl =
static_cast<SAPInterval*
>(*pos_start);
702 if(ivl->obj->getAABB().distance(obj->getAABB()) < min_dist)
704 if(callback(ivl->obj, obj, cdata, min_dist))
712 if(ivl->obj->getAABB().distance(obj->getAABB()) < min_dist)
714 if(callback(ivl->obj, obj, cdata, min_dist))
730 template <
typename S>
731 bool IntervalTreeCollisionManager<S>::EndPoint::operator<(
732 const typename IntervalTreeCollisionManager<S>::EndPoint& p)
const 734 return value < p.value;
738 template <
typename S>
739 IntervalTreeCollisionManager<S>::SAPInterval::SAPInterval(
740 S low_, S high_, CollisionObject<S>* obj_)
741 : detail::SimpleInterval<S>()
void distance(CollisionObject< S > *obj, void *cdata, DistanceCallBack< S > callback) const
perform distance computation between one object and all the objects belonging to the manager ...
size_t size() const
the number of objects managed by the manager
std::vector< EndPoint > endpoints[3]
vector stores all the end points
template void minmax(double a, double b, double &minv, double &maxv)
void unregisterObject(CollisionObject< S > *obj)
add one object to the manager
bool distance_(CollisionObject< S > *obj, void *cdata, DistanceCallBack< S > callback, S &min_dist) const
bool overlap(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2)
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity.
IntervalTreeCollisionManager()
bool setup_
tag for whether the interval tree is maintained suitably
~IntervalTreeCollisionManager()
void collide(CollisionObject< S > *obj, void *cdata, CollisionCallBack< S > callback) const
perform collision test between one object and all the objects belonging to the manager ...
std::set< std::pair< CollisionObject< S > *, CollisionObject< S > * > > tested_set
tools help to avoid repeating collision or distance callback for the pairs of objects tested before...
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
detail::IntervalTree< S > * interval_trees[3]
interval tree manages the intervals
void clear()
clear the manager
bool collide_(CollisionObject< S > *obj, void *cdata, CollisionCallBack< S > callback) const
bool inTestedSet(CollisionObject< S > *a, CollisionObject< S > *b) const
bool checkColl(typename std::deque< detail::SimpleInterval< S > *>::const_iterator pos_start, typename std::deque< detail::SimpleInterval< S > *>::const_iterator pos_end, CollisionObject< S > *obj, void *cdata, CollisionCallBack< S > callback) const
bool empty() const
whether the manager is empty
void registerObject(CollisionObject< S > *obj)
remove one object from the manager
void getObjects(std::vector< CollisionObject< S > *> &objs) const
return the objects managed by the manager
void setup()
initialize the manager, related with the specific type of manager
CollisionObject< S > * obj
object
void insertTestedSet(CollisionObject< S > *a, CollisionObject< S > *b) const
bool checkDist(typename std::deque< detail::SimpleInterval< S > *>::const_iterator pos_start, typename std::deque< detail::SimpleInterval< S > *>::const_iterator pos_end, CollisionObject< S > *obj, void *cdata, DistanceCallBack< S > callback, S &min_dist) const
void update()
update the condition of manager
std::map< CollisionObject< S > *, SAPInterval * > obj_interval_maps[3]
template class FCL_EXPORT IntervalTreeCollisionManager< double >