Responsible for managing multiple variables storing information on the goal.
More...
#include <nav2_smac_planner/include/nav2_smac_planner/goal_manager.hpp>
|
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 |
|
|
NodeSet | _goals_set |
|
GoalStateVector | _goals_state |
|
CoordinateVector | _goals_coordinate |
|
Coordinates | _ref_goal_coord |
|
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.
◆ addGoal()
template<typename NodeT >
Adds goal to the goal vector.
- Parameters
-
goal | Reference to the NodePtr |
Definition at line 79 of file goal_manager.hpp.
◆ getGoalsCoordinates()
template<typename NodeT >
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 >
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 >
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 >
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 >
Checks whether the Reference goal coordinate has changed.
- Parameters
-
coord | Coordinates 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 >
Check if a given node is part of the goal set.
- Parameters
-
node | Node 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_goals | Output list of goals for coarse search expansion. |
fine_check_goals | Output list of goals for fine search refinement. |
coarse_search_resolution | Number of fine goals per coarse goal. |
Definition at line 100 of file goal_manager.hpp.
◆ removeInvalidGoals()
template<typename NodeT >
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
-
tolerance | Heuristic tolerance allowed for infeasible goals. |
collision_checker | Collision checker to validate goal positions. |
traverse_unknown | Flag whether traversal through unknown space is allowed. |
Definition at line 124 of file goal_manager.hpp.
◆ setRefGoalCoordinates()
template<typename NodeT >
Set the Reference goal coordinate.
- Parameters
-
coord | Coordinates 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: