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
fcl::SplineMotion
Definition: bv_motion_bound_visitor.h:48
fcl::CollisionGeometry< double >
template class FCL_EXPORT CollisionGeometry< double >
fcl::CCDM_TRANS
@ CCDM_TRANS
Definition: continuous_collision_request.h:48
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
screw_motion.h
fcl::detail::MeshContinuousCollisionTraversalNode
Traversal node for continuous collision between meshes.
Definition: mesh_continuous_collision_traversal_node.h:69
fcl::kIOS< S >
fcl::ContinuousCollisionRequest::toc_err
S toc_err
error in first contact time
Definition: continuous_collision_request.h:58
fcl::detail::ConservativeAdvancementFunctionMatrix
Definition: conservative_advancement_func_matrix.h:52
fcl::BVHModel::vertices
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
interp_motion.h
fcl::ContinuousCollisionResult::time_of_contact
S time_of_contact
time of contact in [0, 1]
Definition: continuous_collision_result.h:54
fcl::detail::MeshContinuousCollisionTraversalNode::pairs
std::vector< BVHContinuousCollisionPair< S > > pairs
Definition: mesh_continuous_collision_traversal_node.h:96
translation_motion.h
fcl::detail::GJKSolver_libccd
collision and distance solver based on libccd library.
Definition: gjk_solver_libccd.h:54
fcl::continuousCollideNaive
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)
Definition: continuous_collision-inl.h:136
fcl::MotionBasePtr
std::shared_ptr< MotionBase< S > > MotionBasePtr
Definition: motion_base.h:97
fcl::ScrewMotion
Definition: bv_motion_bound_visitor.h:51
fcl::ContinuousCollisionResult::contact_tf2
Transform3< S > contact_tf2
Definition: continuous_collision_result.h:58
fcl::ContinuousCollisionRequest
Definition: continuous_collision_request.h:52
fcl::CCDC_NAIVE
@ CCDC_NAIVE
Definition: continuous_collision_request.h:49
unused.h
fcl::CCDC_CONSERVATIVE_ADVANCEMENT
@ CCDC_CONSERVATIVE_ADVANCEMENT
Definition: continuous_collision_request.h:49
fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_geometry.h:53
fcl::ContinuousCollisionRequest::ccd_solver_type
CCDSolverType ccd_solver_type
ccd solver type
Definition: continuous_collision_request.h:67
fcl::continuousCollide
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)
fcl::ContinuousCollisionRequest::gjk_solver_type
GJKSolverType gjk_solver_type
gjk solver type
Definition: continuous_collision_request.h:64
fcl::TranslationMotion
Definition: bv_motion_bound_visitor.h:57
fcl::ContinuousCollisionObject
the object for continuous collision or distance computation, contains the geometry and the motion inf...
Definition: continuous_collision_object.h:51
fcl::MotionBase::integrate
virtual bool integrate(S dt) const =0
Integrate the motion from 0 to dt.
fcl::CollisionResult
collision result
Definition: collision_request.h:48
fcl::RSS< S >
fcl::CCDM_LINEAR
@ CCDM_LINEAR
Definition: continuous_collision_request.h:48
fcl::TranslationMotion::getVelocity
Vector3< S > getVelocity() const
Definition: translation_motion-inl.h:127
fcl::CCDMotionType
CCDMotionType
Definition: continuous_collision_request.h:48
spline_motion.h
fcl::getMotionBase
FCL_EXPORT MotionBasePtr< S > getMotionBase(const Transform3< S > &tf_beg, const Transform3< S > &tf_end, CCDMotionType motion_type)
Definition: continuous_collision-inl.h:109
fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_geometry.h:58
fcl::OBB< S >
fcl::BVHModel::beginUpdateModel
int beginUpdateModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
Definition: BVH_model-inl.h:624
fcl::ContinuousCollisionResult::contact_tf1
Transform3< S > contact_tf1
Definition: continuous_collision_result.h:56
fcl::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: collision_geometry-inl.h:79
fcl::MotionBase< double >
template class FCL_EXPORT MotionBase< double >
fcl::ContinuousCollisionObject< double >
template class FCL_EXPORT ContinuousCollisionObject< double >
fcl::MotionBase
Definition: bv_motion_bound_visitor.h:45
fcl::ContinuousCollisionResult::is_collide
bool is_collide
collision or not
Definition: continuous_collision_result.h:51
fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_geometry.h:53
fcl::GST_LIBCCD
@ GST_LIBCCD
Definition: gjk_solver_type.h:45
fcl::continuousCollideConservativeAdvancement
FCL_EXPORT S continuousCollideConservativeAdvancement(const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result)
Definition: continuous_collision-inl.h:359
fcl::detail::GJKSolver_indep
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: gjk_solver_indep.h:54
fcl::detail::MeshContinuousCollisionTraversalNode::time_of_contact
S time_of_contact
Definition: mesh_continuous_collision_traversal_node.h:98
fcl::BV_OBB
@ BV_OBB
Definition: collision_geometry.h:53
fcl::CollisionRequest
Parameters for performing collision request.
Definition: collision_request.h:52
fcl::CCDC_RAY_SHOOTING
@ CCDC_RAY_SHOOTING
Definition: continuous_collision_request.h:49
fcl::detail::continuousCollideBVHPolynomial
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)
Definition: continuous_collision-inl.h:179
fcl::ContinuousCollisionRequest::num_max_iterations
std::size_t num_max_iterations
maximum num of iterations
Definition: continuous_collision_request.h:55
fcl::TranslationMotion::getCurrentTransform
void getCurrentTransform(Transform3< S > &tf_) const override
Definition: translation_motion-inl.h:109
fcl::BV_KDOP16
@ BV_KDOP16
Definition: collision_geometry.h:53
fcl::CollisionObject::collisionGeometry
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
Definition: collision_object-inl.h:243
fcl::ContinuousCollisionObject::collisionGeometry
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
Definition: continuous_collision_object-inl.h:170
fcl::ContinuousCollisionRequest::ccd_motion_type
CCDMotionType ccd_motion_type
ccd motion type
Definition: continuous_collision_request.h:61
fcl::ContinuousCollisionObject::getMotion
MotionBase< S > * getMotion() const
get motion from the object instance
Definition: continuous_collision_object-inl.h:154
fcl::collide
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
fcl::KDOP
KDOP class describes the KDOP collision structures. K is set as the template parameter,...
Definition: kDOP.h:84
continuous_collision.h
fcl::OBBRSS< S >
fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
fcl::CollisionObject::getTransform
const Transform3< S > & getTransform() const
get object's transform
Definition: collision_object-inl.h:170
collision_result.h
fcl::BVHModel::endUpdateModel
int endUpdateModel(bool refit=true, bool bottomup=true)
End BVH model update, will also refit or rebuild the bounding volume hierarchy.
Definition: BVH_model-inl.h:703
fcl::InterpMotion
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular veloc...
Definition: bv_motion_bound_visitor.h:54
fcl::TranslationMotion::integrate
bool integrate(S dt) const override
Definition: translation_motion-inl.h:80
fcl::detail::continuousCollideConservativeAdvancement
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)
Definition: continuous_collision-inl.h:305
fcl::BVHModel::num_vertices
int num_vertices
Number of points.
Definition: BVH_model.h:174
fcl::ContinuousCollisionResult
continuous collision result
Definition: continuous_collision_result.h:48
FCL_UNUSED
#define FCL_UNUSED(x)
Definition: unused.h:39
fcl::BV_kIOS
@ BV_kIOS
Definition: collision_geometry.h:53
fcl::getConservativeAdvancementFunctionLookTable
detail::ConservativeAdvancementFunctionMatrix< GJKSolver > & getConservativeAdvancementFunctionLookTable()
Definition: continuous_collision-inl.h:100
fcl::CollisionObject< double >
template class FCL_EXPORT CollisionObject< double >
fcl::continuousCollideBVHPolynomial
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)
Definition: continuous_collision-inl.h:248
fcl::BV_RSS
@ BV_RSS
Definition: collision_geometry.h:53
fcl::OT_BVH
@ OT_BVH
Definition: collision_geometry.h:50
min
static T min(T x, T y)
Definition: svm.cpp:49
fcl::BVHModel::updateSubModel
int updateSubModel(const std::vector< Vector3< S >> &ps)
Update a set of points in the old BVH model.
Definition: BVH_model-inl.h:685
fcl::MotionBase::getCurrentTransform
void getCurrentTransform(Matrix3< S > &R, Vector3< S > &T) const
Get the rotation and translation in current step.
Definition: motion_base-inl.h:64
collision_node.h
fcl::GST_INDEP
@ GST_INDEP
Definition: gjk_solver_type.h:45
fcl::CollisionGeometry::getObjectType
virtual OBJECT_TYPE getObjectType() const
get the type of the object
Definition: collision_geometry-inl.h:72
fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_geometry.h:53
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
fcl::BV_AABB
@ BV_AABB
Definition: collision_geometry.h:53
fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:51
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::CCDM_SPLINE
@ CCDM_SPLINE
Definition: continuous_collision_request.h:48
fcl::CCDC_POLYNOMIAL_SOLVER
@ CCDC_POLYNOMIAL_SOLVER
Definition: continuous_collision_request.h:49
fcl::CCDM_SCREW
@ CCDM_SCREW
Definition: continuous_collision_request.h:48
fcl::OT_GEOM
@ OT_GEOM
Definition: collision_geometry.h:50
collision.h


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48