22 #include "nav2_route/path_converter.hpp"
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();
40 path_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"plan", 1);
41 path_pub_->on_activate();
42 logger_ = node->get_logger();
48 const std::string & frame,
49 const rclcpp::Time & now)
51 nav_msgs::msg::Path path;
52 path.header.stamp = now;
53 path.header.frame_id = frame;
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;
67 if (!route.edges.empty()) {
68 start = route.edges[0]->start->coords;
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;
76 CornerArc corner_arc(start, end, next_edge->end->coords, smoothing_radius_);
85 corner_arc.
interpolateArc(density_ / smoothing_radius_, path.poses);
90 if (smooth_corners_) {
92 logger_,
"Unable to smooth corner between edge %i and edge %i", edge->edgeid,
101 if (route.edges.empty()) {
102 path.poses.push_back(utils::toMsg(route.start_node->coords.x, route.start_node->coords.y));
105 start.x, start.y, route.edges.back()->end->coords.x,
106 route.edges.back()->end->coords.y, path.poses);
108 path.poses.push_back(
109 utils::toMsg(route.edges.back()->end->coords.x, route.edges.back()->end->coords.y));
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);
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));
132 path_pub_->publish(std::make_unique<nav_msgs::msg::Path>(path));
138 float x0,
float y0,
float x1,
float y1,
139 std::vector<geometry_msgs::msg::PoseStamped> & poses)
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;
147 float ux = (x1 - x0) / mag;
148 float uy = (y1 - y0) / mag;
153 poses.push_back(utils::toMsg(x, y));
155 unsigned int pt_ctr = 0;
156 while (pt_ctr < num_pts - 1) {
157 x += ux * iterpolated_dist;
158 y += uy * iterpolated_dist;
160 poses.push_back(utils::toMsg(x, y));
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 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.
void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node)
Configure the object.
An object to store Node coordinates in different frames.
An object representing edges between nodes.
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
An ordered set of nodes and edges corresponding to the planned route.