22 #include "nav2_route/route_planner.hpp"
28 nav2::LifecycleNode::SharedPtr node,
29 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
30 const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber)
32 nav2::declare_parameter_if_not_declared(
33 node,
"max_iterations", rclcpp::ParameterValue(0));
34 max_iterations_ = node->get_parameter(
"max_iterations").as_int();
36 if (max_iterations_ <= 0) {
37 max_iterations_ = std::numeric_limits<int>::max();
40 edge_scorer_ = std::make_unique<EdgeScorer>(node, tf_buffer, costmap_subscriber);
44 Graph & graph,
unsigned int start_index,
unsigned int goal_index,
45 const std::vector<unsigned int> & blocked_ids,
55 const NodePtr & start_node = &graph.at(start_index);
56 const NodePtr & goal_node = &graph.at(goal_index);
59 EdgePtr & parent_edge = goal_node->search_state.parent_edge;
67 route.edges.push_back(parent_edge);
68 parent_edge = parent_edge->start->search_state.parent_edge;
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;
81 for (
unsigned int i = 0; i != graph.size(); i++) {
82 graph[i].search_state.reset();
88 const std::vector<unsigned int> & blocked_ids,
93 start_id_ = start_node->nodeid;
94 goal_id_ = goal_node->nodeid;
95 start_node->search_state.integrated_cost = 0.0;
100 float potential_cost = 0.0, traversal_cost = 0.0;
102 while (!queue_.empty() && iterations < max_iterations_) {
109 if (curr_cost != node->search_state.integrated_cost) {
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;
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);
141 if (iterations == max_iterations_) {
149 const EdgePtr edge,
float & score,
const std::vector<unsigned int> & blocked_ids,
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()) {
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!");
168 score = edge->edge_cost.cost;
172 return edge_scorer_->score(edge, route_request,
classifyEdge(edge), score);
177 NodeElement data = queue_.top();
184 queue_.emplace(cost, node);
189 return node->neighbors;
195 std::swap(queue_, q);
200 return node->nodeid == goal_id_;
205 return node->nodeid == start_id_;
211 return EdgeType::START;
212 }
else if (
isGoal(edge->end)) {
213 return EdgeType::END;
215 return nav2_route::EdgeType::NONE;
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.
void configure(nav2::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.
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.
An object to store the nodes in the graph file.
An object to store salient features of the route request including its start and goal node ids,...
An ordered set of nodes and edges corresponding to the planned route.