19 #include "tf2_ros/transform_listener.hpp"
20 #include "nav2_util/robot_utils.hpp"
21 #include "nav2_ros_common/simple_action_server.hpp"
22 #include "nav2_msgs/action/compute_and_track_route.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "nav2_core/route_exceptions.hpp"
25 #include "nav2_route/operations_manager.hpp"
27 #ifndef NAV2_ROUTE__ROUTE_TRACKER_HPP_
28 #define NAV2_ROUTE__ROUTE_TRACKER_HPP_
42 using Feedback = nav2_msgs::action::ComputeAndTrackRoute::Feedback;
60 nav2::LifecycleNode::SharedPtr node,
61 std::shared_ptr<tf2_ros::Buffer> tf_buffer,
62 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
63 typename ActionServerTrack::SharedPtr action_server,
64 const std::string & route_frame,
65 const std::string & base_frame);
75 const geometry_msgs::msg::PoseStamped & pose,
102 const bool rereouted,
103 const unsigned int next_node_id,
104 const unsigned int last_node_id,
105 const unsigned int edge_id,
106 const std::vector<std::string> & operations);
116 const Route & route,
const nav_msgs::msg::Path & path,
120 nav2_msgs::msg::Route route_msg_;
121 nav_msgs::msg::Path path_;
122 std::string route_frame_, base_frame_;
123 rclcpp::Clock::SharedPtr clock_;
124 rclcpp::Logger logger_{rclcpp::get_logger(
"RouteTracker")};
125 double radius_threshold_, boundary_radius_threshold_, tracker_update_rate_;
126 bool aggregate_blocked_ids_;
127 typename ActionServerTrack::SharedPtr action_server_;
128 std::unique_ptr<OperationsManager> operations_manager_;
129 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
An action server wrapper to make applications simpler using Actions.
Takes a processing route request and tracks it for progress in accordance with executing behavioral o...
~RouteTracker()=default
A constructor for nav2_route::RouteTracker.
bool nodeAchieved(const geometry_msgs::msg::PoseStamped &pose, RouteTrackingState &state, const Route &route)
Determine if a node is to be considered achieved at the current position.
TrackerResult trackRoute(const Route &route, const nav_msgs::msg::Path &path, ReroutingState &rerouting_info)
Main function to track route, manage state, and trigger operations.
void publishFeedback(const bool rereouted, const unsigned int next_node_id, const unsigned int last_node_id, const unsigned int edge_id, const std::vector< std::string > &operations)
A utility to publish feedback for the action on important changes.
RouteTracker()=default
A constructor for nav2_route::RouteTracker.
geometry_msgs::msg::PoseStamped getRobotPose()
Get the current robot's base_frame pose in route_frame.
bool isStartOrEndNode(RouteTrackingState &state, const Route &route)
Determine if a node is the start or last node in the route.
void configure(nav2::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf_buffer, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, typename ActionServerTrack::SharedPtr action_server, const std::string &route_frame, const std::string &base_frame)
Configure route tracker.
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
Current state management of route tracking class.
An ordered set of nodes and edges corresponding to the planned route.