15 #ifndef NAV2_ROUTE__GOAL_INTENT_SEARCH_HPP_
16 #define NAV2_ROUTE__GOAL_INTENT_SEARCH_HPP_
22 #include <unordered_set>
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_ros_common/lifecycle_node.hpp"
40 namespace GoalIntentSearch
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())
70 closest_node_idx_ = 0u;
73 unsigned int goal_x, goal_y;
74 if (!costmap_->worldToMap(reference_node.pose.position.x, reference_node.pose.position.y,
79 unsigned int goal_id = costmap_->getIndex(goal_x, goal_y);
82 std::vector<unsigned int> candidate_ids;
83 candidate_ids.reserve(candidate_nodes.size());
84 for (
const auto & node : candidate_nodes) {
85 unsigned int node_x, node_y;
86 if (!costmap_->worldToMap(node.pose.position.x, node.pose.position.y, node_x, node_y)) {
90 candidate_ids.push_back(costmap_->getIndex(node_x, node_y));
93 if (candidate_ids.empty()) {
98 std::queue<unsigned int> search_queue;
99 std::unordered_set<unsigned int> visited;
100 visited.insert(goal_id);
101 search_queue.push(goal_id);
103 while (!search_queue.empty() && iterations < max_iterations) {
104 unsigned int current_id = search_queue.front();
109 auto iter = std::find(candidate_ids.begin(), candidate_ids.end(), current_id);
110 if (iter != candidate_ids.end()) {
111 closest_node_idx_ = std::distance(candidate_ids.begin(), iter);
116 std::vector<unsigned int> neighbors =
getNeighbors(current_id);
119 for (
const auto & neighbor : neighbors) {
120 if (visited.find(neighbor) == visited.end()) {
121 visited.insert(neighbor);
122 search_queue.push(neighbor);
138 int size_x =
static_cast<int>(costmap_->getSizeInCellsX());
139 const std::vector<int> offsets = {
140 -1, 1, -size_x, size_x,
141 -size_x - 1, -size_x + 1,
142 size_x - 1, size_x + 1};
143 int costmap_size =
static_cast<int>(costmap_->getSizeInCellsX() * costmap_->getSizeInCellsY());
145 unsigned int p_mx, p_my;
146 costmap_->indexToCells(current_id, p_mx, p_my);
148 std::vector<unsigned int> neighbors;
149 for (
const auto & offset : offsets) {
151 int signed_neighbor_id =
static_cast<int>(current_id) + offset;
152 if (signed_neighbor_id < 0 || signed_neighbor_id >= costmap_size) {
155 unsigned int neighbor_id =
static_cast<unsigned int>(signed_neighbor_id);
158 unsigned int n_mx, n_my;
159 costmap_->indexToCells(neighbor_id, n_mx, n_my);
160 if (std::fabs(
static_cast<float>(p_mx) -
static_cast<float>(n_mx)) > 1 ||
161 std::fabs(
static_cast<float>(p_my) -
static_cast<float>(n_my)) > 1)
168 neighbors.push_back(neighbor_id);
183 float cost =
static_cast<float>(costmap_->getCost(
id));
184 return cost >= 253.0f && cost != 255.0f;
193 return closest_node_idx_;
202 std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_;
203 unsigned int closest_node_idx_{0u};
232 bool worldToMap(
const geometry_msgs::msg::Point & start,
const geometry_msgs::msg::Point & end)
234 if (!costmap_->worldToMap(start.x, start.y, x0_, y0_) ||
235 !costmap_->worldToMap(end.x, end.y, x1_, y1_))
250 float cost =
static_cast<float>(costmap_->getCost(iter.
getX(), iter.
getY()));
251 if (cost >= 253.0f && cost != 255.0 ) {
259 std::shared_ptr<nav2_costmap_2d::Costmap2D> costmap_;
260 unsigned int x0_, x1_, y0_, y1_;
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.
~BreadthFirstSearch()=default
Destructor.
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.
~LoSCollisionChecker()=default
Destructor.
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.