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