test_distance_map.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2021, 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 <string>
33 #include <vector>
34 
35 #include <gtest/gtest.h>
36 
37 #include <omp.h>
38 
39 #include <costmap_cspace_msgs/MapMetaData3D.h>
44 
46 
47 namespace planner_cspace
48 {
49 namespace planner_3d
50 {
52 using Astar = GridAstar<3, 2>;
53 
54 class DistanceMapTest : public ::testing::Test
55 {
56 protected:
57  const int w_ = 10;
58  const int h_ = 10;
59  const int angle_ = 10;
60 
61  const Astar::Vec s_;
62  const Astar::Vec e_;
63 
65  const float tolerance_ = 0.4;
66 
67  Astar::Gridmap<char, 0x80> cm_rough_;
69 
71 
73  : s_(2, 2, 0)
74  , e_(8, 8, 0)
75  , ec_(0.5f, 0.5f, 0.2f)
76  , dm_(cm_rough_, bbf_costmap_)
77  {
78  const int range = 4;
79  const int local_range = 10;
80  omp_set_num_threads(2);
81 
82  costmap_cspace_msgs::MapMetaData3D map_info;
83  map_info.width = w_;
84  map_info.height = h_;
85  map_info.angle = angle_;
86  map_info.linear_resolution = 1.0;
87  map_info.angular_resolution = M_PI * 2 / angle_;
88 
89  CostCoeff cc;
90  cc.weight_costmap_ = 1.0f;
91  cc.weight_remembered_ = 0.0f;
92  cc.angle_resolution_aspect_ = 2.0f / tanf(map_info.angular_resolution);
93  dm_.setParams(cc, 64 * 2);
94 
95  const Astar::Vec size3d(w_, h_, angle_);
96  const Astar::Vec size2d(w_, h_, 1);
97  Astar::Gridmap<char, 0x40> cm;
98  Astar::Gridmap<char, 0x80> cm_hyst;
100  new GridAstarModel3D(
101  map_info,
102  ec_,
103  local_range,
104  dm_.gridmap(), cm, cm_hyst, cm_rough_,
105  cc, range));
106  cm.reset(size3d);
107  cm_hyst.reset(size3d);
108  cm_rough_.reset(size2d);
109  bbf_costmap_.reset(size2d);
110 
111  cm.clear(0);
112  cm_hyst.clear(0);
113  cm_rough_.clear(0);
114  bbf_costmap_.clear();
115 
116  const DistanceMap::Params dmp =
117  {
118  .euclid_cost = ec_,
119  .range = range,
120  .local_range = local_range,
121  .longcut_range = 10,
122  .size = size2d,
123  .resolution = map_info.linear_resolution,
124  };
125  dm_.init(model, dmp);
126  }
127 
129  {
130  /*
131  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
132  [ ][S][ ][ ][ ][ ][ ][ ][ ][ ]
133  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
134  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
135  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
136  [X][X][X][ ][X][X][X][X][X][X]
137  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
138  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
139  [ ][ ][ ][ ][ ][ ][ ][ ][G][ ]
140  [ ][ ][ ][ ][ ][ ][ ][ ][ ][ ]
141  */
142  cm_rough_.clear(0);
143  for (int x = 0; x < w_; x++)
144  {
145  cm_rough_[Astar::Vec(x, 5, 0)] = 100;
146  }
147  cm_rough_[Astar::Vec(3, 5, 0)] = 0;
148  }
149 
151  const Astar::Vec p,
152  const float d,
153  const std::string& msg) const
154  {
155  if (p[1] < 5)
156  {
157  ASSERT_NEAR(
158  2.7 + ec_[0] * (p - Astar::Vec(3, 5, 0)).norm(),
159  d, tolerance_)
160  << msg;
161  }
162  else if (p[1] > 5)
163  {
164  ASSERT_NEAR(
165  ec_[0] * (p - e_).norm(),
166  d, tolerance_)
167  << msg;
168  }
169  else if (p == Astar::Vec(3, 5, 0))
170  {
171  ASSERT_NEAR(2.7, d, tolerance_) << msg;
172  }
173  }
174 
175  bool validate(const std::string& msg) const
176  {
177  for (int y = 0; y < h_; y++)
178  {
179  for (int x = 0; x < w_; x++)
180  {
181  const Astar::Vec pos(x, y, 0);
182  validateDistance(pos, dm_[pos], msg + " failed at " + xyStr(x, y));
183  if (::testing::Test::HasFatalFailure())
184  return false;
185  }
186  }
187  return true;
188  }
189 };
190 
192  : public DistanceMapTest,
193  public ::testing::WithParamInterface<std::vector<Vec3>>
194 {
195 };
196 
198  UpdateWithTemporaryObstacles,
200  ::testing::Values(
201  std::vector<Vec3>(
202  {
203  Vec3(7, 7, 0),
204  }), // NOLINT(whitespace/braces)
205  std::vector<Vec3>(
206  {
207  Vec3(4, 2, 0),
208  Vec3(7, 2, 0),
209  }), // NOLINT(whitespace/braces)
210  std::vector<Vec3>(
211  {
212  // goal is unreachable
213  Vec3(3, 5, 0),
214  }), // NOLINT(whitespace/braces)
215  std::vector<Vec3>()));
216 
218 {
219  setupCostmap();
220 
221  dm_.create(s_, e_);
222  debugOutput(dm_, cm_rough_, s_, e_);
223 
224  if (!validate("create"))
225  {
226  debugOutput(dm_, cm_rough_, s_, e_);
227  return;
228  }
229 }
230 
232 {
233  const std::vector<Vec3> obstacles = GetParam();
234 
235  // Slide update area to check all combination of updated area
236  for (int from_y = 0; from_y < h_; from_y++)
237  {
238  for (int from_x = 0; from_x < w_; from_x++)
239  {
240  const std::string from(xyStr(from_x, from_y));
241  for (int to_y = from_y; to_y < h_; to_y++)
242  {
243  for (int to_x = from_x; to_x < w_; to_x++)
244  {
245  const std::string to(xyStr(to_x, to_y));
246 
247  // Add obstacles to the costmap and create distance map
248  setupCostmap();
249  for (const Vec3& obstacle : obstacles)
250  {
251  if (from_x < obstacle[0] && obstacle[0] < to_x &&
252  from_y < obstacle[1] && obstacle[1] < to_y)
253  {
254  cm_rough_[obstacle] = 100;
255  }
256  }
257  dm_.create(s_, e_);
258 
259  // Reset costmap
260  setupCostmap();
261 
262  // Update multiple times to check idempotence
263  for (int i = 0; i < 5; i++)
264  {
265  dm_.update(
266  s_, e_,
268  Vec3(from_x, from_y, 0), Vec3(to_x, to_y, 0)));
269  if (!validate("update " + from + "-" + to))
270  {
271  debugOutput(dm_, cm_rough_, s_, e_);
272  return;
273  }
274  }
275  }
276  }
277  }
278  }
279 }
280 
281 class DistanceMapTestLongMap : public ::testing::Test
282 {
283 protected:
284  const int w_ = 20;
285  const int h_ = 3;
286  const int angle_ = 10;
287 
288  const int range_ = 2;
289  const int local_range_ = 2;
290  const int longcut_range_ = 2;
291 
293 
294  const int search_range_ = 4;
295 
296  Astar::Gridmap<char, 0x80> cm_rough_;
298 
300 
302  : ec_(0.5f, 0.5f, 0.2f)
303  , dm_(cm_rough_, bbf_costmap_)
304  {
305  costmap_cspace_msgs::MapMetaData3D map_info;
306  map_info.width = w_;
307  map_info.height = h_;
308  map_info.angle = angle_;
309  map_info.linear_resolution = 1.0;
310  map_info.angular_resolution = M_PI * 2 / angle_;
311 
312  CostCoeff cc;
313  cc.weight_costmap_ = 1.0f;
314  cc.weight_remembered_ = 0.0f;
315  cc.angle_resolution_aspect_ = 2.0f / tanf(map_info.angular_resolution);
316  omp_set_num_threads(1);
317  dm_.setParams(cc, 1);
318 
319  const Astar::Vec size3d(w_, h_, angle_);
320  const Astar::Vec size2d(w_, h_, 1);
321  Astar::Gridmap<char, 0x40> cm;
322  Astar::Gridmap<char, 0x80> cm_hyst;
323  GridAstarModel3D::Ptr model(
324  new GridAstarModel3D(
325  map_info,
326  ec_,
327  local_range_,
328  dm_.gridmap(), cm, cm_hyst, cm_rough_,
329  cc, range_));
330  cm.reset(size3d);
331  cm_hyst.reset(size3d);
332  cm_rough_.reset(size2d);
333  bbf_costmap_.reset(size2d);
334  cm.clear(0);
335  cm_hyst.clear(0);
336  cm_rough_.clear(0);
337  bbf_costmap_.clear();
338 
339  const DistanceMap::Params dmp =
340  {
341  .euclid_cost = ec_,
342  .range = range_,
343  .local_range = local_range_,
344  .longcut_range = longcut_range_,
345  .size = size2d,
346  .resolution = map_info.linear_resolution,
347  };
348  dm_.init(model, dmp);
349  }
350 };
351 
353 {
354  const Astar::Vec s(4, 1, 0);
355  const Astar::Vec e(1, 1, 0);
356 
357  const float tolerance = 0.4;
358 
359  const int range_overshoot = range_ + local_range_ + longcut_range_ + search_range_;
360 
361  const auto validate = [this, s, e, tolerance, range_overshoot]()
362  {
363  for (int y = 0; y < h_; y++)
364  {
365  for (int x = 0; x < w_; x++)
366  {
367  const Astar::Vec p(x, y, 0);
368  const float cost = dm_[p];
369  const float d = (p - e).norm();
370  const float d_from_start = (p - s).norm();
371  if (x < s[0] || d_from_start <= range_overshoot)
372  {
373  ASSERT_NEAR(ec_[0] * d, cost, tolerance) << xyStr(x, y);
374  }
375  else if (d_from_start > range_overshoot)
376  {
377  ASSERT_EQ(std::numeric_limits<float>::max(), cost) << xyStr(x, y);
378  }
379  }
380  }
381  };
382 
383  dm_.create(s, e);
384  {
385  SCOPED_TRACE("After create");
386  validate();
387  }
388  if (::testing::Test::HasFatalFailure())
389  debugOutput(dm_, cm_rough_, s, e);
390 
391  dm_.update(
392  s, e,
394  Vec3(8, 0, 0), Vec3(9, 2, 0)));
395  {
396  SCOPED_TRACE("After update");
397  validate();
398  }
399  if (::testing::Test::HasFatalFailure())
400  debugOutput(dm_, cm_rough_, s, e);
401 }
402 
403 TEST_F(DistanceMapTestLongMap, BlockedAndRecovered)
404 {
405  const Astar::Vec s(7, 1, 0);
406  const Astar::Vec e(1, 1, 0);
407 
408  const float tolerance = 0.4;
409 
410  const int range_overshoot = range_ + local_range_ + longcut_range_ + search_range_;
411  const auto validate = [this, s, e, tolerance, range_overshoot](const int obstacle_x)
412  {
413  for (int y = 0; y < h_; y++)
414  {
415  for (int x = 0; x < w_; x++)
416  {
417  const Astar::Vec p(x, y, 0);
418  const float cost = dm_[p];
419  const float d = (p - e).norm();
420  const float d_from_start = (p - s).norm();
421  if ((x < s[0] || d_from_start < range_overshoot) && x < obstacle_x)
422  {
423  ASSERT_NEAR(ec_[0] * d, cost, tolerance) << xyStr(x, y);
424  }
425  else if (x > obstacle_x)
426  {
427  ASSERT_EQ(std::numeric_limits<float>::max(), cost) << xyStr(x, y);
428  }
429  }
430  }
431  };
432 
433  dm_.create(s, e);
434  {
435  SCOPED_TRACE("No obstacle");
436  validate(w_);
437  }
438 
439  for (int y = 0; y < h_; y++)
440  {
441  cm_rough_[Astar::Vec(5, y, 0)] = 100;
442  }
443  dm_.update(
444  s, e,
446  Vec3(5, 0, 0), Vec3(5, 2, 0)));
447  {
448  SCOPED_TRACE("Obstacle at x=5");
449  validate(5);
450  }
451  if (::testing::Test::HasFatalFailure())
452  {
453  debugOutput(dm_, cm_rough_, s, e);
454  return;
455  }
456 
457  cm_rough_.clear(0);
458 
459  dm_.update(
460  s, e,
462  Vec3(5, 0, 0), Vec3(5, 2, 0)));
463  {
464  SCOPED_TRACE("No obstacle");
465  validate(w_);
466  }
467  if (::testing::Test::HasFatalFailure())
468  {
469  debugOutput(dm_, cm_rough_, s, e);
470  return;
471  }
472 }
473 } // namespace planner_3d
474 } // namespace planner_cspace
475 
476 int main(int argc, char** argv)
477 {
478  testing::InitGoogleTest(&argc, argv);
479 
480  return RUN_ALL_TESTS();
481 }
d
void init(const GridAstarModel3D::Ptr model, const Params &p)
f
XmlRpcServer s
CyclicVecInt< DIM, NONCYCLIC > Vec
Definition: grid_astar.h:67
int main(int argc, char **argv)
TEST_P(DistanceMapTestWithParam, Update)
void validateDistance(const Astar::Vec p, const float d, const std::string &msg) const
TEST_F(DistanceMapTest, Create)
const Astar::Gridmap< float > & gridmap() const
Definition: distance_map.h:114
INSTANTIATE_TEST_CASE_P(UpdateWithTemporaryObstacles, DistanceMapTestWithParam, ::testing::Values(std::vector< Vec3 >({ Vec3(7, 7, 0), }), std::vector< Vec3 >({ Vec3(4, 2, 0), Vec3(7, 2, 0), }), std::vector< Vec3 >({ Vec3(3, 5, 0), }), std::vector< Vec3 >()))
void setParams(const CostCoeff &cc, const int num_cost_estim_task)
bool validate(const std::string &msg) const
void create(const Astar::Vec &s, const Astar::Vec &e)
void update(const Astar::Vec &s, const Astar::Vec &e, const Rect &rect)


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