Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
goal_manager.hpp
1 // Copyright (c) 2020, Samsung Research America
2 // Copyright (c) 2020, Applied Electric Vehicles Pty Ltd
3 // Copyright (c) 2024, Stevedan Ogochukwu Omodolor Omodia
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License. Reserved.
16 
17 #ifndef NAV2_SMAC_PLANNER__GOAL_MANAGER_HPP_
18 #define NAV2_SMAC_PLANNER__GOAL_MANAGER_HPP_
19 
20 #include <algorithm>
21 #include <unordered_set>
22 #include <vector>
23 #include <functional>
24 
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"
31 
32 
33 namespace nav2_smac_planner
34 {
35 
40 template<typename NodeT>
42 {
43 public:
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;
50 
55  : _goals_set(NodeSet()),
56  _goals_state(GoalStateVector()),
57  _goals_coordinate(CoordinateVector()),
58  _ref_goal_coord(Coordinates())
59  {
60  }
61 
65  ~GoalManager() = default;
66 
71  bool goalsIsEmpty()
72  {
73  return _goals_state.empty();
74  }
75 
80  void addGoal(NodePtr & goal)
81  {
82  _goals_state.push_back({goal, true});
83  }
84 
88  void clear()
89  {
90  _goals_set.clear();
91  _goals_state.clear();
92  _goals_coordinate.clear();
93  }
94 
102  NodeVector & coarse_check_goals, NodeVector & fine_check_goals,
103  int coarse_search_resolution)
104  {
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);
109  } else {
110  fine_check_goals.push_back(_goals_state[i].goal);
111  }
112  }
113  }
114  }
115 
127  const NodePtr node, const float & radius, GridCollisionChecker * collision_checker,
128  const bool & traverse_unknown) const
129  {
130  if (radius < 1) {
131  return false;
132  }
133 
134  const auto size_x = collision_checker->getCostmap()->getSizeInCellsX();
135  const auto size_y = collision_checker->getCostmap()->getSizeInCellsY();
136 
137  auto getIndexFromPoint = [&size_x] (const Coordinates & point) {
138  unsigned int index = 0;
139 
140  const auto mx = static_cast<unsigned int>(point.x);
141  const auto my = static_cast<unsigned int>(point.y);
142 
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);
146  } else {
147  index = NodeT::getIndex(mx, my, size_x);
148  }
149 
150  return index;
151  };
152 
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));
156  const float max_x =
157  std::min(static_cast<float>(size_x - 1), std::ceil(center_point.x + radius));
158  const float max_y =
159  std::min(static_cast<float>(size_y - 1), std::ceil(center_point.y + radius));
160  const float radius_sq = radius * radius;
161 
162  Coordinates m;
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;
167 
168  if (dx * dx + dy * dy > radius_sq) {
169  continue;
170  }
171 
172  NodeT current_node(getIndexFromPoint(m));
173  current_node.setPose(m);
174 
175  if (current_node.isNodeValid(traverse_unknown, collision_checker)) {
176  return true;
177  }
178  }
179  }
180 
181  return false;
182  }
183 
194  const float & tolerance,
195  GridCollisionChecker * collision_checker,
196  const bool & traverse_unknown)
197  {
198  // Make sure that there was a goal clear before this was run
199  if (!_goals_set.empty() || !_goals_coordinate.empty()) {
200  throw std::runtime_error("Goal set should be cleared before calling "
201  "removeinvalidgoals");
202  }
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))
206  {
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);
210  } else {
211  _goals_state[i].is_valid = false;
212  }
213  }
214  }
215 
221  inline bool isGoal(const NodePtr & node)
222  {
223  return _goals_set.find(node) != _goals_set.end();
224  }
225 
230  inline NodeSet & getGoalsSet()
231  {
232  return _goals_set;
233  }
234 
239  inline GoalStateVector & getGoalsState()
240  {
241  return _goals_state;
242  }
243 
248  inline CoordinateVector & getGoalsCoordinates()
249  {
250  return _goals_coordinate;
251  }
252 
257  inline void setRefGoalCoordinates(const Coordinates & coord)
258  {
259  _ref_goal_coord = coord;
260  }
261 
267  inline bool hasGoalChanged(const Coordinates & coord)
268  {
275  return _ref_goal_coord != coord;
276  }
277 
278 protected:
279  NodeSet _goals_set;
280  GoalStateVector _goals_state;
281  CoordinateVector _goals_coordinate;
282  Coordinates _ref_goal_coord;
283 };
284 
285 } // namespace nav2_smac_planner
286 
287 #endif // NAV2_SMAC_PLANNER__GOAL_MANAGER_HPP_
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:548
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:553
CostmapT getCostmap()
Get the current costmap object.
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.