Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_route::GoalIntentSearch::BreadthFirstSearch Class Reference

Public Member Functions

 BreadthFirstSearch (std::shared_ptr< nav2_costmap_2d::Costmap2D > costmap)
 Constructor. More...
 
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. More...
 
std::vector< unsigned int > getNeighbors (const unsigned int current_id)
 Get the neighbors of a given node. More...
 
bool inCollision (const unsigned int id)
 Check if a node is in collision with the costmap. More...
 
unsigned int getClosestNodeIdx ()
 Get the output closest node in candidate indices. More...
 
 ~BreadthFirstSearch ()=default
 Destructor.
 

Protected Attributes

std::shared_ptr< nav2_costmap_2d::Costmap2Dcostmap_
 
unsigned int closest_node_idx_ {0u}
 

Detailed Description

Definition at line 45 of file goal_intent_search.hpp.

Constructor & Destructor Documentation

◆ BreadthFirstSearch()

nav2_route::GoalIntentSearch::BreadthFirstSearch::BreadthFirstSearch ( std::shared_ptr< nav2_costmap_2d::Costmap2D costmap)
inlineexplicit

Constructor.

Parameters
costmapCostmap to check

Definition at line 52 of file goal_intent_search.hpp.

Member Function Documentation

◆ getClosestNodeIdx()

unsigned int nav2_route::GoalIntentSearch::BreadthFirstSearch::getClosestNodeIdx ( )
inline

Get the output closest node in candidate indices.

Returns
closest_node The closest candidate node index to the given point by search

Definition at line 190 of file goal_intent_search.hpp.

Referenced by nav2_route::GoalIntentExtractor::findStartandGoal().

Here is the caller graph for this function:

◆ getNeighbors()

std::vector<unsigned int> nav2_route::GoalIntentSearch::BreadthFirstSearch::getNeighbors ( const unsigned int  current_id)
inline

Get the neighbors of a given node.

Parameters
current_idThe current node id
Returns
A vector of neighbor node ids

Definition at line 135 of file goal_intent_search.hpp.

References inCollision().

Referenced by search().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inCollision()

bool nav2_route::GoalIntentSearch::BreadthFirstSearch::inCollision ( const unsigned int  id)
inline

Check if a node is in collision with the costmap.

Parameters
idThe node id to check
Returns
True if the node is in collision, false otherwise

Definition at line 179 of file goal_intent_search.hpp.

Referenced by getNeighbors().

Here is the caller graph for this function:

◆ search()

bool nav2_route::GoalIntentSearch::BreadthFirstSearch::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() 
)
inline

Search for the closest node to the given reference node.

Parameters
reference_nodeThe reference node to search from
candidate_nodesThe candidate nodes to search for
max_iterationsThe maximum number of iterations to perform
Returns
True if a candidate node is found, false otherwise

Definition at line 64 of file goal_intent_search.hpp.

References getNeighbors().

Referenced by nav2_route::GoalIntentExtractor::findStartandGoal().

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following file: