38 #ifndef FCL_NARROWPHASE_DETAIL_SPHERETRIANGLE_INL_H 
   39 #define FCL_NARROWPHASE_DETAIL_SPHERETRIANGLE_INL_H 
   53 double segmentSqrDistance(
const Vector3<double>& from, 
const Vector3<double>& to,
const Vector3<double>& p, Vector3<double>& nearest);
 
   57 bool projectInTriangle(
const Vector3<double>& p1, 
const Vector3<double>& p2, 
const Vector3<double>& p3, 
const Vector3<double>& normal, 
const Vector3<double>& p);
 
   62                              const Vector3<double>& P1, 
const Vector3<double>& P2, 
const Vector3<double>& P3, Vector3<double>* contact_points, 
double* penetration_depth, Vector3<double>* normal_);
 
   67                             const Vector3<double>& P1, 
const Vector3<double>& P2, 
const Vector3<double>& P3,
 
   73                             const Vector3<double>& P1, 
const Vector3<double>& P2, 
const Vector3<double>& P3,
 
   74                             double* dist, Vector3<double>* p1, Vector3<double>* p2);
 
   79                             const Vector3<double>& P1, 
const Vector3<double>& P2, 
const Vector3<double>& P3, 
const Transform3<double>& tf2,
 
   80                             double* dist, Vector3<double>* p1, Vector3<double>* p2);
 
  107   nearest = from + v * t;
 
  108   return diff.dot(diff);
 
  112 template <
typename S>
 
  128   r1 = edge1_normal.dot(p1_to_p);
 
  129   r2 = edge2_normal.dot(p2_to_p);
 
  130   r3 = edge3_normal.dot(p3_to_p);
 
  131   if ( ( r1 > 0 && r2 > 0 && r3 > 0 ) ||
 
  132        ( r1 <= 0 && r2 <= 0 && r3 <= 0 ) )
 
  138 template <
typename S>
 
  145   const S& radius = s.
radius;
 
  148   S distance_from_plane = p1_to_center.dot(normal);
 
  150   if(distance_from_plane < 0)
 
  152     distance_from_plane *= -1;
 
  156   bool is_inside_contact_plane = (distance_from_plane < radius_with_threshold);
 
  158   bool has_contact = 
false;
 
  160   if(is_inside_contact_plane)
 
  165       contact_point = center - normal * distance_from_plane;
 
  169       S contact_capsule_radius_sqr = radius_with_threshold * radius_with_threshold;
 
  173       if(distance_sqr < contact_capsule_radius_sqr)
 
  176         contact_point = nearest_on_edge;
 
  180       if(distance_sqr < contact_capsule_radius_sqr)
 
  183         contact_point = nearest_on_edge;
 
  187       if(distance_sqr < contact_capsule_radius_sqr)
 
  190         contact_point = nearest_on_edge;
 
  197     Vector3<S> contact_to_center = contact_point - center;
 
  198     S distance_sqr = contact_to_center.squaredNorm();
 
  200     if(distance_sqr < radius_with_threshold * radius_with_threshold)
 
  204         S 
distance = std::sqrt(distance_sqr);
 
  205         if(normal_) *normal_ = contact_to_center.normalized();
 
  206         if(contact_points) *contact_points = contact_point;
 
  207         if(penetration_depth) *penetration_depth = -(radius - 
distance);
 
  211         if(normal_) *normal_ = -normal;
 
  212         if(contact_points) *contact_points = contact_point;
 
  213         if(penetration_depth) *penetration_depth = -radius;
 
  224 template <
typename S>
 
  236   S a00 = edge0.squaredNorm();
 
  237   S a01 = edge0.dot(edge1);
 
  238   S a11 = edge1.squaredNorm();
 
  239   S b0 = diff.dot(edge0);
 
  240   S b1 = diff.dot(edge1);
 
  241   S c = diff.squaredNorm();
 
  242   S det = fabs(a00*a11 - a01*a01);
 
  243   S s = a01*b1 - a11*b0;
 
  244   S t = a01*b0 - a00*b1;
 
  260             sqr_dist = a00 + 2*b0 + c;
 
  279             sqr_dist = a11 + 2*b1 + c;
 
  299           sqr_dist = a11 + 2*b1 + c;
 
  319         sqr_dist = a00 + 2*b0 + c;
 
  333       sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
 
  338     S tmp0, tmp1, numer, denom;
 
  347         denom = a00 - 2*a01 + a11;
 
  352           sqr_dist = a00 + 2*b0 + c;
 
  358           sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
 
  367           sqr_dist = a11 + 2*b1 + c;
 
  388         denom = a00 - 2*a01 + a11;
 
  393           sqr_dist = a11 + 2*b1 + c;
 
  399           sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
 
  408           sqr_dist = a00 + 2*b0 + c;
 
  424       numer = a11 + b1 - a01 - b0;
 
  429         sqr_dist = a11 + 2*b1 + c;
 
  433         denom = a00 - 2*a01 + a11;
 
  438           sqr_dist = a00 + 2*b0 + c;
 
  444           sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
 
  454   if(sqr_dist > radius * radius)
 
  456     if(dist) *dist = std::sqrt(sqr_dist) - radius;
 
  467 template <
typename S>
 
  483       if(p1) { *p1 = o - dir * sp.
radius; *p1 = tf.inverse(Eigen::Isometry) * (*p1); }
 
  484       if(p2) *p2 = project_p;
 
  497 template <
typename S>
 
  503   if(p2) *p2 = tf2.inverse(Eigen::Isometry) * (*p2);