Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
route_planner.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__ROUTE_PLANNER_HPP_
16 #define NAV2_ROUTE__ROUTE_PLANNER_HPP_
17 
18 #include <string>
19 #include <limits>
20 #include <memory>
21 #include <vector>
22 #include <mutex>
23 #include <algorithm>
24 
25 #include "tf2_ros/buffer.h"
26 #include "tf2_ros/transform_listener.h"
27 #include "nav2_route/types.hpp"
28 #include "nav2_route/utils.hpp"
29 #include "nav2_route/edge_scorer.hpp"
30 #include "nav2_core/route_exceptions.hpp"
31 #include "geometry_msgs/msg/pose_stamped.hpp"
32 #include "nav2_util/lifecycle_node.hpp"
33 
34 namespace nav2_route
35 {
41 {
42 public:
46  RoutePlanner() = default;
47 
51  virtual ~RoutePlanner() = default;
52 
59  void configure(
60  rclcpp_lifecycle::LifecycleNode::SharedPtr node,
61  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
62  const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber);
63 
72  virtual Route findRoute(
73  Graph & graph, unsigned int start_index, unsigned int goal_index,
74  const std::vector<unsigned int> & blocked_ids,
75  const RouteRequest & route_request);
76 
77 protected:
82  inline void resetSearchStates(Graph & graph);
83 
92  Graph & graph, const NodePtr start_node, const NodePtr goal_node,
93  const std::vector<unsigned int> & blocked_ids,
94  const RouteRequest & route_request);
95 
103  inline bool getTraversalCost(
104  const EdgePtr edge, float & score, const std::vector<unsigned int> & blocked_ids,
105  const RouteRequest & route_request);
106 
111  inline NodeElement getNextNode();
112 
118  inline void addNode(const float cost, const NodePtr node);
119 
125  inline EdgeVector & getEdges(const NodePtr node);
126 
130  inline void clearQueue();
131 
137  inline bool isGoal(const NodePtr node);
138 
144  inline bool isStart(const NodePtr node);
145 
151  nav2_route::EdgeType classifyEdge(const EdgePtr edge);
152 
153  int max_iterations_{0};
154  unsigned int start_id_{0};
155  unsigned int goal_id_{0};
156  NodeQueue queue_;
157  std::unique_ptr<EdgeScorer> edge_scorer_;
158  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
159 };
160 
161 } // namespace nav2_route
162 
163 #endif // NAV2_ROUTE__ROUTE_PLANNER_HPP_
An optimal planner to compute a route from a start to a goal in an arbitrary graph.
void findShortestGraphTraversal(Graph &graph, const NodePtr start_node, const NodePtr goal_node, const std::vector< unsigned int > &blocked_ids, const RouteRequest &route_request)
Dikstra's algorithm search on the graph.
RoutePlanner()=default
A constructor for nav2_route::RoutePlanner.
nav2_route::EdgeType classifyEdge(const EdgePtr edge)
Checks edge is a start or end edge.
bool getTraversalCost(const EdgePtr edge, float &score, const std::vector< unsigned int > &blocked_ids, const RouteRequest &route_request)
Gets the traversal cost for an edge using edge scorers.
bool isGoal(const NodePtr node)
Checks if a given node is the goal node.
NodeElement getNextNode()
Gets the next node in the priority queue for search.
virtual ~RoutePlanner()=default
A destructor for nav2_route::RoutePlanner.
virtual Route findRoute(Graph &graph, unsigned int start_index, unsigned int goal_index, const std::vector< unsigned int > &blocked_ids, const RouteRequest &route_request)
Find the route from start to goal on the graph.
EdgeVector & getEdges(const NodePtr node)
Gets the edges from a given node.
void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
Configure the route planner, get parameters.
void addNode(const float cost, const NodePtr node)
Adds a node to the priority queue for search.
void resetSearchStates(Graph &graph)
Reset the search state of the graph nodes.
bool isStart(const NodePtr node)
Checks if a given node is the start node.
void clearQueue()
Clears the priority queue.
An object representing edges between nodes.
Definition: types.hpp:134
An object to store the nodes in the graph file.
Definition: types.hpp:183
An object to store salient features of the route request including its start and goal node ids,...
Definition: types.hpp:224
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211