Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
theta_star.hpp
1 // Copyright 2020 Anshumaan Singh
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_THETA_STAR_PLANNER__THETA_STAR_HPP_
16 #define NAV2_THETA_STAR_PLANNER__THETA_STAR_HPP_
17 
18 #include <cmath>
19 #include <chrono>
20 #include <vector>
21 #include <queue>
22 #include <algorithm>
23 #include "rclcpp/rclcpp.hpp"
24 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
25 
26 const double INF_COST = DBL_MAX;
27 const int UNKNOWN_COST = 255;
28 const int OBS_COST = 254;
29 const int LETHAL_COST = 252;
30 
31 struct coordsM
32 {
33  int x, y;
34 };
35 
36 struct coordsW
37 {
38  double x, y;
39 };
40 
41 struct tree_node
42 {
43  int x, y;
44  double g = INF_COST;
45  double h = INF_COST;
46  const tree_node * parent_id = nullptr;
47  bool is_in_queue = false;
48  double f = INF_COST;
49 };
50 
51 struct comp
52 {
53  bool operator()(const tree_node * p1, const tree_node * p2)
54  {
55  return (p1->f) > (p2->f);
56  }
57 };
58 
59 namespace theta_star
60 {
61 class ThetaStar
62 {
63 public:
64  coordsM src_{}, dst_{};
65  nav2_costmap_2d::Costmap2D * costmap_{};
66 
70  double w_euc_cost_;
78  int size_x_, size_y_;
79 
80  ThetaStar();
81 
82  ~ThetaStar() = default;
83 
90  bool generatePath(std::vector<coordsW> & raw_path);
91 
96  inline bool isSafe(const int & cx, const int & cy) const
97  {
98  return (costmap_->getCost(
99  cx,
100  cy) == UNKNOWN_COST && allow_unknown_) || costmap_->getCost(cx, cy) < LETHAL_COST;
101  }
102 
106  void setStartAndGoal(
107  const geometry_msgs::msg::PoseStamped & start,
108  const geometry_msgs::msg::PoseStamped & goal);
109 
114  bool isUnsafeToPlan() const
115  {
116  return !(isSafe(src_.x, src_.y)) || !(isSafe(dst_.x, dst_.y));
117  }
118 
119  int nodes_opened = 0;
120 
121 protected:
126  std::vector<tree_node *> node_position_;
127 
132  std::vector<tree_node> nodes_data_;
133 
135  std::priority_queue<tree_node *, std::vector<tree_node *>, comp> queue_;
136 
141 
142  const coordsM moves[8] = {{0, 1},
143  {0, -1},
144  {1, 0},
145  {-1, 0},
146  {1, -1},
147  {-1, 1},
148  {1, 1},
149  {-1, -1}};
150 
151  tree_node * exp_node;
152 
153 
159  void resetParent(tree_node * curr_data);
160 
166  void setNeighbors(const tree_node * curr_data);
167 
175  bool losCheck(
176  const int & x0, const int & y0, const int & x1, const int & y1,
177  double & sl_cost) const;
178 
184  void backtrace(std::vector<coordsW> & raw_points, const tree_node * curr_n) const;
185 
191  bool isSafe(const int & cx, const int & cy, double & cost) const
192  {
193  double curr_cost = getCost(cx, cy);
194  if ((costmap_->getCost(cx, cy) == UNKNOWN_COST && allow_unknown_) || curr_cost < LETHAL_COST) {
195  if (costmap_->getCost(cx, cy) == UNKNOWN_COST) {
196  curr_cost = OBS_COST - 1;
197  }
198  cost += w_traversal_cost_ * curr_cost * curr_cost / LETHAL_COST / LETHAL_COST;
199  return true;
200  } else {
201  return false;
202  }
203  }
204 
205  /*
206  * @brief this function scales the costmap cost by shifting the origin to 25 and then multiply
207  * the actual costmap cost by 0.9 to keep the output in the range of [25, 255)
208  */
209  inline double getCost(const int & cx, const int & cy) const
210  {
211  return 26 + 0.9 * costmap_->getCost(cx, cy);
212  }
213 
219  inline double getTraversalCost(const int & cx, const int & cy)
220  {
221  double curr_cost = getCost(cx, cy);
222  return w_traversal_cost_ * curr_cost * curr_cost / LETHAL_COST / LETHAL_COST;
223  }
224 
230  inline double getEuclideanCost(const int & ax, const int & ay, const int & bx, const int & by)
231  {
232  return w_euc_cost_ * std::hypot(ax - bx, ay - by);
233  }
234 
240  inline double getHCost(const int & cx, const int & cy)
241  {
242  return w_heuristic_cost_ * std::hypot(cx - dst_.x, cy - dst_.y);
243  }
244 
249  inline bool withinLimits(const int & cx, const int & cy) const
250  {
251  return cx >= 0 && cx < size_x_ && cy >= 0 && cy < size_y_;
252  }
253 
258  inline bool isGoal(const tree_node & this_node) const
259  {
260  return this_node.x == dst_.x && this_node.y == dst_.y;
261  }
262 
267  void initializePosn(int size_inc = 0);
268 
273  inline void addIndex(const int & cx, const int & cy, tree_node * node_this)
274  {
275  node_position_[size_x_ * cy + cx] = node_this;
276  }
277 
282  inline tree_node * getIndex(const int & cx, const int & cy)
283  {
284  return node_position_[size_x_ * cy + cx];
285  }
286 
291  void addToNodesData(const int & id_this)
292  {
293  if (static_cast<int>(nodes_data_.size()) <= id_this) {
294  nodes_data_.push_back({});
295  } else {
296  nodes_data_[id_this] = {};
297  }
298  }
299 
303  void resetContainers();
304 
308  void clearQueue()
309  {
310  queue_ = std::priority_queue<tree_node *, std::vector<tree_node *>, comp>();
311  }
312 };
313 } // namespace theta_star
314 
315 #endif // NAV2_THETA_STAR_PLANNER__THETA_STAR_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:266
std::vector< tree_node * > node_position_
Definition: theta_star.hpp:126
void addIndex(const int &cx, const int &cy, tree_node *node_this)
it stores id_this in node_position_ at the index [ size_x_*cy + cx ]
Definition: theta_star.hpp:273
double w_euc_cost_
weight on the euclidean distance cost (used for calculations of g_cost)
Definition: theta_star.hpp:70
double w_heuristic_cost_
weight on the heuristic cost (used for h_cost calculations)
Definition: theta_star.hpp:72
int how_many_corners_
parameter to set the number of adjacent nodes to be searched on
Definition: theta_star.hpp:74
int size_x_
the x-directional and y-directional lengths of the map respectively
Definition: theta_star.hpp:78
bool generatePath(std::vector< coordsW > &raw_path)
it iteratively searches upon the nodes in the queue (open list) until the current node is the goal po...
Definition: theta_star.cpp:46
bool losCheck(const int &x0, const int &y0, const int &x1, const int &y1, double &sl_cost) const
performs the line of sight check using Bresenham's Algorithm, and has been modified to calculate the ...
Definition: theta_star.cpp:173
bool isGoal(const tree_node &this_node) const
checks if the coordinates of a node is the goal or not
Definition: theta_star.hpp:258
void backtrace(std::vector< coordsW > &raw_points, const tree_node *curr_n) const
it returns the path by backtracking from the goal to the start, by using their parent nodes
Definition: theta_star.cpp:153
bool withinLimits(const int &cx, const int &cy) const
checks if the given coordinates(cx, cy) lies within the map
Definition: theta_star.hpp:249
double getEuclideanCost(const int &ax, const int &ay, const int &bx, const int &by)
calculates the piecewise straight line euclidean distances by <euc_cost_parameter>*<euclidean distanc...
Definition: theta_star.hpp:230
bool isUnsafeToPlan() const
checks whether the start and goal points have costmap costs greater than LETHAL_COST
Definition: theta_star.hpp:114
std::priority_queue< tree_node *, std::vector< tree_node * >, comp > queue_
this is the priority queue (open_list) to select the next node to be expanded
Definition: theta_star.hpp:135
void initializePosn(int size_inc=0)
initialises the node_position_ vector by storing -1 as index for all points(x, y) within the limits o...
Definition: theta_star.cpp:249
bool allow_unknown_
parameter to set weather the planner can plan through unknown space
Definition: theta_star.hpp:76
void setNeighbors(const tree_node *curr_data)
this function expands the current node
Definition: theta_star.cpp:104
tree_node * getIndex(const int &cx, const int &cy)
retrieves the pointer of the location at which the data of the point(cx, cy) is stored in nodes_data
Definition: theta_star.hpp:282
bool isSafe(const int &cx, const int &cy) const
this function checks whether the cost of a point(cx, cy) on the costmap is less than the LETHAL_COST
Definition: theta_star.hpp:96
double w_traversal_cost_
weight on the costmap traversal cost
Definition: theta_star.hpp:68
void setStartAndGoal(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal)
initialises the values of the start and goal points
Definition: theta_star.cpp:34
std::vector< tree_node > nodes_data_
Definition: theta_star.hpp:132
double getHCost(const int &cx, const int &cy)
for the point(cx, cy), its heuristic cost is calculated by <heuristic_cost_parameter>*<euclidean dist...
Definition: theta_star.hpp:240
double getTraversalCost(const int &cx, const int &cy)
for the point(cx, cy), its traversal cost is calculated by <parameter>*(<actual_traversal_cost_from_c...
Definition: theta_star.hpp:219
void resetParent(tree_node *curr_data)
it performs a line of sight (los) check between the current node and the parent node of its parent no...
Definition: theta_star.cpp:85
void addToNodesData(const int &id_this)
this function depending on the size of the nodes_data_ vector allots space to store the data for a no...
Definition: theta_star.hpp:291
void clearQueue()
clears the priority queue after each execution of the generatePath function
Definition: theta_star.hpp:308
void resetContainers()
initialises the values of global variables at beginning of the execution of the generatePath function
Definition: theta_star.cpp:230
bool isSafe(const int &cx, const int &cy, double &cost) const
it is an overloaded function to ease the cost calculations while performing the LOS check
Definition: theta_star.hpp:191