Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
path_converter.hpp
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 #ifndef NAV2_ROUTE__PATH_CONVERTER_HPP_
16 #define NAV2_ROUTE__PATH_CONVERTER_HPP_
17 
18 #include <string>
19 #include <limits>
20 #include <memory>
21 #include <vector>
22 #include <mutex>
23 #include <algorithm>
24 
25 #include "nav2_util/lifecycle_node.hpp"
26 #include "nav2_util/node_utils.hpp"
27 #include "nav2_route/types.hpp"
28 #include "nav2_route/utils.hpp"
29 #include "nav2_route/corner_smoothing.hpp"
30 
31 namespace nav2_route
32 {
38 {
39 public:
43  PathConverter() = default;
44 
48  ~PathConverter() = default;
49 
54  void configure(nav2_util::LifecycleNode::SharedPtr node);
55 
64  nav_msgs::msg::Path densify(
65  const Route & route,
66  const ReroutingState & rerouting_info,
67  const std::string & frame,
68  const rclcpp::Time & now);
69 
78  void interpolateEdge(
79  float x0, float y0, float x1, float y1,
80  std::vector<geometry_msgs::msg::PoseStamped> & poses);
81 
82 protected:
83  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr path_pub_;
84  rclcpp::Logger logger_{rclcpp::get_logger("PathConverter")};
85  float density_;
86  float smoothing_radius_;
87  bool smooth_corners_;
88 };
89 
90 } // namespace nav2_route
91 
92 #endif // NAV2_ROUTE__PATH_CONVERTER_HPP_
An helper to convert the route into dense paths.
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.
~PathConverter()=default
A destructor for nav2_route::PathConverter.
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.
PathConverter()=default
A constructor for nav2_route::PathConverter.
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