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_);
41 graph_vis_publisher_ =
42 node->create_publisher<visualization_msgs::msg::MarkerArray>(
43 "route_graph", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
45 compute_route_server_ = std::make_shared<ComputeRouteServer>(
46 node,
"compute_route",
48 nullptr, std::chrono::milliseconds(500),
true);
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);
55 set_graph_service_ = node->create_service<nav2_msgs::srv::SetRouteGraph>(
56 std::string(node->get_name()) +
"/set_route_graph",
59 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
61 declare_parameter_if_not_declared(
62 node,
"route_frame", rclcpp::ParameterValue(std::string(
"map")));
63 declare_parameter_if_not_declared(
64 node,
"global_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));
70 route_frame_ = node->get_parameter(
"route_frame").as_string();
71 global_frame_ = node->get_parameter(
"global_frame").as_string();
72 base_frame_ = node->get_parameter(
"base_frame").as_string();
73 max_planning_time_ = node->get_parameter(
"max_planning_time").as_double();
76 nav2_util::declare_parameter_if_not_declared(
77 node,
"costmap_topic",
78 rclcpp::ParameterValue(std::string(
"global_costmap/costmap_raw")));
79 std::string costmap_topic = node->get_parameter(
"costmap_topic").as_string();
80 costmap_subscriber_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
83 graph_loader_ = std::make_shared<GraphLoader>(node, tf_, route_frame_);
84 if (!graph_loader_->loadGraphFromParameter(graph_, id_to_graph_map_)) {
85 return nav2_util::CallbackReturn::FAILURE;
88 goal_intent_extractor_ = std::make_shared<GoalIntentExtractor>();
89 goal_intent_extractor_->configure(
90 node, graph_, &id_to_graph_map_, tf_, costmap_subscriber_, route_frame_,
91 global_frame_, base_frame_);
93 route_planner_ = std::make_shared<RoutePlanner>();
94 route_planner_->configure(node, tf_, costmap_subscriber_);
96 route_tracker_ = std::make_shared<RouteTracker>();
97 route_tracker_->configure(
98 node, tf_, costmap_subscriber_, compute_and_track_route_server_, route_frame_, base_frame_);
100 path_converter_ = std::make_shared<PathConverter>();
101 path_converter_->configure(node);
102 }
catch (std::exception & e) {
103 RCLCPP_FATAL(get_logger(),
"Failed to configure route server: %s", e.what());
104 return nav2_util::CallbackReturn::FAILURE;
107 return nav2_util::CallbackReturn::SUCCESS;
110 nav2_util::CallbackReturn
113 RCLCPP_INFO(get_logger(),
"Activating");
114 compute_route_server_->activate();
115 compute_and_track_route_server_->activate();
116 graph_vis_publisher_->on_activate();
117 graph_vis_publisher_->publish(utils::toMsg(graph_, route_frame_, this->now()));
119 return nav2_util::CallbackReturn::SUCCESS;
122 nav2_util::CallbackReturn
125 RCLCPP_INFO(get_logger(),
"Deactivating");
126 compute_route_server_->deactivate();
127 compute_and_track_route_server_->deactivate();
128 graph_vis_publisher_->on_deactivate();
130 return nav2_util::CallbackReturn::SUCCESS;
133 nav2_util::CallbackReturn
136 RCLCPP_INFO(get_logger(),
"Cleaning up");
137 compute_route_server_.reset();
138 compute_and_track_route_server_.reset();
139 set_graph_service_.reset();
140 graph_loader_.reset();
141 route_planner_.reset();
142 route_tracker_.reset();
143 path_converter_.reset();
144 goal_intent_extractor_.reset();
145 graph_vis_publisher_.reset();
146 transform_listener_.reset();
149 return nav2_util::CallbackReturn::SUCCESS;
152 nav2_util::CallbackReturn
155 RCLCPP_INFO(get_logger(),
"Shutting down");
156 return nav2_util::CallbackReturn::SUCCESS;
162 auto cycle_duration = this->now() - start_time;
163 if (max_planning_time_ > 0.0 && cycle_duration.seconds() > max_planning_time_) {
166 "Route planner missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
167 1 / max_planning_time_, 1 / cycle_duration.seconds());
170 return cycle_duration;
173 template<
typename ActionT>
178 if (!action_server || !action_server->is_server_active()) {
179 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
183 if (action_server->is_cancel_requested()) {
184 RCLCPP_INFO(get_logger(),
"Goal was canceled. Canceling route planning action.");
185 action_server->terminate_all();
189 if (graph_.empty()) {
190 RCLCPP_INFO(get_logger(),
"No graph set! Aborting request.");
191 action_server->terminate_current();
199 std::shared_ptr<ComputeRoute::Result> result,
201 const nav_msgs::msg::Path & path,
202 const rclcpp::Duration & planning_duration)
204 result->route = utils::toMsg(route, route_frame_, this->now());
206 result->planning_time = planning_duration;
210 std::shared_ptr<ComputeAndTrackRoute::Result> result,
212 const nav_msgs::msg::Path &,
213 const rclcpp::Duration & execution_duration)
215 result->execution_duration = execution_duration;
218 template<
typename GoalT>
220 const std::shared_ptr<const GoalT> goal,
224 auto [start_route, end_route] = goal_intent_extractor_->findStartandGoal(goal);
227 if (rerouting_info.rerouting_start_id != std::numeric_limits<unsigned int>::max()) {
228 start_route = id_to_graph_map_.at(rerouting_info.rerouting_start_id);
229 goal_intent_extractor_->overrideStart(rerouting_info.rerouting_start_pose);
233 if (start_route == end_route) {
235 route.route_cost = 0.0;
236 route.start_node = &graph_.at(start_route);
240 route_request.start_nodeid = start_route;
241 route_request.goal_nodeid = end_route;
242 route_request.start_pose = goal_intent_extractor_->getStart();
243 route_request.goal_pose = goal->goal;
244 route_request.use_poses = goal->use_poses;
247 route = route_planner_->findRoute(
248 graph_, start_route, end_route, rerouting_info.blocked_ids, route_request);
251 return goal_intent_extractor_->pruneStartandGoal(route, goal, rerouting_info);
254 template<
typename ActionT>
259 auto goal = action_server->get_current_goal();
260 auto result = std::make_shared<typename ActionT::Result>();
262 auto start_time = this->now();
265 while (rclcpp::ok()) {
266 if (!isRequestValid<ActionT>(action_server)) {
270 if (action_server->is_preempt_requested()) {
271 RCLCPP_INFO(get_logger(),
"Computing new preempted route to goal.");
272 goal = action_server->accept_pending_goal();
273 rerouting_info.reset();
279 get_logger(),
"Route found with %zu nodes and %zu edges",
280 route.edges.size() + 1u, route.edges.size());
281 auto path = path_converter_->densify(route, rerouting_info, route_frame_, this->now());
283 if (std::is_same<ActionT, ComputeAndTrackRoute>::value) {
285 switch (route_tracker_->trackRoute(route, path, rerouting_info)) {
286 case TrackerResult::COMPLETED:
288 action_server->succeeded_current(result);
290 case TrackerResult::INTERRUPTED:
293 case TrackerResult::EXITED:
300 action_server->succeeded_current(result);
306 action_server->terminate_current(result);
309 action_server->terminate_current(result);
312 action_server->terminate_current(result);
315 action_server->terminate_current(result);
318 action_server->terminate_current(result);
321 action_server->terminate_current(result);
326 action_server->terminate_current(result);
329 action_server->terminate_current(result);
330 }
catch (std::exception & ex) {
332 action_server->terminate_current(result);
339 RCLCPP_INFO(get_logger(),
"Computing route to goal.");
340 processRouteRequest<ComputeRoute>(compute_route_server_);
344 RouteServer::computeAndTrackRoute()
346 RCLCPP_INFO(get_logger(),
"Computing and tracking route to goal.");
347 processRouteRequest<ComputeAndTrackRoute>(compute_and_track_route_server_);
351 const std::shared_ptr<rmw_request_id_t>,
352 const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request,
353 std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response)
355 RCLCPP_INFO(get_logger(),
"Setting new route graph: %s.", request->graph_filepath.c_str());
357 id_to_graph_map_.clear();
359 if (graph_loader_->loadGraphFromFile(graph_, id_to_graph_map_, request->graph_filepath)) {
360 goal_intent_extractor_->setGraph(graph_, &id_to_graph_map_);
361 graph_vis_publisher_->publish(utils::toMsg(graph_, route_frame_, this->now()));
362 response->success =
true;
365 }
catch (std::exception & ex) {
370 "Failed to set new route graph: %s!", request->graph_filepath.c_str());
371 response->success =
false;
374 template<
typename GoalT>
376 const std::shared_ptr<const GoalT> goal,
377 const std::exception & ex)
381 "Route server failed on request: Start: [(%0.2f, %0.2f) / %i] Goal: [(%0.2f, %0.2f) / %i]:"
382 " \"%s\"", goal->start.pose.position.x, goal->start.pose.position.y, goal->start_id,
383 goal->goal.pose.position.x, goal->goal.pose.position.y, goal->goal_id, ex.what());
388 #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.