38 #ifndef FCL_TRAVERSAL_SHAPEMESHDISTANCETRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_SHAPEMESHDISTANCETRAVERSALNODE_INL_H 52 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
58 tri_indices =
nullptr;
67 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
72 using S =
typename BV::S;
74 if(this->enable_statistics) this->num_leaf_tests++;
76 const BVNode<BV>& node = this->model2->getBV(b2);
80 const Triangle& tri_id = tri_indices[primitive_id];
88 nsolver->shapeTriangleDistance(*(this->model1), this->tf1, p1, p2, p3, &distance, &closest_p1, &closest_p2);
101 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
104 if((c >= this->result->min_distance - abs_err) && (c * (1 + rel_err) >= this->result->min_distance))
110 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
118 const NarrowPhaseSolver* nsolver,
124 using S =
typename BV::S;
129 if(!tf2.matrix().isIdentity())
131 std::vector<Vector3<S>> vertices_transformed(model2.
num_vertices);
136 vertices_transformed[i] = new_v;
164 template <
typename Shape,
typename NarrowPhaseSolver>
171 template <
typename Shape,
typename NarrowPhaseSolver>
180 template <
typename Shape,
typename NarrowPhaseSolver>
186 template <
typename Shape,
typename NarrowPhaseSolver>
198 template <
typename Shape,
typename NarrowPhaseSolver>
207 template <
typename Shape,
typename NarrowPhaseSolver>
215 template <
typename Shape,
typename NarrowPhaseSolver>
231 template <
typename Shape,
typename NarrowPhaseSolver>
237 template <
typename Shape,
typename NarrowPhaseSolver>
249 template <
typename Shape,
typename NarrowPhaseSolver>
258 template <
typename Shape,
typename NarrowPhaseSolver>
265 template <
typename Shape,
typename NarrowPhaseSolver>
281 template <
typename Shape,
typename NarrowPhaseSolver>
288 template <
typename Shape,
typename NarrowPhaseSolver>
300 template <
typename Shape,
typename NarrowPhaseSolver>
320 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver,
template <
typename,
typename>
class OrientedNode>
324 const NarrowPhaseSolver*
nsolver,
344 node.R = tf2.linear();
345 node.T = tf2.translation();
351 template <
typename Shape,
typename NarrowPhaseSolver>
356 const NarrowPhaseSolver*
nsolver,
364 template <
typename Shape,
typename NarrowPhaseSolver>
369 const NarrowPhaseSolver*
nsolver,
377 template <
typename Shape,
typename NarrowPhaseSolver>
382 const NarrowPhaseSolver*
nsolver,
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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.
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
static bool setupShapeMeshDistanceOrientedNode(OrientedNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
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...
ShapeMeshDistanceTraversalNode()
const BVHModel< BV > * model2
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.
typename kIOS< Shape::S > ::S S
Eigen::Matrix< S, 3, 1 > Vector3
int num_vertices
Number of points.
Traversal node for distance computation between shape and BVH.
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
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)
S BVTesting(int b1, int b2) const
BV test between b1 and b2.
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)
FCL_EXPORT bool initialize(ShapeMeshDistanceTraversalNodeOBBRSS< 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, const DistanceRequest< typename Shape::S > &request, DistanceResult< typename Shape::S > &result)
Initialize traversal node for distance computation between one shape and one mesh, specialized for OBBRSS type.
const NarrowPhaseSolver * nsolver
ShapeMeshDistanceTraversalNodekIOS()
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
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
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
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.