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