|
Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
An optimal planner to compute a route from a start to a goal in an arbitrary graph. More...
#include <nav2_route/include/nav2_route/route_planner.hpp>
Public Member Functions | |
| RoutePlanner ()=default | |
| A constructor for nav2_route::RoutePlanner. | |
| virtual | ~RoutePlanner ()=default |
| A destructor for nav2_route::RoutePlanner. | |
| 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. More... | |
| 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. More... | |
Protected Member Functions | |
| void | resetSearchStates (Graph &graph) |
| Reset the search state of the graph nodes. More... | |
| 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. More... | |
| 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. More... | |
| NodeElement | getNextNode () |
| Gets the next node in the priority queue for search. More... | |
| void | addNode (const float cost, const NodePtr node) |
| Adds a node to the priority queue for search. More... | |
| EdgeVector & | getEdges (const NodePtr node) |
| Gets the edges from a given node. More... | |
| void | clearQueue () |
| Clears the priority queue. | |
| bool | isGoal (const NodePtr node) |
| Checks if a given node is the goal node. More... | |
| bool | isStart (const NodePtr node) |
| Checks if a given node is the start node. More... | |
| nav2_route::EdgeType | classifyEdge (const EdgePtr edge) |
| Checks edge is a start or end edge. More... | |
Protected Attributes | |
| int | max_iterations_ {0} |
| unsigned int | start_id_ {0} |
| unsigned int | goal_id_ {0} |
| NodeQueue | queue_ |
| std::unique_ptr< EdgeScorer > | edge_scorer_ |
| std::shared_ptr< tf2_ros::Buffer > | tf_buffer_ |
An optimal planner to compute a route from a start to a goal in an arbitrary graph.
Definition at line 40 of file route_planner.hpp.
|
inlineprotected |
Adds a node to the priority queue for search.
| cost | Priority level |
| node | Node pointer to insert |
Definition at line 182 of file route_planner.cpp.
Referenced by findShortestGraphTraversal().

|
protected |
Checks edge is a start or end edge.
| edge | Edge to check |
Definition at line 208 of file route_planner.cpp.
References isStart().
Referenced by getTraversalCost().


| void nav2_route::RoutePlanner::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.
| node | Node object to get parametersfrom |
| tf_buffer | TF buffer to use for transformations |
| costmap_subscriber | Costmap subscriber to use for blocked nodes |
Definition at line 27 of file route_planner.cpp.
|
virtual |
Find the route from start to goal on the graph.
| graph | Graph to search |
| start | Start index in the graph of the start node |
| goal | Goal index in the graph of the goal node |
| blocked_ids | A set of blocked node and edge IDs not to traverse |
Definition at line 43 of file route_planner.cpp.
References findShortestGraphTraversal().

|
protected |
Dikstra's algorithm search on the graph.
| graph | Graph to search |
| start | Start Node pointer |
| goal | Goal node pointer |
| blocked_ids | A set of blocked node and edge IDs not to traverse |
Definition at line 86 of file route_planner.cpp.
References addNode(), clearQueue(), getEdges(), getNextNode(), getTraversalCost(), isGoal(), and resetSearchStates().
Referenced by findRoute().


|
inlineprotected |
Gets the edges from a given node.
| node | Node pointer to check |
Definition at line 187 of file route_planner.cpp.
Referenced by findShortestGraphTraversal().

|
inlineprotected |
Gets the next node in the priority queue for search.
Definition at line 175 of file route_planner.cpp.
Referenced by findShortestGraphTraversal().

|
inlineprotected |
Gets the traversal cost for an edge using edge scorers.
| edge | Edge pointer to find traversal cost for |
| travel | cost |
| blocked_ids | A set of blocked node and edge IDs not to traverse |
Definition at line 148 of file route_planner.cpp.
References classifyEdge().
Referenced by findShortestGraphTraversal().


|
inlineprotected |
Checks if a given node is the goal node.
| node | Node to check |
Definition at line 198 of file route_planner.cpp.
Referenced by findShortestGraphTraversal().

|
inlineprotected |
Checks if a given node is the start node.
| node | Node to check |
Definition at line 203 of file route_planner.cpp.
Referenced by classifyEdge().

|
inlineprotected |
Reset the search state of the graph nodes.
| graph | Graph to reset |
Definition at line 77 of file route_planner.cpp.
Referenced by findShortestGraphTraversal().
