17 #ifndef NAV2_SMAC_PLANNER__GOAL_MANAGER_HPP_
18 #define NAV2_SMAC_PLANNER__GOAL_MANAGER_HPP_
21 #include <unordered_set>
25 #include "nav2_smac_planner/types.hpp"
26 #include "nav2_smac_planner/node_2d.hpp"
27 #include "nav2_smac_planner/node_hybrid.hpp"
28 #include "nav2_smac_planner/node_lattice.hpp"
29 #include "nav2_smac_planner/node_basic.hpp"
30 #include "nav2_smac_planner/collision_checker.hpp"
33 namespace nav2_smac_planner
40 template<
typename NodeT>
44 typedef NodeT * NodePtr;
45 typedef std::vector<NodePtr> NodeVector;
46 typedef std::unordered_set<NodePtr> NodeSet;
47 typedef std::vector<GoalState<NodeT>> GoalStateVector;
48 typedef typename NodeT::Coordinates Coordinates;
49 typedef typename NodeT::CoordinateVector CoordinateVector;
55 : _goals_set(NodeSet()),
56 _goals_state(GoalStateVector()),
57 _goals_coordinate(CoordinateVector()),
58 _ref_goal_coord(Coordinates())
73 return _goals_state.empty();
82 _goals_state.push_back({goal,
true});
92 _goals_coordinate.clear();
102 NodeVector & coarse_check_goals, NodeVector & fine_check_goals,
103 int coarse_search_resolution)
105 for (
unsigned int i = 0; i < _goals_state.size(); i++) {
106 if (_goals_state[i].is_valid) {
107 if (i % coarse_search_resolution == 0) {
108 coarse_check_goals.push_back(_goals_state[i].goal);
110 fine_check_goals.push_back(_goals_state[i].goal);
128 const bool & traverse_unknown)
const
137 auto getIndexFromPoint = [&size_x] (
const Coordinates & point) {
138 unsigned int index = 0;
140 const auto mx =
static_cast<unsigned int>(point.x);
141 const auto my =
static_cast<unsigned int>(point.y);
143 if constexpr (!std::is_same_v<NodeT, Node2D>) {
144 const auto angle =
static_cast<unsigned int>(point.theta);
145 index = NodeT::getIndex(mx, my, angle);
147 index = NodeT::getIndex(mx, my, size_x);
153 const Coordinates & center_point = node->pose;
154 const float min_x = std::max(0.0f, std::floor(center_point.x - radius));
155 const float min_y = std::max(0.0f, std::floor(center_point.y - radius));
157 std::min(
static_cast<float>(size_x - 1), std::ceil(center_point.x + radius));
159 std::min(
static_cast<float>(size_y - 1), std::ceil(center_point.y + radius));
160 const float radius_sq = radius * radius;
163 for (m.x = min_x; m.x <= max_x; m.x += 1.0f) {
164 for (m.y = min_y; m.y <= max_y; m.y += 1.0f) {
165 const float dx = m.x - center_point.x;
166 const float dy = m.y - center_point.y;
168 if (dx * dx + dy * dy > radius_sq) {
172 NodeT current_node(getIndexFromPoint(m));
173 current_node.setPose(m);
175 if (current_node.isNodeValid(traverse_unknown, collision_checker)) {
194 const float & tolerance,
196 const bool & traverse_unknown)
199 if (!_goals_set.empty() || !_goals_coordinate.empty()) {
200 throw std::runtime_error(
"Goal set should be cleared before calling "
201 "removeinvalidgoals");
203 for (
unsigned int i = 0; i < _goals_state.size(); i++) {
204 if (_goals_state[i].goal->isNodeValid(traverse_unknown, collision_checker) ||
205 isZoneValid(_goals_state[i].goal, tolerance, collision_checker, traverse_unknown))
207 _goals_state[i].is_valid =
true;
208 _goals_set.insert(_goals_state[i].goal);
209 _goals_coordinate.push_back(_goals_state[i].goal->pose);
211 _goals_state[i].is_valid =
false;
223 return _goals_set.find(node) != _goals_set.end();
250 return _goals_coordinate;
259 _ref_goal_coord = coord;
275 return _ref_goal_coord != coord;
280 GoalStateVector _goals_state;
281 CoordinateVector _goals_coordinate;
282 Coordinates _ref_goal_coord;
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Responsible for managing multiple variables storing information on the goal.
GoalManager()
Constructor: Initializes empty goal state. sets and coordinate lists.
~GoalManager()=default
Destructor for the GoalManager.
bool isZoneValid(const NodePtr node, const float &radius, GridCollisionChecker *collision_checker, const bool &traverse_unknown) const
Checks if zone within the radius of a node is feasible. Returns true if there's at least one non-leth...
void removeInvalidGoals(const float &tolerance, GridCollisionChecker *collision_checker, const bool &traverse_unknown)
Filters and marks invalid goals based on collision checking and tolerance thresholds.
NodeSet & getGoalsSet()
Get pointer reference to goals set vector.
bool hasGoalChanged(const Coordinates &coord)
Checks whether the Reference goal coordinate has changed.
void addGoal(NodePtr &goal)
Adds goal to the goal vector.
void prepareGoalsForAnalyticExpansion(NodeVector &coarse_check_goals, NodeVector &fine_check_goals, int coarse_search_resolution)
Populates coarse and fine goal lists for analytic expansion.
GoalStateVector & getGoalsState()
Get pointer reference to goals state.
void setRefGoalCoordinates(const Coordinates &coord)
Set the Reference goal coordinate.
void clear()
Clears all internal goal data, including goals, states, and coordinates.
bool goalsIsEmpty()
Checks if the goals set is empty.
bool isGoal(const NodePtr &node)
Check if a given node is part of the goal set.
CoordinateVector & getGoalsCoordinates()
Get pointer reference to goals coordinates.
A costmap grid collision checker.