Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Attributes | List of all members
nav2_smac_planner::GoalManager< NodeT > Class Template Reference

Responsible for managing multiple variables storing information on the goal. More...

#include <nav2_smac_planner/include/nav2_smac_planner/goal_manager.hpp>

Public Types

typedef NodeT * NodePtr
 
typedef std::vector< NodePtr > NodeVector
 
typedef std::unordered_set< NodePtr > NodeSet
 
typedef std::vector< GoalState< NodeT > > GoalStateVector
 
typedef NodeT::Coordinates Coordinates
 
typedef NodeT::CoordinateVector CoordinateVector
 

Public Member Functions

 GoalManager ()
 Constructor: Initializes empty goal state. sets and coordinate lists.
 
 ~GoalManager ()=default
 Destructor for the GoalManager.
 
bool goalsIsEmpty ()
 Checks if the goals set is empty. More...
 
void addGoal (NodePtr &goal)
 Adds goal to the goal vector. More...
 
void clear ()
 Clears all internal goal data, including goals, states, and coordinates.
 
void prepareGoalsForAnalyticExpansion (NodeVector &coarse_check_goals, NodeVector &fine_check_goals, int coarse_search_resolution)
 Populates coarse and fine goal lists for analytic expansion. More...
 
void removeInvalidGoals (const float &tolerance, GridCollisionChecker *collision_checker, const bool &traverse_unknown)
 Filters and marks invalid goals based on collision checking and tolerance thresholds. More...
 
bool isGoal (const NodePtr &node)
 Check if a given node is part of the goal set. More...
 
NodeSet & getGoalsSet ()
 Get pointer reference to goals set vector. More...
 
GoalStateVector & getGoalsState ()
 Get pointer reference to goals state. More...
 
CoordinateVector & getGoalsCoordinates ()
 Get pointer reference to goals coordinates. More...
 
void setRefGoalCoordinates (const Coordinates &coord)
 Set the Reference goal coordinate. More...
 
bool hasGoalChanged (const Coordinates &coord)
 Checks whether the Reference goal coordinate has changed. More...
 

Protected Attributes

NodeSet _goals_set
 
GoalStateVector _goals_state
 
CoordinateVector _goals_coordinate
 
Coordinates _ref_goal_coord
 

Detailed Description

template<typename NodeT>
class nav2_smac_planner::GoalManager< NodeT >

Responsible for managing multiple variables storing information on the goal.

Definition at line 40 of file goal_manager.hpp.

Member Function Documentation

◆ addGoal()

template<typename NodeT >
void nav2_smac_planner::GoalManager< NodeT >::addGoal ( NodePtr &  goal)
inline

Adds goal to the goal vector.

Parameters
goalReference to the NodePtr

Definition at line 79 of file goal_manager.hpp.

◆ getGoalsCoordinates()

template<typename NodeT >
CoordinateVector& nav2_smac_planner::GoalManager< NodeT >::getGoalsCoordinates ( )
inline

Get pointer reference to goals coordinates.

Returns
vector of goals coordinates reference to the goals coordinates

Definition at line 179 of file goal_manager.hpp.

◆ getGoalsSet()

template<typename NodeT >
NodeSet& nav2_smac_planner::GoalManager< NodeT >::getGoalsSet ( )
inline

Get pointer reference to goals set vector.

Returns
unordered_set of node pointers reference to the goals nodes

Definition at line 161 of file goal_manager.hpp.

◆ getGoalsState()

template<typename NodeT >
GoalStateVector& nav2_smac_planner::GoalManager< NodeT >::getGoalsState ( )
inline

Get pointer reference to goals state.

Returns
vector of node pointers reference to the goals state

Definition at line 170 of file goal_manager.hpp.

◆ goalsIsEmpty()

template<typename NodeT >
bool nav2_smac_planner::GoalManager< NodeT >::goalsIsEmpty ( )
inline

Checks if the goals set is empty.

Returns
true if the goals set is empty

Definition at line 70 of file goal_manager.hpp.

◆ hasGoalChanged()

template<typename NodeT >
bool nav2_smac_planner::GoalManager< NodeT >::hasGoalChanged ( const Coordinates &  coord)
inline

Checks whether the Reference goal coordinate has changed.

Parameters
coordCoordinates to compare with the current Reference goal coordinate.
Returns
true if the Reference goal coordinate has changed, false otherwise.

Note: This function checks if the goal has changed. This has to be done with the coordinates not the Node pointer because the Node pointer can be reused for different goals, but the coordinates will always be unique for each goal.

Definition at line 198 of file goal_manager.hpp.

◆ isGoal()

template<typename NodeT >
bool nav2_smac_planner::GoalManager< NodeT >::isGoal ( const NodePtr &  node)
inline

Check if a given node is part of the goal set.

Parameters
nodeNode pointer to check.
Returns
if node matches any goal in the goal set.

Definition at line 152 of file goal_manager.hpp.

◆ prepareGoalsForAnalyticExpansion()

template<typename NodeT >
void nav2_smac_planner::GoalManager< NodeT >::prepareGoalsForAnalyticExpansion ( NodeVector &  coarse_check_goals,
NodeVector &  fine_check_goals,
int  coarse_search_resolution 
)
inline

Populates coarse and fine goal lists for analytic expansion.

Parameters
coarse_check_goalsOutput list of goals for coarse search expansion.
fine_check_goalsOutput list of goals for fine search refinement.
coarse_search_resolutionNumber of fine goals per coarse goal.

Definition at line 100 of file goal_manager.hpp.

◆ removeInvalidGoals()

template<typename NodeT >
void nav2_smac_planner::GoalManager< NodeT >::removeInvalidGoals ( const float &  tolerance,
GridCollisionChecker collision_checker,
const bool &  traverse_unknown 
)
inline

Filters and marks invalid goals based on collision checking and tolerance thresholds.

Stores only valid (or tolerably infeasible) goals into internal goal sets and coordinates.

Parameters
toleranceHeuristic tolerance allowed for infeasible goals.
collision_checkerCollision checker to validate goal positions.
traverse_unknownFlag whether traversal through unknown space is allowed.

Definition at line 124 of file goal_manager.hpp.

◆ setRefGoalCoordinates()

template<typename NodeT >
void nav2_smac_planner::GoalManager< NodeT >::setRefGoalCoordinates ( const Coordinates &  coord)
inline

Set the Reference goal coordinate.

Parameters
coordCoordinates to set as Reference goal

Definition at line 188 of file goal_manager.hpp.


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