38 #ifndef FCL_TRAVERSAL_MESHSHAPEDISTANCETRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_MESHSHAPEDISTANCETRAVERSALNODE_INL_H 52 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
58 tri_indices =
nullptr;
67 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
73 if(this->enable_statistics) this->num_leaf_tests++;
75 const BVNode<BV>& node = this->model1->getBV(b1);
79 const Triangle& tri_id = tri_indices[primitive_id];
87 nsolver->shapeTriangleDistance(*(this->model2), this->tf2, p1, p2, p3, &d, &closest_p2, &closest_p1);
100 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
104 if((c >= this->result->min_distance - abs_err) && (c * (1 + rel_err) >= this->result->min_distance))
110 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
117 const NarrowPhaseSolver* nsolver,
123 using S =
typename BV::S;
128 if(!tf1.matrix().isIdentity())
130 std::vector<Vector3<S>> vertices_transformed1(model1.
num_vertices);
135 vertices_transformed1[i] = new_v;
163 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
170 const NarrowPhaseSolver* nsolver,
171 bool enable_statistics,
172 int & num_leaf_tests,
176 using S =
typename BV::S;
178 if(enable_statistics) num_leaf_tests++;
183 const Triangle& tri_id = tri_indices[primitive_id];
190 nsolver->shapeTriangleDistance(model2, tf2, p1, p2, p3, tf1, &distance, &closest_p2, &closest_p1);
203 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
212 const NarrowPhaseSolver* nsolver,
216 using S =
typename BV::S;
218 const Triangle& init_tri = tri_indices[init_tri_id];
226 nsolver->shapeTriangleDistance(model2, tf2, p1, p2, p3, tf1, &distance, &closest_p2, &closest_p1);
239 template <
typename Shape,
typename NarrowPhaseSolver>
243 RSS<typename Shape::
S>, Shape, NarrowPhaseSolver>()
248 template <
typename Shape,
typename NarrowPhaseSolver>
265 template <
typename Shape,
typename NarrowPhaseSolver>
271 template <
typename Shape,
typename NarrowPhaseSolver>
274 int b1,
int b2)
const 284 template <
typename Shape,
typename NarrowPhaseSolver>
305 template <
typename Shape,
typename NarrowPhaseSolver>
311 template <
typename Shape,
typename NarrowPhaseSolver>
319 template <
typename Shape,
typename NarrowPhaseSolver>
325 template <
typename Shape,
typename NarrowPhaseSolver>
336 template <
typename Shape,
typename NarrowPhaseSolver>
344 template <
typename Shape,
typename NarrowPhaseSolver>
350 template <
typename Shape,
typename NarrowPhaseSolver>
358 template <
typename Shape,
typename NarrowPhaseSolver>
365 template <
typename Shape,
typename NarrowPhaseSolver>
378 template <
typename Shape,
typename NarrowPhaseSolver>
385 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver,
template <
typename,
typename>
class OrientedNode>
389 const NarrowPhaseSolver*
nsolver,
414 template <
typename Shape,
typename NarrowPhaseSolver>
419 const NarrowPhaseSolver*
nsolver,
427 template <
typename Shape,
typename NarrowPhaseSolver>
432 const NarrowPhaseSolver*
nsolver,
440 template <
typename Shape,
typename NarrowPhaseSolver>
445 const NarrowPhaseSolver*
nsolver,
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.
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
BVHModelType getModelType() const
Model type described by the instance.
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
static bool setupMeshShapeDistanceOrientedNode(OrientedNode< Shape, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
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)...
Vector3< S > * vertices
Geometry point data.
Eigen::Matrix< S, 3, 1 > Vector3
typename kIOS< Shape::S > ::S S
int num_vertices
Number of points.
Traversal node for distance computation between BVH and shape.
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
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
void distancePreprocessOrientedNode(const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
void meshShapeDistanceOrientedNodeLeafTesting(int b1, int, const BVHModel< BV > *model1, const Shape &model2, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &, DistanceResult< typename BV::S > &result)
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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)
DistanceRequest< BV::S > request
request setting for distance
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
bool initialize(MeshShapeDistanceTraversalNodeOBBRSS< 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, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result)
Initialize traversal node for distance computation between one mesh and one shape, specialized for OBBRSS type.
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
MeshShapeDistanceTraversalNode()
void distancePreprocessOrientedNode(const BVHModel< BV > *model1, Vector3< typename BV::S > *vertices, Triangle *tri_indices, int init_tri_id, const Shape &model2, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &, DistanceResult< typename BV::S > &result)
DistanceResult< BV::S > * result
distance result kept during the traversal iteration
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Transform3< BV::S > tf1
configuation of first object
MeshShapeDistanceTraversalNodekIOS()
void update(S distance, const CollisionGeometry< S > *o1_, const CollisionGeometry< S > *o2_, int b1_, int b2_)
add distance information into the result
request to the distance computation
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.
A class describing the kIOS collision structure, which is a set of spheres.