36 namespace mnm = marti_nav_msgs;
 
   44                const std::string &target_frame)
 
   46   for (
auto &point : path.points) {
 
   47     tf::Vector3 position(point.x, point.y, 0.0);
 
   50     point.x = position.x();
 
   51     point.y = position.y();
 
   56   path.header.frame_id = target_frame;
 
   61   for (
auto &point : route.points) {
 
   71   if (path.points.size() < 2) {
 
   76   for (
size_t i = 0; i + 1 < path.points.size(); i++)
 
   78     auto& pt = path.points[i];
 
   79     const auto& next_pt = path.points[i+1];
 
   86     if (pt.flags & marti_nav_msgs::PlanPoint::FLAG_REVERSE)
 
   95   path.points.back().yaw = path.points[path.points.size() - 2].yaw;
 
  100     const marti_nav_msgs::Plan& path,
 
  101     const double x, 
const double y,
 
  102     marti_nav_msgs::PlanPosition& nearest_position,
 
  103     double& nearest_separation)
 
  106   size_t num_points = path.points.size();
 
  111   else if (num_points == 1)
 
  113     nearest_position.index = 0;
 
  114     nearest_position.distance = 0.0;
 
  115     nearest_separation = std::sqrt(std::pow(path.points[0].x - x, 2.0) +
 
  116                                    std::pow(path.points[0].y - y, 2.0));
 
  120   cv::Vec2d point(x, y);
 
  123   double min_separation_sqr = std::numeric_limits<double>::infinity();
 
  124   for (
size_t i = 0; i + 1 < num_points; i++)
 
  126     auto& 
start = path.points[i];
 
  127     auto& end = path.points[i+1];
 
  130                                                               cv::Vec2d(end.x, end.y),
 
  133     double separation_sqr = std::pow(x - proj[0], 2.0) + std::pow(y - proj[1], 2.0);
 
  134     if (separation_sqr <= min_separation_sqr)
 
  136       min_separation_sqr = separation_sqr;
 
  137       nearest_position.index = i;
 
  138       nearest_position.distance = std::sqrt(std::pow(
start.x - proj[0], 2.0) +
 
  139                                             std::pow(
start.y - proj[1], 2.0));
 
  143     if (separation_sqr > 2.0*min_separation_sqr)
 
  149   nearest_separation = std::sqrt(min_separation_sqr);
 
  155   const marti_nav_msgs::Plan& path)
 
  158   if (position.index > path.points.size() - 1)
 
  160     position.distance = 0.0;
 
  161     position.index = path.points.size() - 1;
 
  165   double distance = position.distance;
 
  166   size_t index = position.index;
 
  167   while (distance < 0.0)
 
  175     auto& 
s = path.points[index];
 
  176     auto& e = path.points[index-1];
 
  177     double len = std::sqrt(std::pow(
s.x - e.x, 2.0) +
 
  178                            std::pow(
s.y - e.y, 2.0));
 
  179     if (-distance >= len)
 
  190   while (distance > 0.0)
 
  192     if (index+1 == path.points.size())
 
  197     auto& 
s = path.points[index];
 
  198     auto& e = path.points[index+1];
 
  199     double len = std::sqrt(std::pow(
s.x - e.x, 2.0) +
 
  200                            std::pow(
s.y - e.y, 2.0));
 
  212   position.index = index;
 
  213   position.distance = distance;
 
  218   from = std::fmod(from + M_PI*2.0, M_PI*2.0);
 
  219   to = std::fmod(to + M_PI*2.0, M_PI*2.0);
 
  220   double diff = std::abs(from - to);
 
  223     return from*(1.0-t) + to*t;
 
  228     return from*(1.0-t) + to*t;
 
  233     return from*(1.0-t) + to*t;
 
  245   double &min_distance_from_line,
 
  246   double &min_distance_on_line,
 
  247   const tf::Vector3 &p0,
 
  248   const tf::Vector3 &p1,
 
  249   const tf::Vector3 &p,
 
  250   bool extrapolate_start,
 
  251   bool extrapolate_end)
 
  253   tf::Vector3 v = p1 - p0;
 
  254   const double v_len_sq = v.dot(v);
 
  259   if (v_len_sq > 1e-6) {
 
  260     s = v.dot(p - p0) / v_len_sq;
 
  269   if (!extrapolate_start && 
s < 0.0) {
 
  271   } 
else if (!extrapolate_end && 
s > 1.0) {
 
  275   tf::Vector3 x_nearest = p0 + 
s*v;
 
  277   min_distance_from_line = x_nearest.distance(p);
 
  278   min_distance_on_line = 
s*std::sqrt(v_len_sq);
 
  282                       const mnm::Plan &route,
 
  283                       const tf::Vector3 &point,
 
  284                       bool extrapolate_before_start,
 
  285                       bool extrapolate_past_end)
 
  287   if (route.points.size() == 0) {
 
  292   if (route.points.size() == 1) {
 
  295     position.distance = 0.0;
 
  301   double min_distance_from_line = std::numeric_limits<double>::infinity();
 
  302   double min_distance_on_line = std::numeric_limits<double>::infinity();
 
  303   size_t min_segment_index = 0;
 
  305   for (
size_t i = 0; i+1 < route.points.size(); ++i) {
 
  306     double distance_from_line;
 
  307     double distance_on_line;
 
  316     if (distance_from_line <= min_distance_from_line) {
 
  317       min_segment_index = i;
 
  318       min_distance_on_line = distance_on_line;
 
  319       min_distance_from_line = distance_from_line;
 
  328   if (extrapolate_before_start && min_segment_index == 0) {
 
  331                                  min_distance_on_line,
 
  336   } 
else if (min_segment_index + 2 == route.points.size()) {
 
  342     size_t i = min_segment_index;
 
  344                                  min_distance_on_line,
 
  351     if (min_distance_on_line > last_length) {
 
  353       min_distance_on_line -= last_length;
 
  356     if (!extrapolate_past_end) {
 
  357       min_distance_on_line = 0.0;
 
  361   position.index = min_segment_index;
 
  362   position.distance = min_distance_on_line;
 
  367   marti_nav_msgs::PlanPosition &position,
 
  368   const marti_nav_msgs::Plan &route,
 
  369   const tf::Vector3 &point,
 
  370   const marti_nav_msgs::PlanPosition &window_start,
 
  371   const marti_nav_msgs::PlanPosition &window_end)
 
  373   if (route.points.size() < 2) {
 
  379   auto start = window_start;
 
  381   auto end = window_end;
 
  386   if (
start.index == end.index && 
start.distance == end.distance) {
 
  393   size_t start_index = 
start.index;
 
  394   size_t end_index = end.index;
 
  397   if ((end_index < start_index) ||
 
  398       (start_index == end_index && end.distance < 
start.distance)) {
 
  399     std::swap(end, 
start);
 
  400     std::swap(start_index, end_index);
 
  406   if (start_index+1 == route.points.size()) {
 
  411   if (end_index+1 == route.points.size()) {
 
  420   if (start_index == end_index) {
 
  421     double distance_from_line;
 
  422     double distance_on_line;
 
  431     if (distance_on_line < 
start.distance) {
 
  432       distance_on_line = 
start.distance;
 
  433     } 
else if (distance_on_line > end.distance) {
 
  434       distance_on_line = end.distance;
 
  437     marti_nav_msgs::PlanPosition denormal_position;
 
  438     denormal_position.index = 
start.index;
 
  439     denormal_position.distance = distance_on_line;
 
  440     position = denormal_position;
 
  449   double min_distance_from_line = std::numeric_limits<double>::infinity();
 
  450   double min_distance_on_line = std::numeric_limits<double>::infinity();
 
  451   size_t min_segment_index = 0;
 
  453   for (
size_t i = start_index; i <= end_index; ++i) {
 
  454     double distance_from_line;
 
  455     double distance_on_line;
 
  464     if (distance_from_line <= min_distance_from_line) {
 
  465       min_segment_index = i;
 
  466       min_distance_on_line = distance_on_line;
 
  467       min_distance_from_line = distance_from_line;
 
  473   if (min_segment_index == start_index) {
 
  475                                  min_distance_on_line,
 
  480     if (min_distance_on_line < 
start.distance) {
 
  481       min_distance_on_line = 
start.distance;
 
  483   } 
else if (min_segment_index == end_index) {
 
  485                                  min_distance_on_line,
 
  490     if (min_distance_on_line > end.distance) {
 
  491       min_distance_on_line = end.distance;
 
  495   marti_nav_msgs::PlanPosition denormal_position;
 
  496   denormal_position.index = min_segment_index;
 
  497   denormal_position.distance = min_distance_on_line;
 
  498   position = denormal_position;
 
  506   const marti_nav_msgs::PlanPosition &start,
 
  507   const marti_nav_msgs::PlanPosition &end,
 
  508   const mnm::Plan &route)
 
  510   size_t start_index = 
start.index;
 
  511   size_t end_index = end.index;
 
  513   size_t min_index = std::min(start_index, end_index);
 
  514   size_t max_index = std::max(start_index, end_index);
 
  517   if (route.header.frame_id == stu::_wgs84_frame) {
 
  518     for (
size_t i = min_index; i < max_index; i++) {
 
  522     for (
size_t i = min_index; i < max_index; i++) {
 
  527   if (end_index < start_index) {
 
  531   distance = 
d + end.distance - 
start.distance;
 
  536                  const marti_nav_msgs::PlanPosition position,
 
  537                  marti_nav_msgs::PlanPoint& pt,
 
  540   auto npos = position;
 
  543   if (npos.distance == 0.0 || npos.index == path.points.size() - 1)
 
  545     pt = path.points[npos.index];
 
  549   auto& 
start = path.points[npos.index];
 
  550   auto& end = path.points[npos.index+1];
 
  552   double distance = std::sqrt(std::pow(
start.x - end.x, 2.0) + std::pow(
start.y - end.y, 2.0));
 
  553   double frac = npos.distance/distance;
 
  557     frac = std::min(1.0, frac);
 
  558     frac = std::max(0.0, frac);
 
  562   pt.x = 
start.x*(1.0 - frac) + end.x*frac;
 
  563   pt.y = 
start.y*(1.0 - frac) + end.y*frac;
 
  564   pt.z = 
start.z*(1.0 - frac) + end.z*frac;
 
  569                      const marti_nav_msgs::PlanPosition position,
 
  573   auto npos = position;
 
  576   if (npos.distance == 0.0 || npos.index == path.points.size() - 1)
 
  578     auto& point = path.points[npos.index];
 
  579     pos = tf::Vector3(point.x, point.y, 0.0);
 
  583   auto& 
start = path.points[npos.index];
 
  584   auto& end = path.points[npos.index+1];
 
  586   double distance = std::sqrt(std::pow(
start.x - end.x, 2.0) + std::pow(
start.y - end.y, 2.0));
 
  587   double frac = npos.distance/distance;
 
  591     frac = std::min(1.0, frac);
 
  592     frac = std::max(0.0, frac);
 
  595   pos = tf::Vector3(
start.x*(1.0 - frac) + end.x*frac,
 
  596                     start.y*(1.0 - frac) + end.y*frac,
 
  597                     start.z*(1.0 - frac) + end.z*frac);