38 #ifndef FCL_BROADPHASE_BROADPAHSESPATIALHASH_INL_H 39 #define FCL_BROADPHASE_BROADPAHSESPATIALHASH_INL_H 48 class FCL_EXPORT SpatialHashingCollisionManager<
50 detail::SimpleHashTable<
54 template<
typename S,
typename HashTable>
59 unsigned int default_table_size)
60 : scene_limit(
AABB<S>(scene_min, scene_max)),
61 hash_table(new HashTable(detail::SpatialHash<S>(scene_limit, cell_size)))
67 template<
typename S,
typename HashTable>
74 template<
typename S,
typename HashTable>
99 template<
typename S,
typename HashTable>
123 template<
typename S,
typename HashTable>
130 template<
typename S,
typename HashTable>
137 for(
auto it =
objs.cbegin(), end =
objs.cend(); it != end; ++it)
160 template<
typename S,
typename HashTable>
167 const auto is_old_aabb_overlapping
169 if(is_old_aabb_overlapping)
170 hash_table->remove(old_overlap_aabb, updated_obj);
173 const auto is_new_aabb_overlapping
175 if(is_new_aabb_overlapping)
176 hash_table->insert(new_overlap_aabb, updated_obj);
179 if(is_old_aabb_overlapping)
191 if(is_new_aabb_overlapping)
206 else if (old_status ==
Outside)
228 else if (old_status ==
Outside)
274 template<
typename S,
typename HashTable>
277 for(
size_t i = 0; i < updated_objs.size(); ++i)
282 template<
typename S,
typename HashTable>
292 template<
typename S,
typename HashTable>
295 objs_.resize(
objs.size());
296 std::copy(
objs.begin(),
objs.end(), objs_.begin());
300 template<
typename S,
typename HashTable>
303 if(
size() == 0)
return;
308 template<
typename S,
typename HashTable>
311 if(
size() == 0)
return;
313 distance_(obj, cdata, callback, min_dist);
317 template<
typename S,
typename HashTable>
321 const auto& obj_aabb = obj->
getAABB();
326 const auto query_result =
hash_table->query(overlap_aabb);
327 for(
const auto&
obj2 : query_result)
332 if(callback(obj,
obj2, cdata))
343 if(callback(obj,
obj2, cdata))
355 if(callback(obj,
obj2, cdata))
364 if(callback(obj,
obj2, cdata))
373 template<
typename S,
typename HashTable>
381 Vector3<S> min_dist_delta(min_dist, min_dist, min_dist);
382 aabb.expand(min_dist_delta);
392 old_min_distance = min_dist;
397 obj,
hash_table->query(overlap_aabb), cdata, callback, min_dist))
434 if(min_dist < old_min_distance)
436 Vector3<S> min_dist_delta(min_dist, min_dist, min_dist);
459 template<
typename S,
typename HashTable>
468 const auto& obj_aabb =
obj1->getAABB();
473 auto query_result =
hash_table->query(overlap_aabb);
474 for(
const auto&
obj2 : query_result)
519 template<
typename S,
typename HashTable>
542 template<
typename S,
typename HashTable>
547 if((
size() == 0) || (other_manager->size() == 0))
550 if(
this == other_manager)
556 if(this->
size() < other_manager->size())
560 if(other_manager->collide_(
obj, cdata, callback))
566 for(
const auto&
obj : other_manager->objs)
575 template<
typename S,
typename HashTable>
580 if((
size() == 0) || (other_manager->size() == 0))
583 if(
this == other_manager)
591 if(this->
size() < other_manager->size())
594 if(other_manager->distance_(
obj, cdata, callback, min_dist))
return;
598 for(
const auto&
obj : other_manager->objs)
604 template<
typename S,
typename HashTable>
611 template<
typename S,
typename HashTable>
618 template<
typename S,
typename HashTable>
623 for(
unsigned int i = 0; i <
objs.size(); ++i)
624 bound +=
objs[i]->getAABB();
631 template<
typename S,
typename HashTable>
632 template<
typename Container>
635 const Container&
objs,
640 for(
auto&
obj2 : objs)
649 if(callback(obj,
obj2, cdata, min_dist))
659 if(callback(obj,
obj2, cdata, min_dist))
SpatialHashingCollisionManager(S cell_size, const Vector3< S > &scene_min, const Vector3< S > &scene_max, unsigned int default_table_size=1000)
std::list< CollisionObject< S > * > objs_outside_scene_limit
objects outside the scene limit are in another list
void clear()
clear the manager
AABB< S > scene_limit
the size of the scene
void getObjects(std::vector< CollisionObject< S > *> &objs) const
return the objects managed by the manager
const AABB< S > & getAABB() const
get the AABB in world space
std::map< CollisionObject< S > *, AABB< S > > obj_aabb_map
store the map between objects and their aabbs. will make update more convenient
CollisionObject< S > * obj1
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
size_t size() const
the number of objects managed by the manager
static void computeBound(std::vector< CollisionObject< S > *> &objs, Vector3< S > &l, Vector3< S > &u)
compute the bound for the environent
bool empty() const
whether the manager is empty
spatial hashing collision mananger
bool contain(const AABB< S > &other) const
Check whether the AABB contains another AABB.
void distance(CollisionObject< S > *obj, void *cdata, DistanceCallBack< S > callback) const
perform distance computation between one object and all the objects belonging ot the manager ...
Vector3< S > max_
The max point in the AABB.
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...
Eigen::Matrix< S, 3, 1 > Vector3
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
~SpatialHashingCollisionManager()
HashTable * hash_table
objects in the scene limit (given by scene_min and scene_max) are in the spatial hash table ...
bool(*)(CollisionObject< S > *o1, CollisionObject< S > *o2, void *cdata) CollisionCallBack
Callback for collision between two objects. Return value is whether can stop now. ...
bool distance_(CollisionObject< S > *obj, void *cdata, DistanceCallBack< S > callback, S &min_dist) const
perform distance computation between one object and all the objects belonging ot the manager ...
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 ...
bool(*)(CollisionObject< S > *o1, CollisionObject< S > *o2, void *cdata, S &dist) DistanceCallBack
Callback for distance between two objects, Return value is whether can stop now, also return the mini...
std::list< CollisionObject< S > * > objs_partially_penetrating_scene_limit
objects partially penetrating (not totally inside nor outside) the scene limit are in another list ...
std::list< CollisionObject< S > * > objs
all objects in the scene
void registerObject(CollisionObject< S > *obj)
add one object to the manager
bool distanceObjectToObjects(CollisionObject< S > *obj, const Container &objs, void *cdata, DistanceCallBack< S > callback, S &min_dist) const
Vector3< S > min_
The min point in the AABB.
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.
bool inTestedSet(CollisionObject< S > *a, CollisionObject< S > *b) const
void setup()
initialize the manager, related with the specific type of manager
template class FCL_EXPORT AABB< double >
the object for collision or distance computation, contains the geometry and the transform information...
CollisionObject< S > * obj2
bool overlap(const AABB< S > &other) const
Check whether two AABB are overlap.
template Interval< double > bound(const Interval< double > &i, double v)
bool collide_(CollisionObject< S > *obj, void *cdata, CollisionCallBack< S > callback) const
perform collision test between one object and all the objects belonging to the manager ...
template class FCL_EXPORT CollisionObject< double >
Base class for broad phase collision. It helps to accelerate the collision/distance between N objects...
CollisionObject< S > * obj
object
void unregisterObject(CollisionObject< S > *obj)
remove one object from the manager
void insertTestedSet(CollisionObject< S > *a, CollisionObject< S > *b) const
void update()
update the condition of manager