15 #include "nav2_route/route_server.hpp"
17 using nav2::declare_parameter_if_not_declared;
18 using std::placeholders::_1;
19 using std::placeholders::_2;
25 : nav2::LifecycleNode(
"route_server",
"", options)
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>(
45 compute_route_server_ = create_action_server<ComputeRoute>(
48 nullptr, std::chrono::milliseconds(500),
true);
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);
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,
"base_frame", rclcpp::ParameterValue(std::string(
"base_link")));
65 declare_parameter_if_not_declared(
66 node,
"max_planning_time", rclcpp::ParameterValue(2.0));
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();
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);
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;
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_);
89 route_planner_ = std::make_shared<RoutePlanner>();
90 route_planner_->configure(node, tf_, costmap_subscriber_);
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_);
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;
103 return nav2::CallbackReturn::SUCCESS;
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()));
115 return nav2::CallbackReturn::SUCCESS;
121 RCLCPP_INFO(get_logger(),
"Deactivating");
122 compute_route_server_->deactivate();
123 compute_and_track_route_server_->deactivate();
124 graph_vis_publisher_->on_deactivate();
126 return nav2::CallbackReturn::SUCCESS;
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();
145 return nav2::CallbackReturn::SUCCESS;
151 RCLCPP_INFO(get_logger(),
"Shutting down");
152 return nav2::CallbackReturn::SUCCESS;
158 auto cycle_duration = this->now() - start_time;
159 if (max_planning_time_ > 0.0 && cycle_duration.seconds() > max_planning_time_) {
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());
166 return cycle_duration;
169 template<
typename ActionT>
172 typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server)
175 RCLCPP_DEBUG(get_logger(),
"Action server unavailable or inactive. Stopping.");
180 RCLCPP_INFO(get_logger(),
"Goal was canceled. Canceling route planning action.");
185 if (graph_.empty()) {
186 RCLCPP_INFO(get_logger(),
"No graph set! Aborting request.");
195 std::shared_ptr<ComputeRoute::Result> result,
197 const nav_msgs::msg::Path & path,
198 const rclcpp::Duration & planning_duration)
200 result->route = utils::toMsg(route, route_frame_, this->now());
202 result->planning_time = planning_duration;
206 std::shared_ptr<ComputeAndTrackRoute::Result> result,
208 const nav_msgs::msg::Path &,
209 const rclcpp::Duration & execution_duration)
211 result->execution_duration = execution_duration;
214 template<
typename GoalT>
216 const std::shared_ptr<const GoalT> goal,
220 auto [start_route, end_route] = goal_intent_extractor_->findStartandGoal(goal);
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);
229 if (start_route == end_route) {
231 route.route_cost = 0.0;
232 route.start_node = &graph_.at(start_route);
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;
243 route = route_planner_->findRoute(
244 graph_, start_route, end_route, rerouting_info.blocked_ids, route_request);
247 return goal_intent_extractor_->pruneStartandGoal(route, goal, rerouting_info);
250 template<
typename ActionT>
253 typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server)
256 auto result = std::make_shared<typename ActionT::Result>();
258 auto start_time = this->now();
261 while (rclcpp::ok()) {
262 if (!isRequestValid<ActionT>(action_server)) {
267 RCLCPP_INFO(get_logger(),
"Computing new preempted route to goal.");
269 rerouting_info.reset();
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());
278 if (std::is_same<ActionT, ComputeAndTrackRoute>::value) {
280 switch (route_tracker_->trackRoute(route, path, rerouting_info)) {
281 case TrackerResult::COMPLETED:
285 case TrackerResult::INTERRUPTED:
288 case TrackerResult::EXITED:
301 result->error_code = ActionT::Result::NO_VALID_ROUTE;
302 result->error_msg = ex.what();
306 result->error_code = ActionT::Result::TIMEOUT;
307 result->error_msg = ex.what();
311 result->error_code = ActionT::Result::TF_ERROR;
312 result->error_msg = ex.what();
316 result->error_code = ActionT::Result::NO_VALID_GRAPH;
317 result->error_msg = ex.what();
321 result->error_code = ActionT::Result::INDETERMINANT_NODES_ON_GRAPH;
322 result->error_msg = ex.what();
326 result->error_code = ActionT::Result::INVALID_EDGE_SCORER_USE;
327 result->error_msg = ex.what();
333 result->error_code = ComputeAndTrackRoute::Result::OPERATION_FAILED;
334 result->error_msg = ex.what();
338 result->error_code = ActionT::Result::UNKNOWN;
339 result->error_msg = ex.what();
341 }
catch (std::exception & ex) {
343 result->error_code = ActionT::Result::UNKNOWN;
344 result->error_msg = ex.what();
352 RCLCPP_INFO(get_logger(),
"Computing route to goal.");
353 processRouteRequest<ComputeRoute>(compute_route_server_);
357 RouteServer::computeAndTrackRoute()
359 RCLCPP_INFO(get_logger(),
"Computing and tracking route to goal.");
360 processRouteRequest<ComputeAndTrackRoute>(compute_and_track_route_server_);
364 const std::shared_ptr<rmw_request_id_t>,
365 const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request,
366 std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response)
368 RCLCPP_INFO(get_logger(),
"Setting new route graph: %s.", request->graph_filepath.c_str());
370 id_to_graph_map_.clear();
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;
378 }
catch (std::exception & ex) {
383 "Failed to set new route graph: %s!", request->graph_filepath.c_str());
384 response->success =
false;
387 template<
typename GoalT>
389 const std::shared_ptr<const GoalT> goal,
390 const std::exception & ex)
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());
401 #include "rclcpp_components/register_node_macro.hpp"
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...
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.