Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
path_converter.cpp
1 // Copyright (c) 2025, Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <string>
16 #include <limits>
17 #include <memory>
18 #include <vector>
19 #include <mutex>
20 #include <algorithm>
21 
22 #include "nav2_route/path_converter.hpp"
23 
24 namespace nav2_route
25 {
26 
27 void PathConverter::configure(nav2_util::LifecycleNode::SharedPtr node)
28 {
29  // Density to make path points
30  nav2_util::declare_parameter_if_not_declared(
31  node, "path_density", rclcpp::ParameterValue(0.05));
32  density_ = static_cast<float>(node->get_parameter("path_density").as_double());
33  nav2_util::declare_parameter_if_not_declared(
34  node, "smoothing_radius", rclcpp::ParameterValue(1.0));
35  smoothing_radius_ = static_cast<float>(node->get_parameter("smoothing_radius").as_double());
36  nav2_util::declare_parameter_if_not_declared(
37  node, "smooth_corners", rclcpp::ParameterValue(false));
38  smooth_corners_ = node->get_parameter("smooth_corners").as_bool();
39 
40  path_pub_ = node->create_publisher<nav_msgs::msg::Path>("plan", 1);
41  path_pub_->on_activate();
42  logger_ = node->get_logger();
43 }
44 
45 nav_msgs::msg::Path PathConverter::densify(
46  const Route & route,
47  const ReroutingState & rerouting_info,
48  const std::string & frame,
49  const rclcpp::Time & now)
50 {
51  nav_msgs::msg::Path path;
52  path.header.stamp = now;
53  path.header.frame_id = frame;
54 
55  // If we're rerouting and covering the same previous edge to start,
56  // the path should contain the relevant partial information along edge
57  // to avoid unnecessary free-space planning where state is retained
58  if (rerouting_info.curr_edge) {
59  const Coordinates & start = rerouting_info.closest_pt_on_edge;
60  const Coordinates & end = rerouting_info.curr_edge->end->coords;
61  interpolateEdge(start.x, start.y, end.x, end.y, path.poses);
62  }
63 
64  Coordinates start;
65  Coordinates end;
66 
67  if (!route.edges.empty()) {
68  start = route.edges[0]->start->coords;
69 
70  // Fill in path via route edges
71  for (unsigned int i = 0; i < route.edges.size() - 1; i++) {
72  const EdgePtr edge = route.edges[i];
73  const EdgePtr & next_edge = route.edges[i + 1];
74  end = edge->end->coords;
75 
76  CornerArc corner_arc(start, end, next_edge->end->coords, smoothing_radius_);
77  if (corner_arc.isCornerValid() && smooth_corners_) {
78  // if an arc exists, end of the first edge is the start of the arc
79  end = corner_arc.getCornerStart();
80 
81  // interpolate to start of arc
82  interpolateEdge(start.x, start.y, end.x, end.y, path.poses);
83 
84  // interpolate arc
85  corner_arc.interpolateArc(density_ / smoothing_radius_, path.poses);
86 
87  // new start of next edge is end of smoothing arc
88  start = corner_arc.getCornerEnd();
89  } else {
90  if (smooth_corners_) {
91  RCLCPP_WARN(
92  logger_, "Unable to smooth corner between edge %i and edge %i", edge->edgeid,
93  next_edge->edgeid);
94  }
95  interpolateEdge(start.x, start.y, end.x, end.y, path.poses);
96  start = end;
97  }
98  }
99  }
100 
101  if (route.edges.empty()) {
102  path.poses.push_back(utils::toMsg(route.start_node->coords.x, route.start_node->coords.y));
103  } else {
105  start.x, start.y, route.edges.back()->end->coords.x,
106  route.edges.back()->end->coords.y, path.poses);
107 
108  path.poses.push_back(
109  utils::toMsg(route.edges.back()->end->coords.x, route.edges.back()->end->coords.y));
110  }
111 
112  // Set path poses orientations for each point
113  for (size_t i = 0; i < path.poses.size() - 1; ++i) {
114  const auto & pose = path.poses[i];
115  const auto & next_pose = path.poses[i + 1];
116  const double dx = next_pose.pose.position.x - pose.pose.position.x;
117  const double dy = next_pose.pose.position.y - pose.pose.position.y;
118  const double yaw = atan2(dy, dx);
119  path.poses[i].pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
120  }
121 
122  // Set the last pose orientation to the last edge
123  if (!route.edges.empty()) {
124  const auto & last_edge = route.edges.back();
125  const double dx = last_edge->end->coords.x - last_edge->start->coords.x;
126  const double dy = last_edge->end->coords.y - last_edge->start->coords.y;
127  path.poses.back().pose.orientation =
128  nav2_util::geometry_utils::orientationAroundZAxis(atan2(dy, dx));
129  }
130 
131  // publish path similar to planner server
132  path_pub_->publish(std::make_unique<nav_msgs::msg::Path>(path));
133 
134  return path;
135 }
136 
138  float x0, float y0, float x1, float y1,
139  std::vector<geometry_msgs::msg::PoseStamped> & poses)
140 {
141  // Find number of points to populate by given density
142  const float mag = hypotf(x1 - x0, y1 - y0);
143  const unsigned int num_pts = ceil(mag / density_);
144  const float iterpolated_dist = mag / num_pts;
145 
146  // Find unit vector direction
147  float ux = (x1 - x0) / mag;
148  float uy = (y1 - y0) / mag;
149 
150  // March along it until dist
151  float x = x0;
152  float y = y0;
153  poses.push_back(utils::toMsg(x, y));
154 
155  unsigned int pt_ctr = 0;
156  while (pt_ctr < num_pts - 1) {
157  x += ux * iterpolated_dist;
158  y += uy * iterpolated_dist;
159  pt_ctr++;
160  poses.push_back(utils::toMsg(x, y));
161  }
162 }
163 
164 } // namespace nav2_route
A class used to smooth corners defined by the edges and nodes of the route graph. Used with path conv...
bool isCornerValid() const
return if a valid corner arc (one that doesn't overrun the edge lengths) is generated
void interpolateArc(const float &max_angle_resolution, std::vector< geometry_msgs::msg::PoseStamped > &poses)
interpolates the arc for a path of certain density
Coordinates getCornerStart() const
return the start coordinate of the corner arc
Coordinates getCornerEnd() const
return the end coordinate of the corner arc
void configure(nav2_util::LifecycleNode::SharedPtr node)
Configure the object.
void interpolateEdge(float x0, float y0, float x1, float y1, std::vector< geometry_msgs::msg::PoseStamped > &poses)
Convert an individual edge into a dense line.
nav_msgs::msg::Path densify(const Route &route, const ReroutingState &rerouting_info, const std::string &frame, const rclcpp::Time &now)
Convert a Route into a dense path.
An object to store Node coordinates in different frames.
Definition: types.hpp:173
An object representing edges between nodes.
Definition: types.hpp:134
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
Definition: types.hpp:264
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211