38 #ifndef FCL_DISTANCERESULT_INL_H 39 #define FCL_DISTANCERESULT_INL_H 48 struct DistanceResult<double>;
54 : min_distance(min_distance_),
73 if(min_distance > distance)
95 if(min_distance > distance)
102 nearest_points[0] = p1;
103 nearest_points[1] = p2;
108 template <
typename S>
115 o1 = other_result.
o1;
116 o2 = other_result.
o2;
117 b1 = other_result.
b1;
118 b2 = other_result.
b2;
125 template <
typename S>
S min_distance
Minimum distance between two objects.
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.
const CollisionGeometry< S > * o2
collision object 2
Eigen::Matrix< S, 3, 1 > Vector3
The geometry for the object for collision or distance computation.
const CollisionGeometry< S > * o1
collision object 1
intptr_t b2
information about the nearest point in object 2 if object 2 is mesh or point cloud, it is the triangle or point id if object 2 is geometry shape, it is NONE (-1), if object 2 is octree, it is the query cell id (see OcTree::getNodeByQueryCellId)
intptr_t b1
information about the nearest point in object 1 if object 1 is mesh or point cloud, it is the triangle or point id if object 1 is geometry shape, it is NONE (-1), if object 1 is octree, it is the query cell id (see OcTree::getNodeByQueryCellId)
DistanceResult(S min_distance_=std::numeric_limits< S >::max())
Vector3< S > nearest_points[2]
Nearest points in the world coordinates.