38 #ifndef FCL_TRAVERSAL_MESHSHAPECONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_MESHSHAPECONSERVATIVEADVANCEMENTTRAVERSALNODE_INL_H 52 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
68 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
73 if(this->enable_statistics) this->num_bv_tests++;
75 S d = this->model2_bv.distance(this->model1->getBV(b1).bv, &P2, &P1);
77 stack.emplace_back(P1, P2, b1, b2, d);
83 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
89 if(this->enable_statistics) this->num_leaf_tests++;
91 const BVNode<BV>& node = this->model1->getBV(b1);
95 const Triangle& tri_id = this->tri_indices[primitive_id];
97 const Vector3<S>& p1 = this->vertices[tri_id[0]];
98 const Vector3<S>& p2 = this->vertices[tri_id[1]];
99 const Vector3<S>& p3 = this->vertices[tri_id[2]];
103 this->nsolver->shapeTriangleDistance(*(this->model2), this->tf2, p1, p2, p3, &d, &P2, &P1);
105 if(d < this->min_distance)
107 this->min_distance = d;
112 last_tri_id = primitive_id;
115 Vector3<S> n = this->tf2 * p2 - P1; n.normalize();
119 S bound1 = motion1->computeMotionBound(mb_visitor1);
120 S bound2 = motion2->computeMotionBound(mb_visitor2);
122 S bound = bound1 + bound2;
125 if(bound <= d) cur_delta_t = 1;
126 else cur_delta_t = d /
bound;
128 if(cur_delta_t < delta_t)
129 delta_t = cur_delta_t;
133 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
137 if((c >= w * (this->min_distance - this->abs_err))
138 && (c * (1 + this->rel_err) >= w * this->min_distance))
140 const auto& data = stack.back();
142 Vector3<S> n = this->tf2 * data.P2 - data.P1; n.normalize();
147 S bound1 = motion1->computeMotionBound(mb_visitor1);
148 S bound2 = motion2->computeMotionBound(mb_visitor2);
150 S bound = bound1 + bound2;
153 if(bound < c) cur_delta_t = 1;
154 else cur_delta_t = c /
bound;
156 if(cur_delta_t < delta_t)
157 delta_t = cur_delta_t;
172 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
179 const NarrowPhaseSolver* nsolver,
184 using S =
typename BV::S;
186 std::vector<Vector3<S>> vertices_transformed(model1.
num_vertices);
191 vertices_transformed[i] = new_v;
216 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
229 const NarrowPhaseSolver* nsolver,
230 bool enable_statistics,
231 typename BV::S& min_distance,
235 typename BV::S& delta_t,
238 using S =
typename BV::S;
240 if(enable_statistics) num_leaf_tests++;
245 const Triangle& tri_id = tri_indices[primitive_id];
253 nsolver->shapeTriangleDistance(model2, tf2, t1, t2, t3, tf1, &distance, &P2, &P1);
255 if(distance < min_distance)
262 last_tri_id = primitive_id;
273 S
bound = bound1 + bound2;
276 if(bound <= distance) cur_delta_t = 1;
277 else cur_delta_t = distance /
bound;
279 if(cur_delta_t < delta_t)
280 delta_t = cur_delta_t;
284 template <
typename BV,
typename Shape>
287 typename BV::S min_distance,
288 typename BV::S abs_err,
289 typename BV::S rel_err,
297 typename BV::S& delta_t)
301 using S =
typename BV::S;
303 if((c >= w * (min_distance - abs_err)) && (c * (1 + rel_err) >= w * min_distance))
305 const auto& data = stack.back();
306 Vector3<S> n = data.P2 - data.P1; n.normalize();
315 S
bound = bound1 + bound2;
318 if(bound <= c) cur_delta_t = 1;
319 else cur_delta_t = c /
bound;
321 if(cur_delta_t < delta_t)
322 delta_t = cur_delta_t;
336 template <
typename Shape,
typename NarrowPhaseSolver>
340 RSS<
S>, Shape, NarrowPhaseSolver>(w_)
346 template <
typename Shape,
typename NarrowPhaseSolver>
355 this->
stack.emplace_back(P1, P2, b1, b2, d);
361 template <
typename Shape,
typename NarrowPhaseSolver>
389 template <
typename Shape,
typename NarrowPhaseSolver>
410 template <
typename Shape,
typename NarrowPhaseSolver>
417 const NarrowPhaseSolver*
nsolver,
420 using S =
typename Shape::S;
436 template <
typename Shape,
typename NarrowPhaseSolver>
439 typename Shape::S w_)
441 OBBRSS<
S>, Shape, NarrowPhaseSolver>(w_)
447 template <
typename Shape,
typename NarrowPhaseSolver>
456 this->
stack.emplace_back(P1, P2, b1, b2, d);
462 template <
typename Shape,
typename NarrowPhaseSolver>
490 template <
typename Shape,
typename NarrowPhaseSolver>
511 template <
typename Shape,
typename NarrowPhaseSolver>
518 const NarrowPhaseSolver*
nsolver,
521 using S =
typename Shape::S;
S delta_t
The delta_t each step.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
const NarrowPhaseSolver * nsolver
Traversal node for distance between mesh and shape.
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...
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...
Transform3< BV::S > tf2
configuration of second object
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
bool initialize(MeshShapeConservativeAdvancementTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, typename Shape::S w)
const MotionBase< S > * motion2
Vector3< S > * vertices
Geometry point data.
Eigen::Matrix< S, 3, 1 > Vector3
typename RSS< Shape::S > ::S S
int num_vertices
Number of points.
const BVHModel< BV > * model1
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
Traversal node for conservative advancement computation between BVH and shape.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
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)
MeshShapeConservativeAdvancementTraversalNode(S w_=1)
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)
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
std::vector< ConservativeAdvancementStackData< S > > stack
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...
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
S w
CA controlling variable: early stop for the early iterations of CA.
const MotionBase< S > * motion1
Motions for the two objects in query.
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.