Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
route_server.hpp
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.
14 
15 #ifndef NAV2_ROUTE__ROUTE_SERVER_HPP_
16 #define NAV2_ROUTE__ROUTE_SERVER_HPP_
17 
18 #include <chrono>
19 #include <string>
20 #include <memory>
21 #include <vector>
22 #include <unordered_map>
23 #include <mutex>
24 
25 #include "nav2_util/lifecycle_node.hpp"
26 #include "tf2_ros/transform_listener.h"
27 #include "tf2_ros/create_timer_ros.h"
28 #include "nav2_util/simple_action_server.hpp"
29 #include "nav2_util/node_utils.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 #include "nav2_msgs/action/compute_route.hpp"
32 #include "nav2_msgs/action/compute_and_track_route.hpp"
33 #include "nav2_msgs/msg/route.hpp"
34 #include "nav2_msgs/msg/route_node.hpp"
35 #include "nav2_msgs/srv/set_route_graph.hpp"
36 #include "nav2_core/route_exceptions.hpp"
37 #include "visualization_msgs/msg/marker_array.hpp"
38 
39 #include "nav2_route/types.hpp"
40 #include "nav2_route/utils.hpp"
41 #include "nav2_route/graph_loader.hpp"
42 #include "nav2_route/route_planner.hpp"
43 #include "nav2_route/path_converter.hpp"
44 #include "nav2_route/route_tracker.hpp"
45 #include "nav2_route/goal_intent_extractor.hpp"
46 
47 namespace nav2_route
48 {
55 {
56 public:
57  using ComputeRoute = nav2_msgs::action::ComputeRoute;
58  using ComputeRouteGoal = ComputeRoute::Goal;
59  using ComputeRouteResult = ComputeRoute::Result;
61 
62  using ComputeAndTrackRoute = nav2_msgs::action::ComputeAndTrackRoute;
63  using ComputeAndTrackRouteGoal = ComputeAndTrackRoute::Goal;
64  using ComputeAndTrackRouteFeedback = ComputeAndTrackRoute::Feedback;
65  using ComputeAndTrackRouteResult = ComputeAndTrackRoute::Result;
67 
72  explicit RouteServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
76  ~RouteServer() = default;
77 
78 protected:
84  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
85 
91  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
92 
98  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
99 
105  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
106 
112  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
113 
117  void computeRoute();
118  void computeAndTrackRoute();
119 
129  template<typename GoalT>
131  const std::shared_ptr<const GoalT> goal,
132  ReroutingState & rerouting_info = ReroutingState());
133 
138  template<typename ActionT>
139  void processRouteRequest(
140  std::shared_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server);
141 
147  rclcpp::Duration findPlanningDuration(const rclcpp::Time & start_time);
148 
154  template<typename ActionT>
155  bool isRequestValid(std::shared_ptr<nav2_util::SimpleActionServer<ActionT>> & action_server);
156 
165  std::shared_ptr<ComputeRoute::Result> result,
166  const Route & route,
167  const nav_msgs::msg::Path & path,
168  const rclcpp::Duration & planning_duration);
169 
178  std::shared_ptr<ComputeAndTrackRoute::Result>/*result*/,
179  const Route & /*route*/,
180  const nav_msgs::msg::Path & /*path*/,
181  const rclcpp::Duration & /*planning_duration*/);
182 
189  void setRouteGraph(
190  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
191  const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request,
192  std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response);
193 
199  template<typename GoalT>
200  void exceptionWarning(const std::shared_ptr<const GoalT> goal, const std::exception & ex);
201 
202  std::shared_ptr<ComputeRouteServer> compute_route_server_;
203  std::shared_ptr<ComputeAndTrackRouteServer> compute_and_track_route_server_;
204 
205  // TF
206  std::shared_ptr<tf2_ros::Buffer> tf_;
207  std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
208 
209  // Publish the route for visualization
210  rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
211  graph_vis_publisher_;
212 
213  // Set or modify graph
214  rclcpp::Service<nav2_msgs::srv::SetRouteGraph>::SharedPtr set_graph_service_;
215 
216  // Internal tools
217  std::shared_ptr<GraphLoader> graph_loader_;
218  std::shared_ptr<RoutePlanner> route_planner_;
219  std::shared_ptr<RouteTracker> route_tracker_;
220  std::shared_ptr<PathConverter> path_converter_;
221  std::shared_ptr<GoalIntentExtractor> goal_intent_extractor_;
222 
223  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
224 
225  // State Data
226  Graph graph_;
227  GraphToIDMap id_to_graph_map_;
228  std::string route_frame_, global_frame_, base_frame_;
229  double max_planning_time_;
230 };
231 
232 } // namespace nav2_route
233 
234 #endif // NAV2_ROUTE__ROUTE_SERVER_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.
~RouteServer()=default
A destructor for nav2_route::RouteServer.
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.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
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 ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211