15 #ifndef NAV2_ROUTE__ROUTE_SERVER_HPP_
16 #define NAV2_ROUTE__ROUTE_SERVER_HPP_
22 #include <unordered_map>
25 #include "nav2_ros_common/lifecycle_node.hpp"
26 #include "tf2_ros/transform_listener.hpp"
27 #include "tf2_ros/create_timer_ros.hpp"
28 #include "nav2_ros_common/simple_action_server.hpp"
29 #include "nav2_ros_common/node_utils.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 #include "nav2_ros_common/service_server.hpp"
32 #include "nav2_msgs/action/compute_route.hpp"
33 #include "nav2_msgs/action/compute_and_track_route.hpp"
34 #include "nav2_msgs/msg/route.hpp"
35 #include "nav2_msgs/msg/route_node.hpp"
36 #include "nav2_msgs/srv/set_route_graph.hpp"
37 #include "nav2_core/route_exceptions.hpp"
38 #include "visualization_msgs/msg/marker_array.hpp"
40 #include "nav2_route/types.hpp"
41 #include "nav2_route/utils.hpp"
42 #include "nav2_route/graph_loader.hpp"
43 #include "nav2_route/route_planner.hpp"
44 #include "nav2_route/path_converter.hpp"
45 #include "nav2_route/route_tracker.hpp"
46 #include "nav2_route/goal_intent_extractor.hpp"
58 using ComputeRoute = nav2_msgs::action::ComputeRoute;
59 using ComputeRouteGoal = ComputeRoute::Goal;
60 using ComputeRouteResult = ComputeRoute::Result;
63 using ComputeAndTrackRoute = nav2_msgs::action::ComputeAndTrackRoute;
64 using ComputeAndTrackRouteGoal = ComputeAndTrackRoute::Goal;
65 using ComputeAndTrackRouteFeedback = ComputeAndTrackRoute::Feedback;
66 using ComputeAndTrackRouteResult = ComputeAndTrackRoute::Result;
73 explicit RouteServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
85 nav2::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
92 nav2::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
99 nav2::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
106 nav2::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
113 nav2::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
119 void computeAndTrackRoute();
130 template<
typename GoalT>
132 const std::shared_ptr<const GoalT> goal,
139 template<
typename ActionT>
141 typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server);
155 template<
typename ActionT>
156 bool isRequestValid(
typename nav2::SimpleActionServer<ActionT>::SharedPtr & action_server);
166 std::shared_ptr<ComputeRoute::Result> result,
168 const nav_msgs::msg::Path & path,
169 const rclcpp::Duration & planning_duration);
179 std::shared_ptr<ComputeAndTrackRoute::Result>,
181 const nav_msgs::msg::Path & ,
182 const rclcpp::Duration & );
191 const std::shared_ptr<rmw_request_id_t>,
192 const std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Request> request,
193 std::shared_ptr<nav2_msgs::srv::SetRouteGraph::Response> response);
200 template<
typename GoalT>
201 void exceptionWarning(
const std::shared_ptr<const GoalT> goal,
const std::exception & ex);
203 typename ComputeRouteServer::SharedPtr compute_route_server_;
204 typename ComputeAndTrackRouteServer::SharedPtr compute_and_track_route_server_;
207 std::shared_ptr<tf2_ros::Buffer> tf_;
208 std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
211 nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
212 graph_vis_publisher_;
215 nav2::ServiceServer<nav2_msgs::srv::SetRouteGraph>::SharedPtr set_graph_service_;
218 std::shared_ptr<GraphLoader> graph_loader_;
219 std::shared_ptr<RoutePlanner> route_planner_;
220 std::shared_ptr<RouteTracker> route_tracker_;
221 std::shared_ptr<PathConverter> path_converter_;
222 std::shared_ptr<GoalIntentExtractor> goal_intent_extractor_;
224 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber_;
228 GraphToIDMap id_to_graph_map_;
229 std::string route_frame_, base_frame_;
230 double max_planning_time_;
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.
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.
~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::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 ordered set of nodes and edges corresponding to the planned route.