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;
 
   62   if (path.points.size() < 2) {
 
   67   for (
size_t i = 0; i + 1 < path.points.size(); i++)
 
   69     marti_nav_msgs::PathPoint& pt = path.points[i];
 
   70     const marti_nav_msgs::PathPoint& next_pt = path.points[i+1];
 
   86   path.points.back().yaw = path.points[path.points.size() - 2].yaw;
 
   91     const marti_nav_msgs::Path& path,
 
   92     const double x, 
const double y,
 
   94     double& nearest_separation)
 
   97   size_t num_points = path.points.size();
 
  102   else if (num_points == 1)
 
  104     nearest_position.
index = 0;
 
  106     nearest_separation = std::sqrt(std::pow(path.points[0].x - x, 2.0) +
 
  107                                    std::pow(path.points[0].y - y, 2.0));
 
  111   cv::Vec2d point(x, y);
 
  114   double min_separation_sqr = std::numeric_limits<double>::infinity();
 
  115   for (
size_t i = 0; i + 1 < num_points; i++)
 
  117     auto& 
start = path.points[i];
 
  118     auto& end = path.points[i+1];
 
  121                                                               cv::Vec2d(end.x, end.y),
 
  124     double separation_sqr = std::pow(x - proj[0], 2.0) + std::pow(y - proj[1], 2.0);
 
  125     if (separation_sqr <= min_separation_sqr)
 
  127       min_separation_sqr = separation_sqr;
 
  128       nearest_position.
index = i;
 
  129       nearest_position.
distance = std::sqrt(std::pow(
start.x - proj[0], 2.0) +
 
  130                                             std::pow(
start.y - proj[1], 2.0));
 
  134     if (separation_sqr > 2.0*min_separation_sqr)
 
  140   nearest_separation = std::sqrt(min_separation_sqr);
 
  149   if (position.
index > path.points.size() - 1)
 
  152     position.
index = path.points.size() - 1;
 
  156   double distance = position.
distance;
 
  157   size_t index = position.
index;
 
  158   while (distance < 0.0)
 
  166     auto& 
s = path.points[index];
 
  167     auto& e = path.points[index-1];
 
  168     double len = std::sqrt(std::pow(
s.x - e.x, 2.0) +
 
  169                            std::pow(
s.y - e.y, 2.0));
 
  170     if (-distance >= len)
 
  181   while (distance > 0.0)
 
  183     if (index+1 == path.points.size())
 
  188     auto& 
s = path.points[index];
 
  189     auto& e = path.points[index+1];
 
  190     double len = std::sqrt(std::pow(
s.x - e.x, 2.0) +
 
  191                            std::pow(
s.y - e.y, 2.0));
 
  203   position.
index = index;
 
  209   from = std::fmod(from + M_PI*2.0, M_PI*2.0);
 
  210   to = std::fmod(to + M_PI*2.0, M_PI*2.0);
 
  211   double diff = std::abs(from - to);
 
  214     return from*(1.0-t) + to*t;
 
  219     return from*(1.0-t) + to*t;
 
  224     return from*(1.0-t) + to*t;
 
  235   if (npos.
distance == 0.0 || npos.
index == path.points.size() - 1)
 
  237     auto& point = path.points[npos.
index];
 
  238     pos = tf::Vector3(point.x, point.y, 0.0);
 
  243   auto& end = path.points[npos.
index+1];
 
  245   double distance = std::sqrt(std::pow(
start.x - end.x, 2.0) + std::pow(
start.y - end.y, 2.0));
 
  246   double frac = npos.
distance/distance;
 
  248   pos = tf::Vector3(
start.x*(1.0 - frac) + end.x*frac,
 
  249                   start.y*(1.0 - frac) + end.y*frac,
 
  256                  const bool allow_extrapolation)
 
  261   if (npos.
distance == 0.0 || npos.
index == path.points.size() - 1)
 
  263     if (npos.
index == path.points.size() - 1 && npos.
distance > 0.0
 
  264         && path.points.size() > 1 
 
  265         && allow_extrapolation)
 
  269       auto& prev = path.points[npos.
index-1];
 
  272       tf::Vector3 dir = tf::Vector3(
start.x-prev.x, 
start.y-prev.y, 0.0).normalized();
 
  278     auto& point = path.points[npos.
index];
 
  280                          tf::Vector3(point.x, point.y, 0.0));
 
  285   auto& end = path.points[npos.
index+1];
 
  287   double distance = std::sqrt(std::pow(
start.x - end.x, 2.0) + std::pow(
start.y - end.y, 2.0));
 
  288   double frac = npos.
distance/distance;
 
  290   tf::Vector3 pos(
start.x*(1.0 - frac) + end.x*frac,
 
  291                   start.y*(1.0 - frac) + end.y*frac,