broadphase_SSaP.cpp
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 
39 
40 namespace coal {
41 
43 struct SortByXLow {
44  bool operator()(const CollisionObject* a, const CollisionObject* b) const {
45  if (a->getAABB().min_[0] < b->getAABB().min_[0]) return true;
46  return false;
47  }
48 };
49 
51 struct SortByYLow {
52  bool operator()(const CollisionObject* a, const CollisionObject* b) const {
53  if (a->getAABB().min_[1] < b->getAABB().min_[1]) return true;
54  return false;
55  }
56 };
57 
59 struct SortByZLow {
60  bool operator()(const CollisionObject* a, const CollisionObject* b) const {
61  if (a->getAABB().min_[2] < b->getAABB().min_[2]) return true;
62  return false;
63  }
64 };
65 
67 class COAL_DLLAPI DummyCollisionObject : public CollisionObject {
68  public:
69  DummyCollisionObject(const AABB& aabb_)
70  : CollisionObject(shared_ptr<CollisionGeometry>()) {
71  this->aabb = aabb_;
72  }
73 
74  void computeLocalAABB() {}
75 };
76 
77 //==============================================================================
79  setup();
80 
81  DummyCollisionObject dummyHigh(AABB(obj->getAABB().max_));
82 
83  auto pos_start1 = objs_x.begin();
84  auto pos_end1 =
85  std::upper_bound(pos_start1, objs_x.end(), &dummyHigh, SortByXLow());
86 
87  while (pos_start1 < pos_end1) {
88  if (*pos_start1 == obj) {
89  objs_x.erase(pos_start1);
90  break;
91  }
92  ++pos_start1;
93  }
94 
95  auto pos_start2 = objs_y.begin();
96  auto pos_end2 =
97  std::upper_bound(pos_start2, objs_y.end(), &dummyHigh, SortByYLow());
98 
99  while (pos_start2 < pos_end2) {
100  if (*pos_start2 == obj) {
101  objs_y.erase(pos_start2);
102  break;
103  }
104  ++pos_start2;
105  }
106 
107  auto pos_start3 = objs_z.begin();
108  auto pos_end3 =
109  std::upper_bound(pos_start3, objs_z.end(), &dummyHigh, SortByZLow());
110 
111  while (pos_start3 < pos_end3) {
112  if (*pos_start3 == obj) {
113  objs_z.erase(pos_start3);
114  break;
115  }
116  ++pos_start3;
117  }
118 }
119 
120 //==============================================================================
122  // Do nothing
123 }
124 
125 //==============================================================================
127  objs_x.push_back(obj);
128  objs_y.push_back(obj);
129  objs_z.push_back(obj);
130  setup_ = false;
131 }
132 
133 //==============================================================================
135  if (!setup_) {
136  std::sort(objs_x.begin(), objs_x.end(), SortByXLow());
137  std::sort(objs_y.begin(), objs_y.end(), SortByYLow());
138  std::sort(objs_z.begin(), objs_z.end(), SortByZLow());
139  setup_ = true;
140  }
141 }
142 
143 //==============================================================================
145  setup_ = false;
146  setup();
147 }
148 
149 //==============================================================================
151  objs_x.clear();
152  objs_y.clear();
153  objs_z.clear();
154  setup_ = false;
155 }
156 
157 //==============================================================================
159  std::vector<CollisionObject*>& objs) const {
160  objs.resize(objs_x.size());
161  std::copy(objs_x.begin(), objs_x.end(), objs.begin());
162 }
163 
164 //==============================================================================
166  std::vector<CollisionObject*>::const_iterator pos_start,
167  std::vector<CollisionObject*>::const_iterator pos_end, CollisionObject* obj,
169  while (pos_start < pos_end) {
170  if (*pos_start != obj) // no collision between the same object
171  {
172  if ((*pos_start)->getAABB().overlap(obj->getAABB())) {
173  if ((*callback)(*pos_start, obj)) return true;
174  }
175  }
176  pos_start++;
177  }
178  return false;
179 }
180 
181 //==============================================================================
183  typename std::vector<CollisionObject*>::const_iterator pos_start,
184  typename std::vector<CollisionObject*>::const_iterator pos_end,
186  CoalScalar& min_dist) const {
187  while (pos_start < pos_end) {
188  if (*pos_start != obj) // no distance between the same object
189  {
190  if ((*pos_start)->getAABB().distance(obj->getAABB()) < min_dist) {
191  if ((*callback)(*pos_start, obj, min_dist)) return true;
192  }
193  }
194  pos_start++;
195  }
196 
197  return false;
198 }
199 
200 //==============================================================================
203  callback->init();
204  if (size() == 0) return;
205 
206  collide_(obj, callback);
207 }
208 
209 //==============================================================================
212  static const unsigned int CUTOFF = 100;
213 
214  DummyCollisionObject dummyHigh(AABB(obj->getAABB().max_));
215  bool coll_res = false;
216 
217  const auto pos_start1 = objs_x.begin();
218  const auto pos_end1 =
219  std::upper_bound(pos_start1, objs_x.end(), &dummyHigh, SortByXLow());
220  long d1 = pos_end1 - pos_start1;
221 
222  if (d1 > CUTOFF) {
223  const auto pos_start2 = objs_y.begin();
224  const auto pos_end2 =
225  std::upper_bound(pos_start2, objs_y.end(), &dummyHigh, SortByYLow());
226  long d2 = pos_end2 - pos_start2;
227 
228  if (d2 > CUTOFF) {
229  const auto pos_start3 = objs_z.begin();
230  const auto pos_end3 =
231  std::upper_bound(pos_start3, objs_z.end(), &dummyHigh, SortByZLow());
232  long d3 = pos_end3 - pos_start3;
233 
234  if (d3 > CUTOFF) {
235  if (d3 <= d2 && d3 <= d1)
236  coll_res = checkColl(pos_start3, pos_end3, obj, callback);
237  else {
238  if (d2 <= d3 && d2 <= d1)
239  coll_res = checkColl(pos_start2, pos_end2, obj, callback);
240  else
241  coll_res = checkColl(pos_start1, pos_end1, obj, callback);
242  }
243  } else
244  coll_res = checkColl(pos_start3, pos_end3, obj, callback);
245  } else
246  coll_res = checkColl(pos_start2, pos_end2, obj, callback);
247  } else
248  coll_res = checkColl(pos_start1, pos_end1, obj, callback);
249 
250  return coll_res;
251 }
252 
253 //==============================================================================
256  callback->init();
257  if (size() == 0) return;
258 
259  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
260  distance_(obj, callback, min_dist);
261 }
262 
263 //==============================================================================
266  CoalScalar& min_dist) const {
267  static const unsigned int CUTOFF = 100;
268  Vec3s delta = (obj->getAABB().max_ - obj->getAABB().min_) * 0.5;
269  Vec3s dummy_vector = obj->getAABB().max_;
270  if (min_dist < (std::numeric_limits<CoalScalar>::max)())
271  dummy_vector += Vec3s(min_dist, min_dist, min_dist);
272 
273  typename std::vector<CollisionObject*>::const_iterator pos_start1 =
274  objs_x.begin();
275  typename std::vector<CollisionObject*>::const_iterator pos_start2 =
276  objs_y.begin();
277  typename std::vector<CollisionObject*>::const_iterator pos_start3 =
278  objs_z.begin();
279  typename std::vector<CollisionObject*>::const_iterator pos_end1 =
280  objs_x.end();
281  typename std::vector<CollisionObject*>::const_iterator pos_end2 =
282  objs_y.end();
283  typename std::vector<CollisionObject*>::const_iterator pos_end3 =
284  objs_z.end();
285 
286  int status = 1;
287  CoalScalar old_min_distance;
288 
289  while (1) {
290  old_min_distance = min_dist;
291  DummyCollisionObject dummyHigh((AABB(dummy_vector)));
292 
293  pos_end1 =
294  std::upper_bound(pos_start1, objs_x.end(), &dummyHigh, SortByXLow());
295  long d1 = pos_end1 - pos_start1;
296 
297  bool dist_res = false;
298 
299  if (d1 > CUTOFF) {
300  pos_end2 =
301  std::upper_bound(pos_start2, objs_y.end(), &dummyHigh, SortByYLow());
302  long d2 = pos_end2 - pos_start2;
303 
304  if (d2 > CUTOFF) {
305  pos_end3 = std::upper_bound(pos_start3, objs_z.end(), &dummyHigh,
306  SortByZLow());
307  long d3 = pos_end3 - pos_start3;
308 
309  if (d3 > CUTOFF) {
310  if (d3 <= d2 && d3 <= d1)
311  dist_res = checkDis(pos_start3, pos_end3, obj, callback, min_dist);
312  else {
313  if (d2 <= d3 && d2 <= d1)
314  dist_res =
315  checkDis(pos_start2, pos_end2, obj, callback, min_dist);
316  else
317  dist_res =
318  checkDis(pos_start1, pos_end1, obj, callback, min_dist);
319  }
320  } else
321  dist_res = checkDis(pos_start3, pos_end3, obj, callback, min_dist);
322  } else
323  dist_res = checkDis(pos_start2, pos_end2, obj, callback, min_dist);
324  } else {
325  dist_res = checkDis(pos_start1, pos_end1, obj, callback, min_dist);
326  }
327 
328  if (dist_res) return true;
329 
330  if (status == 1) {
331  if (old_min_distance < (std::numeric_limits<CoalScalar>::max)())
332  break;
333  else {
334  // from infinity to a finite one, only need one additional loop
335  // to check the possible missed ones to the right of the objs array
336  if (min_dist < old_min_distance) {
337  dummy_vector =
338  obj->getAABB().max_ + Vec3s(min_dist, min_dist, min_dist);
339  status = 0;
340  } else // need more loop
341  {
342  if (dummy_vector.isApprox(
343  obj->getAABB().max_,
345  dummy_vector = dummy_vector + delta;
346  else
347  dummy_vector = dummy_vector * 2 - obj->getAABB().max_;
348  }
349  }
350 
351  // yes, following is wrong, will result in too large distance.
352  // if(pos_end1 != objs_x.end()) pos_start1 = pos_end1;
353  // if(pos_end2 != objs_y.end()) pos_start2 = pos_end2;
354  // if(pos_end3 != objs_z.end()) pos_start3 = pos_end3;
355  } else if (status == 0)
356  break;
357  }
358 
359  return false;
360 }
361 
362 //==============================================================================
364  const std::vector<CollisionObject*>& objs_x,
365  const std::vector<CollisionObject*>& objs_y,
366  const std::vector<CollisionObject*>& objs_z,
367  typename std::vector<CollisionObject*>::const_iterator& it_beg,
368  typename std::vector<CollisionObject*>::const_iterator& it_end) {
370  CoalScalar delta_x = (objs_x[objs_x.size() - 1])->getAABB().min_[0] -
371  (objs_x[0])->getAABB().min_[0];
372  CoalScalar delta_y = (objs_x[objs_y.size() - 1])->getAABB().min_[1] -
373  (objs_y[0])->getAABB().min_[1];
374  CoalScalar delta_z = (objs_z[objs_z.size() - 1])->getAABB().min_[2] -
375  (objs_z[0])->getAABB().min_[2];
376 
377  int axis = 0;
378  if (delta_y > delta_x && delta_y > delta_z)
379  axis = 1;
380  else if (delta_z > delta_y && delta_z > delta_x)
381  axis = 2;
382 
383  switch (axis) {
384  case 0:
385  it_beg = objs_x.begin();
386  it_end = objs_x.end();
387  break;
388  case 1:
389  it_beg = objs_y.begin();
390  it_end = objs_y.end();
391  break;
392  case 2:
393  it_beg = objs_z.begin();
394  it_end = objs_z.end();
395  break;
396  }
397 
398  return axis;
399 }
400 
401 //==============================================================================
403  callback->init();
404  if (size() == 0) return;
405 
406  typename std::vector<CollisionObject*>::const_iterator pos, run_pos, pos_end;
407  int axis = selectOptimalAxis(objs_x, objs_y, objs_z, pos, pos_end);
408  int axis2 = (axis + 1 > 2) ? 0 : (axis + 1);
409  int axis3 = (axis2 + 1 > 2) ? 0 : (axis2 + 1);
410 
411  run_pos = pos;
412 
413  while ((run_pos < pos_end) && (pos < pos_end)) {
414  CollisionObject* obj = *(pos++);
415 
416  while (1) {
417  if ((*run_pos)->getAABB().min_[axis] < obj->getAABB().min_[axis]) {
418  run_pos++;
419  if (run_pos == pos_end) break;
420  continue;
421  } else {
422  run_pos++;
423  break;
424  }
425  }
426 
427  if (run_pos < pos_end) {
428  typename std::vector<CollisionObject*>::const_iterator run_pos2 = run_pos;
429 
430  while ((*run_pos2)->getAABB().min_[axis] <= obj->getAABB().max_[axis]) {
431  CollisionObject* obj2 = *run_pos2;
432  run_pos2++;
433 
434  if ((obj->getAABB().max_[axis2] >= obj2->getAABB().min_[axis2]) &&
435  (obj2->getAABB().max_[axis2] >= obj->getAABB().min_[axis2])) {
436  if ((obj->getAABB().max_[axis3] >= obj2->getAABB().min_[axis3]) &&
437  (obj2->getAABB().max_[axis3] >= obj->getAABB().min_[axis3])) {
438  if ((*callback)(obj, obj2)) return;
439  }
440  }
441 
442  if (run_pos2 == pos_end) break;
443  }
444  }
445  }
446 }
447 
448 //==============================================================================
450  callback->init();
451  if (size() == 0) return;
452 
453  typename std::vector<CollisionObject*>::const_iterator it, it_end;
454  selectOptimalAxis(objs_x, objs_y, objs_z, it, it_end);
455 
456  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
457  for (; it != it_end; ++it) {
458  if (distance_(*it, callback, min_dist)) return;
459  }
460 }
461 
462 //==============================================================================
465  callback->init();
466  SSaPCollisionManager* other_manager =
467  static_cast<SSaPCollisionManager*>(other_manager_);
468 
469  if ((size() == 0) || (other_manager->size() == 0)) return;
470 
471  if (this == other_manager) {
472  collide(callback);
473  return;
474  }
475 
476  typename std::vector<CollisionObject*>::const_iterator it, end;
477  if (this->size() < other_manager->size()) {
478  for (it = objs_x.begin(), end = objs_x.end(); it != end; ++it)
479  if (other_manager->collide_(*it, callback)) return;
480  } else {
481  for (it = other_manager->objs_x.begin(), end = other_manager->objs_x.end();
482  it != end; ++it)
483  if (collide_(*it, callback)) return;
484  }
485 }
486 
487 //==============================================================================
490  callback->init();
491  SSaPCollisionManager* other_manager =
492  static_cast<SSaPCollisionManager*>(other_manager_);
493 
494  if ((size() == 0) || (other_manager->size() == 0)) return;
495 
496  if (this == other_manager) {
498  return;
499  }
500 
501  CoalScalar min_dist = (std::numeric_limits<CoalScalar>::max)();
502  typename std::vector<CollisionObject*>::const_iterator it, end;
503  if (this->size() < other_manager->size()) {
504  for (it = objs_x.begin(), end = objs_x.end(); it != end; ++it)
505  if (other_manager->distance_(*it, callback, min_dist)) return;
506  } else {
507  for (it = other_manager->objs_x.begin(), end = other_manager->objs_x.end();
508  it != end; ++it)
509  if (distance_(*it, callback, min_dist)) return;
510  }
511 }
512 
513 //==============================================================================
514 bool SSaPCollisionManager::empty() const { return objs_x.empty(); }
515 
516 //==============================================================================
517 size_t SSaPCollisionManager::size() const { return objs_x.size(); }
518 
519 } // namespace coal
coal::SSaPCollisionManager::update
virtual void update()
update the condition of manager
Definition: broadphase_SSaP.cpp:144
coal::SSaPCollisionManager::distance
void distance(CollisionObject *obj, DistanceCallBackBase *callback) const
perform distance computation between one object and all the objects belonging to the manager
Definition: broadphase_SSaP.cpp:254
coal::SSaPCollisionManager::setup_
bool setup_
tag about whether the environment is maintained suitably (i.e., the objs_x, objs_y,...
Definition: coal/broadphase/broadphase_SSaP.h:141
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
geometric_shapes.d1
float d1
Definition: scripts/geometric_shapes.py:31
collision_manager.callback
callback
Definition: collision_manager.py:27
coal::DummyCollisionObject::DummyCollisionObject
DummyCollisionObject(const AABB &aabb_)
Definition: broadphase_SSaP.cpp:69
coal::SSaPCollisionManager::unregisterObject
void unregisterObject(CollisionObject *obj)
add one object to the manager
Definition: broadphase_SSaP.cpp:78
coal::SSaPCollisionManager::size
size_t size() const
the number of objects managed by the manager
Definition: broadphase_SSaP.cpp:517
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
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
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::SortByZLow::operator()
bool operator()(const CollisionObject *a, const CollisionObject *b) const
Definition: broadphase_SSaP.cpp:60
coal::SortByZLow
Functor sorting objects according to the AABB lower z bound.
Definition: broadphase_SSaP.cpp:59
coal::SSaPCollisionManager::registerObject
void registerObject(CollisionObject *obj)
remove one object from the manager
Definition: broadphase_SSaP.cpp:126
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
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
a
list a
coal::SSaPCollisionManager
Simple SAP collision manager.
Definition: coal/broadphase/broadphase_SSaP.h:47
coal::SSaPCollisionManager::objs_y
std::vector< CollisionObject * > objs_y
Objects sorted according to lower y value.
Definition: coal/broadphase/broadphase_SSaP.h:134
coal::AABB::max_
Vec3s max_
The max point in the AABB.
Definition: coal/BV/AABB.h:60
coal::SSaPCollisionManager::SSaPCollisionManager
SSaPCollisionManager()
Definition: broadphase_SSaP.cpp:121
coal::DummyCollisionObject
Dummy collision object with a point AABB.
Definition: broadphase_SSaP.cpp:67
coal::SortByXLow::operator()
bool operator()(const CollisionObject *a, const CollisionObject *b) const
Definition: broadphase_SSaP.cpp:44
coal::SSaPCollisionManager::empty
bool empty() const
whether the manager is empty
Definition: broadphase_SSaP.cpp:514
coal::SSaPCollisionManager::collide
void collide(CollisionObject *obj, CollisionCallBackBase *callback) const
perform collision test between one object and all the objects belonging to the manager
Definition: broadphase_SSaP.cpp:201
coal::SortByYLow
Functor sorting objects according to the AABB lower y bound.
Definition: broadphase_SSaP.cpp:51
coal::SortByXLow
Functor sorting objects according to the AABB lower x bound.
Definition: broadphase_SSaP.cpp:43
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
coal::SSaPCollisionManager::clear
void clear()
clear the manager
Definition: broadphase_SSaP.cpp:150
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
octree.pos
pos
Definition: octree.py:7
axis
axis
coal::CollisionObject::getAABB
const AABB & getAABB() const
get the AABB in world space
Definition: coal/collision_object.h:252
coal::SSaPCollisionManager::checkColl
bool checkColl(typename std::vector< CollisionObject * >::const_iterator pos_start, typename std::vector< CollisionObject * >::const_iterator pos_end, CollisionObject *obj, CollisionCallBackBase *callback) const
check collision between one object and a list of objects, return value is whether stop is possible
Definition: broadphase_SSaP.cpp:165
coal::AABB::min_
Vec3s min_
The min point in the AABB.
Definition: coal/BV/AABB.h:58
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
epsilon
static CoalScalar epsilon
Definition: simple.cpp:12
coal::DummyCollisionObject::computeLocalAABB
void computeLocalAABB()
Definition: broadphase_SSaP.cpp:74
coal::SSaPCollisionManager::distance_
bool distance_(CollisionObject *obj, DistanceCallBackBase *callback, CoalScalar &min_dist) const
Definition: broadphase_SSaP.cpp:264
coal::SSaPCollisionManager::collide_
bool collide_(CollisionObject *obj, CollisionCallBackBase *callback) const
Definition: broadphase_SSaP.cpp:210
coal::SortByYLow::operator()
bool operator()(const CollisionObject *a, const CollisionObject *b) const
Definition: broadphase_SSaP.cpp:52
coal::SSaPCollisionManager::setup
void setup()
initialize the manager, related with the specific type of manager
Definition: broadphase_SSaP.cpp:134
coal::SSaPCollisionManager::objs_z
std::vector< CollisionObject * > objs_z
Objects sorted according to lower z value.
Definition: coal/broadphase/broadphase_SSaP.h:137
coal::SSaPCollisionManager::objs_x
std::vector< CollisionObject * > objs_x
Objects sorted according to lower x value.
Definition: coal/broadphase/broadphase_SSaP.h:131
broadphase_SSaP.h
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::SSaPCollisionManager::selectOptimalAxis
static int selectOptimalAxis(const std::vector< CollisionObject * > &objs_x, const std::vector< CollisionObject * > &objs_y, const std::vector< CollisionObject * > &objs_z, typename std::vector< CollisionObject * >::const_iterator &it_beg, typename std::vector< CollisionObject * >::const_iterator &it_end)
Definition: broadphase_SSaP.cpp:363
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::SSaPCollisionManager::checkDis
bool checkDis(typename std::vector< CollisionObject * >::const_iterator pos_start, typename std::vector< CollisionObject * >::const_iterator pos_end, CollisionObject *obj, DistanceCallBackBase *callback, CoalScalar &min_dist) const
check distance between one object and a list of objects, return value is whether stop is possible
Definition: broadphase_SSaP.cpp:182


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