Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
route_tracker.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 #include <vector>
16 #include <string>
17 #include <memory>
18 
19 #include "tf2_ros/transform_listener.h"
20 #include "nav2_util/robot_utils.hpp"
21 #include "nav2_util/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"
26 
27 #ifndef NAV2_ROUTE__ROUTE_TRACKER_HPP_
28 #define NAV2_ROUTE__ROUTE_TRACKER_HPP_
29 
30 namespace nav2_route
31 {
32 
39 {
40 public:
42  using Feedback = nav2_msgs::action::ComputeAndTrackRoute::Feedback;
43 
47  RouteTracker() = default;
48 
52  ~RouteTracker() = default;
53 
59  void configure(
60  nav2_util::LifecycleNode::SharedPtr node,
61  std::shared_ptr<tf2_ros::Buffer> tf_buffer,
62  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
63  std::shared_ptr<ActionServerTrack> action_server,
64  const std::string & route_frame,
65  const std::string & base_frame);
66 
74  bool nodeAchieved(
75  const geometry_msgs::msg::PoseStamped & pose,
76  RouteTrackingState & state,
77  const Route & route);
78 
85  bool isStartOrEndNode(RouteTrackingState & state, const Route & route);
86 
91  geometry_msgs::msg::PoseStamped getRobotPose();
92 
101  void publishFeedback(
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);
107 
115  TrackerResult trackRoute(
116  const Route & route, const nav_msgs::msg::Path & path,
117  ReroutingState & rerouting_info);
118 
119 protected:
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  std::shared_ptr<ActionServerTrack> action_server_;
128  std::unique_ptr<OperationsManager> operations_manager_;
129  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
130 };
131 
132 } // namespace nav2_route
133 
134 #endif // NAV2_ROUTE__ROUTE_TRACKER_HPP_
Takes a processing route request and tracks it for progress in accordance with executing behavioral o...
~RouteTracker()=default
A constructor for nav2_route::RouteTracker.
void configure(nav2_util::LifecycleNode::SharedPtr node, std::shared_ptr< tf2_ros::Buffer > tf_buffer, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, std::shared_ptr< ActionServerTrack > action_server, const std::string &route_frame, const std::string &base_frame)
Configure route tracker.
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.
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
Current state management of route tracking class.
Definition: types.hpp:248
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211