Go to the documentation of this file.
38 #ifndef FCL_CONTINUOUS_COLLISION_INL_H
39 #define FCL_CONTINUOUS_COLLISION_INL_H
64 const ContinuousCollisionRequest<double>& request,
65 ContinuousCollisionResult<double>& result);
71 const Transform3<double>& tf1_beg,
72 const Transform3<double>& tf1_end,
74 const Transform3<double>& tf2_beg,
75 const Transform3<double>& tf2_end,
76 const ContinuousCollisionRequest<double>& request,
77 ContinuousCollisionResult<double>& result);
83 const Transform3<double>& tf1_end,
85 const Transform3<double>& tf2_end,
86 const ContinuousCollisionRequest<double>& request,
87 ContinuousCollisionResult<double>& result);
94 const ContinuousCollisionRequest<double>& request,
95 ContinuousCollisionResult<double>& result);
98 template<
typename GJKSolver>
99 detail::ConservativeAdvancementFunctionMatrix<GJKSolver>&
107 template <
typename S>
134 template <
typename S>
146 for(std::size_t i = 0; i < n_iter; ++i)
148 S t = i / (S) (n_iter - 1);
158 if(
collide(o1, cur_tf1, o2, cur_tf2, c_request, c_result))
177 template<
typename BV>
189 using S =
typename BV::S;
200 for(std::size_t i = 0; i < new_v1.size(); ++i)
202 for(std::size_t i = 0; i < new_v2.size(); ++i)
222 if(!initialize<BV>(node, *o1, tf1, *o2, tf2, c_request))
246 template <
typename S>
260 return detail::continuousCollideBVHPolynomial<AABB<S>>(o1, motion1, o2, motion2, request, result);
263 if(o2->getNodeType() ==
BV_OBB)
267 if(o2->getNodeType() ==
BV_RSS)
271 if(o2->getNodeType() ==
BV_kIOS)
294 std::cerr <<
"Warning: BV type not supported by polynomial solver CCD\n";
303 template<
typename NarrowPhaseSolver>
310 const NarrowPhaseSolver* nsolver_,
314 using S =
typename NarrowPhaseSolver::S;
316 const NarrowPhaseSolver* nsolver = nsolver_;
318 nsolver =
new NarrowPhaseSolver();
320 const auto& looktable = getConservativeAdvancementFunctionLookTable<NarrowPhaseSolver>();
327 if(!looktable.conservative_advancement_matrix[node_type1][node_type2])
329 std::cerr <<
"Warning: collision function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported\n";
333 res = looktable.conservative_advancement_matrix[node_type1][node_type2](o1, motion1, o2, motion2, nsolver, request, result);
357 template <
typename S>
385 template <
typename S>
415 std::cerr <<
"Warning! Invalid continuous collision setting\n";
425 std::cerr <<
"Warning! Invalid continuous collision checking\n";
428 std::cerr <<
"Warning! Invalid continuous collision setting\n";
435 template <
typename S>
454 template <
typename S>
470 template <
typename S>
template class FCL_EXPORT CollisionGeometry< double >
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Traversal node for continuous collision between meshes.
S toc_err
error in first contact time
Vector3< S > * vertices
Geometry point data.
S time_of_contact
time of contact in [0, 1]
std::vector< BVHContinuousCollisionPair< S > > pairs
collision and distance solver based on libccd library.
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)
std::shared_ptr< MotionBase< S > > MotionBasePtr
Transform3< S > contact_tf2
@ CCDC_CONSERVATIVE_ADVANCEMENT
CCDSolverType ccd_solver_type
ccd solver type
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)
GJKSolverType gjk_solver_type
gjk solver type
the object for continuous collision or distance computation, contains the geometry and the motion inf...
virtual bool integrate(S dt) const =0
Integrate the motion from 0 to dt.
Vector3< S > getVelocity() const
FCL_EXPORT MotionBasePtr< S > getMotionBase(const Transform3< S > &tf_beg, const Transform3< S > &tf_end, CCDMotionType motion_type)
The geometry for the object for collision or distance computation.
int beginUpdateModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
Transform3< S > contact_tf1
virtual NODE_TYPE getNodeType() const
get the node type
template class FCL_EXPORT MotionBase< double >
template class FCL_EXPORT ContinuousCollisionObject< double >
bool is_collide
collision or not
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)
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Parameters for performing collision request.
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)
std::size_t num_max_iterations
maximum num of iterations
void getCurrentTransform(Transform3< S > &tf_) const override
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
CCDMotionType ccd_motion_type
ccd motion type
MotionBase< S > * getMotion() const
get motion from the object instance
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
KDOP class describes the KDOP collision structures. K is set as the template parameter,...
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
const Transform3< S > & getTransform() const
get object's transform
int endUpdateModel(bool refit=true, bool bottomup=true)
End BVH model update, will also refit or rebuild the bounding volume hierarchy.
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular veloc...
bool integrate(S dt) const override
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)
int num_vertices
Number of points.
continuous collision result
detail::ConservativeAdvancementFunctionMatrix< GJKSolver > & getConservativeAdvancementFunctionLookTable()
template class FCL_EXPORT CollisionObject< double >
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)
int updateSubModel(const std::vector< Vector3< S >> &ps)
Update a set of points in the old BVH model.
void getCurrentTransform(Matrix3< S > &R, Vector3< S > &T) const
Get the rotation and translation in current step.
virtual OBJECT_TYPE getObjectType() const
get the type of the object
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
the object for collision or distance computation, contains the geometry and the transform information
fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48