Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
goal_intent_extractor.cpp
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 #include <string>
16 #include <memory>
17 #include <vector>
18 
19 #include "nav2_route/goal_intent_extractor.hpp"
20 
21 namespace nav2_route
22 {
23 
24 static float EPSILON = 1e-6;
25 
27  nav2_util::LifecycleNode::SharedPtr node,
28  Graph & graph,
29  GraphToIDMap * id_to_graph_map,
30  std::shared_ptr<tf2_ros::Buffer> tf,
31  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
32  const std::string & route_frame,
33  const std::string & global_frame,
34  const std::string & base_frame)
35 {
36  logger_ = node->get_logger();
37  id_to_graph_map_ = id_to_graph_map;
38  graph_ = &graph;
39  tf_ = tf;
40  costmap_subscriber_ = costmap_subscriber;
41  route_frame_ = route_frame;
42  base_frame_ = base_frame;
43  global_frame_ = global_frame;
44  node_spatial_tree_ = std::make_shared<NodeSpatialTree>();
45  node_spatial_tree_->computeTree(graph);
46 
47  nav2_util::declare_parameter_if_not_declared(
48  node, "prune_goal", rclcpp::ParameterValue(true));
49  prune_goal_ = node->get_parameter("prune_goal").as_bool();
50 
51  nav2_util::declare_parameter_if_not_declared(
52  node, "max_prune_dist_from_edge", rclcpp::ParameterValue(8.0));
53  max_dist_from_edge_ = static_cast<float>(
54  node->get_parameter("max_prune_dist_from_edge").as_double());
55  nav2_util::declare_parameter_if_not_declared(
56  node, "min_prune_dist_from_goal", rclcpp::ParameterValue(0.15));
57  min_dist_from_goal_ = static_cast<float>(
58  node->get_parameter("min_prune_dist_from_goal").as_double());
59  nav2_util::declare_parameter_if_not_declared(
60  node, "min_prune_dist_from_start", rclcpp::ParameterValue(0.10));
61  min_dist_from_start_ = static_cast<float>(
62  node->get_parameter("min_prune_dist_from_start").as_double());
63 
64  nav2_util::declare_parameter_if_not_declared(
65  node, "enable_nn_search", rclcpp::ParameterValue(true));
66  enable_search_ = node->get_parameter("enable_nn_search").as_bool();
67  nav2_util::declare_parameter_if_not_declared(
68  node, "max_nn_search_iterations", rclcpp::ParameterValue(10000));
69  max_nn_search_iterations_ = node->get_parameter("max_nn_search_iterations").as_int();
70 
71  nav2_util::declare_parameter_if_not_declared(
72  node, "num_nearest_nodes", rclcpp::ParameterValue(5));
73  int num_of_nearest_nodes = node->get_parameter("num_nearest_nodes").as_int();
74  node_spatial_tree_->setNumOfNearestNodes(num_of_nearest_nodes);
75 }
76 
77 void GoalIntentExtractor::setGraph(Graph & graph, GraphToIDMap * id_to_graph_map)
78 {
79  id_to_graph_map_ = id_to_graph_map;
80  graph_ = &graph;
81  node_spatial_tree_->computeTree(graph);
82 }
83 
84 geometry_msgs::msg::PoseStamped GoalIntentExtractor::transformPose(
85  geometry_msgs::msg::PoseStamped & pose,
86  const std::string & target_frame)
87 {
88  if (pose.header.frame_id != target_frame) {
89  RCLCPP_INFO(
90  logger_,
91  "Request pose in %s frame. Converting to route server frame: %s.",
92  pose.header.frame_id.c_str(), target_frame.c_str());
93  if (!nav2_util::transformPoseInTargetFrame(pose, pose, *tf_, target_frame)) {
94  throw nav2_core::RouteTFError("Failed to transform starting pose to: " + target_frame);
95  }
96  }
97  return pose;
98 }
99 
100 void GoalIntentExtractor::overrideStart(const geometry_msgs::msg::PoseStamped & start_pose)
101 {
102  // Override the start pose when rerouting is requested, using the current pose
103  start_ = start_pose;
104 }
105 
106 template<typename GoalT>
107 NodeExtents
108 GoalIntentExtractor::findStartandGoal(const std::shared_ptr<const GoalT> goal)
109 {
110  // If not using the poses, then use the requests Node IDs to establish start and goal
111  if (!goal->use_poses) {
112  unsigned int start_idx = id_to_graph_map_->at(goal->start_id);
113  unsigned int goal_idx = id_to_graph_map_->at(goal->goal_id);
114  const Coordinates & start_coords = graph_->at(start_idx).coords;
115  const Coordinates & goal_coords = graph_->at(goal_idx).coords;
116  start_.pose.position.x = start_coords.x;
117  start_.pose.position.y = start_coords.y;
118  goal_.pose.position.x = goal_coords.x;
119  goal_.pose.position.y = goal_coords.y;
120  return {start_idx, goal_idx};
121  }
122 
123  // Find request start pose
124  geometry_msgs::msg::PoseStamped start_pose, goal_pose = goal->goal;
125  if (goal->use_start) {
126  start_pose = goal->start;
127  } else {
128  if (!nav2_util::getCurrentPose(start_pose, *tf_, route_frame_, base_frame_)) {
129  throw nav2_core::RouteTFError("Failed to obtain starting pose in: " + route_frame_);
130  }
131  }
132 
133  // transform to route_frame
134  start_ = transformPose(start_pose, route_frame_);
135  goal_ = transformPose(goal_pose, route_frame_);
136 
137  // Find closest route graph nodes to start and goal to plan between.
138  // Note that these are the location indices in the graph
139  std::vector<unsigned int> start_route, end_route;
140  if (!node_spatial_tree_->findNearestGraphNodesToPose(start_, start_route) ||
141  !node_spatial_tree_->findNearestGraphNodesToPose(goal_, end_route))
142  {
144  "Could not determine node closest to start or goal pose requested!");
145  }
146 
147  unsigned int start_route_loc = start_route.front();
148  unsigned int end_route_loc = end_route.front();
149 
150  // If given cost information, check which of the nearest graph nodes is nearest by
151  // traversability, not just Euclidean distance, in case of obstacles, walls, etc.
152  // However, if the closest node has Line of Sight to the goal, then use that node
153  // skipping the search as we know it is the closest and now optimally traversible node.
154  std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap = nullptr;
155  std::string costmap_frame_id;
156  bool enable_search = enable_search_;
157  if (enable_search) {
158  try {
159  costmap = costmap_subscriber_->getCostmap();
160  costmap_frame_id = global_frame_;
161  } catch (const std::exception & ex) {
162  enable_search = false;
163  RCLCPP_WARN(
164  logger_,
165  "Failed to get costmap for goal intent extractor: %s. "
166  "Falling back to closest euclidean route node instead.", ex.what());
167  }
168  }
169 
170  if (enable_search && start_route.size() > 1u) {
171  // Convert the nearest node candidates to the costmap frame for search
172  std::vector<geometry_msgs::msg::PoseStamped> candidate_nodes;
173  candidate_nodes.reserve(start_route.size());
174  for (const auto & node : start_route) {
175  auto & node_data = graph_->at(node);
176  geometry_msgs::msg::PoseStamped node_pose;
177  node_pose.pose.position.x = node_data.coords.x;
178  node_pose.pose.position.y = node_data.coords.y;
179  node_pose.header.frame_id = node_data.coords.frame_id;
180  node_pose.header.stamp = start_pose.header.stamp;
181  candidate_nodes.push_back(transformPose(node_pose, costmap_frame_id));
182  }
183 
184  auto transformed_start = transformPose(start_, costmap_frame_id);
185  GoalIntentSearch::LoSCollisionChecker los_checker(costmap);
186  if (los_checker.worldToMap(
187  candidate_nodes.front().pose.position, transformed_start.pose.position))
188  {
189  if (los_checker.isInCollision()) {
191  if (bfs.search(transformed_start, candidate_nodes, max_nn_search_iterations_)) {
192  start_route_loc = start_route[bfs.getClosestNodeIdx()];
193  }
194  }
195  }
196  }
197 
198  if (enable_search && end_route.size() > 1u) {
199  // Convert the nearest node candidates to the costmap frame for search
200  std::vector<geometry_msgs::msg::PoseStamped> candidate_nodes;
201  candidate_nodes.reserve(end_route.size());
202  for (const auto & node : end_route) {
203  auto & node_data = graph_->at(node);
204  geometry_msgs::msg::PoseStamped node_pose;
205  node_pose.pose.position.x = node_data.coords.x;
206  node_pose.pose.position.y = node_data.coords.y;
207  node_pose.header.frame_id = node_data.coords.frame_id;
208  node_pose.header.stamp = goal_pose.header.stamp;
209  candidate_nodes.push_back(transformPose(node_pose, costmap_frame_id));
210  }
211 
212  auto transformed_end = transformPose(goal_, costmap_frame_id);
213  GoalIntentSearch::LoSCollisionChecker los_checker(costmap);
214  if (los_checker.worldToMap(
215  candidate_nodes.front().pose.position, transformed_end.pose.position))
216  {
217  if (los_checker.isInCollision()) {
219  if (bfs.search(transformed_end, candidate_nodes)) {
220  end_route_loc = end_route[bfs.getClosestNodeIdx()];
221  }
222  }
223  }
224  }
225 
226  return {start_route_loc, end_route_loc};
227 }
228 
229 template<typename GoalT>
231  const Route & input_route,
232  const std::shared_ptr<const GoalT> goal,
233  ReroutingState & rerouting_info)
234 {
235  Route pruned_route = input_route;
236 
237  // Grab and update the rerouting state
238  EdgePtr last_curr_edge = rerouting_info.curr_edge;
239  rerouting_info.curr_edge = nullptr;
240  bool first_time = rerouting_info.first_time;
241  rerouting_info.first_time = false;
242 
243  // Cannot prune if no edges to prune or if using nodeIDs in the initial request (no effect)
244  if (input_route.edges.empty() || (!goal->use_poses && first_time)) {
245  return pruned_route;
246  }
247 
248  // Check on pruning the start node
249  NodePtr first = pruned_route.start_node;
250  NodePtr next = pruned_route.edges[0]->end;
251  float vrx = next->coords.x - first->coords.x;
252  float vry = next->coords.y - first->coords.y;
253  float vpx = start_.pose.position.x - first->coords.x;
254  float vpy = start_.pose.position.y - first->coords.y;
255  float dot_prod = utils::normalizedDot(vrx, vry, vpx, vpy);
256  Coordinates closest_pt_on_edge = utils::findClosestPoint(start_, first->coords, next->coords);
257  if (dot_prod > EPSILON && // A projection exists
258  hypotf(vpx, vpy) > min_dist_from_start_ && // We're not on the node to prune entire edge
259  utils::distance(closest_pt_on_edge, start_) <= max_dist_from_edge_) // Close enough to edge
260  {
261  // Record the pruned edge information if its the same edge as previously routed so that
262  // the tracker can seed this information into its state to proceed with its task losslessly
263  if (last_curr_edge && last_curr_edge->edgeid == pruned_route.edges.front()->edgeid) {
264  rerouting_info.closest_pt_on_edge = closest_pt_on_edge;
265  rerouting_info.curr_edge = pruned_route.edges.front();
266  }
267 
268  pruned_route.start_node = next;
269  pruned_route.route_cost -= pruned_route.edges.front()->end->search_state.traversal_cost;
270  pruned_route.edges.erase(pruned_route.edges.begin());
271  }
272 
273  // Don't prune the goal if requested, if given a known goal_id (no effect), or now empty
274  if (!prune_goal_ || !goal->use_poses || pruned_route.edges.empty()) {
275  return pruned_route;
276  }
277 
278  // Check on pruning the goal node
279  next = pruned_route.edges.back()->start;
280  NodePtr last = pruned_route.edges.back()->end;
281  vrx = last->coords.x - next->coords.x;
282  vry = last->coords.y - next->coords.y;
283  vpx = goal_.pose.position.x - last->coords.x;
284  vpy = goal_.pose.position.y - last->coords.y;
285 
286  dot_prod = utils::normalizedDot(vrx, vry, vpx, vpy);
287  closest_pt_on_edge = utils::findClosestPoint(goal_, next->coords, last->coords);
288  if (dot_prod < -EPSILON && // A projection exists
289  hypotf(vpx, vpy) > min_dist_from_goal_ && // We're not on the node to prune entire edge
290  utils::distance(closest_pt_on_edge, goal_) <= max_dist_from_edge_) // Close enough to edge
291  {
292  pruned_route.route_cost -= pruned_route.edges.back()->end->search_state.traversal_cost;
293  pruned_route.edges.pop_back();
294  }
295 
296  return pruned_route;
297 }
298 
299 geometry_msgs::msg::PoseStamped GoalIntentExtractor::getStart()
300 {
301  return start_;
302 }
303 
304 template Route GoalIntentExtractor::pruneStartandGoal<nav2_msgs::action::ComputeRoute::Goal>(
305  const Route & input_route,
306  const std::shared_ptr<const nav2_msgs::action::ComputeRoute::Goal> goal,
307  ReroutingState & rerouting_info);
308 template
309 Route GoalIntentExtractor::pruneStartandGoal<nav2_msgs::action::ComputeAndTrackRoute::Goal>(
310  const Route & input_route,
311  const std::shared_ptr<const nav2_msgs::action::ComputeAndTrackRoute::Goal> goal,
312  ReroutingState & rerouting_info);
313 template NodeExtents GoalIntentExtractor::findStartandGoal<nav2_msgs::action::ComputeRoute::Goal>(
314  const std::shared_ptr<const nav2_msgs::action::ComputeRoute::Goal> goal);
315 template
316 NodeExtents GoalIntentExtractor::findStartandGoal<nav2_msgs::action::ComputeAndTrackRoute::Goal>(
317  const std::shared_ptr<const nav2_msgs::action::ComputeAndTrackRoute::Goal> goal);
318 
319 } // namespace nav2_route
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 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...
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 &global_frame, const std::string &base_frame)
Configure extractor.
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
bool search(const geometry_msgs::msg::PoseStamped &reference_node, const std::vector< geometry_msgs::msg::PoseStamped > &candidate_nodes, const int max_iterations=std::numeric_limits< int >::max())
Search for the closest node to the given reference node.
unsigned int getClosestNodeIdx()
Get the output closest node in candidate indices.
bool isInCollision()
Check if the line segment is in collision with the costmap.
bool worldToMap(const geometry_msgs::msg::Point &start, const geometry_msgs::msg::Point &end)
Find the line segment in cosmap frame.
An object to store Node coordinates in different frames.
Definition: types.hpp:173
An object representing edges between nodes.
Definition: types.hpp:134
An object to store the nodes in the graph file.
Definition: types.hpp:183
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