Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
route_tracker.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 "nav2_route/route_tracker.hpp"
16 
17 namespace nav2_route
18 {
19 
21  nav2_util::LifecycleNode::SharedPtr node,
22  std::shared_ptr<tf2_ros::Buffer> tf_buffer,
23  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
24  std::shared_ptr<ActionServerTrack> action_server,
25  const std::string & route_frame,
26  const std::string & base_frame)
27 {
28  clock_ = node->get_clock();
29  logger_ = node->get_logger();
30  route_frame_ = route_frame;
31  base_frame_ = base_frame;
32  action_server_ = action_server;
33  tf_buffer_ = tf_buffer;
34 
35  nav2_util::declare_parameter_if_not_declared(
36  node, "radius_to_achieve_node", rclcpp::ParameterValue(2.0));
37  radius_threshold_ = node->get_parameter("radius_to_achieve_node").as_double();
38  nav2_util::declare_parameter_if_not_declared(
39  node, "boundary_radius_to_achieve_node", rclcpp::ParameterValue(1.0));
40  boundary_radius_threshold_ = node->get_parameter("boundary_radius_to_achieve_node").as_double();
41  nav2_util::declare_parameter_if_not_declared(
42  node, "tracker_update_rate", rclcpp::ParameterValue(50.0));
43  tracker_update_rate_ = node->get_parameter("tracker_update_rate").as_double();
44  nav2_util::declare_parameter_if_not_declared(
45  node, "aggregate_blocked_ids", rclcpp::ParameterValue(false));
46  aggregate_blocked_ids_ = node->get_parameter("aggregate_blocked_ids").as_bool();
47 
48  operations_manager_ = std::make_unique<OperationsManager>(node, costmap_subscriber);
49 }
50 
51 geometry_msgs::msg::PoseStamped RouteTracker::getRobotPose()
52 {
53  geometry_msgs::msg::PoseStamped pose;
54  if (!nav2_util::getCurrentPose(pose, *tf_buffer_, route_frame_, base_frame_)) {
55  throw nav2_core::RouteTFError("Unable to get robot pose in route frame: " + route_frame_);
56  }
57  return pose;
58 }
59 
61  const geometry_msgs::msg::PoseStamped & pose,
62  RouteTrackingState & state,
63  const Route & route)
64 {
65  // check if inside a *generous* radius window
66  const double dx = state.next_node->coords.x - pose.pose.position.x;
67  const double dy = state.next_node->coords.y - pose.pose.position.y;
68  const double dist_mag = std::sqrt(dx * dx + dy * dy);
69  const bool is_boundary_node = isStartOrEndNode(state, route);
70  const bool in_radius =
71  (dist_mag <= (is_boundary_node ? boundary_radius_threshold_ : radius_threshold_));
72 
73  // Within 0.1mm is achieved or within radius and now not, consider node achieved
74  if (dist_mag < 1e-4 || (!in_radius && state.within_radius)) {
75  return true;
76  }
77 
78  // Update the state for the next iteration
79  state.within_radius = in_radius;
80 
81  // If start or end node, use the radius check only since the final node may not pass
82  // threshold depending on the configurations. The start node has no last_node for
83  // computing the vector bisector. If this is an issue, please file a ticket to discuss.
84  if (is_boundary_node) {
85  return state.within_radius;
86  }
87 
88  // We can evaluate the unit distance vector from the node w.r.t. the unit vector bisecting
89  // the last and current edges to find the average whose orthogonal is an imaginary
90  // line representing the migration from one edge's spatial domain to the other.
91  // When the dot product is negative, it means that there exists a projection between
92  // the vectors and that the robot position has passed this imaginary orthogonal line.
93  // This enables a more refined definition of when a node is considered achieved while
94  // enabling the use of dynamic behavior that may deviate from the path non-trivially
95  if (state.within_radius) {
96  NodePtr last_node = state.current_edge->start;
97  const double nx = state.next_node->coords.x - last_node->coords.x;
98  const double ny = state.next_node->coords.y - last_node->coords.y;
99  const double n_mag = std::sqrt(nx * nx + ny * ny);
100 
101  NodePtr future_next_node = route.edges[state.route_edges_idx + 1]->end;
102  const double mx = future_next_node->coords.x - state.next_node->coords.x;
103  const double my = future_next_node->coords.y - state.next_node->coords.y;
104  const double m_mag = std::sqrt(mx * mx + my * my);
105 
106  // If nodes overlap so there is no vector, use radius check only (divide by zero)
107  if (n_mag < 1e-6 || m_mag < 1e-6) {
108  return true;
109  }
110 
111  // Unnormalized Bisector = |n|*m + |m|*n
112  const double bx = nx * m_mag + mx * n_mag;
113  const double by = ny * m_mag + my * n_mag;
114  return utils::normalizedDot(bx, by, dx, dy) <= 0;
115  }
116 
117  return false;
118 }
119 
121 {
122  // Check if current_edge is nullptr in case we have a rerouted previous
123  // edge to use for the refined node achievement vectorized estimate
124  return
125  (state.route_edges_idx == static_cast<int>(route.edges.size() - 1)) ||
126  (state.route_edges_idx == -1 && !state.current_edge);
127 }
128 
130  const bool rereouted,
131  const unsigned int next_node_id,
132  const unsigned int last_node_id,
133  const unsigned int edge_id,
134  const std::vector<std::string> & operations)
135 {
136  auto feedback = std::make_unique<Feedback>();
137  feedback->route = route_msg_;
138  feedback->path = path_;
139  feedback->rerouted = rereouted;
140  feedback->next_node_id = next_node_id;
141  feedback->last_node_id = last_node_id;
142  feedback->current_edge_id = edge_id;
143  feedback->operations_triggered = operations;
144  action_server_->publish_feedback(std::move(feedback));
145 }
146 
148  const Route & route, const nav_msgs::msg::Path & path,
149  ReroutingState & rerouting_info)
150 {
151  route_msg_ = utils::toMsg(route, route_frame_, clock_->now());
152  path_ = path;
153  RouteTrackingState state;
154  state.next_node = route.start_node;
155 
156  // If we're rerouted but still covering the same previous edge to
157  // start, retain the state so we can continue as previously set with
158  // refined node achievement logic and performing edge operations on exit
159  if (rerouting_info.curr_edge) {
160  // state.next_node is not updated since the first edge is removed from route when rerouted
161  // along the same edge in the goal intent extractor. Thus, state.next_node is still the
162  // future node to reach in this case and we add in the state.last_node and state.current_edge
163  // to represent the 'currently' progressing edge that is omitted from the route (and its start)
164  state.current_edge = rerouting_info.curr_edge;
165  state.last_node = state.current_edge->start;
167  true, route.start_node->nodeid, state.last_node->nodeid, state.current_edge->edgeid, {});
168  } else {
169  publishFeedback(true, route.start_node->nodeid, 0, 0, {});
170  }
171 
172  rclcpp::Rate r(tracker_update_rate_);
173  while (rclcpp::ok()) {
174  bool status_change = false, completed = false;
175 
176  // Check if OK to keep processing
177  if (action_server_->is_cancel_requested()) {
178  return TrackerResult::INTERRUPTED;
179  } else if (action_server_->is_preempt_requested()) {
180  return TrackerResult::INTERRUPTED;
181  }
182 
183  // Update the tracking state
184  geometry_msgs::msg::PoseStamped robot_pose = getRobotPose();
185  if (nodeAchieved(robot_pose, state, route)) {
186  status_change = true;
187  state.within_radius = false;
188  state.last_node = state.next_node;
189  if (++state.route_edges_idx < static_cast<int>(route.edges.size())) {
190  state.current_edge = route.edges[state.route_edges_idx];
191  state.next_node = state.current_edge->end;
192  } else { // At achieved the last node in the route
193  state.current_edge = nullptr;
194  state.next_node = nullptr;
195  completed = true;
196  }
197  }
198 
199  // Process any operations necessary
200  OperationsResult ops_result =
201  operations_manager_->process(status_change, state, route, robot_pose, rerouting_info);
202 
203  if (completed) {
204  RCLCPP_INFO(logger_, "Routing to goal completed!");
205  // Publishing last feedback
206  publishFeedback(false, 0, state.last_node->nodeid, 0, ops_result.operations_triggered);
207  return TrackerResult::COMPLETED;
208  }
209 
210  if ((status_change || !ops_result.operations_triggered.empty()) && state.current_edge) {
212  false, // No rerouting occurred
213  state.next_node->nodeid, state.last_node->nodeid,
214  state.current_edge->edgeid, ops_result.operations_triggered);
215  }
216 
217  if (ops_result.reroute) {
218  if (!aggregate_blocked_ids_) {
219  rerouting_info.blocked_ids = ops_result.blocked_ids;
220  } else {
221  rerouting_info.blocked_ids.insert(
222  rerouting_info.blocked_ids.end(),
223  ops_result.blocked_ids.begin(), ops_result.blocked_ids.end());
224  }
225 
226  if (state.last_node) {
227  rerouting_info.rerouting_start_id = state.last_node->nodeid;
228  rerouting_info.rerouting_start_pose = robot_pose;
229  } else {
230  rerouting_info.rerouting_start_id = std::numeric_limits<unsigned int>::max();
231  rerouting_info.rerouting_start_pose = geometry_msgs::msg::PoseStamped();
232  }
233 
234  // Update so during rerouting we can check if we are continuing on the same edge
235  rerouting_info.curr_edge = state.current_edge;
236  RCLCPP_INFO(logger_, "Rerouting requested by route tracking operations!");
237  return TrackerResult::INTERRUPTED;
238  }
239 
240  r.sleep();
241  }
242 
243  return TrackerResult::EXITED;
244 }
245 
246 } // namespace nav2_route
void configure(nav2_util::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf_buffer, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, std::shared_ptr< ActionServerTrack > action_server, const std::string &route_frame, const std::string &base_frame)
Configure route tracker.
bool nodeAchieved(const geometry_msgs::msg::PoseStamped &pose, RouteTrackingState &state, const Route &route)
Determine if a node is to be considered achieved at the current position.
TrackerResult trackRoute(const Route &route, const nav_msgs::msg::Path &path, ReroutingState &rerouting_info)
Main function to track route, manage state, and trigger operations.
void publishFeedback(const bool rereouted, const unsigned int next_node_id, const unsigned int last_node_id, const unsigned int edge_id, const std::vector< std::string > &operations)
A utility to publish feedback for the action on important changes.
geometry_msgs::msg::PoseStamped getRobotPose()
Get the current robot's base_frame pose in route_frame.
bool isStartOrEndNode(RouteTrackingState &state, const Route &route)
Determine if a node is the start or last node in the route.
An object to store the nodes in the graph file.
Definition: types.hpp:183
Result information from the operations manager.
Definition: types.hpp:123
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
Definition: types.hpp:264
Current state management of route tracking class.
Definition: types.hpp:248
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211