util.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2016, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 #include <swri_route_util/util.h>
00030 #include <swri_route_util/route.h>
00031 #include <swri_route_util/route_point.h>
00032 
00033 #include <swri_transform_util/frames.h>
00034 #include <swri_transform_util/transform_util.h>
00035 
00036 namespace mnm = marti_nav_msgs;
00037 namespace stu = swri_transform_util;
00038 
00039 namespace swri_route_util
00040 {
00041 void transform(Route &route,
00042                const stu::Transform &transform,
00043                const std::string &target_frame)
00044 {
00045   for (auto &point : route.points) {
00046     point.setPosition(transform*point.position());
00047     point.setOrientation(transform*point.orientation());
00048   }
00049   route.header.frame_id = target_frame;
00050 }
00051 
00052 void projectToXY(Route &route)
00053 {
00054   for (auto &point : route.points) {
00055     point.position().setZ(0.0);
00056     // todo(exjohnson): if orientation is valid, project it to a
00057     // rotation around the Z axis only.
00058   }
00059 }
00060 
00061 void fillOrientations(Route &route, const tf::Vector3 &up)
00062 {
00063   // We can't estimate any orientations for 0 or 1 points.
00064   if (route.points.size() < 2) {
00065     return;
00066   }
00067 
00068   std::vector<size_t> degenerate_orientations;
00069 
00070   for (size_t i = 0; i < route.points.size(); ++i) {
00071     // We're going to estimate the orientation by the center difference using
00072     // the vector from the previous point to the next point in the route. This
00073     // assumes that the points are evenly spaced, but it is a reasonable
00074     // estimate even if they are not.
00075     tf::Vector3 v_forward;
00076     if (i == 0) {
00077       // For the first point, we use the forward difference
00078       v_forward = route.points[i+1].position() - route.points[i+0].position();
00079     } else if (i+1 == route.points.size()) {
00080       // For the last point, we use the backward difference
00081       v_forward = route.points[i+0].position() - route.points[i-1].position();
00082     } else {
00083       v_forward = route.points[i+1].position() - route.points[i-1].position();
00084     }
00085 
00086     v_forward.normalize();
00087 
00088     // Y = Z x X
00089     tf::Vector3 v_left = up.cross(v_forward);
00090     // Since Z and X are not necessarily orthogonal, we need to normalize this
00091     // to get a unit vector.  This is where we'll have problems if our
00092     // v_forward happens to be really closely aligned with the up
00093     // axis.  We ignore that.
00094     v_left.normalize();
00095 
00096     if (std::isnan(v_left.x()))
00097     {
00098       // This should catch issues with repeated route points, and co-linear
00099       // v_forward and up vectors (though the latter should never happen)
00100       degenerate_orientations.push_back(i);
00101     }
00102 
00103 
00104     // We now have left unit vector that is perpendicular to the
00105     // forward unit vector, so we can find our actual up vector, which
00106     // should be in the plane spanned by v_forward and the user
00107     // provided up direction.
00108     tf::Vector3 v_up = v_forward.cross(v_left);
00109     // We shouldn't need to normalize v_up, but it's good practice
00110     // since I don't know if the Matrix3x3 handles errors well.
00111     v_up.normalize();
00112 
00113     // Don't understand why Matrix3x3 doesn't have a constructor for 3
00114     // vectors.
00115     tf::Matrix3x3 rotation(
00116       v_forward.x(), v_left.x(), v_up.x(),
00117       v_forward.y(), v_left.y(), v_up.y(),
00118       v_forward.z(), v_left.z(), v_up.z());
00119 
00120     // Finally we can extract the orientation as a quaternion from the
00121     // matrix.
00122     tf::Quaternion orientation;
00123     rotation.getRotation(orientation);
00124     route.points[i].setOrientation(orientation);
00125 
00126     // There is probably a simpler, more elegant way to do this.
00127   }
00128 
00129   // If there are any degenerate orientations, assign the same orientation as
00130   // the nearest neighbor. There is probably a better way to do this.
00131   for (size_t i = 0; i < degenerate_orientations.size(); ++i)
00132   {
00133     size_t d_idx = degenerate_orientations[i];
00134     bool repaired_orientation = false;
00135     for (size_t j = 1; j < route.points.size(); ++j)
00136     {
00137       size_t up_idx = d_idx + j;
00138       int64_t down_idx = (int64_t)d_idx - (int64_t)j;
00139       if (up_idx < route.points.size())
00140       {
00141         if (std::find(degenerate_orientations.begin(), degenerate_orientations.end(), up_idx) == degenerate_orientations.end())
00142         {
00143           // Found a neighboring point with valid orientation.
00144           route.points[d_idx].setOrientation(route.points[up_idx].orientation());
00145           repaired_orientation = true;
00146           break;
00147         }
00148       }
00149 
00150       if (down_idx >= 0)
00151       {
00152         if (std::find(degenerate_orientations.begin(), degenerate_orientations.end(), down_idx) == degenerate_orientations.end())
00153         {
00154           // Found a neighboring point with valid orientation.
00155           route.points[d_idx].setOrientation(route.points[down_idx].orientation());
00156           repaired_orientation = true;
00157           break;
00158         }
00159       }
00160     }
00161 
00162     if (!repaired_orientation)
00163     {
00164       ROS_ERROR_THROTTLE(1.0, "fillOrientations was unable to repair an invalid "
00165                         "orientation. The route may be malformed.");
00166     }
00167     else
00168     {
00169       ROS_WARN_THROTTLE(1.0, "fillOrientations found and repaired an invalid "
00170                         "orientation. Note that the source route may contain "
00171                         "repeated points.");
00172     }
00173   }
00174 }
00175 
00176 // This is a private helper function that finds the nearest distance
00177 // between a point p and the line segment defined by p0 ad p1.  It
00178 // also returns the distance along the segment to the point that is
00179 // nearest to p.  If extrapolate_start/extrapolate_end are true, the
00180 // calculation considers the line segment to extend infinitely in the
00181 // corresponding directions.
00182 static
00183 void nearestDistanceToLineSegment(
00184   double &min_distance_from_line,
00185   double &min_distance_on_line,
00186   const tf::Vector3 &p0,
00187   const tf::Vector3 &p1,
00188   const tf::Vector3 &p,
00189   bool extrapolate_start,
00190   bool extrapolate_end)
00191 {
00192   tf::Vector3 v = p1 - p0;
00193   const double v_len_sq = v.dot(v);
00194 
00195   // s will be the normalized distance along v that is closest to the
00196   // desired point.
00197   double s = 0.0;
00198   if (v_len_sq > 1e-6) {
00199     s = v.dot(p - p0) / v_len_sq;
00200   } else {
00201     // The two points are too close to define a reasonable line
00202     // segment, so just pick p1 as the closest point.
00203     s = 1.0;
00204   }
00205 
00206   // If we don't allow extrapolation and the nearest point is beyond
00207   // the line segment boundaries, we need to clamp to the boundary.
00208   if (!extrapolate_start && s < 0.0) {
00209     s = 0.0;
00210   } else if (!extrapolate_end && s > 1.0) {
00211     s = 1.0;
00212   }
00213 
00214   tf::Vector3 x_nearest = p0 + s*v;
00215 
00216   min_distance_from_line = x_nearest.distance(p);
00217   min_distance_on_line = s*std::sqrt(v_len_sq);
00218 }
00219 
00220 bool projectOntoRoute(mnm::RoutePosition &position,
00221                       const Route &route,
00222                       const tf::Vector3 &point,
00223                       bool extrapolate_before_start,
00224                       bool extrapolate_past_end)
00225 {
00226   if (route.points.size() == 0) {
00227     // We can't do anything with this.
00228     return false;
00229   }
00230 
00231   if (route.points.size() == 1) {
00232     // We can't do much with this.
00233     position.route_id = route.guid();
00234     position.id = route.points[0].id();
00235     position.distance = 0.0;
00236     return true;
00237   }
00238 
00239   // First we find the nearest point on the route, without allowing
00240   // extrapolation.
00241   double min_distance_from_line = std::numeric_limits<double>::infinity();
00242   double min_distance_on_line = std::numeric_limits<double>::infinity();
00243   size_t min_segment_index = 0;
00244 
00245   for (size_t i = 0; i+1 < route.points.size(); ++i) {
00246     double distance_from_line;
00247     double distance_on_line;
00248 
00249     nearestDistanceToLineSegment(distance_from_line,
00250                                  distance_on_line,
00251                                  route.points[i+0].position(),
00252                                  route.points[i+1].position(),
00253                                  point,
00254                                  false, false);
00255 
00256     if (distance_from_line <= min_distance_from_line) {
00257       min_segment_index = i;
00258       min_distance_on_line = distance_on_line;
00259       min_distance_from_line = distance_from_line;
00260     }
00261   }
00262 
00263   // If the nearest segment is the first or last segment, we redo
00264   // the search while allowing the segment to be extrapolated
00265   // backward or forward, respectively.  This allows graceful
00266   // operation if the vehicle is past the boundary of the route.
00267 
00268   if (extrapolate_before_start && min_segment_index == 0) {
00269     size_t i = 0;
00270     nearestDistanceToLineSegment(min_distance_from_line,
00271                                  min_distance_on_line,
00272                                  route.points[i+0].position(),
00273                                  route.points[i+1].position(),
00274                                  point,
00275                                  true, false);
00276   } else if (min_segment_index + 2 == route.points.size()) {
00277     // The end of the route is a special case.  If we go past the end,
00278     // we want to return a position with the id of the last point and
00279     // the distance past it.  This annoying complicates things in a
00280     // number of places, but makes it easy to check if a point is past
00281     // the end of a route.
00282     size_t i = min_segment_index;
00283     nearestDistanceToLineSegment(min_distance_from_line,
00284                                  min_distance_on_line,
00285                                  route.points[i+0].position(),
00286                                  route.points[i+1].position(),
00287                                  point,
00288                                  false, true);
00289 
00290     double last_length = (route.points[i+1].position() - route.points[i+0].position()).length();
00291     if (min_distance_on_line > last_length) {
00292       min_segment_index++;
00293       min_distance_on_line -= last_length;
00294     }
00295 
00296     if (!extrapolate_past_end) {
00297       min_distance_on_line = 0.0;
00298     }
00299   }
00300 
00301   position.route_id = route.guid();
00302   position.id = route.points[min_segment_index].id();
00303   position.distance = min_distance_on_line;
00304   return true;
00305 }
00306 
00307 bool projectOntoRouteWindow(
00308   mnm::RoutePosition &position,
00309   const Route &route,
00310   const tf::Vector3 &point,
00311   const mnm::RoutePosition &window_start,
00312   const mnm::RoutePosition &window_end)
00313 {
00314   if (route.points.size() < 2) {
00315     // We can't do anything with this.
00316     return false;
00317   }
00318 
00319   // First we normalize the window boundaries.
00320   mnm::RoutePosition start;
00321   if (!normalizeRoutePosition(start, route, window_start)) {
00322     return false;
00323   }
00324   mnm::RoutePosition end;
00325   if (!normalizeRoutePosition(end, route, window_end)) {
00326     return false;
00327   }
00328 
00329   // Handle the special case where the start and end points are
00330   // identical.
00331   if (start.id == end.id && start.distance == end.distance) {
00332     position.route_id = route.guid();
00333     position = start;
00334     return true;
00335   }
00336 
00337   // Find the indices of the start and end points.  Since we have
00338   // normalized positions, we know they exist in the route.
00339   size_t start_index;
00340   route.findPointId(start_index, start.id);
00341   size_t end_index;
00342   route.findPointId(end_index, end.id);
00343 
00344   // Fix the ordering so that start comes before end.
00345   if ((end_index < start_index) ||
00346       (start_index == end_index && end.distance < start.distance)) {
00347     std::swap(end, start);
00348     std::swap(start_index, end_index);
00349   }
00350 
00351   // If either of the points are past the end of the route, we want to
00352   // back them up to the previous segment to reduce the number of
00353   // special cases we have to handle.
00354   if (start_index+1 == route.points.size()) {
00355     start_index -= 1;
00356     start.id = route.points[start_index].id();
00357     start.distance += (route.points[start_index+1].position() -
00358                        route.points[start_index+0].position()).length();
00359   }
00360   if (end_index+1 == route.points.size()) {
00361     end_index -= 1;
00362     end.id = route.points[end_index].id();
00363     end.distance += (route.points[end_index+1].position() -
00364                      route.points[end_index+0].position()).length();
00365   }
00366 
00367   // Although it causes a little duplication, it's easier over all to
00368   // explicitly handle the special case where the window is over a
00369   // single segment.
00370   if (start_index == end_index) {
00371     double distance_from_line;
00372     double distance_on_line;
00373 
00374     nearestDistanceToLineSegment(distance_from_line,
00375                                  distance_on_line,
00376                                  route.points[start_index+0].position(),
00377                                  route.points[start_index+1].position(),
00378                                  point,
00379                                  true, true);
00380 
00381     if (distance_on_line < start.distance) {
00382       distance_on_line = start.distance;
00383     } else if (distance_on_line > end.distance) {
00384       distance_on_line = end.distance;
00385     }
00386 
00387     mnm::RoutePosition denormal_position;
00388     denormal_position.id = start.id;
00389     denormal_position.distance = distance_on_line;
00390     if (!normalizeRoutePosition(position, route, denormal_position)) {
00391       return false;
00392     }
00393 
00394     position.route_id = route.guid();
00395     return true;
00396   }
00397 
00398   // Find the nearest point on the route, without allowing
00399   // extrapolation.
00400   double min_distance_from_line = std::numeric_limits<double>::infinity();
00401   double min_distance_on_line = std::numeric_limits<double>::infinity();
00402   size_t min_segment_index = 0;
00403 
00404   for (size_t i = start_index; i <= end_index; ++i) {
00405     double distance_from_line;
00406     double distance_on_line;
00407 
00408     nearestDistanceToLineSegment(distance_from_line,
00409                                  distance_on_line,
00410                                  route.points[i+0].position(),
00411                                  route.points[i+1].position(),
00412                                  point,
00413                                  false, false);
00414 
00415     if (distance_from_line <= min_distance_from_line) {
00416       min_segment_index = i;
00417       min_distance_on_line = distance_on_line;
00418       min_distance_from_line = distance_from_line;
00419     }
00420   }
00421 
00422   // We have identified the closest segment.  We need to clamp it
00423   // to the window boundaries.
00424   if (min_segment_index == start_index) {
00425     nearestDistanceToLineSegment(min_distance_from_line,
00426                                  min_distance_on_line,
00427                                  route.points[min_segment_index+0].position(),
00428                                  route.points[min_segment_index+1].position(),
00429                                  point,
00430                                  true, false);
00431     if (min_distance_on_line < start.distance) {
00432       min_distance_on_line = start.distance;
00433     }
00434   } else if (min_segment_index == end_index) {
00435     nearestDistanceToLineSegment(min_distance_from_line,
00436                                  min_distance_on_line,
00437                                  route.points[min_segment_index+0].position(),
00438                                  route.points[min_segment_index+1].position(),
00439                                  point,
00440                                  false, true);
00441     if (min_distance_on_line > end.distance) {
00442       min_distance_on_line = end.distance;
00443     }
00444   }
00445 
00446   mnm::RoutePosition denormal_position;
00447   denormal_position.id = route.points[min_segment_index].id();
00448   denormal_position.distance = min_distance_on_line;
00449   if (!normalizeRoutePosition(position, route, denormal_position)) {
00450     return false;
00451   }
00452 
00453   position.route_id = route.guid();
00454   return true;
00455 }
00456 
00457 static
00458 void interpolateRouteSegment(
00459   RoutePoint &dst,
00460   const RoutePoint &p0,
00461   const RoutePoint &p1,
00462   double distance)
00463 {
00464   double len = (p0.position()-p1.position()).length();
00465 
00466   double s;
00467   if (len > 1e-6) {
00468     s = distance / len;
00469   } else {
00470     // This is a degenerate case where the points are too close
00471     // together to define a numerically stable route point.
00472     if (distance < 0) {
00473       // If the distance is negative, the interpolated value will be
00474       // the first route point.
00475       s = 0.0;
00476     } else if (distance > 1) {
00477       // If the distance is positive, the interpolated value will be
00478       // the second route point.
00479       s = 1.0;
00480     } else {
00481       // Otherwise just take the center of the two points.
00482       s = 0.5;
00483     }
00484   }
00485 
00486   dst.setPosition((1.0-s)*p0.position() + s*p1.position());
00487   dst.setOrientation(p0.orientation().slerp(p1.orientation(), s));
00488 
00489   // Interpolate other known properties here.
00490 }
00491 
00492 bool normalizeRoutePosition(mnm::RoutePosition &normalized_position,
00493                             const Route &route,
00494                             const mnm::RoutePosition &position)
00495 {
00496   size_t index;
00497   if (!route.findPointId(index, position.id)) {
00498     return false;
00499   }
00500 
00501   double distance = position.distance;
00502   while (distance < 0.0) {
00503     // We can't go past the start of the route.
00504     if (index == 0) {
00505       break;
00506     }
00507 
00508     // The distance is still negative, so we can't be on this
00509     // segment.  Move to the preceding segment.
00510     distance += (route.points[index-0].position() -
00511                  route.points[index-1].position()).length();
00512     index--;
00513   }
00514 
00515   while (distance > 0.0) {
00516     // We can't go past the end of the route.
00517     if (index+1 == route.points.size()) {
00518       break;
00519     }
00520 
00521     double segment_length = (route.points[index+0].position() -
00522                              route.points[index+1].position()).length();
00523     if (distance > segment_length) {
00524       // The distance is greater than this segment length, so we're
00525       // not on this segment.  Move to the following segment.
00526       distance -= segment_length;
00527       index++;
00528     } else {
00529       // The distance is within the length of this segment, so the
00530       // point is on this segment.
00531       break;
00532     }
00533   }
00534 
00535   normalized_position.route_id = position.route_id;
00536   normalized_position.distance = distance;
00537   normalized_position.id = route.points[index].id();
00538   return true;
00539 }
00540 
00541 
00542 bool interpolateRoutePosition(RoutePoint &dst,
00543                               const Route &route,
00544                               const mnm::RoutePosition &position,
00545                               bool allow_extrapolation)
00546 {
00547   mnm::RoutePosition norm_position;
00548   if (!normalizeRoutePosition(norm_position, route, position)) {
00549     return false;
00550   }
00551 
00552   // Since we have a normalized position, we know it exists in the route.
00553   size_t index;
00554   route.findPointId(index, norm_position.id);
00555 
00556   // Special case when the point is before the start of the route.
00557   if (index == 0 && norm_position.distance < 0.0) {
00558     if (!allow_extrapolation) {
00559       return false;
00560     }
00561 
00562     if (route.points.size() < 2) {
00563       // This route point is before the start of the route and we
00564       // don't have enough information to extrapolate.
00565       return false;
00566     }
00567 
00568     interpolateRouteSegment(dst,
00569                             route.points[0],
00570                             route.points[1],
00571                             norm_position.distance);
00572     return true;
00573   }
00574 
00575   // Special case when the point is after the end of the route.
00576   if (index+1 == route.points.size() && norm_position.distance > 0.0) {
00577     if (!allow_extrapolation) {
00578       return false;
00579     }
00580     if (route.points.size() < 2) {
00581       // This route point is after the end of the route and we don't
00582       // have enough information to extrapolate.
00583       return false;
00584     }
00585 
00586     const RoutePoint &p0 = route.points[index-1];
00587     const RoutePoint &p1 = route.points[index-0];
00588     double extra_dist = (p1.position() - p0.position()).length();
00589 
00590     interpolateRouteSegment(dst,
00591                             p0,
00592                             p1,
00593                             norm_position.distance + extra_dist);
00594     return true;
00595   }
00596 
00597   interpolateRouteSegment(dst,
00598                           route.points[index+0],
00599                           route.points[index+1],
00600                           norm_position.distance);
00601   return true;
00602 }
00603 
00604 bool routeDistance(
00605   double &distance,
00606   const mnm::RoutePosition &start,
00607   const mnm::RoutePosition &end,
00608   const Route &route)
00609 {
00610   size_t start_index;
00611   if (!route.findPointId(start_index, start.id)) {
00612     return false;
00613   }
00614 
00615   size_t end_index;
00616   if (!route.findPointId(end_index, end.id)) {
00617     return false;
00618   }
00619 
00620   size_t min_index = std::min(start_index, end_index);
00621   size_t max_index = std::max(start_index, end_index);
00622 
00623   double d = 0.0;
00624   if (route.header.frame_id == stu::_wgs84_frame) {
00625     for (size_t i = min_index; i < max_index; i++) {
00626       d += stu::GreatCircleDistance(route.points[i+1].position(), route.points[i].position());
00627     }
00628   } else {
00629     for (size_t i = min_index; i < max_index; i++) {
00630       d += (route.points[i+1].position() - route.points[i].position()).length();
00631     }
00632   }
00633 
00634   if (end_index < start_index) {
00635     d = -d;
00636   }
00637 
00638   distance = d + end.distance - start.distance;
00639   return true;
00640 }
00641 
00642 bool routeDistances(
00643   std::vector<double> &distances,
00644   const mnm::RoutePosition &start,
00645   const std::vector<mnm::RoutePosition> &ends,
00646   const Route &route)
00647 {
00648   size_t start_index;
00649   if (!route.findPointId(start_index, start.id)) {
00650     // Without a start index, we can't calculate anything.
00651     return false;
00652   }
00653 
00654   // Find the indices for every point in the route, and the minimum
00655   // and maximum indices that we need to work over (the ROI).
00656   size_t min_index = start_index;
00657   size_t max_index = start_index;
00658   std::vector<int> indices;
00659   indices.resize(ends.size());
00660   for (size_t i = 0; i < ends.size(); ++i) {
00661     size_t pt_index;
00662     if (route.findPointId(pt_index, ends[i].id)) {
00663       indices[i] = pt_index;
00664       min_index = std::min(min_index, pt_index);
00665       max_index = std::max(max_index, pt_index);
00666     } else {
00667       indices[i] = -1;
00668     }
00669   }
00670 
00671   // This is the index of the start point in the ROI.
00672   const size_t roi_start_index = start_index - min_index;
00673 
00674   // We calculate the arc length of each point in the ROI relative to
00675   // the start point.  This vector covers the ROI (so it corresponds
00676   // from min_index to max_index)
00677   std::vector<double> arc_lengths;
00678   arc_lengths.resize(max_index-min_index+1);
00679 
00680   arc_lengths[roi_start_index] = 0.0;
00681   if (route.header.frame_id == stu::_wgs84_frame) {
00682     // Calculate the lengths before the start point.
00683     for (size_t rev_i = 1; rev_i <= roi_start_index; ++rev_i) {
00684       const size_t i = roi_start_index - rev_i;
00685       const tf::Vector3 pt1 = route.points[min_index+i].position();
00686       const tf::Vector3 pt2 = route.points[min_index+i+1].position();
00687       arc_lengths[i] = arc_lengths[i+1] - stu::GreatCircleDistance(pt1, pt2);
00688     }
00689     // Calculate the lengths after the start point.
00690     for (size_t i = roi_start_index+1; i < arc_lengths.size(); ++i) {
00691       const tf::Vector3 pt1 = route.points[min_index+i].position();
00692       const tf::Vector3 pt2 = route.points[min_index+i-1].position();
00693       arc_lengths[i] = arc_lengths[i-1] + stu::GreatCircleDistance(pt1, pt2);
00694     }
00695   } else {
00696     // Assume Euclidean coordinates.
00697     // Calculate the lengths before the start point.
00698     for (size_t rev_i = 1; rev_i <= roi_start_index; ++rev_i) {
00699       const size_t i = roi_start_index - rev_i;
00700       const tf::Vector3 pt1 = route.points[min_index+i].position();
00701       const tf::Vector3 pt2 = route.points[min_index+i+1].position();
00702       arc_lengths[i] = arc_lengths[i+1] - (pt2-pt1).length();
00703     }
00704     // Calculate the lengths after the start point.
00705     for (size_t i = roi_start_index+1; i < arc_lengths.size(); ++i) {
00706       const tf::Vector3 pt1 = route.points[min_index+i].position();
00707       const tf::Vector3 pt2 = route.points[min_index+i-1].position();
00708       arc_lengths[i] = arc_lengths[i-1] + (pt2-pt1).length();
00709     }
00710   }
00711 
00712   // Now we can calculate the distances.
00713   distances.resize(ends.size());
00714   for (size_t i = 0; i < distances.size(); ++i) {
00715     if (indices[i] < 0) {
00716       distances[i] = std::numeric_limits<double>::quiet_NaN();
00717       continue;
00718     }
00719 
00720     const size_t cache_index = indices[i]-min_index;
00721     distances[i] = arc_lengths[cache_index] + ends[i].distance - start.distance;
00722   }
00723 
00724   return true;
00725 }
00726 
00727 bool extractSubroute(
00728   Route &sub_route,
00729   const Route &route,
00730   const marti_nav_msgs::RoutePosition &start,
00731   const marti_nav_msgs::RoutePosition &end)
00732 {
00733   sub_route.header = route.header;
00734   sub_route.properties_ = route.properties_;
00735   sub_route.guid_ = route.guid_;
00736   sub_route.name_ = route.name_;
00737 
00738   mnm::RoutePosition norm_start;
00739   if (!normalizeRoutePosition(norm_start, route, start)) {
00740     return false;
00741   }
00742 
00743   mnm::RoutePosition norm_end;
00744   if (!normalizeRoutePosition(norm_end, route, end)) {
00745     return false;
00746   }
00747 
00748   // Since we have a normalized position, we know it exists in the route.
00749   size_t start_index;
00750   route.findPointId(start_index, norm_start.id);
00751 
00752   size_t end_index;
00753   route.findPointId(end_index, norm_end.id);
00754 
00755   // If the end distance is after the id point, round up to the next
00756   // point.
00757   if (norm_end.distance > 0.0) {
00758     end_index += 1;
00759   }
00760 
00761   // Increment the end_index so that we can iterate from [start, end),
00762   // and make sure we stay within the array bounds.
00763   end_index++;
00764   end_index = std::min(end_index, route.points.size());
00765 
00766   if (end_index <= start_index)
00767   {
00768     sub_route.points.clear();
00769     sub_route.rebuildPointIndex();
00770     return true;
00771   }
00772 
00773   sub_route.points.reserve(end_index - start_index);
00774   for (size_t i = start_index; i < end_index; i++) {
00775     sub_route.points.push_back(route.points[i]);
00776   }
00777   sub_route.rebuildPointIndex();
00778 
00779   return true;
00780 }
00781 }  // namespace swri_route_util


swri_route_util
Author(s):
autogenerated on Thu Jun 6 2019 20:35:04