39 #ifndef DISTANCE_CALCULATIONS_H
40 #define DISTANCE_CALCULATIONS_H
50 typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >
Point2dContainer;
63 double sq_norm = diff.squaredNorm();
98 const Eigen::Ref<const Eigen::Vector2d>& line2_start,
const Eigen::Ref<const Eigen::Vector2d>& line2_end, Eigen::Vector2d* intersection = NULL)
101 double s_numer, t_numer, denom,
t;
102 Eigen::Vector2d line1 = line1_end - line1_start;
103 Eigen::Vector2d line2 = line2_end - line2_start;
105 denom = line1.x() * line2.y() - line2.x() * line1.y();
106 if (denom == 0)
return false;
107 bool denomPositive = denom > 0;
109 Eigen::Vector2d aux = line1_start - line2_start;
111 s_numer = line1.x() * aux.y() - line1.y() * aux.x();
112 if ((s_numer < 0) == denomPositive)
return false;
114 t_numer = line2.x() * aux.y() - line2.y() * aux.x();
115 if ((t_numer < 0) == denomPositive)
return false;
117 if (((s_numer > denom) == denomPositive) || ((t_numer > denom) == denomPositive))
return false;
123 *intersection = line1_start +
t * line1;
138 inline double distance_segment_to_segment_2d(
const Eigen::Ref<const Eigen::Vector2d>& line1_start,
const Eigen::Ref<const Eigen::Vector2d>& line1_end,
139 const Eigen::Ref<const Eigen::Vector2d>& line2_start,
const Eigen::Ref<const Eigen::Vector2d>& line2_end)
148 std::array<double,4> distances;
155 return *std::min_element(distances.begin(), distances.end());
167 double dist = HUGE_VAL;
176 for (
int i=0; i<(int)
vertices.size()-1; ++i)
203 double dist = HUGE_VAL;
212 for (
int i=0; i<(int)
vertices.size()-1; ++i)
238 double dist = HUGE_VAL;
241 if (vertices1.size() == 1)
247 for (
int i=0; i<(int)vertices1.size()-1; ++i)
254 if (vertices1.size()>2)
279 const Eigen::Ref<const Eigen::Vector3d>& x2, Eigen::Ref<const Eigen::Vector3d>& v)
281 Eigen::Vector3d w = x2 - x1;
282 double a = u.squaredNorm();
284 double c = v.squaredNorm();
287 double D = a*c - b*b;
293 tc = (b>c ?
d/b : e/c);
296 sc = (b*e - c*
d) / D;
297 tc = (a*e - b*
d) / D;
301 Eigen::Vector3d dP = w + (sc * u) - (tc * v);
311 const Eigen::Ref<const Eigen::Vector3d>& line2_start, Eigen::Ref<const Eigen::Vector3d>& line2_end)
313 Eigen::Vector3d u = line1_end - line1_start;
314 Eigen::Vector3d v = line2_end - line2_start;
315 Eigen::Vector3d w = line2_start - line1_start;
316 double a = u.squaredNorm();
318 double c = v.squaredNorm();
321 double D = a*c - b*b;
322 double sc, sN, sD = D;
323 double tc, tN, tD = D;
371 else if ((-d + b) > a)
380 sc = (abs(sN) <
SMALL_NUM ? 0.0 : sN / sD);
381 tc = (abs(tN) <
SMALL_NUM ? 0.0 : tN / tD);
384 Eigen::Vector3d dP = w + (sc * u) - (tc * v);
392 template <
typename VectorType>
395 VectorType dv = vel1 - vel2;
397 double dv2 = dv.squaredNorm();
401 VectorType w0 = x1 - x2;
402 double cpatime = -w0.dot(dv) / dv2;
407 template <
typename VectorType>
410 double ctime = calc_closest_point_to_approach_time<VectorType>(x1, vel1, x2, vel2);
411 if (bound_cpa_time!=0 && ctime > bound_cpa_time) ctime = bound_cpa_time;
412 VectorType P1 = x1 + (ctime * vel1);
413 VectorType P2 = x2 + (ctime * vel2);
415 return (P2-P1).norm();
423 template <
typename VectorType>
426 VectorType w =
point - line_base;
428 double c1 = w.dot(line_dir);
429 double c2 = line_dir.dot(line_dir);
432 VectorType Pb = line_base + b * line_dir;
433 return (
point-Pb).norm();
441 template <
typename VectorType>
447 double c1 = w.dot(v);
451 double c2 = v.dot(v);
457 return (
point-Pb).norm();