Go to the documentation of this file.
   38 #ifndef FCL_TRAVERSAL_MESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_H 
   39 #define FCL_TRAVERSAL_MESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_H 
   52 template <
typename BV>
 
   58   using S = 
typename BV::S;
 
   63   S BVTesting(
int b1, 
int b2) 
const;
 
   66   void leafTesting(
int b1, 
int b2) 
const;
 
   69   bool canStop(
S c) 
const;
 
   91   mutable std::vector<ConservativeAdvancementStackData<S>> 
stack;
 
   93   template <
typename, 
typename>
 
   99 template <
typename BV>
 
  107     typename BV::S w = 1,
 
  108     bool use_refit = 
false,
 
  109     bool refit_bottomup = 
false);
 
  111 template <
typename S>
 
  120     if (this->enable_statistics)
 
  121       this->num_bv_tests++;
 
  127         this->model1->getBV(b1).bv,
 
  128         this->model2->getBV(b2).bv,
 
  132     this->stack.emplace_back(P1, P2, b1, b2, d);
 
  137   void leafTesting(
int b1, 
int b2) 
const;
 
  139   bool canStop(S c) 
const;
 
  144   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  152 template <
typename S>
 
  162 template <
typename S>
 
  171     if (this->enable_statistics)
 
  172       this->num_bv_tests++;
 
  178         this->model1->getBV(b1).bv,
 
  179         this->model2->getBV(b2).bv,
 
  183     this->stack.emplace_back(P1, P2, b1, b2, d);
 
  188   void leafTesting(
int b1, 
int b2) 
const;
 
  190   bool canStop(S c) 
const;
 
  195   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  201 template <
typename S>
 
  211 template <
typename S, 
typename BV>
 
  215 template <
typename BV>
 
  219     typename BV::S min_distance,
 
  220     typename BV::S abs_err,
 
  221     typename BV::S rel_err,
 
  228     typename BV::S& delta_t);
 
  230 template <
typename BV>
 
  234     typename BV::S min_distance,
 
  235     typename BV::S abs_err,
 
  236     typename BV::S rel_err,
 
  243     typename BV::S& delta_t);
 
  245 template <
typename BV>
 
  260     bool enable_statistics,
 
  261     typename BV::S& min_distance,
 
  266     typename BV::S& delta_t,
 
  267     int& num_leaf_tests);
 
  
const MotionBase< S > * motion1
Motions for the two objects in query.
bool meshConservativeAdvancementTraversalNodeCanStop(typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
S delta_t
The delta_t each step.
S toc
The time from beginning point.
const MotionBase< S > * motion2
Triangle with 3 indices for points.
Eigen::Matrix< S, 3, 1 > Vector3
Eigen::Matrix< S, 3, 3 > Matrix3
void meshConservativeAdvancementOrientedNodeLeafTesting(int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Triangle *tri_indices1, const Triangle *tri_indices2, const Vector3< typename BV::S > *vertices1, const Vector3< typename BV::S > *vertices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, bool enable_statistics, typename BV::S &min_distance, Vector3< typename BV::S > &p1, Vector3< typename BV::S > &p2, int &last_tri_id1, int &last_tri_id2, typename BV::S &delta_t, int &num_leaf_tests)
const Vector3< typename BV::S > getBVAxis(const BV &bv, int i)
Traversal node for distance computation between two meshes.
template bool initialize(MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result)
std::vector< ConservativeAdvancementStackData< S > > stack
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
S w
CA controlling variable: early stop for the early iterations of CA.
continuous collision node using conservative advancement. when using this default version,...
bool meshConservativeAdvancementOrientedNodeCanStop(typename BV::S c, typename BV::S min_distance, typename BV::S abs_err, typename BV::S rel_err, typename BV::S w, const BVHModel< BV > *model1, const BVHModel< BV > *model2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t)
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:18