38 #ifndef FCL_TRAVERSAL_SHAPEMESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_SHAPEMESHCONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H 52 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
68 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
73 if(this->enable_statistics) this->num_bv_tests++;
75 S d = this->model1_bv.distance(this->model2->getBV(b2).bv, &P1, &P2);
77 stack.emplace_back(P1, P2, b1, b2, d);
83 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
88 if(this->enable_statistics) this->num_leaf_tests++;
90 const BVNode<BV>& node = this->model2->getBV(b2);
94 const Triangle& tri_id = this->tri_indices[primitive_id];
96 const Vector3<S>& p1 = this->vertices[tri_id[0]];
97 const Vector3<S>& p2 = this->vertices[tri_id[1]];
98 const Vector3<S>& p3 = this->vertices[tri_id[2]];
102 this->nsolver->shapeTriangleDistance(*(this->model1), this->tf1, p1, p2, p3, &d, &P1, &P2);
104 if(d < this->min_distance)
106 this->min_distance = d;
111 last_tri_id = primitive_id;
114 Vector3<S> n = P2 - this->tf1 * p1; n.normalize();
118 S bound1 = motion1->computeMotionBound(mb_visitor1);
119 S bound2 = motion2->computeMotionBound(mb_visitor2);
121 S bound = bound1 + bound2;
124 if(bound <= d) cur_delta_t = 1;
125 else cur_delta_t = d /
bound;
127 if(cur_delta_t < delta_t)
128 delta_t = cur_delta_t;
132 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
136 if((c >= w * (this->min_distance - this->abs_err)) && (c * (1 + this->rel_err) >= w * this->min_distance))
138 const auto& data = stack.back();
140 Vector3<S> n = data.P2 - this->tf1 * data.P1; n.normalize();
145 S bound1 = motion1->computeMotionBound(mb_visitor1);
146 S bound2 = motion2->computeMotionBound(mb_visitor2);
148 S bound = bound1 + bound2;
151 if(bound < c) cur_delta_t = 1;
152 else cur_delta_t = c /
bound;
154 if(cur_delta_t < delta_t)
155 delta_t = cur_delta_t;
170 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
177 const NarrowPhaseSolver* nsolver,
182 using S =
typename BV::S;
184 std::vector<Vector3<S>> vertices_transformed(model2.
num_vertices);
189 vertices_transformed[i] = new_v;
214 template <
typename Shape,
typename NarrowPhaseSolver>
217 typename Shape::S w_)
219 Shape,
RSS<typename Shape::
S>, NarrowPhaseSolver>(w_)
225 template <
typename Shape,
typename NarrowPhaseSolver>
230 using S =
typename Shape::S;
236 this->
stack.emplace_back(P1, P2, b1, b2, d);
242 template <
typename Shape,
typename NarrowPhaseSolver>
269 template <
typename Shape,
typename NarrowPhaseSolver>
289 template <
typename Shape,
typename NarrowPhaseSolver>
296 const NarrowPhaseSolver*
nsolver,
299 using S =
typename Shape::S;
315 template <
typename Shape,
typename NarrowPhaseSolver>
318 typename Shape::S w_)
320 Shape,
OBBRSS<typename Shape::
S>, NarrowPhaseSolver>(w_)
325 template <
typename Shape,
typename NarrowPhaseSolver>
330 using S =
typename Shape::S;
336 this->
stack.emplace_back(P1, P2, b1, b2, d);
342 template <
typename Shape,
typename NarrowPhaseSolver>
369 template <
typename Shape,
typename NarrowPhaseSolver>
389 template <
typename Shape,
typename NarrowPhaseSolver>
396 const NarrowPhaseSolver*
nsolver,
399 using S =
typename Shape::S;
const MotionBase< S > * motion1
Motions for the two objects in query.
Traversal node for distance between shape and mesh.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
std::vector< ConservativeAdvancementStackData< S > > stack
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void meshShapeConservativeAdvancementOrientedNodeLeafTesting(int b1, int, const BVHModel< BV > *model1, const Shape &model2, const BV &model2_bv, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, const NarrowPhaseSolver *nsolver, bool enable_statistics, typename BV::S &min_distance, Vector3< typename BV::S > &p1, Vector3< typename BV::S > &p2, int &last_tri_id, typename BV::S &delta_t, int &num_leaf_tests)
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
const BVHModel< BV > * model2
Transform3< BV::S > tf2
configuration of second object
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
Vector3< S > * vertices
Geometry point data.
typename OBBRSS< Shape::S > ::S S
Eigen::Matrix< S, 3, 1 > Vector3
bool initialize(ShapeMeshConservativeAdvancementTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w)
int num_vertices
Number of points.
FCL_EXPORT void computeBV(const Shape &s, const Transform3< typename BV::S > &tf, BV &bv)
calculate a bounding volume for a shape in a specific configuration
const MotionBase< S > * motion2
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
S delta_t
The delta_t each step.
bool meshShapeConservativeAdvancementOrientedNodeCanStop(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 Shape &model2, const BV &model2_bv, const MotionBase< typename BV::S > *motion1, const MotionBase< typename BV::S > *motion2, std::vector< ConservativeAdvancementStackData< typename BV::S >> &stack, typename BV::S &delta_t)
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)
const NarrowPhaseSolver * nsolver
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 ...
BV bv
bounding volume storing the geometry
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
S w
CA controlling variable: early stop for the early iterations of CA.
template Interval< double > bound(const Interval< double > &i, double v)
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Transform3< BV::S > tf1
configuation of first object
ShapeMeshConservativeAdvancementTraversalNode(S w_=1)
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
bool enable_statistics
Whether stores statistics.