Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
theta_star.cpp
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 #include <vector>
16 #include "nav2_core/planner_exceptions.hpp"
17 #include "nav2_theta_star_planner/theta_star.hpp"
18 
19 namespace theta_star
20 {
21 
22 ThetaStar::ThetaStar()
23 : w_traversal_cost_(1.0),
24  w_euc_cost_(2.0),
25  w_heuristic_cost_(1.0),
26  how_many_corners_(8),
27  allow_unknown_(true),
28  size_x_(0),
29  size_y_(0),
30  terminal_checking_interval_(5000),
31  index_generated_(0)
32 {
33  exp_node = new tree_node;
34 }
35 
36 void ThetaStar::setStartAndGoal(
37  const geometry_msgs::msg::PoseStamped & start,
38  const geometry_msgs::msg::PoseStamped & goal)
39 {
40  unsigned int s[2], d[2];
41  costmap_->worldToMap(start.pose.position.x, start.pose.position.y, s[0], s[1]);
42  costmap_->worldToMap(goal.pose.position.x, goal.pose.position.y, d[0], d[1]);
43 
44  src_ = {static_cast<int>(s[0]), static_cast<int>(s[1])};
45  dst_ = {static_cast<int>(d[0]), static_cast<int>(d[1])};
46 }
47 
48 bool ThetaStar::generatePath(std::vector<coordsW> & raw_path, std::function<bool()> cancel_checker)
49 {
50  resetContainers();
51  addToNodesData(index_generated_);
52  double src_g_cost = getTraversalCost(src_.x, src_.y), src_h_cost = getHCost(src_.x, src_.y);
53  nodes_data_[index_generated_] =
54  {src_.x, src_.y, src_g_cost, src_h_cost, &nodes_data_[index_generated_], true,
55  src_g_cost + src_h_cost};
56  queue_.push({&nodes_data_[index_generated_]});
57  addIndex(src_.x, src_.y, &nodes_data_[index_generated_]);
58  tree_node * curr_data = &nodes_data_[index_generated_];
59  index_generated_++;
60  nodes_opened = 0;
61 
62  while (!queue_.empty()) {
63  nodes_opened++;
64 
65  if (nodes_opened % terminal_checking_interval_ == 0 && cancel_checker()) {
66  clearQueue();
67  throw nav2_core::PlannerCancelled("Planner was canceled");
68  }
69 
70  if (isGoal(*curr_data)) {
71  break;
72  }
73 
74  resetParent(curr_data);
75  setNeighbors(curr_data);
76 
77  curr_data = queue_.top();
78  queue_.pop();
79  }
80 
81  if (queue_.empty()) {
82  raw_path.clear();
83  return false;
84  }
85 
86  backtrace(raw_path, curr_data);
87  clearQueue();
88 
89  return true;
90 }
91 
92 void ThetaStar::resetParent(tree_node * curr_data)
93 {
94  double g_cost, los_cost = 0;
95  curr_data->is_in_queue = false;
96  const tree_node * curr_par = curr_data->parent_id;
97  const tree_node * maybe_par = curr_par->parent_id;
98 
99  if (losCheck(curr_data->x, curr_data->y, maybe_par->x, maybe_par->y, los_cost)) {
100  g_cost = maybe_par->g +
101  getEuclideanCost(curr_data->x, curr_data->y, maybe_par->x, maybe_par->y) + los_cost;
102 
103  if (g_cost < curr_data->g) {
104  curr_data->parent_id = maybe_par;
105  curr_data->g = g_cost;
106  curr_data->f = g_cost + curr_data->h;
107  }
108  }
109 }
110 
111 void ThetaStar::setNeighbors(const tree_node * curr_data)
112 {
113  int mx, my;
114  tree_node * m_id = nullptr;
115  double g_cost, h_cost, cal_cost;
116 
117  for (int i = 0; i < how_many_corners_; i++) {
118  mx = curr_data->x + moves[i].x;
119  my = curr_data->y + moves[i].y;
120 
121  if (withinLimits(mx, my)) {
122  if (!isSafe(mx, my)) {
123  continue;
124  }
125  } else {
126  continue;
127  }
128 
129  g_cost = curr_data->g + getEuclideanCost(curr_data->x, curr_data->y, mx, my) +
130  getTraversalCost(mx, my);
131 
132  m_id = getIndex(mx, my);
133 
134  if (m_id == nullptr) {
135  addToNodesData(index_generated_);
136  m_id = &nodes_data_[index_generated_];
137  addIndex(mx, my, m_id);
138  index_generated_++;
139  }
140 
141  exp_node = m_id;
142 
143  h_cost = getHCost(mx, my);
144  cal_cost = g_cost + h_cost;
145  if (exp_node->f > cal_cost) {
146  exp_node->g = g_cost;
147  exp_node->h = h_cost;
148  exp_node->f = cal_cost;
149  exp_node->parent_id = curr_data;
150  if (!exp_node->is_in_queue) {
151  exp_node->x = mx;
152  exp_node->y = my;
153  exp_node->is_in_queue = true;
154  queue_.push({m_id});
155  }
156  }
157  }
158 }
159 
160 void ThetaStar::backtrace(std::vector<coordsW> & raw_points, const tree_node * curr_n) const
161 {
162  std::vector<coordsW> path_rev;
163  coordsW world{};
164  do {
165  costmap_->mapToWorld(curr_n->x, curr_n->y, world.x, world.y);
166  path_rev.push_back(world);
167  if (path_rev.size() > 1) {
168  curr_n = curr_n->parent_id;
169  }
170  } while (curr_n->parent_id != curr_n);
171  costmap_->mapToWorld(curr_n->x, curr_n->y, world.x, world.y);
172  path_rev.push_back(world);
173 
174  raw_points.reserve(path_rev.size());
175  for (int i = static_cast<int>(path_rev.size()) - 1; i >= 0; i--) {
176  raw_points.push_back(path_rev[i]);
177  }
178 }
179 
180 bool ThetaStar::losCheck(
181  const int & x0, const int & y0, const int & x1, const int & y1,
182  double & sl_cost) const
183 {
184  sl_cost = 0;
185 
186  int cx, cy;
187  int dy = abs(y1 - y0), dx = abs(x1 - x0), f = 0;
188  int sx, sy;
189  sx = x1 > x0 ? 1 : -1;
190  sy = y1 > y0 ? 1 : -1;
191 
192  int u_x = (sx - 1) / 2;
193  int u_y = (sy - 1) / 2;
194  cx = x0;
195  cy = y0;
196 
197  if (dx >= dy) {
198  while (cx != x1) {
199  f += dy;
200  if (f >= dx) {
201  if (!isSafe(cx + u_x, cy + u_y, sl_cost)) {
202  return false;
203  }
204  cy += sy;
205  f -= dx;
206  }
207  if (f != 0 && !isSafe(cx + u_x, cy + u_y, sl_cost)) {
208  return false;
209  }
210  if (dy == 0 && !isSafe(cx + u_x, cy, sl_cost) && !isSafe(cx + u_x, cy - 1, sl_cost)) {
211  return false;
212  }
213  cx += sx;
214  }
215  } else {
216  while (cy != y1) {
217  f = f + dx;
218  if (f >= dy) {
219  if (!isSafe(cx + u_x, cy + u_y, sl_cost)) {
220  return false;
221  }
222  cx += sx;
223  f -= dy;
224  }
225  if (f != 0 && !isSafe(cx + u_x, cy + u_y, sl_cost)) {
226  return false;
227  }
228  if (dx == 0 && !isSafe(cx, cy + u_y, sl_cost) && !isSafe(cx - 1, cy + u_y, sl_cost)) {
229  return false;
230  }
231  cy += sy;
232  }
233  }
234  return true;
235 }
236 
237 void ThetaStar::resetContainers()
238 {
239  index_generated_ = 0;
240  int last_size_x = size_x_;
241  int last_size_y = size_y_;
242  int curr_size_x = static_cast<int>(costmap_->getSizeInCellsX());
243  int curr_size_y = static_cast<int>(costmap_->getSizeInCellsY());
244  if (((last_size_x != curr_size_x) || (last_size_y != curr_size_y)) &&
245  static_cast<int>(node_position_.size()) < (curr_size_x * curr_size_y))
246  {
247  initializePosn(curr_size_y * curr_size_x - last_size_y * last_size_x);
248  nodes_data_.reserve(curr_size_x * curr_size_y);
249  } else {
250  initializePosn();
251  }
252  size_x_ = curr_size_x;
253  size_y_ = curr_size_y;
254 }
255 
256 void ThetaStar::initializePosn(int size_inc)
257 {
258  if (!node_position_.empty()) {
259  for (int i = 0; i < size_x_ * size_y_; i++) {
260  node_position_[i] = nullptr;
261  }
262  }
263 
264  for (int i = 0; i < size_inc; i++) {
265  node_position_.push_back(nullptr);
266  }
267 }
268 
269 void ThetaStar::clearStart()
270 {
271  unsigned int mx_start = static_cast<unsigned int>(src_.x);
272  unsigned int my_start = static_cast<unsigned int>(src_.y);
273  costmap_->setCost(mx_start, my_start, nav2_costmap_2d::FREE_SPACE);
274 }
275 
276 } // namespace theta_star