continuous_collision-inl.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013-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 FCL_CONTINUOUS_COLLISION_INL_H
39 #define FCL_CONTINUOUS_COLLISION_INL_H
40 
42 
43 #include "fcl/common/unused.h"
44 
49 
53 
54 namespace fcl
55 {
56 
57 //==============================================================================
58 extern template
59 double continuousCollide(
60  const CollisionGeometry<double>* o1,
61  const MotionBase<double>* motion1,
62  const CollisionGeometry<double>* o2,
63  const MotionBase<double>* motion2,
64  const ContinuousCollisionRequest<double>& request,
65  ContinuousCollisionResult<double>& result);
66 
67 //==============================================================================
68 extern template
69 double continuousCollide(
70  const CollisionGeometry<double>* o1,
71  const Transform3<double>& tf1_beg,
72  const Transform3<double>& tf1_end,
73  const CollisionGeometry<double>* o2,
74  const Transform3<double>& tf2_beg,
75  const Transform3<double>& tf2_end,
76  const ContinuousCollisionRequest<double>& request,
77  ContinuousCollisionResult<double>& result);
78 
79 //==============================================================================
80 extern template
81 double continuousCollide(
82  const CollisionObject<double>* o1,
83  const Transform3<double>& tf1_end,
84  const CollisionObject<double>* o2,
85  const Transform3<double>& tf2_end,
86  const ContinuousCollisionRequest<double>& request,
87  ContinuousCollisionResult<double>& result);
88 
89 //==============================================================================
90 extern template
91 double collide(
94  const ContinuousCollisionRequest<double>& request,
95  ContinuousCollisionResult<double>& result);
96 
97 //==============================================================================
98 template<typename GJKSolver>
99 detail::ConservativeAdvancementFunctionMatrix<GJKSolver>&
101 {
103  return table;
104 }
105 
106 //==============================================================================
107 template <typename S>
108 FCL_EXPORT
110  const Transform3<S>& tf_beg,
111  const Transform3<S>& tf_end,
112  CCDMotionType motion_type)
113 {
114  switch(motion_type)
115  {
116  case CCDM_TRANS:
117  return MotionBasePtr<S>(new TranslationMotion<S>(tf_beg, tf_end));
118  break;
119  case CCDM_LINEAR:
120  return MotionBasePtr<S>(new InterpMotion<S>(tf_beg, tf_end));
121  break;
122  case CCDM_SCREW:
123  return MotionBasePtr<S>(new ScrewMotion<S>(tf_beg, tf_end));
124  break;
125  case CCDM_SPLINE:
126  return MotionBasePtr<S>(new SplineMotion<S>(tf_beg, tf_end));
127  break;
128  default:
129  return MotionBasePtr<S>();
130  }
131 }
132 
133 //==============================================================================
134 template <typename S>
135 FCL_EXPORT
137  const CollisionGeometry<S>* o1,
138  const MotionBase<S>* motion1,
139  const CollisionGeometry<S>* o2,
140  const MotionBase<S>* motion2,
141  const ContinuousCollisionRequest<S>& request,
143 {
144  std::size_t n_iter = std::min(request.num_max_iterations, (std::size_t)ceil(1 / request.toc_err));
145  Transform3<S> cur_tf1, cur_tf2;
146  for(std::size_t i = 0; i < n_iter; ++i)
147  {
148  S t = i / (S) (n_iter - 1);
149  motion1->integrate(t);
150  motion2->integrate(t);
151 
152  motion1->getCurrentTransform(cur_tf1);
153  motion2->getCurrentTransform(cur_tf2);
154 
155  CollisionRequest<S> c_request;
156  CollisionResult<S> c_result;
157 
158  if(collide(o1, cur_tf1, o2, cur_tf2, c_request, c_result))
159  {
160  result.is_collide = true;
161  result.time_of_contact = t;
162  result.contact_tf1 = cur_tf1;
163  result.contact_tf2 = cur_tf2;
164  return t;
165  }
166  }
167 
168  result.is_collide = false;
169  result.time_of_contact = S(1);
170  return result.time_of_contact;
171 }
172 
173 namespace detail
174 {
175 
176 //==============================================================================
177 template<typename BV>
178 FCL_EXPORT
181  const TranslationMotion<typename BV::S>* motion1,
183  const TranslationMotion<typename BV::S>* motion2,
186 {
187  FCL_UNUSED(request);
188 
189  using S = typename BV::S;
190 
191  const BVHModel<BV>* o1__ = static_cast<const BVHModel<BV>*>(o1_);
192  const BVHModel<BV>* o2__ = static_cast<const BVHModel<BV>*>(o2_);
193 
194  // ugly, but lets do it now.
195  BVHModel<BV>* o1 = const_cast<BVHModel<BV>*>(o1__);
196  BVHModel<BV>* o2 = const_cast<BVHModel<BV>*>(o2__);
197  std::vector<Vector3<S>> new_v1(o1->num_vertices);
198  std::vector<Vector3<S>> new_v2(o2->num_vertices);
199 
200  for(std::size_t i = 0; i < new_v1.size(); ++i)
201  new_v1[i] = o1->vertices[i] + motion1->getVelocity();
202  for(std::size_t i = 0; i < new_v2.size(); ++i)
203  new_v2[i] = o2->vertices[i] + motion2->getVelocity();
204 
205  o1->beginUpdateModel();
206  o1->updateSubModel(new_v1);
207  o1->endUpdateModel(true, true);
208 
209  o2->beginUpdateModel();
210  o2->updateSubModel(new_v2);
211  o2->endUpdateModel(true, true);
212 
214  CollisionRequest<S> c_request;
215 
216  motion1->integrate(0);
217  motion2->integrate(0);
218  Transform3<S> tf1;
219  Transform3<S> tf2;
220  motion1->getCurrentTransform(tf1);
221  motion2->getCurrentTransform(tf2);
222  if(!initialize<BV>(node, *o1, tf1, *o2, tf2, c_request))
223  return -1.0;
224 
225  collide(&node);
226 
227  result.is_collide = (node.pairs.size() > 0);
228  result.time_of_contact = node.time_of_contact;
229 
230  if(result.is_collide)
231  {
232  motion1->integrate(node.time_of_contact);
233  motion2->integrate(node.time_of_contact);
234  motion1->getCurrentTransform(tf1);
235  motion2->getCurrentTransform(tf2);
236  result.contact_tf1 = tf1;
237  result.contact_tf2 = tf2;
238  }
239 
240  return result.time_of_contact;
241 }
242 
243 } // namespace detail
244 
245 //==============================================================================
246 template <typename S>
247 FCL_EXPORT
249  const CollisionGeometry<S>* o1,
250  const TranslationMotion<S>* motion1,
251  const CollisionGeometry<S>* o2,
252  const TranslationMotion<S>* motion2,
253  const ContinuousCollisionRequest<S>& request,
255 {
256  switch(o1->getNodeType())
257  {
258  case BV_AABB:
259  if(o2->getNodeType() == BV_AABB)
260  return detail::continuousCollideBVHPolynomial<AABB<S>>(o1, motion1, o2, motion2, request, result);
261  break;
262  case BV_OBB:
263  if(o2->getNodeType() == BV_OBB)
264  return detail::continuousCollideBVHPolynomial<OBB<S>>(o1, motion1, o2, motion2, request, result);
265  break;
266  case BV_RSS:
267  if(o2->getNodeType() == BV_RSS)
268  return detail::continuousCollideBVHPolynomial<RSS<S>>(o1, motion1, o2, motion2, request, result);
269  break;
270  case BV_kIOS:
271  if(o2->getNodeType() == BV_kIOS)
272  return detail::continuousCollideBVHPolynomial<kIOS<S>>(o1, motion1, o2, motion2, request, result);
273  break;
274  case BV_OBBRSS:
275  if(o2->getNodeType() == BV_OBBRSS)
276  return detail::continuousCollideBVHPolynomial<OBBRSS<S>>(o1, motion1, o2, motion2, request, result);
277  break;
278  case BV_KDOP16:
279  if(o2->getNodeType() == BV_KDOP16)
280  return detail::continuousCollideBVHPolynomial<KDOP<S, 16> >(o1, motion1, o2, motion2, request, result);
281  break;
282  case BV_KDOP18:
283  if(o2->getNodeType() == BV_KDOP18)
284  return detail::continuousCollideBVHPolynomial<KDOP<S, 18> >(o1, motion1, o2, motion2, request, result);
285  break;
286  case BV_KDOP24:
287  if(o2->getNodeType() == BV_KDOP24)
288  return detail::continuousCollideBVHPolynomial<KDOP<S, 24> >(o1, motion1, o2, motion2, request, result);
289  break;
290  default:
291  ;
292  }
293 
294  std::cerr << "Warning: BV type not supported by polynomial solver CCD\n";
295 
296  return -1;
297 }
298 
299 namespace detail
300 {
301 
302 //==============================================================================
303 template<typename NarrowPhaseSolver>
304 FCL_EXPORT
305 typename NarrowPhaseSolver::S continuousCollideConservativeAdvancement(
310  const NarrowPhaseSolver* nsolver_,
313 {
314  using S = typename NarrowPhaseSolver::S;
315 
316  const NarrowPhaseSolver* nsolver = nsolver_;
317  if(!nsolver_)
318  nsolver = new NarrowPhaseSolver();
319 
320  const auto& looktable = getConservativeAdvancementFunctionLookTable<NarrowPhaseSolver>();
321 
322  NODE_TYPE node_type1 = o1->getNodeType();
323  NODE_TYPE node_type2 = o2->getNodeType();
324 
325  S res = -1;
326 
327  if(!looktable.conservative_advancement_matrix[node_type1][node_type2])
328  {
329  std::cerr << "Warning: collision function between node type " << node_type1 << " and node type " << node_type2 << " is not supported\n";
330  }
331  else
332  {
333  res = looktable.conservative_advancement_matrix[node_type1][node_type2](o1, motion1, o2, motion2, nsolver, request, result);
334  }
335 
336  if(!nsolver_)
337  delete nsolver;
338 
339  if(result.is_collide)
340  {
341  motion1->integrate(result.time_of_contact);
342  motion2->integrate(result.time_of_contact);
343 
344  Transform3<S> tf1;
345  Transform3<S> tf2;
346  motion1->getCurrentTransform(tf1);
347  motion2->getCurrentTransform(tf2);
348  result.contact_tf1 = tf1;
349  result.contact_tf2 = tf2;
350  }
351 
352  return res;
353 }
354 
355 } // namespace detail
356 
357 template <typename S>
358 FCL_EXPORT
360  const CollisionGeometry<S>* o1,
361  const MotionBase<S>* motion1,
362  const CollisionGeometry<S>* o2,
363  const MotionBase<S>* motion2,
364  const ContinuousCollisionRequest<S>& request,
366 {
367  switch(request.gjk_solver_type)
368  {
369  case GST_LIBCCD:
370  {
372  return detail::continuousCollideConservativeAdvancement(o1, motion1, o2, motion2, &solver, request, result);
373  }
374  case GST_INDEP:
375  {
377  return detail::continuousCollideConservativeAdvancement(o1, motion1, o2, motion2, &solver, request, result);
378  }
379  default:
380  return -1;
381  }
382 }
383 
384 //==============================================================================
385 template <typename S>
386 FCL_EXPORT
388  const CollisionGeometry<S>* o1,
389  const MotionBase<S>* motion1,
390  const CollisionGeometry<S>* o2,
391  const MotionBase<S>* motion2,
392  const ContinuousCollisionRequest<S>& request,
394 {
395  switch(request.ccd_solver_type)
396  {
397  case CCDC_NAIVE:
398  return continuousCollideNaive(o1, motion1,
399  o2, motion2,
400  request,
401  result);
402  break;
404  return continuousCollideConservativeAdvancement(o1, motion1,
405  o2, motion2,
406  request,
407  result);
408  break;
409  case CCDC_RAY_SHOOTING:
410  if(o1->getObjectType() == OT_GEOM && o2->getObjectType() == OT_GEOM && request.ccd_motion_type == CCDM_TRANS)
411  {
412 
413  }
414  else
415  std::cerr << "Warning! Invalid continuous collision setting\n";
416  break;
418  if(o1->getObjectType() == OT_BVH && o2->getObjectType() == OT_BVH && request.ccd_motion_type == CCDM_TRANS)
419  {
420  return continuousCollideBVHPolynomial(o1, (const TranslationMotion<S>*)motion1,
421  o2, (const TranslationMotion<S>*)motion2,
422  request, result);
423  }
424  else
425  std::cerr << "Warning! Invalid continuous collision checking\n";
426  break;
427  default:
428  std::cerr << "Warning! Invalid continuous collision setting\n";
429  }
430 
431  return -1;
432 }
433 
434 //==============================================================================
435 template <typename S>
436 FCL_EXPORT
438  const CollisionGeometry<S>* o1,
439  const Transform3<S>& tf1_beg,
440  const Transform3<S>& tf1_end,
441  const CollisionGeometry<S>* o2,
442  const Transform3<S>& tf2_beg,
443  const Transform3<S>& tf2_end,
444  const ContinuousCollisionRequest<S>& request,
446 {
447  MotionBasePtr<S> motion1 = getMotionBase(tf1_beg, tf1_end, request.ccd_motion_type);
448  MotionBasePtr<S> motion2 = getMotionBase(tf2_beg, tf2_end, request.ccd_motion_type);
449 
450  return continuousCollide(o1, motion1.get(), o2, motion2.get(), request, result);
451 }
452 
453 //==============================================================================
454 template <typename S>
455 FCL_EXPORT
457  const CollisionObject<S>* o1,
458  const Transform3<S>& tf1_end,
459  const CollisionObject<S>* o2,
460  const Transform3<S>& tf2_end,
461  const ContinuousCollisionRequest<S>& request,
463 {
464  return continuousCollide(o1->collisionGeometry().get(), o1->getTransform(), tf1_end,
465  o2->collisionGeometry().get(), o2->getTransform(), tf2_end,
466  request, result);
467 }
468 
469 //==============================================================================
470 template <typename S>
471 FCL_EXPORT
475  const ContinuousCollisionRequest<S>& request,
477 {
478  return continuousCollide(o1->collisionGeometry().get(), o1->getMotion(),
479  o2->collisionGeometry().get(), o2->getMotion(),
480  request, result);
481 }
482 
483 } // namespace fcl
484 
485 #endif
std::size_t num_max_iterations
maximum num of iterations
const Transform3< S > & getTransform() const
get object&#39;s transform
FCL_EXPORT S continuousCollideNaive(const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result)
int updateSubModel(const std::vector< Vector3< S >> &ps)
Update a set of points in the old BVH model.
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, halfspace, triangle), and octree
virtual NODE_TYPE getNodeType() const
get the node type
Main namespace.
virtual OBJECT_TYPE getObjectType() const
get the type of the object
collision result
MotionBase< S > * getMotion() const
get motion from the object instance
std::shared_ptr< MotionBase< S > > MotionBasePtr
Definition: motion_base.h:97
template class FCL_EXPORT CollisionGeometry< double >
template double continuousCollide(const CollisionGeometry< double > *o1, const MotionBase< double > *motion1, const CollisionGeometry< double > *o2, const MotionBase< double > *motion2, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular veloc...
S time_of_contact
time of contact in [0, 1]
virtual bool integrate(S dt) const =0
Integrate the motion from 0 to dt.
FCL_EXPORT MotionBasePtr< S > getMotionBase(const Transform3< S > &tf_beg, const Transform3< S > &tf_end, CCDMotionType motion_type)
the object for continuous collision or distance computation, contains the geometry and the motion inf...
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
int num_vertices
Number of points.
Definition: BVH_model.h:174
The geometry for the object for collision or distance computation.
template class FCL_EXPORT MotionBase< double >
void getCurrentTransform(Transform3< S > &tf_) const override
collision and distance solver based on libccd library.
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
KDOP class describes the KDOP collision structures. K is set as the template parameter, which should be 16, 18, or 24 The KDOP structure is defined by some pairs of parallel planes defined by some axes. For K = 16, the planes are 6 AABB planes and 10 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 8 (0,-1,0) and (0,1,0) -> indices 1 and 9 (0,0,-1) and (0,0,1) -> indices 2 and 10 (-1,-1,0) and (1,1,0) -> indices 3 and 11 (-1,0,-1) and (1,0,1) -> indices 4 and 12 (0,-1,-1) and (0,1,1) -> indices 5 and 13 (-1,1,0) and (1,-1,0) -> indices 6 and 14 (-1,0,1) and (1,0,-1) -> indices 7 and 15 For K = 18, the planes are 6 AABB planes and 12 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 9 (0,-1,0) and (0,1,0) -> indices 1 and 10 (0,0,-1) and (0,0,1) -> indices 2 and 11 (-1,-1,0) and (1,1,0) -> indices 3 and 12 (-1,0,-1) and (1,0,1) -> indices 4 and 13 (0,-1,-1) and (0,1,1) -> indices 5 and 14 (-1,1,0) and (1,-1,0) -> indices 6 and 15 (-1,0,1) and (1,0,-1) -> indices 7 and 16 (0,-1,1) and (0,1,-1) -> indices 8 and 17 For K = 18, the planes are 6 AABB planes and 18 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 12 (0,-1,0) and (0,1,0) -> indices 1 and 13 (0,0,-1) and (0,0,1) -> indices 2 and 14 (-1,-1,0) and (1,1,0) -> indices 3 and 15 (-1,0,-1) and (1,0,1) -> indices 4 and 16 (0,-1,-1) and (0,1,1) -> indices 5 and 17 (-1,1,0) and (1,-1,0) -> indices 6 and 18 (-1,0,1) and (1,0,-1) -> indices 7 and 19 (0,-1,1) and (0,1,-1) -> indices 8 and 20 (-1, -1, 1) and (1, 1, -1) –> indices 9 and 21 (-1, 1, -1) and (1, -1, 1) –> indices 10 and 22 (1, -1, -1) and (-1, 1, 1) –> indices 11 and 23.
Definition: kDOP.h:84
Parameters for performing collision request.
template class FCL_EXPORT ContinuousCollisionObject< double >
GJKSolverType gjk_solver_type
gjk solver type
template void collide(CollisionTraversalNodeBase< double > *node, BVHFrontList *front_list)
bool integrate(S dt) const override
Integrate the motion from 0 to dt.
Traversal node for continuous collision between meshes.
CCDMotionType ccd_motion_type
ccd motion type
FCL_EXPORT BV::S continuousCollideBVHPolynomial(const CollisionGeometry< typename BV::S > *o1_, const TranslationMotion< typename BV::S > *motion1, const CollisionGeometry< typename BV::S > *o2_, const TranslationMotion< typename BV::S > *motion2, const ContinuousCollisionRequest< typename BV::S > &request, ContinuousCollisionResult< typename BV::S > &result)
S toc_err
error in first contact time
FCL_EXPORT S continuousCollideBVHPolynomial(const CollisionGeometry< S > *o1, const TranslationMotion< S > *motion1, const CollisionGeometry< S > *o2, const TranslationMotion< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result)
#define FCL_UNUSED(x)
Definition: unused.h:39
FCL_EXPORT NarrowPhaseSolver::S continuousCollideConservativeAdvancement(const CollisionGeometry< typename NarrowPhaseSolver::S > *o1, const MotionBase< typename NarrowPhaseSolver::S > *motion1, const CollisionGeometry< typename NarrowPhaseSolver::S > *o2, const MotionBase< typename NarrowPhaseSolver::S > *motion2, const NarrowPhaseSolver *nsolver_, const ContinuousCollisionRequest< typename NarrowPhaseSolver::S > &request, ContinuousCollisionResult< typename NarrowPhaseSolver::S > &result)
static T min(T x, T y)
Definition: svm.cpp:49
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
detail::ConservativeAdvancementFunctionMatrix< GJKSolver > & getConservativeAdvancementFunctionLookTable()
the object for collision or distance computation, contains the geometry and the transform information...
template class FCL_EXPORT CollisionObject< double >
int endUpdateModel(bool refit=true, bool bottomup=true)
End BVH model update, will also refit or rebuild the bounding volume hierarchy.
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
void getCurrentTransform(Matrix3< S > &R, Vector3< S > &T) const
Get the rotation and translation in current step.
Vector3< S > getVelocity() const
CCDSolverType ccd_solver_type
ccd solver type
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
int beginUpdateModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...


fcl_catkin
Author(s):
autogenerated on Thu Mar 23 2023 03:00:17