Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
goal_intent_search.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 #ifndef NAV2_ROUTE__GOAL_INTENT_SEARCH_HPP_
16 #define NAV2_ROUTE__GOAL_INTENT_SEARCH_HPP_
17 
18 #include <limits>
19 #include <string>
20 #include <vector>
21 #include <queue>
22 #include <unordered_set>
23 #include <memory>
24 
25 #include "std_msgs/msg/color_rgba.hpp"
26 #include "visualization_msgs/msg/marker_array.hpp"
27 #include "visualization_msgs/msg/marker.hpp"
28 #include "geometry_msgs/msg/vector3.hpp"
29 #include "nav2_util/geometry_utils.hpp"
30 #include "nav2_msgs/msg/route.hpp"
31 #include "nav2_route/types.hpp"
32 #include "nav2_costmap_2d/costmap_2d.hpp"
33 #include "nav2_costmap_2d/cost_values.hpp"
34 #include "nav2_util/line_iterator.hpp"
35 #include "nav2_util/lifecycle_node.hpp"
36 
37 namespace nav2_route
38 {
39 
40 namespace GoalIntentSearch
41 {
42 
47 {
48 public:
53  explicit BreadthFirstSearch(std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap)
54  : costmap_(costmap)
55  {
56  }
57 
65  bool search(
66  const geometry_msgs::msg::PoseStamped & reference_node,
67  const std::vector<geometry_msgs::msg::PoseStamped> & candidate_nodes,
68  const int max_iterations = std::numeric_limits<int>::max())
69  {
70  closest_node_idx_ = 0u;
71 
72  // Convert target to costmap space
73  unsigned int goal_x, goal_y;
74  if (!costmap_->worldToMap(
75  reference_node.pose.position.x, reference_node.pose.position.y,
76  goal_x, goal_y))
77  {
78  return false;
79  }
80  unsigned int goal_id = costmap_->getIndex(goal_x, goal_y);
81 
82  // Convert candidates to costmap space
83  std::vector<unsigned int> candidate_ids;
84  candidate_ids.reserve(candidate_nodes.size());
85  for (const auto & node : candidate_nodes) {
86  unsigned int node_x, node_y;
87  if (!costmap_->worldToMap(node.pose.position.x, node.pose.position.y, node_x, node_y)) {
88  // Off the costmap, consider this candidate invalid
89  continue;
90  }
91  candidate_ids.push_back(costmap_->getIndex(node_x, node_y));
92  }
93 
94  if (candidate_ids.empty()) {
95  return false;
96  }
97 
98  // Main Breadth-First Search
99  std::queue<unsigned int> search_queue;
100  std::unordered_set<unsigned int> visited;
101  visited.insert(goal_id);
102  search_queue.push(goal_id);
103  int iterations = 0;
104  while (!search_queue.empty() && iterations < max_iterations) {
105  unsigned int current_id = search_queue.front();
106  search_queue.pop();
107  iterations++;
108 
109  // Check if the current node is a candidate
110  auto iter = std::find(candidate_ids.begin(), candidate_ids.end(), current_id);
111  if (iter != candidate_ids.end()) {
112  closest_node_idx_ = std::distance(candidate_ids.begin(), iter);
113  return true;
114  }
115 
116  // Get neighbors of the current node
117  std::vector<unsigned int> neighbors = getNeighbors(current_id);
118 
119  // Add unvisited neighbors to the queue
120  for (const auto & neighbor : neighbors) {
121  if (visited.find(neighbor) == visited.end()) {
122  visited.insert(neighbor);
123  search_queue.push(neighbor);
124  }
125  }
126  }
127 
128  // No solution found with full expansion or iterations exceeded
129  return false;
130  }
131 
137  std::vector<unsigned int> getNeighbors(const unsigned int current_id)
138  {
139  int size_x = static_cast<int>(costmap_->getSizeInCellsX());
140  const std::vector<int> offsets = {
141  -1, 1, -size_x, size_x,
142  -size_x - 1, -size_x + 1,
143  size_x - 1, size_x + 1};
144  int costmap_size = static_cast<int>(costmap_->getSizeInCellsX() * costmap_->getSizeInCellsY());
145 
146  unsigned int p_mx, p_my;
147  costmap_->indexToCells(current_id, p_mx, p_my);
148 
149  std::vector<unsigned int> neighbors;
150  for (const auto & offset : offsets) {
151  // If out of bounds of costmap
152  int signed_neighbor_id = static_cast<int>(current_id) + offset;
153  if (signed_neighbor_id < 0 || signed_neighbor_id >= costmap_size) {
154  continue;
155  }
156  unsigned int neighbor_id = static_cast<unsigned int>(signed_neighbor_id);
157 
158  // If wrapping around the costmap
159  unsigned int n_mx, n_my;
160  costmap_->indexToCells(neighbor_id, n_mx, n_my);
161  if (std::fabs(static_cast<float>(p_mx) - static_cast<float>(n_mx)) > 1 ||
162  std::fabs(static_cast<float>(p_my) - static_cast<float>(n_my)) > 1)
163  {
164  continue;
165  }
166 
167  // Add if not in collision
168  if (!inCollision(neighbor_id)) {
169  neighbors.push_back(neighbor_id);
170  }
171  }
172 
173  return neighbors;
174  }
175 
181  bool inCollision(const unsigned int id)
182  {
183  // Check if the node is in collision
184  float cost = static_cast<float>(costmap_->getCost(id));
185  return cost >= 253.0f && cost != 255.0f;
186  }
187 
192  unsigned int getClosestNodeIdx()
193  {
194  return closest_node_idx_;
195  }
196 
200  ~BreadthFirstSearch() = default;
201 
202 protected:
203  std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_;
204  unsigned int closest_node_idx_{0u};
205 };
206 
211 {
212 public:
217  explicit LoSCollisionChecker(std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap)
218  : costmap_(costmap)
219  {
220  }
221 
225  ~LoSCollisionChecker() = default;
226 
233  bool worldToMap(const geometry_msgs::msg::Point & start, const geometry_msgs::msg::Point & end)
234  {
235  if (!costmap_->worldToMap(start.x, start.y, x0_, y0_) ||
236  !costmap_->worldToMap(end.x, end.y, x1_, y1_))
237  {
238  return false;
239  }
240  return true;
241  }
242 
248  {
249  nav2_util::LineIterator iter(x0_, y0_, x1_, y1_);
250  for (; iter.isValid(); iter.advance()) {
251  float cost = static_cast<float>(costmap_->getCost(iter.getX(), iter.getY()));
252  if (cost >= 253.0f && cost != 255.0 /*unknown*/) {
253  return true;
254  }
255  }
256  return false;
257  }
258 
259 protected:
260  std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_;
261  unsigned int x0_, x1_, y0_, y1_;
262 };
263 
264 } // namespace GoalIntentSearch
265 
266 } // namespace nav2_route
267 
268 #endif // NAV2_ROUTE__GOAL_INTENT_SEARCH_HPP_
BreadthFirstSearch(std::shared_ptr< nav2_costmap_2d::Costmap2D > costmap)
Constructor.
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.
std::vector< unsigned int > getNeighbors(const unsigned int current_id)
Get the neighbors of a given node.
unsigned int getClosestNodeIdx()
Get the output closest node in candidate indices.
bool inCollision(const unsigned int id)
Check if a node is in collision with the costmap.
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.
LoSCollisionChecker(std::shared_ptr< nav2_costmap_2d::Costmap2D > costmap)
Constructor.
An iterator implementing Bresenham Ray-Tracing.
bool isValid() const
If the iterator is valid.
int getX() const
Get current X value.
void advance()
Advance iteration along the line.
int getY() const
Get current Y value.