coal/broadphase/broadphase_spatialhash-inl.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef COAL_BROADPHASE_BROADPAHSESPATIALHASH_INL_H
39 #define COAL_BROADPHASE_BROADPAHSESPATIALHASH_INL_H
40 
42 
43 namespace coal {
44 
45 //==============================================================================
46 template <typename HashTable>
48  CoalScalar cell_size, const Vec3s& scene_min, const Vec3s& scene_max,
49  unsigned int default_table_size)
50  : scene_limit(AABB(scene_min, scene_max)),
51  hash_table(new HashTable(detail::SpatialHash(scene_limit, cell_size))) {
52  hash_table->init(default_table_size);
53 }
54 
55 //==============================================================================
56 template <typename HashTable>
58  delete hash_table;
59 }
60 
61 //==============================================================================
62 template <typename HashTable>
64  CollisionObject* obj) {
65  objs.push_back(obj);
66 
67  const AABB& obj_aabb = obj->getAABB();
68  AABB overlap_aabb;
69 
70  if (scene_limit.overlap(obj_aabb, overlap_aabb)) {
71  if (!scene_limit.contain(obj_aabb))
72  objs_partially_penetrating_scene_limit.push_back(obj);
73 
74  hash_table->insert(overlap_aabb, obj);
75  } else {
76  objs_outside_scene_limit.push_back(obj);
77  }
78 
79  obj_aabb_map[obj] = obj_aabb;
80 }
81 
82 //==============================================================================
83 template <typename HashTable>
85  CollisionObject* obj) {
86  objs.remove(obj);
87 
88  const AABB& obj_aabb = obj->getAABB();
89  AABB overlap_aabb;
90 
91  if (scene_limit.overlap(obj_aabb, overlap_aabb)) {
92  if (!scene_limit.contain(obj_aabb))
93  objs_partially_penetrating_scene_limit.remove(obj);
94 
95  hash_table->remove(overlap_aabb, obj);
96  } else {
97  objs_outside_scene_limit.remove(obj);
98  }
99 
100  obj_aabb_map.erase(obj);
101 }
102 
103 //==============================================================================
104 template <typename HashTable>
106  // Do nothing
107 }
108 
109 //==============================================================================
110 template <typename HashTable>
112  hash_table->clear();
113  objs_partially_penetrating_scene_limit.clear();
114  objs_outside_scene_limit.clear();
115 
116  for (auto it = objs.cbegin(), end = objs.cend(); it != end; ++it) {
117  CollisionObject* obj = *it;
118  const AABB& obj_aabb = obj->getAABB();
119  AABB overlap_aabb;
120 
121  if (scene_limit.overlap(obj_aabb, overlap_aabb)) {
122  if (!scene_limit.contain(obj_aabb))
123  objs_partially_penetrating_scene_limit.push_back(obj);
124 
125  hash_table->insert(overlap_aabb, obj);
126  } else {
127  objs_outside_scene_limit.push_back(obj);
128  }
129 
130  obj_aabb_map[obj] = obj_aabb;
131  }
132 }
133 
134 //==============================================================================
135 template <typename HashTable>
137  CollisionObject* updated_obj) {
138  const AABB& new_aabb = updated_obj->getAABB();
139  const AABB& old_aabb = obj_aabb_map[updated_obj];
140 
141  AABB old_overlap_aabb;
142  const auto is_old_aabb_overlapping =
143  scene_limit.overlap(old_aabb, old_overlap_aabb);
144  if (is_old_aabb_overlapping)
145  hash_table->remove(old_overlap_aabb, updated_obj);
146 
147  AABB new_overlap_aabb;
148  const auto is_new_aabb_overlapping =
149  scene_limit.overlap(new_aabb, new_overlap_aabb);
150  if (is_new_aabb_overlapping)
151  hash_table->insert(new_overlap_aabb, updated_obj);
152 
153  ObjectStatus old_status;
154  if (is_old_aabb_overlapping) {
155  if (scene_limit.contain(old_aabb))
156  old_status = Inside;
157  else
158  old_status = PartiallyPenetrating;
159  } else {
160  old_status = Outside;
161  }
162 
163  if (is_new_aabb_overlapping) {
164  if (scene_limit.contain(new_aabb)) {
165  if (old_status == PartiallyPenetrating) {
166  // Status change: PartiallyPenetrating --> Inside
167  // Required action(s):
168  // - remove object from "objs_partially_penetrating_scene_limit"
169 
170  auto find_it = std::find(objs_partially_penetrating_scene_limit.begin(),
171  objs_partially_penetrating_scene_limit.end(),
172  updated_obj);
173  objs_partially_penetrating_scene_limit.erase(find_it);
174  } else if (old_status == Outside) {
175  // Status change: Outside --> Inside
176  // Required action(s):
177  // - remove object from "objs_outside_scene_limit"
178 
179  auto find_it = std::find(objs_outside_scene_limit.begin(),
180  objs_outside_scene_limit.end(), updated_obj);
181  objs_outside_scene_limit.erase(find_it);
182  }
183  } else {
184  if (old_status == Inside) {
185  // Status change: Inside --> PartiallyPenetrating
186  // Required action(s):
187  // - add object to "objs_partially_penetrating_scene_limit"
188 
189  objs_partially_penetrating_scene_limit.push_back(updated_obj);
190  } else if (old_status == Outside) {
191  // Status change: Outside --> PartiallyPenetrating
192  // Required action(s):
193  // - remove object from "objs_outside_scene_limit"
194  // - add object to "objs_partially_penetrating_scene_limit"
195 
196  auto find_it = std::find(objs_outside_scene_limit.begin(),
197  objs_outside_scene_limit.end(), updated_obj);
198  objs_outside_scene_limit.erase(find_it);
199 
200  objs_partially_penetrating_scene_limit.push_back(updated_obj);
201  }
202  }
203  } else {
204  if (old_status == Inside) {
205  // Status change: Inside --> Outside
206  // Required action(s):
207  // - add object to "objs_outside_scene_limit"
208 
209  objs_outside_scene_limit.push_back(updated_obj);
210  } else if (old_status == PartiallyPenetrating) {
211  // Status change: PartiallyPenetrating --> Outside
212  // Required action(s):
213  // - remove object from "objs_partially_penetrating_scene_limit"
214  // - add object to "objs_outside_scene_limit"
215 
216  auto find_it =
217  std::find(objs_partially_penetrating_scene_limit.begin(),
218  objs_partially_penetrating_scene_limit.end(), updated_obj);
219  objs_partially_penetrating_scene_limit.erase(find_it);
220 
221  objs_outside_scene_limit.push_back(updated_obj);
222  }
223  }
224 
225  obj_aabb_map[updated_obj] = new_aabb;
226 }
227 
228 //==============================================================================
229 template <typename HashTable>
231  const std::vector<CollisionObject*>& updated_objs) {
232  for (size_t i = 0; i < updated_objs.size(); ++i) update(updated_objs[i]);
233 }
234 
235 //==============================================================================
236 template <typename HashTable>
238  objs.clear();
239  hash_table->clear();
240  objs_outside_scene_limit.clear();
241  obj_aabb_map.clear();
242 }
243 
244 //==============================================================================
245 template <typename HashTable>
247  std::vector<CollisionObject*>& objs_) const {
248  objs_.resize(objs.size());
249  std::copy(objs.begin(), objs.end(), objs_.begin());
250 }
251 
252 //==============================================================================
253 template <typename HashTable>
256  if (size() == 0) return;
257  collide_(obj, callback);
258 }
259 
260 //==============================================================================
261 template <typename HashTable>
264  if (size() == 0) return;
265  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
266  distance_(obj, callback, min_dist);
267 }
268 
269 //==============================================================================
270 template <typename HashTable>
273  const auto& obj_aabb = obj->getAABB();
274  AABB overlap_aabb;
275 
276  if (scene_limit.overlap(obj_aabb, overlap_aabb)) {
277  const auto query_result = hash_table->query(overlap_aabb);
278  for (const auto& obj2 : query_result) {
279  if (obj == obj2) continue;
280 
281  if ((*callback)(obj, obj2)) return true;
282  }
283 
284  if (!scene_limit.contain(obj_aabb)) {
285  for (const auto& obj2 : objs_outside_scene_limit) {
286  if (obj == obj2) continue;
287 
288  if ((*callback)(obj, obj2)) return true;
289  }
290  }
291  } else {
292  for (const auto& obj2 : objs_partially_penetrating_scene_limit) {
293  if (obj == obj2) continue;
294 
295  if ((*callback)(obj, obj2)) return true;
296  }
297 
298  for (const auto& obj2 : objs_outside_scene_limit) {
299  if (obj == obj2) continue;
300 
301  if ((*callback)(obj, obj2)) return true;
302  }
303  }
304 
305  return false;
306 }
307 
308 //==============================================================================
309 template <typename HashTable>
312  CoalScalar& min_dist) const {
313  auto delta = (obj->getAABB().max_ - obj->getAABB().min_) * 0.5;
314  auto aabb = obj->getAABB();
315  if (min_dist < (std::numeric_limits<CoalScalar>::max)()) {
316  Vec3s min_dist_delta(min_dist, min_dist, min_dist);
317  aabb.expand(min_dist_delta);
318  }
319 
320  AABB overlap_aabb;
321 
322  auto status = 1;
323  CoalScalar old_min_distance;
324 
325  while (1) {
326  old_min_distance = min_dist;
327 
328  if (scene_limit.overlap(aabb, overlap_aabb)) {
329  if (distanceObjectToObjects(obj, hash_table->query(overlap_aabb),
330  callback, min_dist)) {
331  return true;
332  }
333 
334  if (!scene_limit.contain(aabb)) {
335  if (distanceObjectToObjects(obj, objs_outside_scene_limit, callback,
336  min_dist)) {
337  return true;
338  }
339  }
340  } else {
341  if (distanceObjectToObjects(obj, objs_partially_penetrating_scene_limit,
342  callback, min_dist)) {
343  return true;
344  }
345 
346  if (distanceObjectToObjects(obj, objs_outside_scene_limit, callback,
347  min_dist)) {
348  return true;
349  }
350  }
351 
352  if (status == 1) {
353  if (old_min_distance < (std::numeric_limits<CoalScalar>::max)()) {
354  break;
355  } else {
356  if (min_dist < old_min_distance) {
357  Vec3s min_dist_delta(min_dist, min_dist, min_dist);
358  aabb = AABB(obj->getAABB(), min_dist_delta);
359  status = 0;
360  } else {
361  if (aabb == obj->getAABB())
362  aabb.expand(delta);
363  else
364  aabb.expand(obj->getAABB(), 2.0);
365  }
366  }
367  } else if (status == 0) {
368  break;
369  }
370  }
371 
372  return false;
373 }
374 
375 //==============================================================================
376 template <typename HashTable>
379  if (size() == 0) return;
380 
381  for (const auto& obj1 : objs) {
382  const auto& obj_aabb = obj1->getAABB();
383  AABB overlap_aabb;
384 
385  if (scene_limit.overlap(obj_aabb, overlap_aabb)) {
386  auto query_result = hash_table->query(overlap_aabb);
387  for (const auto& obj2 : query_result) {
388  if (obj1 < obj2) {
389  if ((*callback)(obj1, obj2)) return;
390  }
391  }
392 
393  if (!scene_limit.contain(obj_aabb)) {
394  for (const auto& obj2 : objs_outside_scene_limit) {
395  if (obj1 < obj2) {
396  if ((*callback)(obj1, obj2)) return;
397  }
398  }
399  }
400  } else {
401  for (const auto& obj2 : objs_partially_penetrating_scene_limit) {
402  if (obj1 < obj2) {
403  if ((*callback)(obj1, obj2)) return;
404  }
405  }
406 
407  for (const auto& obj2 : objs_outside_scene_limit) {
408  if (obj1 < obj2) {
409  if ((*callback)(obj1, obj2)) return;
410  }
411  }
412  }
413  }
414 }
415 
416 //==============================================================================
417 template <typename HashTable>
420  if (size() == 0) return;
421 
422  this->enable_tested_set_ = true;
423  this->tested_set.clear();
424 
425  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
426 
427  for (const auto& obj : objs) {
428  if (distance_(obj, callback, min_dist)) break;
429  }
430 
431  this->enable_tested_set_ = false;
432  this->tested_set.clear();
433 }
434 
435 //==============================================================================
436 template <typename HashTable>
438  BroadPhaseCollisionManager* other_manager_,
440  auto* other_manager =
441  static_cast<SpatialHashingCollisionManager<HashTable>*>(other_manager_);
442 
443  if ((size() == 0) || (other_manager->size() == 0)) return;
444 
445  if (this == other_manager) {
446  collide(callback);
447  return;
448  }
449 
450  if (this->size() < other_manager->size()) {
451  for (const auto& obj : objs) {
452  if (other_manager->collide_(obj, callback)) return;
453  }
454  } else {
455  for (const auto& obj : other_manager->objs) {
456  if (collide_(obj, callback)) return;
457  }
458  }
459 }
460 
461 //==============================================================================
462 template <typename HashTable>
464  BroadPhaseCollisionManager* other_manager_,
466  auto* other_manager =
467  static_cast<SpatialHashingCollisionManager<HashTable>*>(other_manager_);
468 
469  if ((size() == 0) || (other_manager->size() == 0)) return;
470 
471  if (this == other_manager) {
473  return;
474  }
475 
476  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
477 
478  if (this->size() < other_manager->size()) {
479  for (const auto& obj : objs)
480  if (other_manager->distance_(obj, callback, min_dist)) return;
481  } else {
482  for (const auto& obj : other_manager->objs)
483  if (distance_(obj, callback, min_dist)) return;
484  }
485 }
486 
487 //==============================================================================
488 template <typename HashTable>
490  return objs.empty();
491 }
492 
493 //==============================================================================
494 template <typename HashTable>
496  return objs.size();
497 }
498 
499 //==============================================================================
500 template <typename HashTable>
502  std::vector<CollisionObject*>& objs, Vec3s& l, Vec3s& u) {
503  AABB bound;
504  for (unsigned int i = 0; i < objs.size(); ++i) bound += objs[i]->getAABB();
505 
506  l = bound.min_;
507  u = bound.max_;
508 }
509 
510 //==============================================================================
511 template <typename HashTable>
512 template <typename Container>
514  CollisionObject* obj, const Container& objs, DistanceCallBackBase* callback,
515  CoalScalar& min_dist) const {
516  for (auto& obj2 : objs) {
517  if (obj == obj2) continue;
518 
519  if (!this->enable_tested_set_) {
520  if (obj->getAABB().distance(obj2->getAABB()) < min_dist) {
521  if ((*callback)(obj, obj2, min_dist)) return true;
522  }
523  } else {
524  if (!this->inTestedSet(obj, obj2)) {
525  if (obj->getAABB().distance(obj2->getAABB()) < min_dist) {
526  if ((*callback)(obj, obj2, min_dist)) return true;
527  }
528 
529  this->insertTestedSet(obj, obj2);
530  }
531  }
532  }
533 
534  return false;
535 }
536 
537 } // namespace coal
538 
539 #endif
coal::SpatialHashingCollisionManager
spatial hashing collision mananger
Definition: coal/broadphase/broadphase_spatialhash.h:54
coal::SpatialHashingCollisionManager::~SpatialHashingCollisionManager
~SpatialHashingCollisionManager()
Definition: coal/broadphase/broadphase_spatialhash-inl.h:57
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
collision_manager.callback
callback
Definition: collision_manager.py:27
coal::AABB::distance
CoalScalar distance(const AABB &other) const
Distance between two AABBs.
Definition: AABB.cpp:114
coal::SpatialHashingCollisionManager::distanceObjectToObjects
bool distanceObjectToObjects(CollisionObject *obj, const Container &objs, DistanceCallBackBase *callback, CoalScalar &min_dist) const
Definition: coal/broadphase/broadphase_spatialhash-inl.h:513
coal::BroadPhaseCollisionManager
Base class for broad phase collision. It helps to accelerate the collision/distance between N objects...
Definition: coal/broadphase/broadphase_collision_manager.h:53
coal::SpatialHashingCollisionManager::collide_
bool collide_(CollisionObject *obj, CollisionCallBackBase *callback) const
perform collision test between one object and all the objects belonging to the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:271
coal::SpatialHashingCollisionManager::distance
void distance(CollisionObject *obj, DistanceCallBackBase *callback) const
perform distance computation between one object and all the objects belonging ot the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:262
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::SpatialHashingCollisionManager::distance_
bool distance_(CollisionObject *obj, DistanceCallBackBase *callback, CoalScalar &min_dist) const
perform distance computation between one object and all the objects belonging ot the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:310
coal::BroadPhaseCollisionManager::getObjects
virtual std::vector< CollisionObject * > getObjects() const
return the objects managed by the manager
Definition: coal/broadphase/broadphase_collision_manager.h:87
coal::SpatialHashingCollisionManager::size
size_t size() const
the number of objects managed by the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:495
coal::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::SpatialHashingCollisionManager::unregisterObject
void unregisterObject(CollisionObject *obj)
remove one object from the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:84
coal::AABB::max_
Vec3s max_
The max point in the AABB.
Definition: coal/BV/AABB.h:60
coal::AABB::overlap
bool overlap(const AABB &other) const
Check whether two AABB are overlap.
Definition: coal/BV/AABB.h:111
coal::SpatialHashingCollisionManager::SpatialHashingCollisionManager
SpatialHashingCollisionManager(CoalScalar cell_size, const Vec3s &scene_min, const Vec3s &scene_max, unsigned int default_table_size=1000)
Definition: coal/broadphase/broadphase_spatialhash-inl.h:47
coal::SpatialHashingCollisionManager::update
virtual void update()
update the condition of manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:111
coal::DistanceCallBackBase
Base callback class for distance queries. This class can be supersed by child classes to provide desi...
Definition: coal/broadphase/broadphase_callbacks.h:72
broadphase_spatialhash.h
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
coal::CollisionObject::getAABB
const AABB & getAABB() const
get the AABB in world space
Definition: coal/collision_object.h:252
coal::SpatialHashingCollisionManager::registerObject
void registerObject(CollisionObject *obj)
add one object to the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:63
coal::SpatialHashingCollisionManager::collide
void collide(CollisionObject *obj, CollisionCallBackBase *callback) const
perform collision test between one object and all the objects belonging to the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:254
coal::AABB::min_
Vec3s min_
The min point in the AABB.
Definition: coal/BV/AABB.h:58
coal::SpatialHashingCollisionManager::hash_table
HashTable * hash_table
objects in the scene limit (given by scene_min and scene_max) are in the spatial hash table
Definition: coal/broadphase/broadphase_spatialhash.h:152
coal::SpatialHashingCollisionManager::ObjectStatus
ObjectStatus
Definition: coal/broadphase/broadphase_spatialhash.h:155
coal::SpatialHashingCollisionManager::computeBound
static void computeBound(std::vector< CollisionObject * > &objs, Vec3s &l, Vec3s &u)
compute the bound for the environent
Definition: coal/broadphase/broadphase_spatialhash-inl.h:501
coal::SpatialHashingCollisionManager::empty
bool empty() const
whether the manager is empty
Definition: coal/broadphase/broadphase_spatialhash-inl.h:489
coal::collide
COAL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts,...
Definition: src/collision.cpp:61
coal::CollisionCallBackBase
Base callback class for collision queries. This class can be supersed by child classes to provide des...
Definition: coal/broadphase/broadphase_callbacks.h:49
coal::SpatialHashingCollisionManager::setup
void setup()
initialize the manager, related with the specific type of manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:105
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::SpatialHashingCollisionManager::clear
void clear()
clear the manager
Definition: coal/broadphase/broadphase_spatialhash-inl.h:237


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57