15 #ifndef NAV2_ROUTE__ROUTE_PLANNER_HPP_
16 #define NAV2_ROUTE__ROUTE_PLANNER_HPP_
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"
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);
72 Graph & graph,
unsigned int start_index,
unsigned int goal_index,
73 const std::vector<unsigned int> & blocked_ids,
92 const std::vector<unsigned int> & blocked_ids,
103 const EdgePtr edge,
float & score,
const std::vector<unsigned int> & blocked_ids,
152 int max_iterations_{0};
153 unsigned int start_id_{0};
154 unsigned int goal_id_{0};
156 std::unique_ptr<EdgeScorer> edge_scorer_;
157 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.
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.
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.