Template Class GoalManager

Class Documentation

template<typename NodeT>
class GoalManager

Responsible for managing multiple variables storing information on the goal.

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 Functions

inline GoalManager()

Constructor: Initializes empty goal state. sets and coordinate lists.

~GoalManager() = default

Destructor for the GoalManager.

inline bool goalsIsEmpty()

Checks if the goals set is empty.

Returns:

true if the goals set is empty

inline void addGoal(NodePtr &goal)

Adds goal to the goal vector.

Parameters:

goal – Reference to the NodePtr

inline void clear()

Clears all internal goal data, including goals, states, and coordinates.

inline void prepareGoalsForAnalyticExpansion(NodeVector &coarse_check_goals, NodeVector &fine_check_goals, int coarse_search_resolution)

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.

inline void removeInvalidGoals(const float &tolerance, GridCollisionChecker *collision_checker, const bool &traverse_unknown)

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.

inline bool isGoal(const NodePtr &node)

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.

inline NodeSet &getGoalsSet()

Get pointer reference to goals set vector.

Returns:

unordered_set of node pointers reference to the goals nodes

inline GoalStateVector &getGoalsState()

Get pointer reference to goals state.

Returns:

vector of node pointers reference to the goals state

inline CoordinateVector &getGoalsCoordinates()

Get pointer reference to goals coordinates.

Returns:

vector of goals coordinates reference to the goals coordinates

inline void setRefGoalCoordinates(const Coordinates &coord)

Set the Reference goal coordinate.

Parameters:

coord – Coordinates to set as Reference goal

inline bool hasGoalChanged(const Coordinates &coord)

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.

Protected Attributes

NodeSet _goals_set
GoalStateVector _goals_state
CoordinateVector _goals_coordinate
Coordinates _ref_goal_coord