32 #include <unordered_map>
53 std::vector<Astar::PriorityVec> centers;
61 std::vector<Astar::GridmapUpdate> updates;
63 std::vector<size_t> edge_indexes;
75 const float start_cost =
g_[s_rough];
84 if (center.
p_raw_ - range_overshoot > start_cost)
89 centers.emplace_back(std::move(center));
94 if (centers.size() == 0)
99 #pragma omp for schedule(static)
100 for (
auto it = centers.cbegin(); it < centers.cend(); ++it)
109 if (
static_cast<size_t>(next[0]) >=
static_cast<size_t>(
p_.
size[0]) ||
110 static_cast<size_t>(next[1]) >=
static_cast<size_t>(
p_.
size[1]))
115 float cost = ds.euclid_cost;
117 const float gnext =
g_[next];
119 if (gnext <=
g_[p] + cost)
126 float sum = 0, sum_hist = 0;
127 bool collision =
false;
128 for (
const auto&
d : ds.pos)
142 edge_indexes.push_back(p[0] + p[1] *
p_.
size[0]);
146 (weight_linear * ds.grid_to_len) *
156 const float cost_next = it->p_raw_ + cost;
157 if (gnext > cost_next)
159 updates.emplace_back(p, next, cost_next, cost_next);
166 for (
const Astar::GridmapUpdate& u : updates)
168 if (
g_[u.getPos()] > u.getCost())
170 g_[u.getPos()] = u.getCost();
171 open.push(std::move(u.getPriorityVec()));
174 for (
const size_t& edge_index : edge_indexes)
186 : cm_rough_(cm_rough)
187 , bbf_costmap_(bbf_costmap)
214 const int range_rough = 4;
215 for (
Astar::Vec d(-range_rough, 0, 0);
d[0] <= range_rough;
d[0]++)
217 for (
d[1] = -range_rough;
d[1] <= range_rough;
d[1]++)
219 if (
d[0] == 0 &&
d[1] == 0)
221 if (
d.sqlen() > range_rough * range_rough)
226 const float grid_to_len =
d.gridToLenFactor();
227 const int dist =
d.len();
228 const float dpx =
static_cast<float>(
d[0]) / dist;
229 const float dpy =
static_cast<float>(
d[1]) / dist;
231 for (
int i = 0; i < dist; i++)
234 if (diffs.
pos.size() == 0 || diffs.
pos.back() != ipos)
236 diffs.
pos.push_back(std::move(ipos));
256 if (e_rough !=
goal_)
262 float cost_min = std::numeric_limits<float>::max();
265 for (p[0] = rect.
min[0]; p[0] <= rect.
max[0]; p[0]++)
267 if (cost_min >
g_[p])
289 if (cost_min != std::numeric_limits<float>::max())
294 if (
g_[s_rough] > cost_min)
307 if (
g_[p] == std::numeric_limits<float>::max())
309 g_[p] = std::numeric_limits<float>::max();
313 for (
d[1] = -1;
d[1] <= 1;
d[1]++)
315 if (!((
d[0] == 0) ^ (
d[1] == 0)))
319 if ((
unsigned int)next[0] >= (
unsigned int)
p_.
size[0] ||
320 (
unsigned int)next[1] >= (
unsigned int)
p_.
size[1])
322 const float gn =
g_[next];
323 if (gn == std::numeric_limits<float>::max())
342 const float p =
g_[v];
370 g_.clear(std::numeric_limits<float>::max());