path_ops.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <nav_2d_utils/path_ops.h>
37 #include <cmath>
38 #include <vector>
39 
40 namespace nav_2d_utils
41 {
42 
43 double poseDistance(const geometry_msgs::Pose2D& pose0, const geometry_msgs::Pose2D& pose1)
44 {
45  return hypot(pose0.x - pose1.x, pose0.y - pose1.y);
46 }
47 
48 double getPlanLength(const nav_2d_msgs::Path2D& plan, const unsigned int start_index)
49 {
50  double length = 0.0;
51  for (unsigned int i = start_index + 1; i < plan.poses.size(); i++)
52  {
53  length += poseDistance(plan.poses[i - 1], plan.poses[i]);
54  }
55  return length;
56 }
57 
58 double getPlanLength(const nav_2d_msgs::Path2D& plan, const geometry_msgs::Pose2D& query_pose)
59 {
60  if (plan.poses.size() == 0) return 0.0;
61 
62  unsigned int closest_index = 0;
63  double closest_distance = poseDistance(plan.poses[0], query_pose);
64  for (unsigned int i = 1; i < plan.poses.size(); i++)
65  {
66  double distance = poseDistance(plan.poses[i], query_pose);
67  if (closest_distance > distance)
68  {
69  closest_index = i;
70  closest_distance = distance;
71  }
72  }
73  return getPlanLength(plan, closest_index);
74 }
75 
76 nav_2d_msgs::Path2D adjustPlanResolution(const nav_2d_msgs::Path2D& global_plan_in, double resolution)
77 {
78  nav_2d_msgs::Path2D global_plan_out;
79  global_plan_out.header = global_plan_in.header;
80  if (global_plan_in.poses.size() == 0)
81  {
82  return global_plan_out;
83  }
84 
85  geometry_msgs::Pose2D last = global_plan_in.poses[0];
86  global_plan_out.poses.push_back(last);
87 
88  double sq_resolution = resolution * resolution;
89 
90  for (unsigned int i = 1; i < global_plan_in.poses.size(); ++i)
91  {
92  geometry_msgs::Pose2D loop = global_plan_in.poses[i];
93  double sq_dist = (loop.x - last.x) * (loop.x - last.x) + (loop.y - last.y) * (loop.y - last.y);
94  if (sq_dist > sq_resolution)
95  {
96  // add points in-between
97  double diff = sqrt(sq_dist) - resolution;
98  double steps_double = ceil(diff / resolution) + 1.0;
99  int steps = static_cast<int>(steps_double);
100 
101  double delta_x = (loop.x - last.x) / steps_double;
102  double delta_y = (loop.y - last.y) / steps_double;
103  double delta_t = (loop.theta - last.theta) / steps_double;
104 
105  for (int j = 1; j < steps; ++j)
106  {
107  geometry_msgs::Pose2D pose;
108  pose.x = last.x + j * delta_x;
109  pose.y = last.y + j * delta_y;
110  pose.theta = last.theta + j * delta_t;
111  global_plan_out.poses.push_back(pose);
112  }
113  }
114  global_plan_out.poses.push_back(global_plan_in.poses[i]);
115  last.x = loop.x;
116  last.y = loop.y;
117  }
118  return global_plan_out;
119 }
120 
121 using PoseList = std::vector<geometry_msgs::Pose2D>;
122 
134 PoseList compressPlan(const PoseList& input, unsigned int start_index, unsigned int end_index, double epsilon)
135 {
136  // Skip if only two points
137  if (end_index - start_index <= 1)
138  {
139  PoseList::const_iterator first = input.begin() + start_index;
140  PoseList::const_iterator last = input.begin() + end_index + 1;
141  return PoseList(first, last);
142  }
143 
144  // Find the point with the maximum distance to the line from start to end
145  const geometry_msgs::Pose2D& start = input[start_index],
146  end = input[end_index];
147  double max_distance = 0.0;
148  unsigned int max_index = 0;
149  for (unsigned int i = start_index + 1; i < end_index; i++)
150  {
151  const geometry_msgs::Pose2D& pose = input[i];
152  double d = distanceToLine(pose.x, pose.y, start.x, start.y, end.x, end.y);
153  if (d > max_distance)
154  {
155  max_index = i;
156  max_distance = d;
157  }
158  }
159 
160  // If max distance is less than epsilon, eliminate all the points between start and end
161  if (max_distance <= epsilon)
162  {
163  PoseList outer;
164  outer.push_back(start);
165  outer.push_back(end);
166  return outer;
167  }
168 
169  // If max distance is greater than epsilon, recursively simplify
170  PoseList first_part = compressPlan(input, start_index, max_index, epsilon);
171  PoseList second_part = compressPlan(input, max_index, end_index, epsilon);
172  first_part.insert(first_part.end(), second_part.begin() + 1, second_part.end());
173  return first_part;
174 }
175 
176 nav_2d_msgs::Path2D compressPlan(const nav_2d_msgs::Path2D& input_path, double epsilon)
177 {
178  nav_2d_msgs::Path2D results;
179  results.header = input_path.header;
180  results.poses = compressPlan(input_path.poses, 0, input_path.poses.size() - 1, epsilon);
181  return results;
182 }
183 
184 void addPose(nav_2d_msgs::Path2D& path, double x, double y, double theta)
185 {
186  geometry_msgs::Pose2D pose;
187  pose.x = x;
188  pose.y = y;
189  pose.theta = theta;
190  path.poses.push_back(pose);
191 }
192 } // namespace nav_2d_utils
geometry_help.h
epsilon
double epsilon
nav_2d_utils::compressPlan
nav_2d_msgs::Path2D compressPlan(const nav_2d_msgs::Path2D &input_path, double epsilon=0.1)
Decrease the length of the plan by eliminating colinear points.
Definition: path_ops.cpp:176
nav_2d_utils::addPose
void addPose(nav_2d_msgs::Path2D &path, double x, double y, double theta=0.0)
Convenience function to add a pose to a path in one line.
Definition: path_ops.cpp:184
path_ops.h
nav_2d_utils::PoseList
std::vector< geometry_msgs::Pose2D > PoseList
Definition: path_ops.cpp:121
nav_2d_utils::distanceToLine
double distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1)
Distance from point (pX, pY) to closest point on line from (x0, y0) to (x1, y1)
Definition: geometry_help.h:52
d
d
nav_2d_utils::poseDistance
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
Calculate the linear distance between two poses.
Definition: path_ops.cpp:43
start
ROSCPP_DECL void start()
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
nav_2d_utils
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
nav_2d_utils::getPlanLength
double getPlanLength(const nav_2d_msgs::Path2D &plan, const unsigned int start_index=0)
Calculate the length of the plan, starting from the given index.
Definition: path_ops.cpp:48
nav_2d_utils::adjustPlanResolution
nav_2d_msgs::Path2D adjustPlanResolution(const nav_2d_msgs::Path2D &global_plan_in, double resolution)
Increase plan resolution to match that of the costmap by adding points linearly between points.
Definition: path_ops.cpp:76


nav_2d_utils
Author(s):
autogenerated on Sun May 18 2025 02:47:23