15 #include "nav2_route/route_tracker.hpp"
21 nav2_util::LifecycleNode::SharedPtr node,
22 std::shared_ptr<tf2_ros::Buffer> tf_buffer,
23 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
24 std::shared_ptr<ActionServerTrack> action_server,
25 const std::string & route_frame,
26 const std::string & base_frame)
28 clock_ = node->get_clock();
29 logger_ = node->get_logger();
30 route_frame_ = route_frame;
31 base_frame_ = base_frame;
32 action_server_ = action_server;
33 tf_buffer_ = tf_buffer;
35 nav2_util::declare_parameter_if_not_declared(
36 node,
"radius_to_achieve_node", rclcpp::ParameterValue(2.0));
37 radius_threshold_ = node->get_parameter(
"radius_to_achieve_node").as_double();
38 nav2_util::declare_parameter_if_not_declared(
39 node,
"boundary_radius_to_achieve_node", rclcpp::ParameterValue(1.0));
40 boundary_radius_threshold_ = node->get_parameter(
"boundary_radius_to_achieve_node").as_double();
41 nav2_util::declare_parameter_if_not_declared(
42 node,
"tracker_update_rate", rclcpp::ParameterValue(50.0));
43 tracker_update_rate_ = node->get_parameter(
"tracker_update_rate").as_double();
44 nav2_util::declare_parameter_if_not_declared(
45 node,
"aggregate_blocked_ids", rclcpp::ParameterValue(
false));
46 aggregate_blocked_ids_ = node->get_parameter(
"aggregate_blocked_ids").as_bool();
48 operations_manager_ = std::make_unique<OperationsManager>(node, costmap_subscriber);
53 geometry_msgs::msg::PoseStamped pose;
54 if (!nav2_util::getCurrentPose(pose, *tf_buffer_, route_frame_, base_frame_)) {
61 const geometry_msgs::msg::PoseStamped & pose,
66 const double dx = state.next_node->coords.x - pose.pose.position.x;
67 const double dy = state.next_node->coords.y - pose.pose.position.y;
68 const double dist_mag = std::sqrt(dx * dx + dy * dy);
70 const bool in_radius =
71 (dist_mag <= (is_boundary_node ? boundary_radius_threshold_ : radius_threshold_));
74 if (dist_mag < 1e-4 || (!in_radius && state.within_radius)) {
79 state.within_radius = in_radius;
84 if (is_boundary_node) {
85 return state.within_radius;
95 if (state.within_radius) {
96 NodePtr last_node = state.current_edge->start;
97 const double nx = state.next_node->coords.x - last_node->coords.x;
98 const double ny = state.next_node->coords.y - last_node->coords.y;
99 const double n_mag = std::sqrt(nx * nx + ny * ny);
101 NodePtr future_next_node = route.edges[state.route_edges_idx + 1]->end;
102 const double mx = future_next_node->coords.x - state.next_node->coords.x;
103 const double my = future_next_node->coords.y - state.next_node->coords.y;
104 const double m_mag = std::sqrt(mx * mx + my * my);
107 if (n_mag < 1e-6 || m_mag < 1e-6) {
112 const double bx = nx * m_mag + mx * n_mag;
113 const double by = ny * m_mag + my * n_mag;
114 return utils::normalizedDot(bx, by, dx, dy) <= 0;
125 (state.route_edges_idx ==
static_cast<int>(route.edges.size() - 1)) ||
126 (state.route_edges_idx == -1 && !state.current_edge);
130 const bool rereouted,
131 const unsigned int next_node_id,
132 const unsigned int last_node_id,
133 const unsigned int edge_id,
134 const std::vector<std::string> & operations)
136 auto feedback = std::make_unique<Feedback>();
137 feedback->route = route_msg_;
138 feedback->path = path_;
139 feedback->rerouted = rereouted;
140 feedback->next_node_id = next_node_id;
141 feedback->last_node_id = last_node_id;
142 feedback->current_edge_id = edge_id;
143 feedback->operations_triggered = operations;
144 action_server_->publish_feedback(std::move(feedback));
148 const Route & route,
const nav_msgs::msg::Path & path,
151 route_msg_ = utils::toMsg(route, route_frame_, clock_->now());
154 state.next_node = route.start_node;
159 if (rerouting_info.curr_edge) {
164 state.current_edge = rerouting_info.curr_edge;
165 state.last_node = state.current_edge->start;
167 true, route.start_node->nodeid, state.last_node->nodeid, state.current_edge->edgeid, {});
172 rclcpp::Rate r(tracker_update_rate_);
173 while (rclcpp::ok()) {
174 bool status_change =
false, completed =
false;
177 if (action_server_->is_cancel_requested()) {
178 return TrackerResult::INTERRUPTED;
179 }
else if (action_server_->is_preempt_requested()) {
180 return TrackerResult::INTERRUPTED;
184 geometry_msgs::msg::PoseStamped robot_pose =
getRobotPose();
186 status_change =
true;
187 state.within_radius =
false;
188 state.last_node = state.next_node;
189 if (++state.route_edges_idx <
static_cast<int>(route.edges.size())) {
190 state.current_edge = route.edges[state.route_edges_idx];
191 state.next_node = state.current_edge->end;
193 state.current_edge =
nullptr;
194 state.next_node =
nullptr;
201 operations_manager_->process(status_change, state, route, robot_pose, rerouting_info);
204 RCLCPP_INFO(logger_,
"Routing to goal completed!");
206 publishFeedback(
false, 0, state.last_node->nodeid, 0, ops_result.operations_triggered);
207 return TrackerResult::COMPLETED;
210 if ((status_change || !ops_result.operations_triggered.empty()) && state.current_edge) {
213 state.next_node->nodeid, state.last_node->nodeid,
214 state.current_edge->edgeid, ops_result.operations_triggered);
217 if (ops_result.reroute) {
218 if (!aggregate_blocked_ids_) {
219 rerouting_info.blocked_ids = ops_result.blocked_ids;
221 rerouting_info.blocked_ids.insert(
222 rerouting_info.blocked_ids.end(),
223 ops_result.blocked_ids.begin(), ops_result.blocked_ids.end());
226 if (state.last_node) {
227 rerouting_info.rerouting_start_id = state.last_node->nodeid;
228 rerouting_info.rerouting_start_pose = robot_pose;
230 rerouting_info.rerouting_start_id = std::numeric_limits<unsigned int>::max();
231 rerouting_info.rerouting_start_pose = geometry_msgs::msg::PoseStamped();
235 rerouting_info.curr_edge = state.current_edge;
236 RCLCPP_INFO(logger_,
"Rerouting requested by route tracking operations!");
237 return TrackerResult::INTERRUPTED;
243 return TrackerResult::EXITED;
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.
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 object to store the nodes in the graph file.
Result information from the operations manager.
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.