path_util.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2020, 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::Path &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 fillOrientations(marti_nav_msgs::Path &path)
60 {
61  // We can't estimate any orientations for 0 or 1 points.
62  if (path.points.size() < 2) {
63  return;
64  }
65 
66  double yaw;
67  for (size_t i = 0; i + 1 < path.points.size(); i++)
68  {
69  marti_nav_msgs::PathPoint& pt = path.points[i];
70  const marti_nav_msgs::PathPoint& next_pt = path.points[i+1];
71 
72  // Calculate yaw based on the direction between these points
73  yaw = atan2(
74  next_pt.y - pt.y,
75  next_pt.x - pt.x);
76 
77  if (path.in_reverse)
78  {
79  yaw += M_PI;
80  }
81 
82  pt.yaw = yaw;
83  }
84 
85  // fill in the last yaw
86  path.points.back().yaw = path.points[path.points.size() - 2].yaw;
87 }
88 
89 
91  const marti_nav_msgs::Path& path,
92  const double x, const double y,
93  PathPosition& nearest_position,
94  double& nearest_separation)
95 {
96  // Handle odd sizes
97  size_t num_points = path.points.size();
98  if (num_points == 0)
99  {
100  return false;
101  }
102  else if (num_points == 1)
103  {
104  nearest_position.index = 0;
105  nearest_position.distance = 0.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));
108  return true;
109  }
110 
111  cv::Vec2d point(x, y);
112 
113  // Find the nearest line segment from the beginning of the path
114  double min_separation_sqr = std::numeric_limits<double>::infinity();
115  for (size_t i = 0; i + 1 < num_points; i++)
116  {
117  auto& start = path.points[i];
118  auto& end = path.points[i+1];
119 
120  cv::Vec2d proj = swri_geometry_util::ProjectToLineSegment(cv::Vec2d(start.x, start.y),
121  cv::Vec2d(end.x, end.y),
122  point);
123 
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)
126  {
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));
131  }
132 
133  //if separation is increasing, local minima was found. stop the search
134  if (separation_sqr > 2.0*min_separation_sqr)
135  {
136  break;
137  }
138  }
139 
140  nearest_separation = std::sqrt(min_separation_sqr);
141 
142  return true;
143 }
144 
145 static void normalizePathPosition(const marti_nav_msgs::Path& path,
146  PathPosition& position)
147 {
148  // handle being past the end of the route
149  if (position.index > path.points.size() - 1)
150  {
151  position.distance = 0.0;
152  position.index = path.points.size() - 1;
153  return;
154  }
155 
156  double distance = position.distance;
157  size_t index = position.index;
158  while (distance < 0.0)
159  {
160  if (index == 0)
161  {
162  distance = 0.0;// cant be before start
163  break;
164  }
165 
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)
171  {
172  distance += len;
173  index--;
174  }
175  else
176  {
177  break;
178  }
179  }
180 
181  while (distance > 0.0)
182  {
183  if (index+1 == path.points.size())
184  {
185  break;
186  }
187 
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));
192  if (distance >= len)
193  {
194  distance -= len;
195  index++;
196  }
197  else
198  {
199  break;
200  }
201  }
202 
203  position.index = index;
204  position.distance = distance;
205 }
206 
207 static double interpolateAngle(double from, double to, double t)
208 {
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);
212  if (diff < M_PI)
213  {
214  return from*(1.0-t) + to*t;
215  }
216  else if (from > to)
217  {
218  from -= M_PI*2.0;
219  return from*(1.0-t) + to*t;
220  }
221  else
222  {
223  to -= M_PI*2.0;
224  return from*(1.0-t) + to*t;
225  }
226 }
227 
228 void getPathPosition(const marti_nav_msgs::Path& path,
229  const PathPosition position,
230  tf::Vector3& pos)
231 {
232  PathPosition npos = position;
233  normalizePathPosition(path, npos);
234 
235  if (npos.distance == 0.0 || npos.index == path.points.size() - 1)
236  {
237  auto& point = path.points[npos.index];
238  pos = tf::Vector3(point.x, point.y, 0.0);
239  return;
240  }
241 
242  auto& start = path.points[npos.index];
243  auto& end = path.points[npos.index+1];
244 
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;
247 
248  pos = tf::Vector3(start.x*(1.0 - frac) + end.x*frac,
249  start.y*(1.0 - frac) + end.y*frac,
250  0.0);
251 }
252 
253 void getPathPose(const marti_nav_msgs::Path& path,
254  const PathPosition position,
255  tf::Transform& tf,
256  const bool allow_extrapolation)
257 {
258  PathPosition npos = position;
259  normalizePathPosition(path, npos);
260 
261  if (npos.distance == 0.0 || npos.index == path.points.size() - 1)
262  {
263  if (npos.index == path.points.size() - 1 && npos.distance > 0.0
264  && path.points.size() > 1
265  && allow_extrapolation)
266  {
267  // extrapolate
268  auto& start = path.points[npos.index];
269  auto& prev = path.points[npos.index-1];
270 
271  tf::Vector3 pos(start.x, start.y, 0.0);
272  tf::Vector3 dir = tf::Vector3(start.x-prev.x, start.y-prev.y, 0.0).normalized();
273  pos += npos.distance*dir;
275  return;
276  }
277 
278  auto& point = path.points[npos.index];
280  tf::Vector3(point.x, point.y, 0.0));
281  return;
282  }
283 
284  auto& start = path.points[npos.index];
285  auto& end = path.points[npos.index+1];
286 
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;
289 
290  tf::Vector3 pos(start.x*(1.0 - frac) + end.x*frac,
291  start.y*(1.0 - frac) + end.y*frac,
292  0.0);
293  double yaw = interpolateAngle(start.yaw, end.yaw, frac);
295 }
296 
297 } // namespace swri_route_util
swri_route_util::getPathPosition
void getPathPosition(const marti_nav_msgs::Path &path, const PathPosition position, tf::Vector3 &tf)
Definition: path_util.cpp:228
tf::createQuaternionFromYaw
static Quaternion createQuaternionFromYaw(double yaw)
swri_route_util::PathPosition
Definition: path_util.h:53
s
XmlRpcServer s
swri_route_util::normalizePathPosition
static void normalizePathPosition(const marti_nav_msgs::Path &path, PathPosition &position)
Definition: path_util.cpp:145
geometry_util.h
swri_route_util::getPathPose
void getPathPose(const marti_nav_msgs::Path &path, const PathPosition position, tf::Transform &tf, const bool allow_extrapolation=false)
Definition: path_util.cpp:253
swri_route_util
Definition: path_util.h:35
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
transform_util.h
swri_route_util::PathPosition::distance
double distance
Definition: path_util.h:56
swri_transform_util
swri_transform_util::Transform
swri_route_util::fillOrientations
void fillOrientations(marti_nav_msgs::Path &path)
Definition: path_util.cpp:59
tf::Transform
swri_route_util::PathPosition::index
size_t index
Definition: path_util.h:55
swri_geometry_util::ProjectToLineSegment
cv::Vec2d ProjectToLineSegment(const cv::Vec2d &line_start, const cv::Vec2d &line_end, const cv::Vec2d &point)
path_util.h
start
ROSCPP_DECL void start()
swri_route_util::interpolateAngle
static double interpolateAngle(double from, double to, double t)
Definition: path_util.cpp:207
tf
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
tf::Quaternion


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