grid_astar_model_3dof.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019-2020, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <cmath>
31 #include <limits>
32 #include <utility>
33 #include <vector>
34 
35 #include <ros/ros.h>
36 
37 #include <costmap_cspace_msgs/MapMetaData3D.h>
38 
45 
46 namespace planner_cspace
47 {
48 namespace planner_3d
49 {
51  const costmap_cspace_msgs::MapMetaData3D& map_info,
52  const Vecf& euclid_cost_coef,
53  const int local_range,
54  const BlockMemGridmapBase<float, 3, 2>& cost_estim_cache,
56  const BlockMemGridmapBase<char, 3, 2>& cm_hyst,
57  const BlockMemGridmapBase<char, 3, 2>& cm_rough,
58  const CostCoeff& cc,
59  const int range)
60  : hysteresis_(false)
61  , map_info_(map_info)
62  , euclid_cost_coef_(euclid_cost_coef)
63  , resolution_(
64  1.0f / map_info.linear_resolution,
65  1.0f / map_info.linear_resolution,
66  1.0f / map_info.angular_resolution)
67  , local_range_(local_range)
68  , cost_estim_cache_(cost_estim_cache)
69  , cm_(cm)
70  , cm_hyst_(cm_hyst)
71  , cm_rough_(cm_rough)
72  , cc_(cc)
73  , range_(range)
74 {
75  rot_cache_.reset(map_info_.linear_resolution, map_info_.angular_resolution, range_);
76 
77  costmap_cspace_msgs::MapMetaData3D map_info_linear(map_info_);
78  map_info_linear.angle = 1;
79 
81  map_info_linear.linear_resolution,
82  map_info_linear.angular_resolution,
83  range_,
86  map_info_.linear_resolution,
87  map_info_.angular_resolution,
88  range_,
89  cm_.getAddressor());
90 
91  // Make boundary check threshold
94  Vec(static_cast<int>(map_info_.width),
95  static_cast<int>(map_info_.height),
96  static_cast<int>(map_info_.angle)) -
98  ROS_INFO("x:%d, y:%d grids around the boundary is ignored on path search", min_boundary_[0], min_boundary_[1]);
99 
101 
103  search_list_rough_.clear();
104  Vec d;
105  for (d[0] = -range_; d[0] <= range_; d[0]++)
106  {
107  for (d[1] = -range_; d[1] <= range_; d[1]++)
108  {
109  if (d.sqlen() > range_ * range_)
110  continue;
111  d[2] = 0;
112  search_list_rough_.push_back(d);
113  }
114  }
115  path_interpolator_.reset(map_info_.angular_resolution, range_);
116 }
117 
118 void GridAstarModel3D::enableHysteresis(const bool enable)
119 {
120  hysteresis_ = enable;
121 }
123 {
124  for (int rootsum = 0;
125  rootsum < static_cast<int>(euclid_cost_lin_cache_.size()); ++rootsum)
126  {
127  euclid_cost_lin_cache_[rootsum] = std::sqrt(rootsum) * euclid_cost_coef_[0];
128  }
129 }
130 float GridAstarModel3D::euclidCost(const Vec& v) const
131 {
132  float cost = euclidCostRough(v);
133 
134  int angle = v[2];
135  while (angle > static_cast<int>(map_info_.angle) / 2)
136  angle -= static_cast<int>(map_info_.angle);
137  while (angle < -static_cast<int>(map_info_.angle) / 2)
138  angle += static_cast<int>(map_info_.angle);
139  cost += std::abs(euclid_cost_coef_[2] * angle);
140  return cost;
141 }
143 {
144  int rootsum = 0;
145  for (int i = 0; i < 2; ++i)
146  rootsum += v[i] * v[i];
147 
148  if (rootsum < static_cast<int>(euclid_cost_lin_cache_.size()))
149  {
150  return euclid_cost_lin_cache_[rootsum];
151  }
152 
153  return std::sqrt(rootsum) * euclid_cost_coef_[0];
154 }
156  const Vec& cur, const Vec& next, const std::vector<VecWithCost>& start, const Vec& goal) const
157 {
158  Vec d_raw = next - cur;
159  d_raw.cycle(map_info_.angle);
160  const Vec d = d_raw;
161  float cost = euclidCost(d);
162 
163  if (d[0] == 0 && d[1] == 0)
164  {
165  // In-place turn
166  int sum = 0;
167  const int dir = d[2] < 0 ? -1 : 1;
168  Vec pos = cur;
169  for (int i = 0; i < std::abs(d[2]); i++)
170  {
171  pos[2] += dir;
172  if (pos[2] < 0)
173  pos[2] += map_info_.angle;
174  else if (pos[2] >= static_cast<int>(map_info_.angle))
175  pos[2] -= map_info_.angle;
176  const auto c = cm_[pos];
177  if (c > 99)
178  return -1;
179  sum += c;
180  }
181 
182  cost +=
183  sum * map_info_.angular_resolution * euclid_cost_coef_[2] / euclid_cost_coef_[0] +
184  sum * map_info_.angular_resolution * cc_.weight_costmap_turn_ / 100.0;
185  // simplified from sum * map_info_.angular_resolution * abs(d[2]) * cc_.weight_costmap_turn_ / (100.0 * abs(d[2]))
186  return cc_.in_place_turn_ + cost;
187  }
188 
189  const Vec d2(d[0] + range_, d[1] + range_, next[2]);
190  const Vecf motion = rot_cache_.getMotion(cur[2], d2);
191  const float dist = motion.len();
192 
193  if (motion[0] < 0)
194  {
195  // Going backward
196  cost *= 1.0 + cc_.weight_backward_;
197  }
198 
199  if (d[2] == 0)
200  {
201  const float aspect = motion[0] / motion[1];
202  cost += euclid_cost_coef_[2] * std::abs(1.0 / aspect) * map_info_.angular_resolution / (M_PI * 2.0);
203 
204  // Go-straight
205  int sum = 0, sum_hyst = 0;
206  Vec d_index(d[0], d[1], next[2]);
207  d_index.cycleUnsigned(map_info_.angle);
208 
209  const auto cache_page = motion_cache_.find(cur[2], d_index);
210  if (cache_page == motion_cache_.end(cur[2]))
211  return -1;
212  const int num = cache_page->second.getMotion().size();
213  for (const auto& pos_diff : cache_page->second.getMotion())
214  {
215  const Vec pos(
216  cur[0] + pos_diff[0], cur[1] + pos_diff[1], pos_diff[2]);
217  const auto c = cm_[pos];
218  if (c > 99)
219  return -1;
220  sum += c;
221 
222  if (hysteresis_)
223  sum_hyst += cm_hyst_[pos];
224  }
225  const float distf = cache_page->second.getDistance();
226  cost += sum * map_info_.linear_resolution * distf * cc_.weight_costmap_ / (100.0 * num);
227  cost += sum_hyst * map_info_.linear_resolution * distf * cc_.weight_hysteresis_ / (100.0 * num);
228  }
229  else
230  {
231  const std::pair<float, float>& radiuses = rot_cache_.getRadiuses(cur[2], d2);
232  const float r1 = radiuses.first;
233  const float r2 = radiuses.second;
234  const float curv_radius = (r1 + r2) / 2;
235 
236  // Ignore boundary
237  if (cur[0] < min_boundary_[0] || cur[1] < min_boundary_[1] ||
238  cur[0] >= max_boundary_[0] || cur[1] >= max_boundary_[1])
239  return -1;
240 
241  if (std::abs(cc_.max_vel_ / r1) > cc_.max_ang_vel_)
242  {
243  const float vel = std::abs(curv_radius) * cc_.max_ang_vel_;
244  // Curve deceleration penalty
245  cost += dist * std::abs(vel / cc_.max_vel_) * cc_.weight_decel_;
246  }
247 
248  {
249  int sum = 0, sum_hyst = 0;
250  Vec d_index(d[0], d[1], next[2]);
251  d_index.cycleUnsigned(map_info_.angle);
252 
253  const auto cache_page = motion_cache_.find(cur[2], d_index);
254  if (cache_page == motion_cache_.end(cur[2]))
255  return -1;
256  const int num = cache_page->second.getMotion().size();
257  for (const auto& pos_diff : cache_page->second.getMotion())
258  {
259  const Vec pos(
260  cur[0] + pos_diff[0], cur[1] + pos_diff[1], pos_diff[2]);
261  const auto c = cm_[pos];
262  if (c > 99)
263  return -1;
264  sum += c;
265 
266  if (hysteresis_)
267  sum_hyst += cm_hyst_[pos];
268  }
269  const float distf = cache_page->second.getDistance();
270  cost += sum * map_info_.linear_resolution * distf * cc_.weight_costmap_ / (100.0 * num);
271  cost += sum * map_info_.angular_resolution * std::abs(d[2]) * cc_.weight_costmap_turn_ / (100.0 * num);
272  cost += sum_hyst * map_info_.linear_resolution * distf * cc_.weight_hysteresis_ / (100.0 * num);
273  }
274  }
275 
276  return cost;
277 }
279  const Vec& cur, const Vec& goal) const
280 {
281  Vec s2(cur[0], cur[1], 0);
282  float cost = cost_estim_cache_[s2];
283  if (cost == std::numeric_limits<float>::max())
284  return std::numeric_limits<float>::max();
285 
286  int diff = cur[2] - goal[2];
287  while (diff > static_cast<int>(map_info_.angle) / 2)
288  diff -= static_cast<int>(map_info_.angle);
289  while (diff < -static_cast<int>(map_info_.angle) / 2)
290  diff += static_cast<int>(map_info_.angle);
291 
292  cost += euclid_cost_coef_[2] * std::abs(diff);
293 
294  return cost;
295 }
296 const std::vector<GridAstarModel3D::Vec>& GridAstarModel3D::searchGrids(
297  const Vec& p,
298  const std::vector<VecWithCost>& ss,
299  const Vec& es) const
300 {
301  const float local_range_sq = local_range_ * local_range_;
302  for (const VecWithCost& s : ss)
303  {
304  const Vec ds = s.v_ - p;
305 
306  if (ds.sqlen() < local_range_sq)
307  {
308  return motion_primitives_[p[2]];
309  }
310  }
311  return search_list_rough_;
312 }
313 
315  const Vec& cur, const Vec& next, const std::vector<VecWithCost>& start, const Vec& goal) const
316 {
317  Vec d = next - cur;
318  d[2] = 0;
319  float cost = base_->euclidCostRough(d);
320 
321  int sum = 0;
322  const auto cache_page = base_->motion_cache_linear_.find(0, d);
323  if (cache_page == base_->motion_cache_linear_.end(0))
324  return -1;
325  const int num = cache_page->second.getMotion().size();
326  for (const auto& pos_diff : cache_page->second.getMotion())
327  {
328  const Vec pos(cur[0] + pos_diff[0], cur[1] + pos_diff[1], 0);
329  const auto c = base_->cm_rough_[pos];
330  if (c > 99)
331  return -1;
332  sum += c;
333  }
334  const float distf = cache_page->second.getDistance();
335  cost += sum * base_->map_info_.linear_resolution *
336  distf * base_->cc_.weight_costmap_ / (100.0 * num);
337 
338  return cost;
339 }
341  const Vec& cur, const Vec& goal) const
342 {
343  const Vec d = goal - cur;
344  const float cost = base_->euclidCostRough(d);
345 
346  return cost;
347 }
348 const std::vector<GridAstarModel3D::Vec>& GridAstarModel2D::searchGrids(
349  const Vec& cur, const std::vector<VecWithCost>& start, const Vec& goal) const
350 {
351  return base_->search_list_rough_;
352 }
353 } // namespace planner_3d
354 } // namespace planner_cspace
d
Chain d2()
float cost(const Vec &cur, const Vec &next, const std::vector< VecWithCost > &start, const Vec &goal) const final
float costEstim(const Vec &cur, const Vec &goal) const final
const BlockMemGridmapBase< char, 3, 2 > & cm_
const std::vector< Vec > & searchGrids(const Vec &p, const std::vector< VecWithCost > &ss, const Vec &es) const override
f
const CyclicVecFloat< 3, 2 > & getMotion(const int start_angle, const CyclicVecInt< 3, 2 > &end) const
XmlRpcServer s
virtual std::function< void(CyclicVecInt< DIM, NONCYCLIC >, size_t &, size_t &)> getAddressor() const =0
const BlockMemGridmapBase< float, 3, 2 > & cost_estim_cache_
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
std::vector< std::vector< Vec > > motion_primitives_
const CyclicVecInt< 3, 2 > & getMaxRange() const
Definition: motion_cache.h:88
const std::pair< float, float > & getRadiuses(const int start_angle, const CyclicVecInt< 3, 2 > &end) const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void reset(const float linear_resolution, const float angular_resolution, const int range, const std::function< void(CyclicVecInt< 3, 2 >, size_t &, size_t &)> gm_addr)
void reset(const float linear_resolution, const float angular_resolution, const int range)
#define ROS_INFO(...)
float cost(const Vec &cur, const Vec &next, const std::vector< VecWithCost > &start, const Vec &goal) const override
void cycleUnsigned(const int res, const ArgList &... rest)
Definition: cyclic_vec.h:289
const BlockMemGridmapBase< char, 3, 2 > & cm_hyst_
const BlockMemGridmapBase< char, 3, 2 > & cm_rough_
const Cache::const_iterator find(const int start_yaw, const CyclicVecInt< 3, 2 > &goal) const
Definition: motion_cache.h:70
float costEstim(const Vec &cur, const Vec &goal) const override
const std::vector< Vec > & searchGrids(const Vec &cur, const std::vector< VecWithCost > &start, const Vec &goal) const final
void reset(const float angular_resolution, const int range)
void cycle(const int res, const ArgList &... rest)
Definition: cyclic_vec.h:282
const Cache::const_iterator end(const int start_yaw) const
Definition: motion_cache.h:79
static std::vector< std::vector< Vec > > build(const costmap_cspace_msgs::MapMetaData3D &map_info, const CostCoeff &cc, const int range)
GridAstarModel3D(const costmap_cspace_msgs::MapMetaData3D &map_info, const Vecf &euclid_cost_coef, const int local_range, const BlockMemGridmapBase< float, 3, 2 > &cost_estim_cache, const BlockMemGridmapBase< char, 3, 2 > &cm, const BlockMemGridmapBase< char, 3, 2 > &cm_hyst, const BlockMemGridmapBase< char, 3, 2 > &cm_rough, const CostCoeff &cc, const int range)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06