38 #ifndef FCL_NARROWPHASE_DETAIL_SPHERECAPSULE_INL_H 39 #define FCL_NARROWPHASE_DETAIL_SPHERECAPSULE_INL_H 52 const Vector3<double> &p,
53 const Vector3<double> &s1,
54 const Vector3<double> &s2,
61 std::vector<ContactPoint<double>>* contacts);
67 double* dist, Vector3<double>* p1, Vector3<double>* p2);
80 }
else if (c2 <= c1) {
97 const Vector3<S> s_c = tf2.inverse(Eigen::Isometry) * tf1.translation();
109 const Vector3<S> local_normal = -diff.normalized();
113 const Vector3<S> normal = tf2.linear() * local_normal;
115 const S penetration_depth = -
distance;
117 contacts->emplace_back(normal, point, penetration_depth);
124 template <
typename S>
131 Vector3<S> s_c = tf2.inverse(Eigen::Isometry) * tf1.translation();
147 if (dist) *dist = -1;
153 if(p1 || p2) diff.normalize();
156 *p1 = s_c - diff * s1.
radius;
162 *p2 = segment_point + diff * s2.
radius;
template bool sphereCapsuleIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Eigen::Matrix< S, 3, 1 > Vector3
template void lineSegmentPointClosestToPoint(const Vector3< double > &p, const Vector3< double > &s1, const Vector3< double > &s2, Vector3< double > &sp)
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
std::chrono::system_clock::time_point point
Representation of a point in time.
template class FCL_EXPORT Capsule< double >
S radius
Radius of the sphere.
Center at zero point sphere.
template bool sphereCapsuleDistance(const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2)
S radius
Radius of capsule.
template class FCL_EXPORT Sphere< double >