30 #ifndef PLANNER_CSPACE_GRID_ASTAR_H
31 #define PLANNER_CSPACE_GRID_ASTAR_H
33 #define _USE_MATH_DEFINES
40 #include <unordered_map>
44 #include <boost/chrono.hpp>
63 template <
int DIM = 3,
int NONCYCLIC = 2>
72 template <
class T,
int block_w
idth = 0x20>
107 const Vec& p0,
const Vec& p1,
108 const float cost_estim,
const float cost)
150 g_.
clear(std::numeric_limits<float>::max());
170 const std::vector<VecWithCost>& ss,
const Vec& e,
171 std::list<Vec>& path,
174 const float cost_leave,
175 const float progress_interval,
176 const bool return_best =
false)
181 cost_leave, progress_interval, return_best);
187 const std::vector<VecWithCost>& sts,
const Vec& en,
188 std::list<Vec>& path,
191 const float cost_leave,
192 const float progress_interval,
193 const bool return_best =
false)
198 auto ts = boost::chrono::high_resolution_clock::now();
202 g.clear(std::numeric_limits<float>::max());
206 std::vector<VecWithCost> ss_normalized;
208 int cost_estim_min = std::numeric_limits<int>::max();
215 s.cycleUnsigned(g.size());
216 ss_normalized.emplace_back(
s, st.c_);
219 const int cost_estim = model->
costEstim(
s, e);
220 open_.emplace(cost_estim + st.c_, st.c_,
s);
221 if (cost_estim_min > cost_estim)
223 cost_estim_min = cost_estim;
228 std::vector<PriorityVec> centers;
231 size_t num_updates(0);
232 size_t num_total_updates(0);
239 std::vector<GridmapUpdate> updates;
243 model->
searchGrids(ss_normalized[0].v_, ss_normalized, e).size() /
244 omp_get_num_threads());
245 std::vector<Vec> dont;
253 const size_t num_search_queue =
open_.size();
260 if (
open_.size() == 0)
262 PriorityVec center(
open_.top());
264 if (center.v_ == e || center.p_ - center.p_raw_ < cost_leave)
270 centers.emplace_back(std::move(center));
273 const auto tnow = boost::chrono::high_resolution_clock::now();
274 if (boost::chrono::duration<float>(tnow - ts).count() >= progress_interval)
276 std::list<Vec> path_tmp;
278 findPath(ss_normalized, better, path_tmp);
282 .num_search_queue = num_search_queue,
283 .num_prev_updates = num_updates,
284 .num_total_updates = num_total_updates,
286 if (!cb_progress(path_tmp, stats))
294 if (centers.size() < 1 || found || abort)
299 #pragma omp for schedule(static)
300 for (
auto it = centers.cbegin(); it < centers.cend(); ++it)
302 const Vec p = it->v_;
303 const float c = it->p_raw_;
304 const float c_estim = it->p_;
305 const float gp = g[p];
309 if (c_estim - c < cost_estim_min)
311 cost_estim_min = c_estim - c;
315 const std::vector<Vec> search_list = model->
searchGrids(p, ss_normalized, e);
318 for (
auto it = search_list.cbegin(); it < search_list.cend(); ++it)
331 const float cost_estim = model->
costEstim(next, e);
332 if (cost_estim < 0 || cost_estim == std::numeric_limits<float>::max())
335 const float cost = model->
cost(p, next, ss_normalized, e);
336 if (cost < 0 || cost == std::numeric_limits<float>::max())
339 const float cost_next = c + cost;
340 if (g[next] > cost_next)
343 updates.emplace_back(p, next, cost_next + cost_estim, cost_next);
352 for (
const GridmapUpdate& u : updates)
354 if (g[u.getPos()] > u.getCost())
356 g[u.getPos()] = u.getCost();
357 parents_[u.getPos()] = u.getParentPos();
358 open_.push(std::move(u.getPriorityVec()));
363 for (
const Vec& p : dont)
367 const size_t n = updates.size();
369 num_total_updates += n;
379 findPath(ss_normalized, better, path);
383 return findPath(ss_normalized, e, path);
385 bool findPath(
const std::vector<VecWithCost>& ss,
const Vec& e, std::list<Vec>& path)
const
387 std::unordered_map<Vec, Vec, Vec> parents =
parents_;
404 if (parents.find(n) == parents.end())
409 parents.erase(child);
422 #endif // PLANNER_CSPACE_GRID_ASTAR_H