inflation_tests.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
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 Willow Garage, Inc. 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 
34 #include <map>
35 
36 #include <costmap_2d/costmap_2d.h>
42 #include <gtest/gtest.h>
43 #include <tf/transform_listener.h>
44 
45 using namespace costmap_2d;
46 using geometry_msgs::Point;
47 
48 std::vector<Point> setRadii(LayeredCostmap& layers, double length, double width, double inflation_radius)
49 {
50  std::vector<Point> polygon;
51  Point p;
52  p.x = width;
53  p.y = length;
54  polygon.push_back(p);
55  p.x = width;
56  p.y = -length;
57  polygon.push_back(p);
58  p.x = -width;
59  p.y = -length;
60  polygon.push_back(p);
61  p.x = -width;
62  p.y = length;
63  polygon.push_back(p);
64  layers.setFootprint(polygon);
65 
66  ros::NodeHandle nh;
67  nh.setParam("/inflation_tests/inflation/inflation_radius", inflation_radius);
68 
69  return polygon;
70 }
71 
72 // Test that a single point gets inflated properly
73 void validatePointInflation(unsigned int mx, unsigned int my, Costmap2D* costmap, InflationLayer* ilayer, double inflation_radius)
74 {
75  bool* seen = new bool[costmap->getSizeInCellsX() * costmap->getSizeInCellsY()];
76  memset(seen, false, costmap->getSizeInCellsX() * costmap->getSizeInCellsY() * sizeof(bool));
77  std::map<double, std::vector<CellData> > m;
78  CellData initial(costmap->getIndex(mx, my), mx, my, mx, my);
79  m[0].push_back(initial);
80  for (std::map<double, std::vector<CellData> >::iterator bin = m.begin(); bin != m.end(); ++bin)
81  {
82  for (int i = 0; i < bin->second.size(); ++i)
83  {
84  const CellData& cell = bin->second[i];
85  if (!seen[cell.index_])
86  {
87  seen[cell.index_] = true;
88  unsigned int dx = abs(cell.x_ - cell.src_x_);
89  unsigned int dy = abs(cell.y_ - cell.src_y_);
90  double dist = hypot(dx, dy);
91 
92  unsigned char expected_cost = ilayer->computeCost(dist);
93  ASSERT_TRUE(costmap->getCost(cell.x_, cell.y_) >= expected_cost);
94 
95  if (dist > inflation_radius)
96  {
97  continue;
98  }
99 
100  if (cell.x_ > 0)
101  {
102  CellData data(costmap->getIndex(cell.x_-1, cell.y_),
103  cell.x_-1, cell.y_, cell.src_x_, cell.src_y_);
104  m[dist].push_back(data);
105  }
106  if (cell.y_ > 0)
107  {
108  CellData data(costmap->getIndex(cell.x_, cell.y_-1),
109  cell.x_, cell.y_-1, cell.src_x_, cell.src_y_);
110  m[dist].push_back(data);
111  }
112  if (cell.x_ < costmap->getSizeInCellsX() - 1)
113  {
114  CellData data(costmap->getIndex(cell.x_+1, cell.y_),
115  cell.x_+1, cell.y_, cell.src_x_, cell.src_y_);
116  m[dist].push_back(data);
117  }
118  if (cell.y_ < costmap->getSizeInCellsY() - 1)
119  {
120  CellData data(costmap->getIndex(cell.x_, cell.y_+1),
121  cell.x_, cell.y_+1, cell.src_x_, cell.src_y_);
122  m[dist].push_back(data);
123  }
124  }
125  }
126  }
127  delete[] seen;
128 }
129 
130 TEST(costmap, testAdjacentToObstacleCanStillMove){
132  LayeredCostmap layers("frame", false, false);
133  layers.resizeMap(10, 10, 1, 0, 0);
134 
135  // Footprint with inscribed radius = 2.1
136  // circumscribed radius = 3.1
137  std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
138 
139  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
140  InflationLayer* ilayer = addInflationLayer(layers, tf);
141  layers.setFootprint(polygon);
142 
143  addObservation(olayer, 0, 0, MAX_Z);
144 
145  layers.updateMap(0,0,0);
146  Costmap2D* costmap = layers.getCostmap();
147  //printMap(*costmap);
148  EXPECT_EQ( LETHAL_OBSTACLE, costmap->getCost( 0, 0 ));
149  EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 0 ));
150  EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 2, 0 ));
151  EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 3, 0 ));
152  EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 2, 1 ));
153  EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 1 ));
154 }
155 
156 TEST(costmap, testInflationShouldNotCreateUnknowns){
158  LayeredCostmap layers("frame", false, false);
159  layers.resizeMap(10, 10, 1, 0, 0);
160 
161  // Footprint with inscribed radius = 2.1
162  // circumscribed radius = 3.1
163  std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
164 
165  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
166  InflationLayer* ilayer = addInflationLayer(layers, tf);
167  layers.setFootprint(polygon);
168 
169  addObservation(olayer, 0, 0, MAX_Z);
170 
171  layers.updateMap(0,0,0);
172  Costmap2D* costmap = layers.getCostmap();
173 
174  EXPECT_EQ( countValues(*costmap, NO_INFORMATION), 0 );
175 }
176 
177 
181 TEST(costmap, testCostFunctionCorrectness){
183  LayeredCostmap layers("frame", false, false);
184  layers.resizeMap(100, 100, 1, 0, 0);
185 
186  // Footprint with inscribed radius = 5.0
187  // circumscribed radius = 8.0
188  std::vector<Point> polygon = setRadii(layers, 5.0, 6.25, 10.5);
189 
190  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
191  InflationLayer* ilayer = addInflationLayer(layers, tf);
192  layers.setFootprint(polygon);
193 
194  addObservation(olayer, 50, 50, MAX_Z);
195 
196  layers.updateMap(0,0,0);
197  Costmap2D* map = layers.getCostmap();
198 
199  // Verify that the circumscribed cost lower bound is as expected: based on the cost function.
200  //unsigned char c = ilayer->computeCost(8.0);
201  //ASSERT_EQ(ilayer->getCircumscribedCost(), c);
202 
203  for(unsigned int i = 0; i <= (unsigned int)ceil(5.0); i++){
204  // To the right
205  ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
206  ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
207  // To the left
208  ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
209  ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
210  // Down
211  ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
212  ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
213  // Up
214  ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
215  ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
216  }
217 
218  // Verify the normalized cost attenuates as expected
219  for(unsigned int i = (unsigned int)(ceil(5.0) + 1); i <= (unsigned int)ceil(10.5); i++){
220  unsigned char expectedValue = ilayer->computeCost(i/1.0);
221  ASSERT_EQ(map->getCost(50 + i, 50), expectedValue);
222  }
223 
224  // Update with no hits. Should clear (revert to the static map
225  /*map->resetMapOutsideWindow(0, 0, 0.0, 0.0);
226  cloud.points.resize(0);
227 
228  p.x = 0.0;
229  p.y = 0.0;
230  p.z = MAX_Z;
231 
232  Observation obs2(p, cloud, 100.0, 100.0);
233  std::vector<Observation> obsBuf2;
234  obsBuf2.push_back(obs2);
235 
236  map->updateWorld(0, 0, obsBuf2, obsBuf2);
237 
238  for(unsigned int i = 0; i < 100; i++)
239  for(unsigned int j = 0; j < 100; j++)
240  ASSERT_EQ(map->getCost(i, j), costmap_2d::FREE_SPACE);*/
241 }
242 
249 TEST(costmap, testInflationOrderCorrectness){
251  LayeredCostmap layers("frame", false, false);
252  layers.resizeMap(10, 10, 1, 0, 0);
253 
254  // Footprint with inscribed radius = 2.1
255  // circumscribed radius = 3.1
256  const double inflation_radius = 4.1;
257  std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, inflation_radius);
258 
259  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
260  InflationLayer* ilayer = addInflationLayer(layers, tf);
261  layers.setFootprint(polygon);
262 
263  // Add two diagonal cells, they would induce problems under the
264  // previous implementations
265  addObservation(olayer, 4, 4, MAX_Z);
266  addObservation(olayer, 5, 5, MAX_Z);
267 
268  layers.updateMap(0, 0, 0);
269 
270  validatePointInflation(4, 4, layers.getCostmap(), ilayer, inflation_radius);
271  validatePointInflation(5, 5, layers.getCostmap(), ilayer, inflation_radius);
272 }
273 
277 TEST(costmap, testInflation){
278 
280  LayeredCostmap layers("frame", false, false);
281 
282  // Footprint with inscribed radius = 2.1
283  // circumscribed radius = 3.1
284  std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
285 
286  addStaticLayer(layers, tf);
287  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
288  InflationLayer* ilayer = addInflationLayer(layers, tf);
289  layers.setFootprint(polygon);
290 
291  Costmap2D* costmap = layers.getCostmap();
292 
293  layers.updateMap(0,0,0);
294  //printMap(*costmap);
295  ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)20);
296  ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)28);
297 
298  /*/ Iterate over all id's and verify they are obstacles
299  for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
300  unsigned int ind = *it;
301  unsigned int x, y;
302  map.indexToCells(ind, x, y);
303  ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
304  ASSERT_EQ(map.getCost(x, y) == costmap_2d::LETHAL_OBSTACLE || map.getCost(x, y) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
305  }*/
306 
307  addObservation(olayer, 0, 0, 0.4);
308  layers.updateMap(0,0,0);
309 
310  // It and its 2 neighbors makes 3 obstacles
311  ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)51);
312 
313  // @todo Rewrite
314  // Add an obstacle at <2,0> which will inflate and refresh to of the other inflated cells
315  addObservation(olayer, 2, 0);
316  layers.updateMap(0,0,0);
317 
318  // Now we expect insertions for it, and 2 more neighbors, but not all 5. Free space will propagate from
319  // the origin to the target, clearing the point at <0, 0>, but not over-writing the inflation of the obstacle
320  // at <0, 1>
321  ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)54);
322 
323  // Add an obstacle at <1, 9>. This will inflate obstacles around it
324  addObservation(olayer, 1, 9);
325  layers.updateMap(0,0,0);
326 
327  ASSERT_EQ(costmap->getCost(1, 9), LETHAL_OBSTACLE);
328  ASSERT_EQ(costmap->getCost(0, 9), INSCRIBED_INFLATED_OBSTACLE);
329  ASSERT_EQ(costmap->getCost(2, 9), INSCRIBED_INFLATED_OBSTACLE);
330 
331  // Add an obstacle and verify that it over-writes its inflated status
332  addObservation(olayer, 0, 9);
333  layers.updateMap(0,0,0);
334 
335  ASSERT_EQ(costmap->getCost(0, 9), LETHAL_OBSTACLE);
336 }
337 
341 TEST(costmap, testInflation2){
342 
344  LayeredCostmap layers("frame", false, false);
345 
346  // Footprint with inscribed radius = 2.1
347  // circumscribed radius = 3.1
348  std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
349 
350  addStaticLayer(layers, tf);
351  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
352  InflationLayer* ilayer = addInflationLayer(layers, tf);
353  layers.setFootprint(polygon);
354 
355  // Creat a small L-Shape all at once
356  addObservation(olayer, 1, 1, MAX_Z);
357  addObservation(olayer, 2, 1, MAX_Z);
358  addObservation(olayer, 2, 2, MAX_Z);
359  layers.updateMap(0,0,0);
360 
361  Costmap2D* costmap = layers.getCostmap();
362  //printMap(*costmap);
363  ASSERT_EQ(costmap->getCost(2, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
364  ASSERT_EQ(costmap->getCost(3, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
365 }
366 
370 TEST(costmap, testInflation3){
372  LayeredCostmap layers("frame", false, false);
373  layers.resizeMap(10, 10, 1, 0, 0);
374 
375  // 1 2 3
376  std::vector<Point> polygon = setRadii(layers, 1, 1.75, 3);
377 
378  ObstacleLayer* olayer = addObstacleLayer(layers, tf);
379  InflationLayer* ilayer = addInflationLayer(layers, tf);
380  layers.setFootprint(polygon);
381 
382  // There should be no occupied cells
383  Costmap2D* costmap = layers.getCostmap();
384  ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)0);
385  ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)0);
386  printMap(*costmap);
387  // Add an obstacle at 5,5
388  addObservation(olayer, 5, 5, MAX_Z);
389  layers.updateMap(0,0,0);
390  printMap(*costmap);
391 
392  // Test fails because updated cell value is 0
393  ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
394  ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
395  ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
396 
397  // Update again - should see no change
398  layers.updateMap(0,0,0);
399 
400  ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
401  ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
402  ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
403 }
404 
405 
406 int main(int argc, char** argv){
407  ros::init(argc, argv, "inflation_tests");
408  testing::InitGoogleTest(&argc, argv);
409  return RUN_ALL_TESTS();
410 }
unsigned int countValues(costmap_2d::Costmap2D &costmap, unsigned char value, bool equal=true)
const double MAX_Z(1.0)
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
costmap_2d::ObstacleLayer * addObstacleLayer(costmap_2d::LayeredCostmap &layers, tf::TransformListener &tf)
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
void addStaticLayer(costmap_2d::LayeredCostmap &layers, tf::TransformListener &tf)
static const unsigned char FREE_SPACE
Definition: cost_values.h:45
TFSIMD_FORCE_INLINE const tfScalar & x() const
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:192
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
Definition: cost_values.h:44
TFSIMD_FORCE_INLINE const tfScalar & y() const
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:431
TEST(costmap, testAdjacentToObstacleCanStillMove)
void validatePointInflation(unsigned int mx, unsigned int my, Costmap2D *costmap, InflationLayer *ilayer, double inflation_radius)
Storage for cell information used during obstacle inflation.
std::vector< Point > setRadii(LayeredCostmap &layers, double length, double width, double inflation_radius)
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:426
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:43
costmap_2d::InflationLayer * addInflationLayer(costmap_2d::LayeredCostmap &layers, tf::TransformListener &tf)
static const unsigned char NO_INFORMATION
Definition: cost_values.h:42
void addObservation(costmap_2d::ObstacleLayer *olayer, double x, double y, double z=0.0, double ox=0.0, double oy=0.0, double oz=MAX_Z)
virtual unsigned char computeCost(double distance) const
Given a distance, compute a cost.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:60
void printMap(costmap_2d::Costmap2D &costmap)
Instantiates different layer plugins and aggregates them into one score.
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.h:171


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:17