Nav2 Navigation Stack - kilted  kilted
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 
33 namespace nav2_route
34 {
40 {
41 public:
45  RoutePlanner() = default;
46 
50  virtual ~RoutePlanner() = default;
51 
58  void configure(
59  nav2_util::LifecycleNode::SharedPtr node,
60  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
61  const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber);
62 
71  virtual Route findRoute(
72  Graph & graph, unsigned int start_index, unsigned int goal_index,
73  const std::vector<unsigned int> & blocked_ids,
74  const RouteRequest & route_request);
75 
76 protected:
81  inline void resetSearchStates(Graph & graph);
82 
91  Graph & graph, const NodePtr start_node, const NodePtr goal_node,
92  const std::vector<unsigned int> & blocked_ids,
93  const RouteRequest & route_request);
94 
102  inline bool getTraversalCost(
103  const EdgePtr edge, float & score, const std::vector<unsigned int> & blocked_ids,
104  const RouteRequest & route_request);
105 
110  inline NodeElement getNextNode();
111 
117  inline void addNode(const float cost, const NodePtr node);
118 
124  inline EdgeVector & getEdges(const NodePtr node);
125 
129  inline void clearQueue();
130 
136  inline bool isGoal(const NodePtr node);
137 
143  inline bool isStart(const NodePtr node);
144 
150  nav2_route::EdgeType classifyEdge(const EdgePtr edge);
151 
152  int max_iterations_{0};
153  unsigned int start_id_{0};
154  unsigned int goal_id_{0};
155  NodeQueue queue_;
156  std::unique_ptr<EdgeScorer> edge_scorer_;
157  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
158 };
159 
160 } // namespace nav2_route
161 
162 #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.
void configure(nav2_util::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.
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 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