15 #ifndef NAV2_ROUTE__GOAL_INTENT_EXTRACTOR_HPP_
16 #define NAV2_ROUTE__GOAL_INTENT_EXTRACTOR_HPP_
22 #include "tf2_ros/transform_listener.h"
23 #include "nav2_core/route_exceptions.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav2_msgs/action/compute_route.hpp"
27 #include "nav2_msgs/action/compute_and_track_route.hpp"
28 #include "nav2_costmap_2d/costmap_subscriber.hpp"
30 #include "nav2_route/types.hpp"
31 #include "nav2_route/utils.hpp"
32 #include "nav2_route/node_spatial_tree.hpp"
33 #include "nav2_route/goal_intent_search.hpp"
68 nav2_util::LifecycleNode::SharedPtr node,
70 GraphToIDMap * id_to_graph_map,
71 std::shared_ptr<tf2_ros::Buffer> tf,
72 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
73 const std::string & route_frame,
74 const std::string & base_frame);
81 void setGraph(Graph & graph, GraphToIDMap * id_to_graph_map);
89 geometry_msgs::msg::PoseStamped & pose,
90 const std::string & frame_id);
96 template<
typename GoalT>
108 template<
typename GoalT>
110 const Route & input_route,
111 const std::shared_ptr<const GoalT> goal,
119 void overrideStart(
const geometry_msgs::msg::PoseStamped & start_pose);
125 geometry_msgs::msg::PoseStamped
getStart();
128 rclcpp::Logger logger_{rclcpp::get_logger(
"GoalIntentExtractor")};
129 std::shared_ptr<NodeSpatialTree> node_spatial_tree_;
130 GraphToIDMap * id_to_graph_map_;
132 std::shared_ptr<tf2_ros::Buffer> tf_;
133 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
134 std::string route_frame_;
135 std::string base_frame_;
136 geometry_msgs::msg::PoseStamped start_, goal_;
137 bool prune_goal_, enable_search_;
138 int max_nn_search_iterations_;
139 float max_dist_from_edge_, min_dist_from_goal_, min_dist_from_start_;
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
An ordered set of nodes and edges corresponding to the planned route.