plan_util.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2021, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
30 
33 
35 
36 namespace mnm = marti_nav_msgs;
37 namespace stu = swri_transform_util;
38 
39 namespace swri_route_util
40 {
41 
42 void transform(marti_nav_msgs::Plan &path,
44  const std::string &target_frame)
45 {
46  for (auto &point : path.points) {
47  tf::Vector3 position(point.x, point.y, 0.0);
48  position = transform*position;
49 
50  point.x = position.x();
51  point.y = position.y();
52 
54  point.yaw = tf::getYaw(transform*q);
55  }
56  path.header.frame_id = target_frame;
57 }
58 
59 void projectToXY(marti_nav_msgs::Plan &route)
60 {
61  for (auto &point : route.points) {
62  point.z = 0.0;
63  // todo(exjohnson): if orientation is valid, project it to a
64  // rotation around the Z axis only.
65  }
66 }
67 
68 void fillOrientations(marti_nav_msgs::Plan &path)
69 {
70  // We can't estimate any orientations for 0 or 1 points.
71  if (path.points.size() < 2) {
72  return;
73  }
74 
75  double yaw;
76  for (size_t i = 0; i + 1 < path.points.size(); i++)
77  {
78  auto& pt = path.points[i];
79  const auto& next_pt = path.points[i+1];
80 
81  // Calculate yaw based on the direction between these points
82  yaw = atan2(
83  next_pt.y - pt.y,
84  next_pt.x - pt.x);
85 
86  if (pt.flags & marti_nav_msgs::PlanPoint::FLAG_REVERSE)
87  {
88  yaw += M_PI;
89  }
90 
91  pt.yaw = yaw;
92  }
93 
94  // fill in the last yaw
95  path.points.back().yaw = path.points[path.points.size() - 2].yaw;
96 }
97 
98 
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)
104 {
105  // Handle odd sizes
106  size_t num_points = path.points.size();
107  if (num_points == 0)
108  {
109  return false;
110  }
111  else if (num_points == 1)
112  {
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));
117  return true;
118  }
119 
120  cv::Vec2d point(x, y);
121 
122  // Find the nearest line segment from the beginning of the path
123  double min_separation_sqr = std::numeric_limits<double>::infinity();
124  for (size_t i = 0; i + 1 < num_points; i++)
125  {
126  auto& start = path.points[i];
127  auto& end = path.points[i+1];
128 
129  cv::Vec2d proj = swri_geometry_util::ProjectToLineSegment(cv::Vec2d(start.x, start.y),
130  cv::Vec2d(end.x, end.y),
131  point);
132 
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)
135  {
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));
140  }
141 
142  //if separation is increasing, local minima was found. stop the search
143  if (separation_sqr > 2.0*min_separation_sqr)
144  {
145  break;
146  }
147  }
148 
149  nearest_separation = std::sqrt(min_separation_sqr);
150 
151  return true;
152 }
153 
154 void normalizePlanPosition(marti_nav_msgs::PlanPosition& position,
155  const marti_nav_msgs::Plan& path)
156 {
157  // handle being past the end of the route
158  if (position.index > path.points.size() - 1)
159  {
160  position.distance = 0.0;
161  position.index = path.points.size() - 1;
162  return;
163  }
164 
165  double distance = position.distance;
166  size_t index = position.index;
167  while (distance < 0.0)
168  {
169  if (index == 0)
170  {
171  distance = 0.0;// cant be before start
172  break;
173  }
174 
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)
180  {
181  distance += len;
182  index--;
183  }
184  else
185  {
186  break;
187  }
188  }
189 
190  while (distance > 0.0)
191  {
192  if (index+1 == path.points.size())
193  {
194  break;
195  }
196 
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));
201  if (distance >= len)
202  {
203  distance -= len;
204  index++;
205  }
206  else
207  {
208  break;
209  }
210  }
211 
212  position.index = index;
213  position.distance = distance;
214 }
215 
216 static double interpolateAngle(double from, double to, double t)
217 {
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);
221  if (diff < M_PI)
222  {
223  return from*(1.0-t) + to*t;
224  }
225  else if (from > to)
226  {
227  from -= M_PI*2.0;
228  return from*(1.0-t) + to*t;
229  }
230  else
231  {
232  to -= M_PI*2.0;
233  return from*(1.0-t) + to*t;
234  }
235 }
236 
237 // This is a private helper function that finds the nearest distance
238 // between a point p and the line segment defined by p0 ad p1. It
239 // also returns the distance along the segment to the point that is
240 // nearest to p. If extrapolate_start/extrapolate_end are true, the
241 // calculation considers the line segment to extend infinitely in the
242 // corresponding directions.
243 static
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)
252 {
253  tf::Vector3 v = p1 - p0;
254  const double v_len_sq = v.dot(v);
255 
256  // s will be the normalized distance along v that is closest to the
257  // desired point.
258  double s = 0.0;
259  if (v_len_sq > 1e-6) {
260  s = v.dot(p - p0) / v_len_sq;
261  } else {
262  // The two points are too close to define a reasonable line
263  // segment, so just pick p1 as the closest point.
264  s = 1.0;
265  }
266 
267  // If we don't allow extrapolation and the nearest point is beyond
268  // the line segment boundaries, we need to clamp to the boundary.
269  if (!extrapolate_start && s < 0.0) {
270  s = 0.0;
271  } else if (!extrapolate_end && s > 1.0) {
272  s = 1.0;
273  }
274 
275  tf::Vector3 x_nearest = p0 + s*v;
276 
277  min_distance_from_line = x_nearest.distance(p);
278  min_distance_on_line = s*std::sqrt(v_len_sq);
279 }
280 
281 bool projectOntoPlan(mnm::PlanPosition &position,
282  const mnm::Plan &route,
283  const tf::Vector3 &point,
284  bool extrapolate_before_start,
285  bool extrapolate_past_end)
286 {
287  if (route.points.size() == 0) {
288  // We can't do anything with this.
289  return false;
290  }
291 
292  if (route.points.size() == 1) {
293  // We can't do much with this.
294  position.index = 0;
295  position.distance = 0.0;
296  return true;
297  }
298 
299  // First we find the nearest point on the route, without allowing
300  // extrapolation.
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;
304 
305  for (size_t i = 0; i+1 < route.points.size(); ++i) {
306  double distance_from_line;
307  double distance_on_line;
308 
309  nearestDistanceToLineSegment(distance_from_line,
310  distance_on_line,
311  getPointPosition(route.points[i+0]),
312  getPointPosition(route.points[i+1]),
313  point,
314  false, false);
315 
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;
320  }
321  }
322 
323  // If the nearest segment is the first or last segment, we redo
324  // the search while allowing the segment to be extrapolated
325  // backward or forward, respectively. This allows graceful
326  // operation if the vehicle is past the boundary of the route.
327 
328  if (extrapolate_before_start && min_segment_index == 0) {
329  size_t i = 0;
330  nearestDistanceToLineSegment(min_distance_from_line,
331  min_distance_on_line,
332  getPointPosition(route.points[i+0]),
333  getPointPosition(route.points[i+1]),
334  point,
335  true, false);
336  } else if (min_segment_index + 2 == route.points.size()) {
337  // The end of the route is a special case. If we go past the end,
338  // we want to return a position with the id of the last point and
339  // the distance past it. This annoying complicates things in a
340  // number of places, but makes it easy to check if a point is past
341  // the end of a route.
342  size_t i = min_segment_index;
343  nearestDistanceToLineSegment(min_distance_from_line,
344  min_distance_on_line,
345  getPointPosition(route.points[i+0]),
346  getPointPosition(route.points[i+1]),
347  point,
348  false, true);
349 
350  double last_length = (getPointPosition(route.points[i+1]) - getPointPosition(route.points[i+0])).length();
351  if (min_distance_on_line > last_length) {
352  min_segment_index++;
353  min_distance_on_line -= last_length;
354  }
355 
356  if (!extrapolate_past_end) {
357  min_distance_on_line = 0.0;
358  }
359  }
360 
361  position.index = min_segment_index;
362  position.distance = min_distance_on_line;
363  return true;
364 }
365 
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)
372 {
373  if (route.points.size() < 2) {
374  // We can't do anything with this.
375  return false;
376  }
377 
378  // First we normalize the window boundaries.
379  auto start = window_start;
381  auto end = window_end;
382  normalizePlanPosition(end, route);
383 
384  // Handle the special case where the start and end points are
385  // identical.
386  if (start.index == end.index && start.distance == end.distance) {
387  position = start;
388  return true;
389  }
390 
391  // Find the indices of the start and end points. Since we have
392  // normalized positions, we know they exist in the route.
393  size_t start_index = start.index;
394  size_t end_index = end.index;
395 
396  // Fix the ordering so that start comes before end.
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);
401  }
402 
403  // If either of the points are past the end of the route, we want to
404  // back them up to the previous segment to reduce the number of
405  // special cases we have to handle.
406  if (start_index+1 == route.points.size()) {
407  start_index -= 1;
408  start.distance += (getPointPosition(route.points[start_index+1]) -
409  getPointPosition(route.points[start_index+0])).length();
410  }
411  if (end_index+1 == route.points.size()) {
412  end_index -= 1;
413  end.distance += (getPointPosition(route.points[end_index+1]) -
414  getPointPosition(route.points[end_index+0])).length();
415  }
416 
417  // Although it causes a little duplication, it's easier over all to
418  // explicitly handle the special case where the window is over a
419  // single segment.
420  if (start_index == end_index) {
421  double distance_from_line;
422  double distance_on_line;
423 
424  nearestDistanceToLineSegment(distance_from_line,
425  distance_on_line,
426  getPointPosition(route.points[start_index+0]),
427  getPointPosition(route.points[start_index+1]),
428  point,
429  true, true);
430 
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;
435  }
436 
437  marti_nav_msgs::PlanPosition denormal_position;
438  denormal_position.index = start.index;
439  denormal_position.distance = distance_on_line;
440  position = denormal_position;
441  normalizePlanPosition(position, route);
442 
443  //position.route_id = route.guid();
444  return true;
445  }
446 
447  // Find the nearest point on the route, without allowing
448  // extrapolation.
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;
452 
453  for (size_t i = start_index; i <= end_index; ++i) {
454  double distance_from_line;
455  double distance_on_line;
456 
457  nearestDistanceToLineSegment(distance_from_line,
458  distance_on_line,
459  getPointPosition(route.points[i+0]),
460  getPointPosition(route.points[i+1]),
461  point,
462  false, false);
463 
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;
468  }
469  }
470 
471  // We have identified the closest segment. We need to clamp it
472  // to the window boundaries.
473  if (min_segment_index == start_index) {
474  nearestDistanceToLineSegment(min_distance_from_line,
475  min_distance_on_line,
476  getPointPosition(route.points[min_segment_index+0]),
477  getPointPosition(route.points[min_segment_index+1]),
478  point,
479  true, false);
480  if (min_distance_on_line < start.distance) {
481  min_distance_on_line = start.distance;
482  }
483  } else if (min_segment_index == end_index) {
484  nearestDistanceToLineSegment(min_distance_from_line,
485  min_distance_on_line,
486  getPointPosition(route.points[min_segment_index+0]),
487  getPointPosition(route.points[min_segment_index+1]),
488  point,
489  false, true);
490  if (min_distance_on_line > end.distance) {
491  min_distance_on_line = end.distance;
492  }
493  }
494 
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;
499  normalizePlanPosition(position, route);
500 
501  return true;
502 }
503 
505  double &distance,
506  const marti_nav_msgs::PlanPosition &start,
507  const marti_nav_msgs::PlanPosition &end,
508  const mnm::Plan &route)
509 {
510  size_t start_index = start.index;
511  size_t end_index = end.index;
512 
513  size_t min_index = std::min(start_index, end_index);
514  size_t max_index = std::max(start_index, end_index);
515 
516  double d = 0.0;
517  if (route.header.frame_id == stu::_wgs84_frame) {
518  for (size_t i = min_index; i < max_index; i++) {
519  d += stu::GreatCircleDistance(getPointPosition(route.points[i+1]), getPointPosition(route.points[i]));
520  }
521  } else {
522  for (size_t i = min_index; i < max_index; i++) {
523  d += (getPointPosition(route.points[i+1]) - getPointPosition(route.points[i])).length();
524  }
525  }
526 
527  if (end_index < start_index) {
528  d = -d;
529  }
530 
531  distance = d + end.distance - start.distance;
532  return true;
533 }
534 
535 void interpolatePlanPosition(const marti_nav_msgs::Plan& path,
536  const marti_nav_msgs::PlanPosition position,
537  marti_nav_msgs::PlanPoint& pt,
538  bool extrapolate)
539 {
540  auto npos = position;
541  normalizePlanPosition(npos, path);
542 
543  if (npos.distance == 0.0 || npos.index == path.points.size() - 1)
544  {
545  pt = path.points[npos.index];
546  return;
547  }
548 
549  auto& start = path.points[npos.index];
550  auto& end = path.points[npos.index+1];
551 
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;
554 
555  if (!extrapolate)
556  {
557  frac = std::min(1.0, frac);
558  frac = std::max(0.0, frac);
559  }
560 
561  pt = start;
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;
565  pt.yaw = interpolateAngle(start.yaw, end.yaw, frac);
566 }
567 
568 void getPlanPosition(const marti_nav_msgs::Plan& path,
569  const marti_nav_msgs::PlanPosition position,
570  tf::Vector3& pos,
571  bool extrapolate)
572 {
573  auto npos = position;
574  normalizePlanPosition(npos, path);
575 
576  if (npos.distance == 0.0 || npos.index == path.points.size() - 1)
577  {
578  auto& point = path.points[npos.index];
579  pos = tf::Vector3(point.x, point.y, 0.0);
580  return;
581  }
582 
583  auto& start = path.points[npos.index];
584  auto& end = path.points[npos.index+1];
585 
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;
588 
589  if (!extrapolate)
590  {
591  frac = std::min(1.0, frac);
592  frac = std::max(0.0, frac);
593  }
594 
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);
598 }
599 
600 } // namespace swri_route_util
tf::createQuaternionFromYaw
static Quaternion createQuaternionFromYaw(double yaw)
swri_route_util::normalizePlanPosition
void normalizePlanPosition(marti_nav_msgs::PlanPosition &position, const marti_nav_msgs::Plan &path)
Definition: plan_util.cpp:154
s
XmlRpcServer s
swri_route_util::projectOntoPlan
bool projectOntoPlan(marti_nav_msgs::PlanPosition &position, const marti_nav_msgs::Plan &route, const tf::Vector3 &point, bool extrapolate_before_start, bool extrapolate_past_end)
geometry_util.h
swri_route_util
Definition: path_util.h:35
swri_route_util::getPointPosition
tf::Vector3 getPointPosition(const marti_nav_msgs::PlanPoint &pt)
Definition: plan_util.h:89
frames.h
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
swri_route_util::transform
void transform(marti_nav_msgs::Path &path, const swri_transform_util::Transform &transform, const std::string &target_frame)
Definition: path_util.cpp:42
swri_route_util::projectOntoPlanWindow
bool projectOntoPlanWindow(marti_nav_msgs::PlanPosition &position, const marti_nav_msgs::Plan &route, const tf::Vector3 &point, const marti_nav_msgs::PlanPosition &window_start, const marti_nav_msgs::PlanPosition &window_end)
Definition: plan_util.cpp:366
transform_util.h
swri_transform_util
swri_transform_util::Transform
d
d
swri_route_util::fillOrientations
void fillOrientations(marti_nav_msgs::Path &path)
Definition: path_util.cpp:59
swri_geometry_util::ProjectToLineSegment
cv::Vec2d ProjectToLineSegment(const cv::Vec2d &line_start, const cv::Vec2d &line_end, const cv::Vec2d &point)
swri_route_util::projectToXY
void projectToXY(marti_nav_msgs::Plan &route)
Definition: plan_util.cpp:59
start
ROSCPP_DECL void start()
swri_route_util::interpolateAngle
static double interpolateAngle(double from, double to, double t)
Definition: path_util.cpp:207
swri_route_util::nearestDistanceToLineSegment
static void nearestDistanceToLineSegment(double &min_distance_from_line, double &min_distance_on_line, const tf::Vector3 &p0, const tf::Vector3 &p1, const tf::Vector3 &p, bool extrapolate_start, bool extrapolate_end)
Definition: plan_util.cpp:244
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
swri_route_util::getPlanPosition
void getPlanPosition(const marti_nav_msgs::Plan &path, const marti_nav_msgs::PlanPosition position, tf::Vector3 &tf, bool extrapolate=false)
Definition: plan_util.cpp:568
plan_util.h
swri_route_util::planDistance
bool planDistance(double &distance, const marti_nav_msgs::PlanPosition &start, const marti_nav_msgs::PlanPosition &end, const marti_nav_msgs::Plan &route)
swri_route_util::findLocalNearestDistanceForward
bool findLocalNearestDistanceForward(const marti_nav_msgs::Path &path, const double x, const double y, PathPosition &nearest_position, double &nearest_separation)
Definition: path_util.cpp:90
swri_route_util::interpolatePlanPosition
void interpolatePlanPosition(const marti_nav_msgs::Plan &path, const marti_nav_msgs::PlanPosition position, marti_nav_msgs::PlanPoint &pt, bool extrapolate=false)
Definition: plan_util.cpp:535
tf::Quaternion


swri_route_util
Author(s):
autogenerated on Tue Oct 3 2023 02:32:40