inflation_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00035 #include <costmap_2d/costmap_2d.h>
00036 #include <costmap_2d/layered_costmap.h>
00037 #include <costmap_2d/obstacle_layer.h>
00038 #include <costmap_2d/inflation_layer.h>
00039 #include <costmap_2d/observation_buffer.h>
00040 #include <costmap_2d/testing_helper.h>
00041 #include <set>
00042 #include <gtest/gtest.h>
00043 #include <tf/transform_listener.h>
00044 
00045 using namespace costmap_2d;
00046 using geometry_msgs::Point;
00047 
00048 std::vector<Point> setRadii(LayeredCostmap& layers, double length, double width, double inflation_radius)
00049 {
00050   std::vector<Point> polygon;
00051   Point p;
00052   p.x = width;
00053   p.y = length; 
00054   polygon.push_back(p);
00055   p.x = width;
00056   p.y = -length; 
00057   polygon.push_back(p);
00058   p.x = -width;
00059   p.y = -length; 
00060   polygon.push_back(p);
00061   p.x = -width;
00062   p.y = length; 
00063   polygon.push_back(p);
00064   layers.setFootprint(polygon);
00065 
00066   ros::NodeHandle nh;
00067   nh.setParam("/inflation_tests/inflation/inflation_radius", inflation_radius);
00068 
00069   return polygon;
00070 }
00071 
00072 TEST(costmap, testAdjacentToObstacleCanStillMove){
00073   tf::TransformListener tf;
00074   LayeredCostmap layers("frame", false, false);
00075   layers.resizeMap(10, 10, 1, 0, 0);
00076 
00077   // Footprint with inscribed radius = 2.1
00078   //               circumscribed radius = 3.1
00079   std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
00080 
00081   ObstacleLayer* olayer = addObstacleLayer(layers, tf);  
00082   InflationLayer* ilayer = addInflationLayer(layers, tf);
00083   layers.setFootprint(polygon);
00084 
00085   addObservation(olayer, 0, 0, MAX_Z);
00086 
00087   layers.updateMap(0,0,0);
00088   Costmap2D* costmap = layers.getCostmap();
00089   //printMap(*costmap);
00090   EXPECT_EQ( LETHAL_OBSTACLE, costmap->getCost( 0, 0 ));
00091   EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 0 ));
00092   EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 2, 0 ));
00093   EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 3, 0 ));
00094   EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 2, 1 ));
00095   EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 1 ));
00096 }
00097 
00098 TEST(costmap, testInflationShouldNotCreateUnknowns){
00099   tf::TransformListener tf;
00100   LayeredCostmap layers("frame", false, false);
00101   layers.resizeMap(10, 10, 1, 0, 0);
00102 
00103   // Footprint with inscribed radius = 2.1
00104   //               circumscribed radius = 3.1
00105   std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
00106 
00107   ObstacleLayer* olayer = addObstacleLayer(layers, tf);  
00108   InflationLayer* ilayer = addInflationLayer(layers, tf);
00109   layers.setFootprint(polygon);
00110 
00111   addObservation(olayer, 0, 0, MAX_Z);
00112 
00113   layers.updateMap(0,0,0);
00114   Costmap2D* costmap = layers.getCostmap();
00115 
00116   EXPECT_EQ( countValues(*costmap, NO_INFORMATION), 0 );
00117 }
00118 
00119 
00123 TEST(costmap, testCostFunctionCorrectness){
00124   tf::TransformListener tf;
00125   LayeredCostmap layers("frame", false, false);
00126   layers.resizeMap(100, 100, 1, 0, 0);
00127 
00128   // Footprint with inscribed radius = 5.0
00129   //               circumscribed radius = 8.0
00130   std::vector<Point> polygon = setRadii(layers, 5.0, 6.25, 10.5);
00131 
00132   ObstacleLayer* olayer = addObstacleLayer(layers, tf);  
00133   InflationLayer* ilayer = addInflationLayer(layers, tf);
00134   layers.setFootprint(polygon);
00135 
00136   addObservation(olayer, 50, 50, MAX_Z);
00137 
00138   layers.updateMap(0,0,0);
00139   Costmap2D* map = layers.getCostmap();
00140 
00141   // Verify that the circumscribed cost lower bound is as expected: based on the cost function.
00142   //unsigned char c = ilayer->computeCost(8.0);
00143   //ASSERT_EQ(ilayer->getCircumscribedCost(), c);
00144 
00145   for(unsigned int i = 0; i <= (unsigned int)ceil(5.0); i++){
00146     // To the right
00147     ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00148     ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00149     // To the left
00150     ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00151     ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00152     // Down
00153     ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00154     ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00155     // Up
00156     ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00157     ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00158   }
00159 
00160   // Verify the normalized cost attenuates as expected
00161   for(unsigned int i = (unsigned int)(ceil(5.0) + 1); i <= (unsigned int)ceil(10.5); i++){
00162     unsigned char expectedValue = ilayer->computeCost(i/1.0);
00163     ASSERT_EQ(map->getCost(50 + i, 50), expectedValue);
00164   }
00165 
00166   // Update with no hits. Should clear (revert to the static map
00167   /*map->resetMapOutsideWindow(0, 0, 0.0, 0.0);
00168   cloud.points.resize(0);
00169 
00170   p.x = 0.0;
00171   p.y = 0.0;
00172   p.z = MAX_Z;
00173 
00174   Observation obs2(p, cloud, 100.0, 100.0);
00175   std::vector<Observation> obsBuf2;
00176   obsBuf2.push_back(obs2);
00177 
00178   map->updateWorld(0, 0, obsBuf2, obsBuf2);
00179 
00180   for(unsigned int i = 0; i < 100; i++)
00181     for(unsigned int j = 0; j < 100; j++)
00182       ASSERT_EQ(map->getCost(i, j), costmap_2d::FREE_SPACE);*/
00183 }
00184 
00185 
00186 
00190 TEST(costmap, testInflation){
00191 
00192   tf::TransformListener tf;
00193   LayeredCostmap layers("frame", false, false);
00194 
00195   // Footprint with inscribed radius = 2.1
00196   //               circumscribed radius = 3.1
00197   std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
00198 
00199   addStaticLayer(layers, tf);
00200   ObstacleLayer* olayer = addObstacleLayer(layers, tf);  
00201   InflationLayer* ilayer = addInflationLayer(layers, tf);
00202   layers.setFootprint(polygon);
00203 
00204   Costmap2D* costmap = layers.getCostmap();
00205 
00206   layers.updateMap(0,0,0);
00207   //printMap(*costmap);
00208   ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE),             (unsigned int)20);
00209   ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)28);
00210 
00211   /*/ Iterate over all id's and verify they are obstacles
00212   for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
00213     unsigned int ind = *it;
00214     unsigned int x, y;
00215     map.indexToCells(ind, x, y);
00216     ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
00217     ASSERT_EQ(map.getCost(x, y) == costmap_2d::LETHAL_OBSTACLE || map.getCost(x, y) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00218   }*/
00219 
00220   addObservation(olayer, 0, 0, 0.4);
00221   layers.updateMap(0,0,0);
00222 
00223   // It and its 2 neighbors makes 3 obstacles
00224   ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)51);
00225 
00226   // @todo Rewrite 
00227   // Add an obstacle at <2,0> which will inflate and refresh to of the other inflated cells
00228   addObservation(olayer, 2, 0);
00229   layers.updateMap(0,0,0);
00230 
00231   // Now we expect insertions for it, and 2 more neighbors, but not all 5. Free space will propagate from
00232   // the origin to the target, clearing the point at <0, 0>, but not over-writing the inflation of the obstacle
00233   // at <0, 1>
00234   ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)54);
00235 
00236   // Add an obstacle at <1, 9>. This will inflate obstacles around it
00237   addObservation(olayer, 1, 9);
00238   layers.updateMap(0,0,0);
00239 
00240   ASSERT_EQ(costmap->getCost(1, 9), LETHAL_OBSTACLE);
00241   ASSERT_EQ(costmap->getCost(0, 9), INSCRIBED_INFLATED_OBSTACLE);
00242   ASSERT_EQ(costmap->getCost(2, 9), INSCRIBED_INFLATED_OBSTACLE);
00243 
00244   // Add an obstacle and verify that it over-writes its inflated status
00245   addObservation(olayer, 0, 9);
00246   layers.updateMap(0,0,0);
00247 
00248   ASSERT_EQ(costmap->getCost(0, 9), LETHAL_OBSTACLE);
00249 }
00250 
00254 TEST(costmap, testInflation2){
00255 
00256   tf::TransformListener tf;
00257   LayeredCostmap layers("frame", false, false);
00258 
00259   // Footprint with inscribed radius = 2.1
00260   //               circumscribed radius = 3.1
00261   std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
00262 
00263   addStaticLayer(layers, tf);
00264   ObstacleLayer* olayer = addObstacleLayer(layers, tf);  
00265   InflationLayer* ilayer = addInflationLayer(layers, tf);
00266   layers.setFootprint(polygon);
00267 
00268   // Creat a small L-Shape all at once
00269   addObservation(olayer, 1, 1, MAX_Z);
00270   addObservation(olayer, 2, 1, MAX_Z);
00271   addObservation(olayer, 2, 2, MAX_Z);
00272   layers.updateMap(0,0,0);
00273 
00274   Costmap2D* costmap = layers.getCostmap();
00275   //printMap(*costmap);
00276   ASSERT_EQ(costmap->getCost(2, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);  
00277   ASSERT_EQ(costmap->getCost(3, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
00278 }
00279 
00283 TEST(costmap, testInflation3){
00284   tf::TransformListener tf;
00285   LayeredCostmap layers("frame", false, false);
00286   layers.resizeMap(10, 10, 1, 0, 0);
00287 
00288   // 1 2 3
00289   std::vector<Point> polygon = setRadii(layers, 1, 1.75, 3);
00290 
00291   ObstacleLayer* olayer = addObstacleLayer(layers, tf);  
00292   InflationLayer* ilayer = addInflationLayer(layers, tf);
00293   layers.setFootprint(polygon);
00294 
00295   // There should be no occupied cells
00296   Costmap2D* costmap = layers.getCostmap();
00297   ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE),             (unsigned int)0);
00298   ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)0);
00299   printMap(*costmap);
00300   // Add an obstacle at 5,5
00301   addObservation(olayer, 5, 5, MAX_Z);
00302   layers.updateMap(0,0,0);
00303   printMap(*costmap);
00304 
00305   // Test fails because updated cell value is 0
00306   ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
00307   ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
00308   ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
00309 
00310   // Update again - should see no change
00311   layers.updateMap(0,0,0);
00312 
00313   ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
00314   ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
00315   ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
00316 }
00317 
00318 
00319 int main(int argc, char** argv){
00320   ros::init(argc, argv, "inflation_tests");
00321   testing::InitGoogleTest(&argc, argv);
00322   return RUN_ALL_TESTS();
00323 }


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55