00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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
00078
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
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
00104
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
00129
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
00142
00143
00144
00145 for(unsigned int i = 0; i <= (unsigned int)ceil(5.0); i++){
00146
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
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
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
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
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
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183 }
00184
00185
00186
00190 TEST(costmap, testInflation){
00191
00192 tf::TransformListener tf;
00193 LayeredCostmap layers("frame", false, false);
00194
00195
00196
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
00208 ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)20);
00209 ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)28);
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220 addObservation(olayer, 0, 0, 0.4);
00221 layers.updateMap(0,0,0);
00222
00223
00224 ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)51);
00225
00226
00227
00228 addObservation(olayer, 2, 0);
00229 layers.updateMap(0,0,0);
00230
00231
00232
00233
00234 ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)54);
00235
00236
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
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
00260
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
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
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
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
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
00301 addObservation(olayer, 5, 5, MAX_Z);
00302 layers.updateMap(0,0,0);
00303 printMap(*costmap);
00304
00305
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
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 }