Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
route_planner.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/route_planner.hpp"
23 
24 namespace nav2_route
25 {
26 
28  nav2_util::LifecycleNode::SharedPtr node,
29  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
30  const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber)
31 {
32  nav2_util::declare_parameter_if_not_declared(
33  node, "max_iterations", rclcpp::ParameterValue(0));
34  max_iterations_ = node->get_parameter("max_iterations").as_int();
35 
36  if (max_iterations_ <= 0) {
37  max_iterations_ = std::numeric_limits<int>::max();
38  }
39 
40  edge_scorer_ = std::make_unique<EdgeScorer>(node, tf_buffer, costmap_subscriber);
41 }
42 
44  Graph & graph, unsigned int start_index, unsigned int goal_index,
45  const std::vector<unsigned int> & blocked_ids,
46  const RouteRequest & route_request)
47 {
48  if (graph.empty()) {
49  throw nav2_core::NoValidGraph("Graph is invalid for routing!");
50  }
51 
52  // Find the start and goal pointers, it is important in this function
53  // that the start node is the underlying pointer, so that the address
54  // is valid when this function goes out of scope
55  const NodePtr & start_node = &graph.at(start_index);
56  const NodePtr & goal_node = &graph.at(goal_index);
57  findShortestGraphTraversal(graph, start_node, goal_node, blocked_ids, route_request);
58 
59  EdgePtr & parent_edge = goal_node->search_state.parent_edge;
60  if (!parent_edge) {
61  throw nav2_core::NoValidRouteCouldBeFound("Could not find a route to the requested goal!");
62  }
63 
64  // Convert graph traversal into a meaningful route
65  Route route;
66  while (parent_edge) {
67  route.edges.push_back(parent_edge);
68  parent_edge = parent_edge->start->search_state.parent_edge;
69  }
70 
71  std::reverse(route.edges.begin(), route.edges.end());
72  route.start_node = start_node;
73  route.route_cost = goal_node->search_state.integrated_cost;
74  return route;
75 }
76 
78 {
79  // For graphs < 75,000 nodes, iterating through one time on initialization to reset the state
80  // is neglibably different to allocating & deallocating the complimentary blocks of memory
81  for (unsigned int i = 0; i != graph.size(); i++) {
82  graph[i].search_state.reset();
83  }
84 }
85 
87  Graph & graph, const NodePtr start_node, const NodePtr goal_node,
88  const std::vector<unsigned int> & blocked_ids,
89  const RouteRequest & route_request)
90 {
91  // Setup the Dijkstra's search
92  resetSearchStates(graph);
93  start_id_ = start_node->nodeid;
94  goal_id_ = goal_node->nodeid;
95  start_node->search_state.integrated_cost = 0.0;
96  addNode(0.0, start_node);
97 
98  NodePtr neighbor{nullptr};
99  EdgePtr edge{nullptr};
100  float potential_cost = 0.0, traversal_cost = 0.0;
101  int iterations = 0;
102  while (!queue_.empty() && iterations < max_iterations_) {
103  iterations++;
104 
105  // Get the next lowest cost node
106  auto [curr_cost, node] = getNextNode();
107 
108  // This has been visited, thus already lowest cost
109  if (curr_cost != node->search_state.integrated_cost) {
110  continue;
111  }
112 
113  // We have the shortest path
114  if (isGoal(node)) {
115  // Reset states
116  clearQueue();
117  return;
118  }
119 
120  // Expand to connected nodes
121  EdgeVector & edges = getEdges(node);
122  for (unsigned int edge_num = 0; edge_num != edges.size(); edge_num++) {
123  edge = &edges[edge_num];
124  neighbor = edge->end;
125 
126  // If edge is invalid (lane closed, occupied, etc), don't expand
127  if (!getTraversalCost(edge, traversal_cost, blocked_ids, route_request)) {
128  continue;
129  }
130 
131  potential_cost = curr_cost + traversal_cost;
132  if (potential_cost < neighbor->search_state.integrated_cost) {
133  neighbor->search_state.parent_edge = edge;
134  neighbor->search_state.integrated_cost = potential_cost;
135  neighbor->search_state.traversal_cost = traversal_cost;
136  addNode(potential_cost, neighbor);
137  }
138  }
139  }
140 
141  if (iterations == max_iterations_) {
142  // Reset states
143  clearQueue();
144  throw nav2_core::TimedOut("Maximum iterations was exceeded!");
145  }
146 }
147 
149  const EdgePtr edge, float & score, const std::vector<unsigned int> & blocked_ids,
150  const RouteRequest & route_request)
151 {
152  // If edge or node is in the blocked list, don't expand
153  auto is_blocked = std::find_if(
154  blocked_ids.begin(), blocked_ids.end(),
155  [&](unsigned int id) {return id == edge->edgeid || id == edge->end->nodeid;});
156  if (is_blocked != blocked_ids.end()) {
157  return false;
158  }
159 
160  // If an edge's cost is marked as not to be overridden by scoring plugins
161  // Or there are no scoring plugins, use the edge's cost, if it is valid (positive)
162  if (!edge->edge_cost.overridable || edge_scorer_->numPlugins() == 0) {
163  if (edge->edge_cost.cost <= 0.0) {
165  "Edge " + std::to_string(edge->edgeid) +
166  " doesn't contain and cannot compute a valid edge cost!");
167  }
168  score = edge->edge_cost.cost;
169  return true;
170  }
171 
172  return edge_scorer_->score(edge, route_request, classifyEdge(edge), score);
173 }
174 
176 {
177  NodeElement data = queue_.top();
178  queue_.pop();
179  return data;
180 }
181 
182 void RoutePlanner::addNode(const float cost, const NodePtr node)
183 {
184  queue_.emplace(cost, node);
185 }
186 
187 EdgeVector & RoutePlanner::getEdges(const NodePtr node)
188 {
189  return node->neighbors;
190 }
191 
193 {
194  NodeQueue q;
195  std::swap(queue_, q);
196 }
197 
199 {
200  return node->nodeid == goal_id_;
201 }
202 
204 {
205  return node->nodeid == start_id_;
206 }
207 
208 nav2_route::EdgeType RoutePlanner::classifyEdge(const EdgePtr edge)
209 {
210  if (isStart(edge->start)) {
211  return EdgeType::START;
212  } else if (isGoal(edge->end)) {
213  return EdgeType::END;
214  }
215  return nav2_route::EdgeType::NONE;
216 }
217 
218 } // namespace nav2_route
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.
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 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