Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
goal_intent_extractor.hpp
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 #ifndef NAV2_ROUTE__GOAL_INTENT_EXTRACTOR_HPP_
16 #define NAV2_ROUTE__GOAL_INTENT_EXTRACTOR_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <vector>
21 
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"
29 
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"
34 
35 namespace nav2_route
36 {
37 
45 {
46 public:
50  GoalIntentExtractor() = default;
51 
55  ~GoalIntentExtractor() = default;
56 
67  void configure(
68  nav2_util::LifecycleNode::SharedPtr node,
69  Graph & graph,
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);
75 
81  void setGraph(Graph & graph, GraphToIDMap * id_to_graph_map);
82 
88  geometry_msgs::msg::PoseStamped transformPose(
89  geometry_msgs::msg::PoseStamped & pose,
90  const std::string & frame_id);
96  template<typename GoalT>
97  NodeExtents
98  findStartandGoal(const std::shared_ptr<const GoalT> goal);
99 
108  template<typename GoalT>
110  const Route & input_route,
111  const std::shared_ptr<const GoalT> goal,
112  ReroutingState & rerouting_info);
113 
119  void overrideStart(const geometry_msgs::msg::PoseStamped & start_pose);
120 
125  geometry_msgs::msg::PoseStamped getStart();
126 
127 protected:
128  rclcpp::Logger logger_{rclcpp::get_logger("GoalIntentExtractor")};
129  std::shared_ptr<NodeSpatialTree> node_spatial_tree_;
130  GraphToIDMap * id_to_graph_map_;
131  Graph * graph_;
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_;
140 };
141 
142 } // namespace nav2_route
143 
144 #endif // NAV2_ROUTE__GOAL_INTENT_EXTRACTOR_HPP_
Extracts the start and goal nodes in the graph to use for the routing request from the action request...
geometry_msgs::msg::PoseStamped transformPose(geometry_msgs::msg::PoseStamped &pose, const std::string &frame_id)
Transforms a pose into the route frame.
void setGraph(Graph &graph, GraphToIDMap *id_to_graph_map)
Sets a new graph when updated.
Route pruneStartandGoal(const Route &input_route, const std::shared_ptr< const GoalT > goal, ReroutingState &rerouting_info)
Prune the start and end nodes in a route if the start or goal poses, respectively,...
void configure(nav2_util::LifecycleNode::SharedPtr node, Graph &graph, GraphToIDMap *id_to_graph_map, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &route_frame, const std::string &base_frame)
Configure extractor.
void overrideStart(const geometry_msgs::msg::PoseStamped &start_pose)
Override the start pose for use in pruning if it is externally overridden Usually by the rerouting lo...
GoalIntentExtractor()=default
Constructor.
~GoalIntentExtractor()=default
Destructor.
NodeExtents findStartandGoal(const std::shared_ptr< const GoalT > goal)
Main API to find the start and goal graph IDX (not IDs) for routing.
geometry_msgs::msg::PoseStamped getStart()
gets the desired start pose
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
Definition: types.hpp:264
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211