Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
route_server.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. Reserved.
14 
15 #include "nav2_route/route_server.hpp"
16 
17 using nav2::declare_parameter_if_not_declared;
18 using std::placeholders::_1;
19 using std::placeholders::_2;
20 
21 namespace nav2_route
22 {
23 
24 RouteServer::RouteServer(const rclcpp::NodeOptions & options)
25 : nav2::LifecycleNode("route_server", "", options)
26 {}
27 
28 nav2::CallbackReturn
29 RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
30 {
31  RCLCPP_INFO(get_logger(), "Configuring");
32 
33  tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
34  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
35  get_node_base_interface(),
36  get_node_timers_interface());
37  tf_->setCreateTimerInterface(timer_interface);
38  transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
39 
40  auto node = shared_from_this();
41  graph_vis_publisher_ =
42  node->create_publisher<visualization_msgs::msg::MarkerArray>(
43  "route_graph", nav2::qos::LatchedPublisherQoS());
44 
45  compute_route_server_ = create_action_server<ComputeRoute>(
46  "compute_route",
47  std::bind(&RouteServer::computeRoute, this),
48  nullptr, std::chrono::milliseconds(500), true);
49 
50  compute_and_track_route_server_ = create_action_server<ComputeAndTrackRoute>(
51  "compute_and_track_route",
52  std::bind(&RouteServer::computeAndTrackRoute, this),
53  nullptr, std::chrono::milliseconds(500), true);
54 
55  set_graph_service_ = node->create_service<nav2_msgs::srv::SetRouteGraph>(
56  std::string(node->get_name()) + "/set_route_graph",
57  std::bind(
59  std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
60 
61  declare_parameter_if_not_declared(
62  node, "route_frame", rclcpp::ParameterValue(std::string("map")));
63  declare_parameter_if_not_declared(
64  node, "base_frame", rclcpp::ParameterValue(std::string("base_link")));
65  declare_parameter_if_not_declared(
66  node, "max_planning_time", rclcpp::ParameterValue(2.0));
67 
68  route_frame_ = node->get_parameter("route_frame").as_string();
69  base_frame_ = node->get_parameter("base_frame").as_string();
70  max_planning_time_ = node->get_parameter("max_planning_time").as_double();
71 
72  // Create costmap subscriber
73  nav2::declare_parameter_if_not_declared(
74  node, "costmap_topic",
75  rclcpp::ParameterValue(std::string("global_costmap/costmap_raw")));
76  std::string costmap_topic = node->get_parameter("costmap_topic").as_string();
77  costmap_subscriber_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
78 
79  try {
80  graph_loader_ = std::make_shared<GraphLoader>(node, tf_, route_frame_);
81  if (!graph_loader_->loadGraphFromParameter(graph_, id_to_graph_map_)) {
82  return nav2::CallbackReturn::FAILURE;
83  }
84 
85  goal_intent_extractor_ = std::make_shared<GoalIntentExtractor>();
86  goal_intent_extractor_->configure(
87  node, graph_, &id_to_graph_map_, tf_, costmap_subscriber_, route_frame_, base_frame_);
88 
89  route_planner_ = std::make_shared<RoutePlanner>();
90  route_planner_->configure(node, tf_, costmap_subscriber_);
91 
92  route_tracker_ = std::make_shared<RouteTracker>();
93  route_tracker_->configure(
94  node, tf_, costmap_subscriber_, compute_and_track_route_server_, route_frame_, base_frame_);
95 
96  path_converter_ = std::make_shared<PathConverter>();
97  path_converter_->configure(node);
98  } catch (std::exception & e) {
99  RCLCPP_FATAL(get_logger(), "Failed to configure route server: %s", e.what());
100  return nav2::CallbackReturn::FAILURE;
101  }
102 
103  return nav2::CallbackReturn::SUCCESS;
104 }
105 
106 nav2::CallbackReturn
107 RouteServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
108 {
109  RCLCPP_INFO(get_logger(), "Activating");
110  compute_route_server_->activate();
111  compute_and_track_route_server_->activate();
112  graph_vis_publisher_->on_activate();
113  graph_vis_publisher_->publish(utils::toMsg(graph_, route_frame_, this->now()));
114  createBond();
115  return nav2::CallbackReturn::SUCCESS;
116 }
117 
118 nav2::CallbackReturn
119 RouteServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
120 {
121  RCLCPP_INFO(get_logger(), "Deactivating");
122  compute_route_server_->deactivate();
123  compute_and_track_route_server_->deactivate();
124  graph_vis_publisher_->on_deactivate();
125  destroyBond();
126  return nav2::CallbackReturn::SUCCESS;
127 }
128 
129 nav2::CallbackReturn
130 RouteServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
131 {
132  RCLCPP_INFO(get_logger(), "Cleaning up");
133  compute_route_server_.reset();
134  compute_and_track_route_server_.reset();
135  set_graph_service_.reset();
136  graph_loader_.reset();
137  route_planner_.reset();
138  route_tracker_.reset();
139  path_converter_.reset();
140  goal_intent_extractor_.reset();
141  graph_vis_publisher_.reset();
142  transform_listener_.reset();
143  tf_.reset();
144  graph_.clear();
145  return nav2::CallbackReturn::SUCCESS;
146 }
147 
148 nav2::CallbackReturn
149 RouteServer::on_shutdown(const rclcpp_lifecycle::State &)
150 {
151  RCLCPP_INFO(get_logger(), "Shutting down");
152  return nav2::CallbackReturn::SUCCESS;
153 }
154 
155 rclcpp::Duration
156 RouteServer::findPlanningDuration(const rclcpp::Time & start_time)
157 {
158  auto cycle_duration = this->now() - start_time;
159  if (max_planning_time_ > 0.0 && cycle_duration.seconds() > max_planning_time_) {
160  RCLCPP_WARN(
161  get_logger(),
162  "Route planner missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
163  1 / max_planning_time_, 1 / cycle_duration.seconds());
164  }
165 
166  return cycle_duration;
167 }
168 
169 template<typename ActionT>
170 bool
172  typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server)
173 {
174  if (!action_server || !action_server->is_server_active()) {
175  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
176  return false;
177  }
178 
179  if (action_server->is_cancel_requested()) {
180  RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling route planning action.");
181  action_server->terminate_all();
182  return false;
183  }
184 
185  if (graph_.empty()) {
186  RCLCPP_INFO(get_logger(), "No graph set! Aborting request.");
187  action_server->terminate_current();
188  return false;
189  }
190 
191  return true;
192 }
193 
195  std::shared_ptr<ComputeRoute::Result> result,
196  const Route & route,
197  const nav_msgs::msg::Path & path,
198  const rclcpp::Duration & planning_duration)
199 {
200  result->route = utils::toMsg(route, route_frame_, this->now());
201  result->path = path;
202  result->planning_time = planning_duration;
203 }
204 
206  std::shared_ptr<ComputeAndTrackRoute::Result> result,
207  const Route &,
208  const nav_msgs::msg::Path &,
209  const rclcpp::Duration & execution_duration)
210 {
211  result->execution_duration = execution_duration;
212 }
213 
214 template<typename GoalT>
216  const std::shared_ptr<const GoalT> goal,
217  ReroutingState & rerouting_info)
218 {
219  // Find the search boundaries
220  auto [start_route, end_route] = goal_intent_extractor_->findStartandGoal(goal);
221 
222  // If we're rerouting, use the rerouting start node and pose as the new start
223  if (rerouting_info.rerouting_start_id != std::numeric_limits<unsigned int>::max()) {
224  start_route = id_to_graph_map_.at(rerouting_info.rerouting_start_id);
225  goal_intent_extractor_->overrideStart(rerouting_info.rerouting_start_pose);
226  }
227 
228  Route route;
229  if (start_route == end_route) {
230  // Succeed with a single-point route
231  route.route_cost = 0.0;
232  route.start_node = &graph_.at(start_route);
233  } else {
234  // Populate request data (start & goal id, start & goal pose, if set) for routing
235  RouteRequest route_request;
236  route_request.start_nodeid = start_route;
237  route_request.goal_nodeid = end_route;
238  route_request.start_pose = goal_intent_extractor_->getStart();
239  route_request.goal_pose = goal->goal;
240  route_request.use_poses = goal->use_poses;
241 
242  // Compute the route via graph-search, returns a node-edge sequence
243  route = route_planner_->findRoute(
244  graph_, start_route, end_route, rerouting_info.blocked_ids, route_request);
245  }
246 
247  return goal_intent_extractor_->pruneStartandGoal(route, goal, rerouting_info);
248 }
249 
250 template<typename ActionT>
251 void
253  typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server)
254 {
255  auto goal = action_server->get_current_goal();
256  auto result = std::make_shared<typename ActionT::Result>();
257  ReroutingState rerouting_info;
258  auto start_time = this->now();
259 
260  try {
261  while (rclcpp::ok()) {
262  if (!isRequestValid<ActionT>(action_server)) {
263  return;
264  }
265 
266  if (action_server->is_preempt_requested()) {
267  RCLCPP_INFO(get_logger(), "Computing new preempted route to goal.");
268  goal = action_server->accept_pending_goal();
269  rerouting_info.reset();
270  }
271 
272  // Find the route
273  Route route = findRoute(goal, rerouting_info);
274  RCLCPP_INFO(get_logger(), "Route found with %zu nodes and %zu edges",
275  route.edges.size() + 1u, route.edges.size());
276  auto path = path_converter_->densify(route, rerouting_info, route_frame_, this->now());
277 
278  if (std::is_same<ActionT, ComputeAndTrackRoute>::value) {
279  // blocks until re-route requested or task completion, publishes feedback
280  switch (route_tracker_->trackRoute(route, path, rerouting_info)) {
281  case TrackerResult::COMPLETED:
282  populateActionResult(result, route, path, this->now() - start_time);
283  action_server->succeeded_current(result);
284  return;
285  case TrackerResult::INTERRUPTED:
286  // Reroute, cancel, or preempt requested
287  break;
288  case TrackerResult::EXITED:
289  // rclcpp::ok() is false, so just return
290  return;
291  }
292  } else {
293  // Return route if not tracking
294  populateActionResult(result, route, path, findPlanningDuration(start_time));
295  action_server->succeeded_current(result);
296  return;
297  }
298  }
299  } catch (nav2_core::NoValidRouteCouldBeFound & ex) {
300  exceptionWarning(goal, ex);
301  result->error_code = ActionT::Result::NO_VALID_ROUTE;
302  result->error_msg = ex.what();
303  action_server->terminate_current(result);
304  } catch (nav2_core::TimedOut & ex) {
305  exceptionWarning(goal, ex);
306  result->error_code = ActionT::Result::TIMEOUT;
307  result->error_msg = ex.what();
308  action_server->terminate_current(result);
309  } catch (nav2_core::RouteTFError & ex) {
310  exceptionWarning(goal, ex);
311  result->error_code = ActionT::Result::TF_ERROR;
312  result->error_msg = ex.what();
313  action_server->terminate_current(result);
314  } catch (nav2_core::NoValidGraph & ex) {
315  exceptionWarning(goal, ex);
316  result->error_code = ActionT::Result::NO_VALID_GRAPH;
317  result->error_msg = ex.what();
318  action_server->terminate_current(result);
319  } catch (nav2_core::IndeterminantNodesOnGraph & ex) {
320  exceptionWarning(goal, ex);
321  result->error_code = ActionT::Result::INDETERMINANT_NODES_ON_GRAPH;
322  result->error_msg = ex.what();
323  action_server->terminate_current(result);
324  } catch (nav2_core::InvalidEdgeScorerUse & ex) {
325  exceptionWarning(goal, ex);
326  result->error_code = ActionT::Result::INVALID_EDGE_SCORER_USE;
327  result->error_msg = ex.what();
328  action_server->terminate_current(result);
329  } catch (nav2_core::OperationFailed & ex) {
330  // A special case since Operation Failed is only in Compute & Track
331  // actions, specifying it to allow otherwise fully shared code
332  exceptionWarning(goal, ex);
333  result->error_code = ComputeAndTrackRoute::Result::OPERATION_FAILED;
334  result->error_msg = ex.what();
335  action_server->terminate_current(result);
336  } catch (nav2_core::RouteException & ex) {
337  exceptionWarning(goal, ex);
338  result->error_code = ActionT::Result::UNKNOWN;
339  result->error_msg = ex.what();
340  action_server->terminate_current(result);
341  } catch (std::exception & ex) {
342  exceptionWarning(goal, ex);
343  result->error_code = ActionT::Result::UNKNOWN;
344  result->error_msg = ex.what();
345  action_server->terminate_current(result);
346  }
347 }
348 
349 void
351 {
352  RCLCPP_INFO(get_logger(), "Computing route to goal.");
353  processRouteRequest<ComputeRoute>(compute_route_server_);
354 }
355 
356 void
357 RouteServer::computeAndTrackRoute()
358 {
359  RCLCPP_INFO(get_logger(), "Computing and tracking route to goal.");
360  processRouteRequest<ComputeAndTrackRoute>(compute_and_track_route_server_);
361 }
362 
364  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
365  const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request,
366  std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response)
367 {
368  RCLCPP_INFO(get_logger(), "Setting new route graph: %s.", request->graph_filepath.c_str());
369  graph_.clear();
370  id_to_graph_map_.clear();
371  try {
372  if (graph_loader_->loadGraphFromFile(graph_, id_to_graph_map_, request->graph_filepath)) {
373  goal_intent_extractor_->setGraph(graph_, &id_to_graph_map_);
374  graph_vis_publisher_->publish(utils::toMsg(graph_, route_frame_, this->now()));
375  response->success = true;
376  return;
377  }
378  } catch (std::exception & ex) {
379  }
380 
381  RCLCPP_WARN(
382  get_logger(),
383  "Failed to set new route graph: %s!", request->graph_filepath.c_str());
384  response->success = false;
385 }
386 
387 template<typename GoalT>
389  const std::shared_ptr<const GoalT> goal,
390  const std::exception & ex)
391 {
392  RCLCPP_WARN(
393  get_logger(),
394  "Route server failed on request: Start: [(%0.2f, %0.2f) / %i] Goal: [(%0.2f, %0.2f) / %i]:"
395  " \"%s\"", goal->start.pose.position.x, goal->start.pose.position.y, goal->start_id,
396  goal->goal.pose.position.x, goal->goal.pose.position.y, goal->goal_id, ex.what());
397 }
398 
399 } // namespace nav2_route
400 
401 #include "rclcpp_components/register_node_macro.hpp"
402 
403 // Register the component with class_loader.
404 // This acts as a sort of entry point, allowing the component to be discoverable when its library
405 // is being loaded into a running process.
406 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_route::RouteServer)
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void terminate_current(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Terminate the active action.
const std::shared_ptr< const typename ActionT::Goal > get_current_goal() const
Get the current goal object.
bool is_cancel_requested() const
Whether or not a cancel command has come in.
void terminate_all(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Terminate all pending and active actions.
bool is_preempt_requested() const
Whether the action server has been asked to be preempted with a new goal.
void succeeded_current(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Return success of the active action.
bool is_server_active()
Whether the action server is active or not.
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal()
Accept pending goals.
A QoS profile for latched, reliable topics with a history of 1 messages.
An action server implements a Navigation Route-Graph planner to compliment free-space planning in the...
void computeRoute()
Main route action server callbacks for computing and tracking a route.
void setRouteGraph(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< nav2_msgs::srv::SetRouteGraph::Request > request, std::shared_ptr< nav2_msgs::srv::SetRouteGraph::Response > response)
The service callback to set a new route graph.
rclcpp::Duration findPlanningDuration(const rclcpp::Time &start_time)
Find the planning duration of the request and log warnings.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
Route findRoute(const std::shared_ptr< const GoalT > goal, ReroutingState &rerouting_info=ReroutingState())
Abstract method combining finding the starting/ending nodes and the route planner to find the Node lo...
bool isRequestValid(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server)
Find the routing request is valid (action server OK and not cancelled)
RouteServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_route::RouteServer.
void exceptionWarning(const std::shared_ptr< const GoalT > goal, const std::exception &ex)
Log exception warnings, templated by action message type.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
void populateActionResult(std::shared_ptr< ComputeRoute::Result > result, const Route &route, const nav_msgs::msg::Path &path, const rclcpp::Duration &planning_duration)
Populate result for compute route action.
void processRouteRequest(typename nav2::SimpleActionServer< ActionT >::SharedPtr &action_server)
Main processing called by both action server callbacks to centralize the great deal of shared code be...
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
Definition: types.hpp:264
An object to store salient features of the route request including its start and goal node ids,...
Definition: types.hpp:224
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211