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