15 #include "nav2_route/route_server.hpp"
17 using nav2_util::declare_parameter_if_not_declared;
18 using std::placeholders::_1;
19 using std::placeholders::_2;
25 : nav2_util::LifecycleNode(
"route_server",
"", options)
28 nav2_util::CallbackReturn
31 RCLCPP_INFO(get_logger(),
"Configuring");
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);
41 graph_vis_publisher_ =
42 node->create_publisher<visualization_msgs::msg::MarkerArray>(
43 "route_graph", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
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);
52 compute_route_server_ = std::make_unique<ComputeRouteServer>(
57 std::chrono::milliseconds(500),
58 true, server_options);
60 compute_and_track_route_server_ = std::make_unique<ComputeAndTrackRouteServer>(
62 "compute_and_track_route",
63 std::bind(&RouteServer::computeAndTrackRoute,
this),
65 std::chrono::milliseconds(500),
66 true, server_options);
68 set_graph_service_ = node->create_service<nav2_msgs::srv::SetRouteGraph>(
69 std::string(node->get_name()) +
"/set_route_graph",
72 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
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));
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();
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);
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;
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_);
106 route_planner_ = std::make_shared<RoutePlanner>();
107 route_planner_->configure(node, tf_, costmap_subscriber_);
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_);
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;
120 return nav2_util::CallbackReturn::SUCCESS;
123 nav2_util::CallbackReturn
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()));
132 return nav2_util::CallbackReturn::SUCCESS;
135 nav2_util::CallbackReturn
138 RCLCPP_INFO(get_logger(),
"Deactivating");
139 compute_route_server_->deactivate();
140 compute_and_track_route_server_->deactivate();
141 graph_vis_publisher_->on_deactivate();
143 return nav2_util::CallbackReturn::SUCCESS;
146 nav2_util::CallbackReturn
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();
162 return nav2_util::CallbackReturn::SUCCESS;
165 nav2_util::CallbackReturn
168 RCLCPP_INFO(get_logger(),
"Shutting down");
169 return nav2_util::CallbackReturn::SUCCESS;
175 auto cycle_duration = this->now() - start_time;
176 if (max_planning_time_ > 0.0 && cycle_duration.seconds() > max_planning_time_) {
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());
183 return cycle_duration;
186 template<
typename ActionT>
191 if (!action_server || !action_server->is_server_active()) {
192 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
196 if (action_server->is_cancel_requested()) {
197 RCLCPP_INFO(get_logger(),
"Goal was canceled. Canceling route planning action.");
198 action_server->terminate_all();
202 if (graph_.empty()) {
203 RCLCPP_INFO(get_logger(),
"No graph set! Aborting request.");
204 action_server->terminate_current();
212 std::shared_ptr<ComputeRoute::Result> result,
214 const nav_msgs::msg::Path & path,
215 const rclcpp::Duration & planning_duration)
217 result->route = utils::toMsg(route, route_frame_, this->now());
219 result->planning_time = planning_duration;
223 std::shared_ptr<ComputeAndTrackRoute::Result> result,
225 const nav_msgs::msg::Path &,
226 const rclcpp::Duration & execution_duration)
228 result->execution_duration = execution_duration;
231 template<
typename GoalT>
233 const std::shared_ptr<const GoalT> goal,
237 auto [start_route, end_route] = goal_intent_extractor_->findStartandGoal(goal);
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);
246 if (start_route == end_route) {
248 route.route_cost = 0.0;
249 route.start_node = &graph_.at(start_route);
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;
260 route = route_planner_->findRoute(
261 graph_, start_route, end_route, rerouting_info.blocked_ids, route_request);
264 return goal_intent_extractor_->pruneStartandGoal(route, goal, rerouting_info);
267 template<
typename ActionT>
272 auto goal = action_server->get_current_goal();
273 auto result = std::make_shared<typename ActionT::Result>();
275 auto start_time = this->now();
278 while (rclcpp::ok()) {
279 if (!isRequestValid<ActionT>(action_server)) {
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();
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());
295 if (std::is_same<ActionT, ComputeAndTrackRoute>::value) {
297 switch (route_tracker_->trackRoute(route, path, rerouting_info)) {
298 case TrackerResult::COMPLETED:
300 action_server->succeeded_current(result);
302 case TrackerResult::INTERRUPTED:
305 case TrackerResult::EXITED:
312 action_server->succeeded_current(result);
318 result->error_code = ActionT::Result::NO_VALID_ROUTE;
319 action_server->terminate_current(result);
322 result->error_code = ActionT::Result::TIMEOUT;
323 action_server->terminate_current(result);
326 result->error_code = ActionT::Result::TF_ERROR;
327 action_server->terminate_current(result);
330 result->error_code = ActionT::Result::NO_VALID_GRAPH;
331 action_server->terminate_current(result);
334 result->error_code = ActionT::Result::INDETERMINANT_NODES_ON_GRAPH;
335 action_server->terminate_current(result);
338 result->error_code = ActionT::Result::INVALID_EDGE_SCORER_USE;
339 action_server->terminate_current(result);
344 result->error_code = ComputeAndTrackRoute::Result::OPERATION_FAILED;
345 action_server->terminate_current(result);
348 result->error_code = ActionT::Result::UNKNOWN;
349 action_server->terminate_current(result);
350 }
catch (std::exception & ex) {
352 result->error_code = ActionT::Result::UNKNOWN;
353 action_server->terminate_current(result);
360 RCLCPP_INFO(get_logger(),
"Computing route to goal.");
361 processRouteRequest<ComputeRoute>(compute_route_server_);
365 RouteServer::computeAndTrackRoute()
367 RCLCPP_INFO(get_logger(),
"Computing and tracking route to goal.");
368 processRouteRequest<ComputeAndTrackRoute>(compute_and_track_route_server_);
372 const std::shared_ptr<rmw_request_id_t>,
373 const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request,
374 std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response)
376 RCLCPP_INFO(get_logger(),
"Setting new route graph: %s.", request->graph_filepath.c_str());
378 id_to_graph_map_.clear();
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;
386 }
catch (std::exception & ex) {
391 "Failed to set new route graph: %s!", request->graph_filepath.c_str());
392 response->success =
false;
395 template<
typename GoalT>
397 const std::shared_ptr<const GoalT> goal,
398 const std::exception & ex)
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());
409 #include "rclcpp_components/register_node_macro.hpp"
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...
An object to store salient features of the route request including its start and goal node ids,...
An ordered set of nodes and edges corresponding to the planned route.