19 #include "nav2_route/goal_intent_extractor.hpp"
24 static float EPSILON = 1e-6;
27 nav2_util::LifecycleNode::SharedPtr node,
29 GraphToIDMap * id_to_graph_map,
30 std::shared_ptr<tf2_ros::Buffer> tf,
31 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
32 const std::string & route_frame,
33 const std::string & global_frame,
34 const std::string & base_frame)
36 logger_ = node->get_logger();
37 id_to_graph_map_ = id_to_graph_map;
40 costmap_subscriber_ = costmap_subscriber;
41 route_frame_ = route_frame;
42 global_frame_ = global_frame;
43 base_frame_ = base_frame;
44 node_spatial_tree_ = std::make_shared<NodeSpatialTree>();
45 node_spatial_tree_->computeTree(graph);
47 nav2_util::declare_parameter_if_not_declared(
48 node,
"prune_goal", rclcpp::ParameterValue(
true));
49 prune_goal_ = node->get_parameter(
"prune_goal").as_bool();
51 nav2_util::declare_parameter_if_not_declared(
52 node,
"max_prune_dist_from_edge", rclcpp::ParameterValue(8.0));
53 max_dist_from_edge_ =
static_cast<float>(
54 node->get_parameter(
"max_prune_dist_from_edge").as_double());
55 nav2_util::declare_parameter_if_not_declared(
56 node,
"min_prune_dist_from_goal", rclcpp::ParameterValue(0.15));
57 min_dist_from_goal_ =
static_cast<float>(
58 node->get_parameter(
"min_prune_dist_from_goal").as_double());
59 nav2_util::declare_parameter_if_not_declared(
60 node,
"min_prune_dist_from_start", rclcpp::ParameterValue(0.10));
61 min_dist_from_start_ =
static_cast<float>(
62 node->get_parameter(
"min_prune_dist_from_start").as_double());
64 nav2_util::declare_parameter_if_not_declared(
65 node,
"enable_nn_search", rclcpp::ParameterValue(
true));
66 enable_search_ = node->get_parameter(
"enable_nn_search").as_bool();
67 nav2_util::declare_parameter_if_not_declared(
68 node,
"max_nn_search_iterations", rclcpp::ParameterValue(10000));
69 max_nn_search_iterations_ = node->get_parameter(
"max_nn_search_iterations").as_int();
71 nav2_util::declare_parameter_if_not_declared(
72 node,
"num_nearest_nodes", rclcpp::ParameterValue(5));
73 int num_of_nearest_nodes = node->get_parameter(
"num_nearest_nodes").as_int();
74 node_spatial_tree_->setNumOfNearestNodes(num_of_nearest_nodes);
79 id_to_graph_map_ = id_to_graph_map;
81 node_spatial_tree_->computeTree(graph);
85 geometry_msgs::msg::PoseStamped & pose,
86 const std::string & target_frame)
88 if (pose.header.frame_id != target_frame) {
91 "Request pose in %s frame. Converting to route server frame: %s.",
92 pose.header.frame_id.c_str(), target_frame.c_str());
93 if (!nav2_util::transformPoseInTargetFrame(pose, pose, *tf_, target_frame)) {
106 template<
typename GoalT>
111 if (!goal->use_poses) {
112 unsigned int start_idx = id_to_graph_map_->at(goal->start_id);
113 unsigned int goal_idx = id_to_graph_map_->at(goal->goal_id);
114 const Coordinates & start_coords = graph_->at(start_idx).coords;
115 const Coordinates & goal_coords = graph_->at(goal_idx).coords;
116 start_.pose.position.x = start_coords.x;
117 start_.pose.position.y = start_coords.y;
118 goal_.pose.position.x = goal_coords.x;
119 goal_.pose.position.y = goal_coords.y;
120 return {start_idx, goal_idx};
124 geometry_msgs::msg::PoseStamped start_pose, goal_pose = goal->goal;
125 if (goal->use_start) {
126 start_pose = goal->start;
128 if (!nav2_util::getCurrentPose(start_pose, *tf_, route_frame_, base_frame_)) {
139 std::vector<unsigned int> start_route, end_route;
140 if (!node_spatial_tree_->findNearestGraphNodesToPose(start_, start_route) ||
141 !node_spatial_tree_->findNearestGraphNodesToPose(goal_, end_route))
144 "Could not determine node closest to start or goal pose requested!");
147 unsigned int start_route_loc = start_route.front();
148 unsigned int end_route_loc = end_route.front();
154 std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap =
nullptr;
155 std::string costmap_frame_id;
156 bool enable_search = enable_search_;
159 costmap = costmap_subscriber_->getCostmap();
160 costmap_frame_id = global_frame_;
161 }
catch (
const std::exception & ex) {
162 enable_search =
false;
165 "Failed to get costmap for goal intent extractor: %s. "
166 "Falling back to closest euclidean route node instead.", ex.what());
170 if (enable_search && start_route.size() > 1u) {
172 std::vector<geometry_msgs::msg::PoseStamped> candidate_nodes;
173 candidate_nodes.reserve(start_route.size());
174 for (
const auto & node : start_route) {
175 auto & node_data = graph_->at(node);
176 geometry_msgs::msg::PoseStamped node_pose;
177 node_pose.pose.position.x = node_data.coords.x;
178 node_pose.pose.position.y = node_data.coords.y;
179 node_pose.header.frame_id = node_data.coords.frame_id;
180 candidate_nodes.push_back(
transformPose(node_pose, costmap_frame_id));
183 auto transformed_start =
transformPose(start_, costmap_frame_id);
186 candidate_nodes.front().pose.position, transformed_start.pose.position))
190 if (bfs.
search(transformed_start, candidate_nodes, max_nn_search_iterations_)) {
197 if (enable_search && end_route.size() > 1u) {
199 std::vector<geometry_msgs::msg::PoseStamped> candidate_nodes;
200 candidate_nodes.reserve(end_route.size());
201 for (
const auto & node : end_route) {
202 auto & node_data = graph_->at(node);
203 geometry_msgs::msg::PoseStamped node_pose;
204 node_pose.pose.position.x = node_data.coords.x;
205 node_pose.pose.position.y = node_data.coords.y;
206 node_pose.header.frame_id = node_data.coords.frame_id;
207 candidate_nodes.push_back(
transformPose(node_pose, costmap_frame_id));
210 auto transformed_end =
transformPose(goal_, costmap_frame_id);
213 candidate_nodes.front().pose.position, transformed_end.pose.position))
217 if (bfs.
search(transformed_end, candidate_nodes)) {
224 return {start_route_loc, end_route_loc};
227 template<
typename GoalT>
229 const Route & input_route,
230 const std::shared_ptr<const GoalT> goal,
233 Route pruned_route = input_route;
236 EdgePtr last_curr_edge = rerouting_info.curr_edge;
237 rerouting_info.curr_edge =
nullptr;
238 bool first_time = rerouting_info.first_time;
239 rerouting_info.first_time =
false;
242 if (input_route.edges.empty() || (!goal->use_poses && first_time)) {
247 NodePtr first = pruned_route.start_node;
248 NodePtr next = pruned_route.edges[0]->end;
249 float vrx = next->coords.x - first->coords.x;
250 float vry = next->coords.y - first->coords.y;
251 float vpx = start_.pose.position.x - first->coords.x;
252 float vpy = start_.pose.position.y - first->coords.y;
253 float dot_prod = utils::normalizedDot(vrx, vry, vpx, vpy);
254 Coordinates closest_pt_on_edge = utils::findClosestPoint(start_, first->coords, next->coords);
255 if (dot_prod > EPSILON &&
256 hypotf(vpx, vpy) > min_dist_from_start_ &&
257 utils::distance(closest_pt_on_edge, start_) <= max_dist_from_edge_)
261 if (last_curr_edge && last_curr_edge->edgeid == pruned_route.edges.front()->edgeid) {
262 rerouting_info.closest_pt_on_edge = closest_pt_on_edge;
263 rerouting_info.curr_edge = pruned_route.edges.front();
266 pruned_route.start_node = next;
267 pruned_route.route_cost -= pruned_route.edges.front()->end->search_state.traversal_cost;
268 pruned_route.edges.erase(pruned_route.edges.begin());
272 if (!prune_goal_ || !goal->use_poses || pruned_route.edges.empty()) {
277 next = pruned_route.edges.back()->start;
278 NodePtr last = pruned_route.edges.back()->end;
279 vrx = last->coords.x - next->coords.x;
280 vry = last->coords.y - next->coords.y;
281 vpx = goal_.pose.position.x - last->coords.x;
282 vpy = goal_.pose.position.y - last->coords.y;
284 dot_prod = utils::normalizedDot(vrx, vry, vpx, vpy);
285 closest_pt_on_edge = utils::findClosestPoint(goal_, next->coords, last->coords);
286 if (dot_prod < -EPSILON &&
287 hypotf(vpx, vpy) > min_dist_from_goal_ &&
288 utils::distance(closest_pt_on_edge, goal_) <= max_dist_from_edge_)
290 pruned_route.route_cost -= pruned_route.edges.back()->end->search_state.traversal_cost;
291 pruned_route.edges.pop_back();
302 template Route GoalIntentExtractor::pruneStartandGoal<nav2_msgs::action::ComputeRoute::Goal>(
303 const Route & input_route,
304 const std::shared_ptr<const nav2_msgs::action::ComputeRoute::Goal> goal,
307 Route GoalIntentExtractor::pruneStartandGoal<nav2_msgs::action::ComputeAndTrackRoute::Goal>(
308 const Route & input_route,
309 const std::shared_ptr<const nav2_msgs::action::ComputeAndTrackRoute::Goal> goal,
311 template NodeExtents GoalIntentExtractor::findStartandGoal<nav2_msgs::action::ComputeRoute::Goal>(
312 const std::shared_ptr<const nav2_msgs::action::ComputeRoute::Goal> goal);
314 NodeExtents GoalIntentExtractor::findStartandGoal<nav2_msgs::action::ComputeAndTrackRoute::Goal>(
315 const std::shared_ptr<const nav2_msgs::action::ComputeAndTrackRoute::Goal> goal);
bool search(const geometry_msgs::msg::PoseStamped &reference_node, const std::vector< geometry_msgs::msg::PoseStamped > &candidate_nodes, const int max_iterations=std::numeric_limits< int >::max())
Search for the closest node to the given reference node.
unsigned int getClosestNodeIdx()
Get the output closest node in candidate indices.
bool isInCollision()
Check if the line segment is in collision with the costmap.
bool worldToMap(const geometry_msgs::msg::Point &start, const geometry_msgs::msg::Point &end)
Find the line segment in cosmap frame.
An object to store Node coordinates in different frames.
An object representing edges between nodes.
An object to store the nodes in the graph file.
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.