Go to the documentation of this file.
   38 #ifndef FCL_TRAVERSAL_MESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H 
   39 #define FCL_TRAVERSAL_MESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H 
   61     const Transform3<double>& tf1,
 
   63     const Transform3<double>& tf2,
 
   75     const Transform3<double>& tf1,
 
   77     const Transform3<double>& tf2,
 
   81 template <
typename BV>
 
   97 template <
typename BV>
 
  101   if(this->enable_statistics) this->num_bv_tests++;
 
  103   S d = this->model1->getBV(b1).distance(this->model2->getBV(b2), &P1, &P2);
 
  105   stack.emplace_back(P1, P2, b1, b2, d);
 
  111 template <
typename BV>
 
  114   if(this->enable_statistics) this->num_leaf_tests++;
 
  116   const BVNode<BV>& node1 = this->model1->getBV(b1);
 
  117   const BVNode<BV>& node2 = this->model2->getBV(b2);
 
  122   const Triangle& tri_id1 = this->tri_indices1[primitive_id1];
 
  123   const Triangle& tri_id2 = this->tri_indices2[primitive_id2];
 
  125   const Vector3<S>& p1 = this->vertices1[tri_id1[0]];
 
  126   const Vector3<S>& p2 = this->vertices1[tri_id1[1]];
 
  127   const Vector3<S>& p3 = this->vertices1[tri_id1[2]];
 
  129   const Vector3<S>& q1 = this->vertices2[tri_id2[0]];
 
  130   const Vector3<S>& q2 = this->vertices2[tri_id2[1]];
 
  131   const Vector3<S>& q3 = this->vertices2[tri_id2[2]];
 
  139   if(d < this->min_distance)
 
  141     this->min_distance = d;
 
  146     last_tri_id1 = primitive_id1;
 
  147     last_tri_id2 = primitive_id2;
 
  154   S bound1 = motion1->computeMotionBound(mb_visitor1);
 
  155   S bound2 = motion2->computeMotionBound(mb_visitor2);
 
  157   S bound = bound1 + bound2;
 
  160   if(
bound <= d) cur_delta_t = 1;
 
  161   else cur_delta_t = d / 
bound;
 
  163   if(cur_delta_t < delta_t)
 
  164     delta_t = cur_delta_t;
 
  168 template <
typename S, 
typename BV>
 
  186         n = data2.
P2 - data2.
P1; n.normalize();
 
  193         n = data.
P2 - data.
P1; n.normalize();
 
  201       S bound1 = node.
motion1->computeMotionBound(mb_visitor1);
 
  202       S bound2 = node.
motion2->computeMotionBound(mb_visitor2);
 
  204       S 
bound = bound1 + bound2;
 
  207       if(
bound <= c) cur_delta_t = 1;
 
  208       else cur_delta_t = c / 
bound;
 
  213       node.
stack.pop_back();
 
  225       node.
stack.pop_back();
 
  233 template <
typename BV>
 
  235     typename BV::S c)
 const 
  241 template <
typename S>
 
  264 template <
typename S>
 
  287 template <
typename S>
 
  310 template <
typename BV>
 
  321   using S = 
typename BV::S;
 
  323   std::vector<Vector3<S>> vertices_transformed1(model1.
num_vertices);
 
  328     vertices_transformed1[i] = new_v;
 
  331   std::vector<Vector3<S>> vertices_transformed2(model2.
num_vertices);
 
  336     vertices_transformed2[i] = new_v;
 
  362 template <
typename S>
 
  363 MeshConservativeAdvancementTraversalNodeRSS<S>::
 
  364 MeshConservativeAdvancementTraversalNodeRSS(S w_)
 
  371 template <
typename S>
 
  388         this->enable_statistics,
 
  395         this->num_leaf_tests);
 
  399 template <
typename S>
 
  417 template <
typename S>
 
  426 template <
typename S>
 
  443         this->enable_statistics,
 
  450         this->num_leaf_tests);
 
  454 template <
typename S>
 
  474 template <
typename S, 
typename BV>
 
  479     return bv.axis.col(i);
 
  484 template <
typename BV>
 
  488   return getBVAxisImpl(bv, i);
 
  492 template <
typename S>
 
  502 template <
typename BV>
 
  505     typename BV::S min_distance,
 
  506     typename BV::S abs_err,
 
  507     typename BV::S rel_err,
 
  514     typename BV::S& delta_t)
 
  516   using S = 
typename BV::S;
 
  518   if((c >= w * (min_distance - abs_err)) && (c * (1 + rel_err) >= w * min_distance))
 
  529       n = data2.
P2 - data2.
P1; n.normalize();
 
  532       stack[stack.size() - 2] = stack[stack.size() - 1];
 
  536       n = data.
P2 - data.
P1; n.normalize();
 
  552     S 
bound = bound1 + bound2;
 
  555     if(
bound <= c) cur_delta_t = 1;
 
  556     else cur_delta_t = c / 
bound;
 
  558     if(cur_delta_t < delta_t)
 
  559       delta_t = cur_delta_t;
 
  571       stack[stack.size() - 2] = stack[stack.size() - 1];
 
  580 template <
typename BV>
 
  583     typename BV::S min_distance,
 
  584     typename BV::S abs_err,
 
  585     typename BV::S rel_err,
 
  592     typename BV::S& delta_t)
 
  594   using S = 
typename BV::S;
 
  596   if((c >= w * (min_distance - abs_err)) && (c * (1 + rel_err) >= w * min_distance))
 
  607       n = data2.
P2 - data2.
P1; n.normalize();
 
  610       stack[stack.size() - 2] = stack[stack.size() - 1];
 
  614       n = data.
P2 - data.
P1; n.normalize();
 
  628     n_transformed = R0 * n_transformed;
 
  629     n_transformed.normalize();
 
  635     S 
bound = bound1 + bound2;
 
  638     if(
bound <= c) cur_delta_t = 1;
 
  639     else cur_delta_t = c / 
bound;
 
  641     if(cur_delta_t < delta_t)
 
  642       delta_t = cur_delta_t;
 
  654       stack[stack.size() - 2] = stack[stack.size() - 1];
 
  663 template <
typename BV>
 
  677     bool enable_statistics,
 
  678     typename BV::S& min_distance,
 
  683     typename BV::S& delta_t,
 
  686   using S = 
typename BV::S;
 
  688   if(enable_statistics) num_leaf_tests++;
 
  696   const Triangle& tri_id1 = tri_indices1[primitive_id1];
 
  697   const Triangle& tri_id2 = tri_indices2[primitive_id2];
 
  699   const Vector3<S>& t11 = vertices1[tri_id1[0]];
 
  700   const Vector3<S>& t12 = vertices1[tri_id1[1]];
 
  701   const Vector3<S>& t13 = vertices1[tri_id1[2]];
 
  703   const Vector3<S>& t21 = vertices2[tri_id2[0]];
 
  704   const Vector3<S>& t22 = vertices2[tri_id2[1]];
 
  705   const Vector3<S>& t23 = vertices2[tri_id2[2]];
 
  721     last_tri_id1 = primitive_id1;
 
  722     last_tri_id2 = primitive_id2;
 
  732   n_transformed.normalize(); 
 
  738   S 
bound = bound1 + bound2;
 
  741   if(
bound <= d) cur_delta_t = 1;
 
  742   else cur_delta_t = d / 
bound;
 
  744   if(cur_delta_t < delta_t)
 
  745     delta_t = cur_delta_t;
 
  749 template <
typename BV, 
typename OrientedDistanceNode>
 
  751     OrientedDistanceNode& node,
 
  759   node.model1 = &model1;
 
  760   node.model2 = &model2;
 
  770   relativeTransform(tf1.linear(), tf1.translation(), tf2.linear(), tf2.translation(), node.R, node.T);
 
  776 template <
typename S>
 
  786         node, model1, tf1, model2, tf2, w);
 
  790 template <
typename S>
 
  800         node, model1, tf1, model2, tf2, w);
 
  
const MotionBase< S > * motion1
Motions for the two objects in query.
template class FCL_EXPORT RSS< double >
Matrix3< S > axis
Orientation of OBB. The axes of the rotation matrix are the principle directions of the box....
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
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
Vector3< S > * vertices
Geometry point data.
static bool run(const MeshConservativeAdvancementTraversalNode< OBB< S >> &node, S c)
void getCurrentRotation(Matrix3< S > &R) const
Eigen::Quaternion< S > Quaternion
S delta_t
The delta_t each step.
virtual S computeMotionBound(const BVMotionBoundVisitor< S > &mb_visitor) const =0
Compute the motion bound for a bounding volume, given the closest direction n between two query objec...
const MotionBase< S > * motion2
bool initialize(MeshConservativeAdvancementTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, S w)
S rel_err
relative and absolute error, default value is 0.01 for both terms
Triangle with 3 indices for points.
Eigen::Matrix< S, 3, 1 > Vector3
MeshConservativeAdvancementTraversalNode(S w_=1)
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)
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
const BVHModel< BV > * model2
The second BVH model.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
bool setupMeshConservativeAdvancementOrientedDistanceNode(OrientedDistanceNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, typename BV::S w)
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 Interval< double > bound(const Interval< double > &i, double v)
for OBB and RSS, there is local coordinate of BV, so normal need to be transformed
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Triangle distance functions.
template class FCL_EXPORT OBBRSS< double >
int num_vertices
Number of points.
S w
CA controlling variable: early stop for the early iterations of CA.
const BVHModel< BV > * model1
The first BVH model.
template class FCL_EXPORT MeshConservativeAdvancementTraversalNodeRSS< double >
const Vector3< S > operator()(const BV &bv, int i)
continuous collision node using conservative advancement. when using this default version,...
template class FCL_EXPORT MeshConservativeAdvancementTraversalNodeOBBRSS< double >
static bool run(const MeshConservativeAdvancementTraversalNode< BV > &node, S c)
@ BVH_MODEL_TRIANGLES
unknown model type
BVHModelType getModelType() const
Model type described by the instance.
FCL_EXPORT void relativeTransform(const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &t1, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &t2, Eigen::MatrixBase< DerivedC > &R, Eigen::MatrixBase< DerivedD > &t)
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
static S triDistance(const Vector3< S > T1[3], const Vector3< S > T2[3], Vector3< S > &P, Vector3< S > &Q)
Compute the closest points on two triangles given their absolute coordinate, and returns the distance...
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)
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:18