module_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, 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/observation_buffer.h>
00037 #include <set>
00038 #include <gtest/gtest.h>
00039 #include <tf/transform_listener.h>
00040 
00041 using namespace costmap_2d;
00042 
00043 const unsigned char MAP_10_BY_10_CHAR[] = {
00044   0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
00045   0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
00046   0, 0, 0, 0, 0, 0, 0, 200, 200, 200,
00047   0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
00048   0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
00049   70, 70, 0, 0, 0, 0, 0, 0, 0, 0,
00050   0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
00051   0, 0, 0, 200, 200, 200, 0, 0, 0, 0,
00052   0, 0, 0, 0, 0, 0, 0, 255, 255, 255,
00053   0, 0, 0, 0, 0, 0, 0, 255, 255, 255
00054 };
00055 
00056 const unsigned char MAP_5_BY_5_CHAR[] = {
00057   0, 0, 0, 0, 0,
00058   0, 0, 0, 0, 0,
00059   0, 0, 0, 0, 0,
00060   0, 0, 0, 0, 0,
00061   0, 0, 0, 0, 0,
00062 };
00063 
00064 std::vector<unsigned char> MAP_5_BY_5;
00065 std::vector<unsigned char> MAP_10_BY_10;
00066 std::vector<unsigned char> EMPTY_10_BY_10;
00067 std::vector<unsigned char> EMPTY_100_BY_100;
00068 
00069 const unsigned int GRID_WIDTH(10);
00070 const unsigned int GRID_HEIGHT(10);
00071 const double RESOLUTION(1);
00072 const double WINDOW_LENGTH(10);
00073 const unsigned char THRESHOLD(100);
00074 const double MAX_Z(1.0);
00075 const double RAYTRACE_RANGE(20.0);
00076 const double OBSTACLE_RANGE(20.0);
00077 const double ROBOT_RADIUS(1.0);
00078 
00079 bool find(const std::vector<unsigned int>& l, unsigned int n){
00080   for(std::vector<unsigned int>::const_iterator it = l.begin(); it != l.end(); ++it){
00081     if(*it == n)
00082       return true;
00083   }
00084 
00085   return false;
00086 }
00087 
00091 TEST(costmap, testResetForStaticMap){
00092   // Define a static map with a large object in the center
00093   std::vector<unsigned char> staticMap;
00094   for(unsigned int i=0; i<10; i++){
00095     for(unsigned int j=0; j<10; j++){
00096       staticMap.push_back(costmap_2d::LETHAL_OBSTACLE);
00097     }
00098   }
00099 
00100   // Allocate the cost map, with a inflation to 3 cells all around
00101   Costmap2D map(10, 10, RESOLUTION, 0.0, 0.0, 3, 3, 3, OBSTACLE_RANGE, MAX_Z, RAYTRACE_RANGE, 25, staticMap, THRESHOLD);
00102 
00103   // Populate the cost map with a wall around the perimeter. Free space should clear out the room.
00104   pcl::PointCloud<pcl::PointXYZ> cloud;
00105   cloud.points.resize(40);
00106 
00107   // Left wall
00108   unsigned int ind = 0;
00109   for (unsigned int i = 0; i < 10; i++){
00110     // Left
00111     cloud.points[ind].x = 0;
00112     cloud.points[ind].y = i;
00113     cloud.points[ind].z = MAX_Z;
00114     ind++;
00115 
00116     // Top
00117     cloud.points[ind].x = i;
00118     cloud.points[ind].y = 0;
00119     cloud.points[ind].z = MAX_Z;
00120     ind++;
00121 
00122     // Right
00123     cloud.points[ind].x = 9;
00124     cloud.points[ind].y = i;
00125     cloud.points[ind].z = MAX_Z;
00126     ind++;
00127 
00128     // Bottom
00129     cloud.points[ind].x = i;
00130     cloud.points[ind].y = 9;
00131     cloud.points[ind].z = MAX_Z;
00132     ind++;
00133   }
00134 
00135   double wx = 5.0, wy = 5.0;
00136   geometry_msgs::Point p;
00137   p.x = wx;
00138   p.y = wy;
00139   p.z = MAX_Z;
00140   Observation obs(p, cloud, OBSTACLE_RANGE, RAYTRACE_RANGE);
00141   std::vector<Observation> obsBuf;
00142   obsBuf.push_back(obs);
00143 
00144   // Update the cost map for this observation
00145   map.updateWorld(wx, wy, obsBuf, obsBuf);
00146 
00147   // Verify that we now have only 36 cells with lethal cost, thus provong that we have correctly cleared
00148   // free space
00149   int hitCount = 0;
00150   for(unsigned int i=0; i < 10; ++i){
00151     for(unsigned int j=0; j < 10; ++j){
00152       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00153         hitCount++;
00154       }
00155     }
00156   }
00157   ASSERT_EQ(hitCount, 36);
00158 
00159   // Veriy that we have 64 non-leathal
00160   hitCount = 0;
00161   for(unsigned int i=0; i < 10; ++i){
00162     for(unsigned int j=0; j < 10; ++j){
00163       if(map.getCost(i, j) != costmap_2d::LETHAL_OBSTACLE)
00164         hitCount++;
00165     }
00166   }
00167   ASSERT_EQ(hitCount, 64);
00168 
00169   // Now if we reset the cost map, we should have our map go back to being completely occupied
00170   map.resetMapOutsideWindow(wx, wy, 0.0, 0.0);
00171 
00172   //We should now go back to everything being occupied
00173   hitCount = 0;
00174   for(unsigned int i=0; i < 10; ++i){
00175     for(unsigned int j=0; j < 10; ++j){
00176       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE)
00177         hitCount++;
00178     }
00179   }
00180   ASSERT_EQ(hitCount, 100);
00181 
00182 }
00183 
00187 TEST(costmap, testCostFunctionCorrectness){
00188   Costmap2D map(100, 100, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS * 5.0, ROBOT_RADIUS * 8.0, ROBOT_RADIUS * 10.5, 
00189       100.0, MAX_Z, 100.0, 25, EMPTY_100_BY_100, THRESHOLD);
00190 
00191   // Verify that the circumscribed cost lower bound is as expected: based on the cost function.
00192   unsigned char c = map.computeCost((ROBOT_RADIUS * 8.0 / RESOLUTION));
00193   ASSERT_EQ(map.getCircumscribedCost(), c);
00194 
00195   // Add a point in the center
00196   pcl::PointCloud<pcl::PointXYZ> cloud;
00197   cloud.points.resize(1);
00198   cloud.points[0].x = 50;
00199   cloud.points[0].y = 50;
00200   cloud.points[0].z = MAX_Z;
00201 
00202   geometry_msgs::Point p;
00203   p.x = 0.0;
00204   p.y = 0.0;
00205   p.z = MAX_Z;
00206 
00207   Observation obs(p, cloud, 100.0, 100.0);
00208   std::vector<Observation> obsBuf;
00209   obsBuf.push_back(obs);
00210 
00211   map.updateWorld(0, 0, obsBuf, obsBuf);
00212 
00213   for(unsigned int i = 0; i <= (unsigned int)ceil(ROBOT_RADIUS * 5.0); i++){
00214     // To the right
00215     ASSERT_EQ(map.getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00216     ASSERT_EQ(map.getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00217     // To the left
00218     ASSERT_EQ(map.getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00219     ASSERT_EQ(map.getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00220     // Down
00221     ASSERT_EQ(map.getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00222     ASSERT_EQ(map.getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00223     // Up
00224     ASSERT_EQ(map.getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00225     ASSERT_EQ(map.getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00226   }
00227 
00228   // Verify the normalized cost attenuates as expected
00229   for(unsigned int i = (unsigned int)(ceil(ROBOT_RADIUS * 5.0) + 1); i <= (unsigned int)ceil(ROBOT_RADIUS * 10.5); i++){
00230     unsigned char expectedValue = map.computeCost(i / RESOLUTION);
00231     ASSERT_EQ(map.getCost(50 + i, 50), expectedValue);
00232   }
00233 
00234   // Update with no hits. Should clear (revert to the static map
00235   map.resetMapOutsideWindow(0, 0, 0.0, 0.0);
00236   cloud.points.resize(0);
00237 
00238   p.x = 0.0;
00239   p.y = 0.0;
00240   p.z = MAX_Z;
00241 
00242   Observation obs2(p, cloud, 100.0, 100.0);
00243   std::vector<Observation> obsBuf2;
00244   obsBuf2.push_back(obs2);
00245 
00246   map.updateWorld(0, 0, obsBuf2, obsBuf2);
00247 
00248   for(unsigned int i = 0; i < 100; i++)
00249     for(unsigned int j = 0; j < 100; j++)
00250       ASSERT_EQ(map.getCost(i, j), costmap_2d::FREE_SPACE);
00251 }
00252 
00256 TEST(costmap, testWaveInterference){
00257   // Start with an empty map
00258   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS * 2, ROBOT_RADIUS * 3.01,
00259       10.0, MAX_Z * 2, 10.0, 1, EMPTY_10_BY_10, THRESHOLD);
00260 
00261   // Lay out 3 obstacles in a line - along the diagonal, separated by a cell.
00262   pcl::PointCloud<pcl::PointXYZ> cloud;
00263   cloud.points.resize(3);
00264   cloud.points[0].x = 3;
00265   cloud.points[0].y = 3;
00266   cloud.points[0].z = MAX_Z;
00267   cloud.points[1].x = 5;
00268   cloud.points[1].y = 5;
00269   cloud.points[1].z = MAX_Z;
00270   cloud.points[2].x = 7;
00271   cloud.points[2].y = 7;
00272   cloud.points[2].z = MAX_Z;
00273 
00274   geometry_msgs::Point p;
00275   p.x = 0.0;
00276   p.y = 0.0;
00277   p.z = MAX_Z;
00278 
00279   Observation obs(p, cloud, 100.0, 100.0);
00280   std::vector<Observation> obsBuf;
00281   obsBuf.push_back(obs);
00282 
00283   map.updateWorld(0, 0, obsBuf, obsBuf);
00284 
00285   int update_count = 0;
00286 
00287   // Expect to see a union of obstacles
00288   for(unsigned int i = 0; i < 10; ++i){
00289     for(unsigned int j = 0; j < 10; ++j){
00290       if(map.getCost(i, j) != costmap_2d::FREE_SPACE){
00291         update_count++;
00292       }
00293     }
00294   }
00295 
00296   ASSERT_EQ(update_count, 79);
00297 }
00298 
00300 TEST(costmap, testWindowCopy){
00301   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
00302       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00303 
00304   /*
00305   for(unsigned int i = 0; i < 10; ++i){
00306     for(unsigned int j = 0; j < 10; ++j){
00307       printf("%3d ", map.getCost(i, j));
00308     }
00309     printf("\n");
00310   }
00311   printf("\n");
00312   */
00313 
00314   Costmap2D windowCopy;
00315 
00316   //first test that if we try to make a window that is too big, things fail
00317   windowCopy.copyCostmapWindow(map, 2.0, 2.0, 6.0, 12.0);
00318   ASSERT_EQ(windowCopy.getSizeInCellsX(), (unsigned int)0);
00319   ASSERT_EQ(windowCopy.getSizeInCellsY(), (unsigned int)0);
00320 
00321   //Next, test that trying to make a map window itself fails
00322   map.copyCostmapWindow(map, 2.0, 2.0, 6.0, 6.0);
00323   ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)10);
00324   ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)10);
00325 
00326   //Next, test that legal input generates the result that we expect
00327   windowCopy.copyCostmapWindow(map, 2.0, 2.0, 6.0, 6.0);
00328   ASSERT_EQ(windowCopy.getSizeInCellsX(), (unsigned int)6);
00329   ASSERT_EQ(windowCopy.getSizeInCellsY(), (unsigned int)6);
00330 
00331   //check that we actually get the windo that we expect
00332   for(unsigned int i = 0; i < windowCopy.getSizeInCellsX(); ++i){
00333     for(unsigned int j = 0; j < windowCopy.getSizeInCellsY(); ++j){
00334       ASSERT_EQ(windowCopy.getCost(i, j), map.getCost(i + 2, j + 2));
00335       //printf("%3d ", windowCopy.getCost(i, j));
00336     }
00337     //printf("\n");
00338   }
00339 
00340 }
00341 
00342 //test for updating costmaps with static data
00343 TEST(costmap, testFullyContainedStaticMapUpdate){
00344   Costmap2D map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
00345       10.0, MAX_Z, 10.0, 25, MAP_5_BY_5, THRESHOLD);
00346 
00347   Costmap2D static_map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
00348       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00349 
00350   map.updateStaticMapWindow(0, 0, 10, 10, MAP_10_BY_10);
00351 
00352   for(unsigned int i = 0; i < map.getSizeInCellsX(); ++i){
00353     for(unsigned int j = 0; j < map.getSizeInCellsY(); ++j){
00354       ASSERT_EQ(map.getCost(i, j), static_map.getCost(i, j));
00355     }
00356   }
00357 }
00358 
00359 TEST(costmap, testOverlapStaticMapUpdate){
00360   Costmap2D map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
00361       10.0, MAX_Z, 10.0, 25, MAP_5_BY_5, THRESHOLD);
00362 
00363   Costmap2D static_map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
00364       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00365 
00366   map.updateStaticMapWindow(-10, -10, 10, 10, MAP_10_BY_10);
00367 
00368   ASSERT_FLOAT_EQ(map.getOriginX(), -10);
00369   ASSERT_FLOAT_EQ(map.getOriginX(), -10);
00370   ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)15);
00371   ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)15);
00372   for(unsigned int i = 0; i < 10; ++i){
00373     for(unsigned int j = 0; j < 10; ++j){
00374       ASSERT_EQ(map.getCost(i, j), static_map.getCost(i, j));
00375     }
00376   }
00377 
00378   std::vector<unsigned char> blank(100);
00379 
00380   //check to make sure that inflation on updates are being done correctly
00381   map.updateStaticMapWindow(-10, -10, 10, 10, blank);
00382 
00383   for(unsigned int i = 0; i < map.getSizeInCellsX(); ++i){
00384     for(unsigned int j = 0; j < map.getSizeInCellsY(); ++j){
00385       ASSERT_EQ(map.getCost(i, j), 0);
00386     }
00387   }
00388 
00389   std::vector<unsigned char> fully_contained(25);
00390   fully_contained[0] = 254;
00391   fully_contained[4] = 254;
00392   fully_contained[5] = 254;
00393   fully_contained[9] = 254;
00394 
00395   Costmap2D small_static_map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
00396       10.0, MAX_Z, 10.0, 25, fully_contained, THRESHOLD);
00397 
00398   map.updateStaticMapWindow(0, 0, 5, 5, fully_contained);
00399 
00400   ASSERT_FLOAT_EQ(map.getOriginX(), -10);
00401   ASSERT_FLOAT_EQ(map.getOriginX(), -10);
00402   ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)15);
00403   ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)15);
00404   for(unsigned int j = 0; j < 5; ++j){
00405     for(unsigned int i = 0; i < 5; ++i){
00406       ASSERT_EQ(map.getCost(i + 10, j + 10), small_static_map.getCost(i, j));
00407     }
00408   }
00409 
00410 }
00411 
00415 TEST(costmap, testRaytracing){
00416   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00417       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00418 
00419   // Add a point cloud, should not affect the map
00420   pcl::PointCloud<pcl::PointXYZ> cloud;
00421   cloud.points.resize(1);
00422   cloud.points[0].x = 0;
00423   cloud.points[0].y = 0;
00424   cloud.points[0].z = MAX_Z;
00425 
00426   geometry_msgs::Point p;
00427   p.x = 0.0;
00428   p.y = 0.0;
00429   p.z = MAX_Z;
00430 
00431   Observation obs(p, cloud, 100.0, 100.0);
00432   std::vector<Observation> obsBuf;
00433   obsBuf.push_back(obs);
00434 
00435   map.updateWorld(0, 0, obsBuf, obsBuf);
00436 
00437   int lethal_count = 0;
00438 
00439   for(unsigned int i = 0; i < 10; ++i){
00440     for(unsigned int j = 0; j < 10; ++j){
00441       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00442         lethal_count++;
00443       }
00444     }
00445   }
00446 
00447   //we expect just one obstacle to be added
00448   ASSERT_EQ(lethal_count, 21);
00449 }
00450 
00451 unsigned int worldToIndex(Costmap2D& map, double wx, double wy){
00452   unsigned int mx, my;
00453   map.worldToMap(wx, wy, mx, my);
00454   return map.getIndex(mx, my);
00455 }
00456 
00457 void indexToWorld(Costmap2D& map, unsigned int index, double& wx, double& wy){
00458   unsigned int mx, my;
00459   map.indexToCells(index, mx, my);
00460   map.mapToWorld(mx, my, wx, wy);
00461 }
00462 
00463 TEST(costmap, testStaticMap){
00464   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00465       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00466 
00467   ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)10);
00468   ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)10);
00469 
00470   // Verify that obstacles correctly identified from the static map.
00471   std::vector<unsigned int> occupiedCells;
00472 
00473   for(unsigned int i = 0; i < 10; ++i){
00474     for(unsigned int j = 0; j < 10; ++j){
00475       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00476         occupiedCells.push_back(map.getIndex(i, j));
00477       }
00478     }
00479   }
00480 
00481   ASSERT_EQ(occupiedCells.size(), (unsigned int)20);
00482 
00483   // Iterate over all id's and verify that they are present according to their
00484   for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
00485     unsigned int ind = *it;
00486     unsigned int x, y;
00487     map.indexToCells(ind, x, y);
00488     ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
00489     ASSERT_EQ(MAP_10_BY_10[ind] >= 100, true);
00490     ASSERT_EQ(map.getCost(x, y) >= 100, true);
00491   }
00492 
00493   // Block of 200
00494   ASSERT_EQ(find(occupiedCells, map.getIndex(7, 2)), true);
00495   ASSERT_EQ(find(occupiedCells, map.getIndex(8, 2)), true);
00496   ASSERT_EQ(find(occupiedCells, map.getIndex(9, 2)), true);
00497   ASSERT_EQ(find(occupiedCells, map.getIndex(7, 3)), true);
00498   ASSERT_EQ(find(occupiedCells, map.getIndex(8, 3)), true);
00499   ASSERT_EQ(find(occupiedCells, map.getIndex(9, 3)), true);
00500   ASSERT_EQ(find(occupiedCells, map.getIndex(7, 4)), true);
00501   ASSERT_EQ(find(occupiedCells, map.getIndex(8, 4)), true);
00502   ASSERT_EQ(find(occupiedCells, map.getIndex(9, 4)), true);
00503 
00504   // Block of 100
00505   ASSERT_EQ(find(occupiedCells, map.getIndex(4, 3)), true);
00506   ASSERT_EQ(find(occupiedCells, map.getIndex(4, 4)), true);
00507 
00508   // Block of 200
00509   ASSERT_EQ(find(occupiedCells, map.getIndex(3, 7)), true);
00510   ASSERT_EQ(find(occupiedCells, map.getIndex(4, 7)), true);
00511   ASSERT_EQ(find(occupiedCells, map.getIndex(5, 7)), true);
00512 
00513 
00514   // Verify Coordinate Transformations, ROW MAJOR ORDER
00515   ASSERT_EQ(worldToIndex(map, 0.0, 0.0), (unsigned int)0);
00516   ASSERT_EQ(worldToIndex(map, 0.0, 0.99), (unsigned int)0);
00517   ASSERT_EQ(worldToIndex(map, 0.0, 1.0), (unsigned int)10);
00518   ASSERT_EQ(worldToIndex(map, 1.0, 0.99), (unsigned int)1);
00519   ASSERT_EQ(worldToIndex(map, 9.99, 9.99), (unsigned int)99);
00520   ASSERT_EQ(worldToIndex(map, 8.2, 3.4), (unsigned int)38);
00521 
00522   // Ensure we hit the middle of the cell for world co-ordinates
00523   double wx, wy;
00524   indexToWorld(map, 99, wx, wy);
00525   ASSERT_EQ(wx, 9.5);
00526   ASSERT_EQ(wy, 9.5);
00527 }
00528 
00529 
00534 TEST(costmap, testDynamicObstacles){
00535   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00536       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00537 
00538   // Add a point cloud and verify its insertion. There should be only one new one
00539   pcl::PointCloud<pcl::PointXYZ> cloud;
00540   cloud.points.resize(3);
00541   cloud.points[0].x = 0;
00542   cloud.points[0].y = 0;
00543   cloud.points[1].x = 0;
00544   cloud.points[1].y = 0;
00545   cloud.points[2].x = 0;
00546   cloud.points[2].y = 0;
00547 
00548   geometry_msgs::Point p;
00549   p.x = 0.0;
00550   p.y = 0.0;
00551   p.z = MAX_Z;
00552 
00553   Observation obs(p, cloud, 100.0, 100.0);
00554   std::vector<Observation> obsBuf;
00555   obsBuf.push_back(obs);
00556 
00557   map.updateWorld(0, 0, obsBuf, obsBuf);
00558 
00559   std::vector<unsigned int> ids;
00560 
00561   for(unsigned int i = 0; i < 10; ++i){
00562     for(unsigned int j = 0; j < 10; ++j){
00563       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00564         ids.push_back(map.getIndex(i, j));
00565       }
00566     }
00567   }
00568 
00569   // Should now have 1 insertion and no deletions
00570   ASSERT_EQ(ids.size(), (unsigned int)21);
00571 
00572   // Repeating the call - we should see no insertions or deletions
00573   map.updateWorld(0, 0, obsBuf, obsBuf);
00574   ASSERT_EQ(ids.size(), (unsigned int)21);
00575 }
00576 
00580 TEST(costmap, testMultipleAdditions){
00581   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00582       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00583 
00584   // A point cloud with one point that falls within an existing obstacle
00585   pcl::PointCloud<pcl::PointXYZ> cloud;
00586   cloud.points.resize(1);
00587   cloud.points[0].x = 7;
00588   cloud.points[0].y = 2;
00589 
00590   geometry_msgs::Point p;
00591   p.x = 0.0;
00592   p.y = 0.0;
00593   p.z = MAX_Z;
00594 
00595   Observation obs(p, cloud, 100.0, 100.0);
00596   std::vector<Observation> obsBuf;
00597   obsBuf.push_back(obs);
00598 
00599   map.updateWorld(0, 0, obsBuf, obsBuf);
00600 
00601   std::vector<unsigned int> ids;
00602 
00603   for(unsigned int i = 0; i < 10; ++i){
00604     for(unsigned int j = 0; j < 10; ++j){
00605       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00606         ids.push_back(map.getIndex(i, j));
00607       }
00608     }
00609   }
00610 
00611   ASSERT_EQ(ids.size(), (unsigned int)20);
00612 }
00613 
00617 TEST(costmap, testZThreshold){
00618   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00619       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00620 
00621   // A point cloud with 2 points falling in a cell with a non-lethal cost
00622   pcl::PointCloud<pcl::PointXYZ> c0;
00623   c0.points.resize(2);
00624   c0.points[0].x = 0;
00625   c0.points[0].y = 5;
00626   c0.points[0].z = 0.4;
00627   c0.points[1].x = 1;
00628   c0.points[1].y = 5;
00629   c0.points[1].z = 1.2;
00630 
00631   geometry_msgs::Point p;
00632   p.x = 0.0;
00633   p.y = 0.0;
00634   p.z = MAX_Z;
00635 
00636   Observation obs(p, c0, 100.0, 100.0);
00637   std::vector<Observation> obsBuf;
00638   obsBuf.push_back(obs);
00639 
00640   map.updateWorld(0, 0, obsBuf, obsBuf);
00641 
00642   std::vector<unsigned int> ids;
00643 
00644   for(unsigned int i = 0; i < 10; ++i){
00645     for(unsigned int j = 0; j < 10; ++j){
00646       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00647         ids.push_back(map.getIndex(i, j));
00648       }
00649     }
00650   }
00651 
00652   ASSERT_EQ(ids.size(), (unsigned int)21);
00653 }
00654 
00659 TEST(costmap, testInflation){
00660   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00661       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00662 
00663   // Verify that obstacles correctly identified
00664   std::vector<unsigned int> occupiedCells;
00665 
00666   for(unsigned int i = 0; i < 10; ++i){
00667     for(unsigned int j = 0; j < 10; ++j){
00668       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00669         occupiedCells.push_back(map.getIndex(i, j));
00670       }
00671     }
00672   }
00673 
00674   // There should be no duplicates
00675   std::set<unsigned int> setOfCells;
00676   for(unsigned int i=0;i<occupiedCells.size(); i++)
00677     setOfCells.insert(i);
00678 
00679   ASSERT_EQ(setOfCells.size(), occupiedCells.size());
00680   ASSERT_EQ(setOfCells.size(), (unsigned int)48);
00681 
00682   // Iterate over all id's and verify they are obstacles
00683   for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
00684     unsigned int ind = *it;
00685     unsigned int x, y;
00686     map.indexToCells(ind, x, y);
00687     ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
00688     ASSERT_EQ(map.getCost(x, y) == costmap_2d::LETHAL_OBSTACLE || map.getCost(x, y) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
00689   }
00690 
00691   // Set an obstacle at the origin and observe insertions for it and its neighbors
00692   pcl::PointCloud<pcl::PointXYZ> c0;
00693   c0.points.resize(1);
00694   c0.points[0].x = 0;
00695   c0.points[0].y = 0;
00696   c0.points[0].z = 0.4;
00697 
00698   geometry_msgs::Point p;
00699   p.x = 0.0;
00700   p.y = 0.0;
00701   p.z = MAX_Z;
00702 
00703   Observation obs(p, c0, 100.0, 100.0);
00704   std::vector<Observation> obsBuf, empty;
00705   obsBuf.push_back(obs);
00706 
00707   map.updateWorld(0, 0, obsBuf, empty);
00708 
00709   occupiedCells.clear();
00710   for(unsigned int i = 0; i < 10; ++i){
00711     for(unsigned int j = 0; j < 10; ++j){
00712       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00713         occupiedCells.push_back(map.getIndex(i, j));
00714       }
00715     }
00716   }
00717 
00718   // It and its 2 neighbors makes 3 obstacles
00719   ASSERT_EQ(occupiedCells.size(), (unsigned int)51);
00720 
00721   // @todo Rewrite 
00722   // Add an obstacle at <2,0> which will inflate and refresh to of the other inflated cells
00723   pcl::PointCloud<pcl::PointXYZ> c1;
00724   c1.points.resize(1);
00725   c1.points[0].x = 2;
00726   c1.points[0].y = 0;
00727   c1.points[0].z = 0.0;
00728 
00729   geometry_msgs::Point p1;
00730   p1.x = 0.0;
00731   p1.y = 0.0;
00732   p1.z = MAX_Z;
00733 
00734   Observation obs1(p1, c1, 100.0, 100.0);
00735   std::vector<Observation> obsBuf1;
00736   obsBuf1.push_back(obs1);
00737 
00738   map.updateWorld(0, 0, obsBuf1, empty);
00739 
00740   occupiedCells.clear();
00741   for(unsigned int i = 0; i < 10; ++i){
00742     for(unsigned int j = 0; j < 10; ++j){
00743       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00744         occupiedCells.push_back(map.getIndex(i, j));
00745       }
00746     }
00747   }
00748 
00749   // Now we expect insertions for it, and 2 more neighbors, but not all 5. Free space will propagate from
00750   // the origin to the target, clearing the point at <0, 0>, but not over-writing the inflation of the obstacle
00751   // at <0, 1>
00752   ASSERT_EQ(occupiedCells.size(), (unsigned int)54);
00753 
00754 
00755   // Add an obstacle at <1, 9>. This will inflate obstacles around it
00756   pcl::PointCloud<pcl::PointXYZ> c2;
00757   c2.points.resize(1);
00758   c2.points[0].x = 1;
00759   c2.points[0].y = 9;
00760   c2.points[0].z = 0.0;
00761 
00762   geometry_msgs::Point p2;
00763   p2.x = 0.0;
00764   p2.y = 0.0;
00765   p2.z = MAX_Z;
00766 
00767   Observation obs2(p2, c2, 100.0, 100.0);
00768   std::vector<Observation> obsBuf2;
00769   obsBuf2.push_back(obs2);
00770 
00771   map.updateWorld(0, 0, obsBuf2, empty);
00772 
00773   ASSERT_EQ(map.getCost(1, 9), costmap_2d::LETHAL_OBSTACLE);
00774   ASSERT_EQ(map.getCost(0, 9), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
00775   ASSERT_EQ(map.getCost(2, 9), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
00776 
00777   // Add an obstacle and verify that it over-writes its inflated status
00778   pcl::PointCloud<pcl::PointXYZ> c3;
00779   c3.points.resize(1);
00780   c3.points[0].x = 0;
00781   c3.points[0].y = 9;
00782   c3.points[0].z = 0.0;
00783 
00784   geometry_msgs::Point p3;
00785   p3.x = 0.0;
00786   p3.y = 0.0;
00787   p3.z = MAX_Z;
00788 
00789   Observation obs3(p3, c3, 100.0, 100.0);
00790   std::vector<Observation> obsBuf3;
00791   obsBuf3.push_back(obs3);
00792 
00793   map.updateWorld(0, 0, obsBuf3, empty);
00794 
00795   ASSERT_EQ(map.getCost(0, 9), costmap_2d::LETHAL_OBSTACLE);
00796 }
00797 
00801 TEST(costmap, testInflation2){
00802   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00803       10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
00804 
00805   // Creat a small L-Shape all at once
00806   pcl::PointCloud<pcl::PointXYZ> c0;
00807   c0.points.resize(3);
00808   c0.points[0].x = 1;
00809   c0.points[0].y = 1;
00810   c0.points[0].z = MAX_Z;
00811   c0.points[1].x = 1;
00812   c0.points[1].y = 2;
00813   c0.points[1].z = MAX_Z;
00814   c0.points[2].x = 2;
00815   c0.points[2].y = 2;
00816   c0.points[2].z = MAX_Z;
00817 
00818   geometry_msgs::Point p;
00819   p.x = 0.0;
00820   p.y = 0.0;
00821   p.z = MAX_Z;
00822 
00823   Observation obs(p, c0, 100.0, 100.0);
00824   std::vector<Observation> obsBuf;
00825   obsBuf.push_back(obs);
00826 
00827   map.updateWorld(0, 0, obsBuf, obsBuf);
00828 
00829   ASSERT_EQ(map.getCost(3, 2), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);  
00830   ASSERT_EQ(map.getCost(3, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
00831 }
00832 
00836 TEST(costmap, testInflation3){
00837   std::vector<unsigned char> mapData;
00838   for(unsigned int i=0; i< GRID_WIDTH; i++){
00839     for(unsigned int j = 0; j < GRID_HEIGHT; j++){
00840       mapData.push_back(0);
00841     }
00842   }
00843 
00844   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS * 2, ROBOT_RADIUS * 3, 
00845       10.0, MAX_Z, 10.0, 1, mapData, THRESHOLD);
00846 
00847   // There should be no occupied cells
00848   std::vector<unsigned int> ids;
00849 
00850   for(unsigned int i = 0; i < 10; ++i){
00851     for(unsigned int j = 0; j < 10; ++j){
00852       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00853         ids.push_back(map.getIndex(i, j));
00854       }
00855     }
00856   }
00857 
00858   ASSERT_EQ(ids.size(), (unsigned int)0);
00859 
00860   // Add an obstacle at 5,5
00861   pcl::PointCloud<pcl::PointXYZ> c0;
00862   c0.points.resize(1);
00863   c0.points[0].x = 5;
00864   c0.points[0].y = 5;
00865   c0.points[0].z = MAX_Z;
00866 
00867   geometry_msgs::Point p;
00868   p.x = 0.0;
00869   p.y = 0.0;
00870   p.z = MAX_Z;
00871 
00872   Observation obs(p, c0, 100.0, 100.0);
00873   std::vector<Observation> obsBuf;
00874   obsBuf.push_back(obs);
00875 
00876   map.updateWorld(0, 0, obsBuf, obsBuf);
00877 
00878   for(unsigned int i = 0; i < 10; ++i){
00879     for(unsigned int j = 0; j < 10; ++j){
00880       if(map.getCost(i, j) != costmap_2d::FREE_SPACE){
00881         ids.push_back(map.getIndex(i, j));
00882       }
00883     }
00884   }
00885 
00886   ASSERT_EQ(ids.size(), (unsigned int)29);
00887 
00888   ids.clear();
00889   for(unsigned int i = 0; i < 10; ++i){
00890     for(unsigned int j = 0; j < 10; ++j){
00891       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00892         ids.push_back(map.getIndex(i, j));
00893       }
00894     }
00895   }
00896 
00897   ASSERT_EQ(ids.size(), (unsigned int)5);
00898 
00899   // Update again - should see no change
00900   map.updateWorld(0, 0, obsBuf, obsBuf);
00901 
00902   ids.clear();
00903   for(unsigned int i = 0; i < 10; ++i){
00904     for(unsigned int j = 0; j < 10; ++j){
00905       if(map.getCost(i, j) != costmap_2d::FREE_SPACE){
00906         ids.push_back(map.getIndex(i, j));
00907       }
00908     }
00909   }
00910   
00911   ASSERT_EQ(ids.size(), (unsigned int)29);
00912 }
00913 
00918 TEST(costmap, testRaytracing2){
00919   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00920       100.0, MAX_Z, 100.0, 1, MAP_10_BY_10, THRESHOLD);
00921 
00922   // The sensor origin will be <0,0>. So if we add an obstacle at 9,9, we would expect cells
00923   // <0, 0> thru <8, 8> to be traced through
00924   pcl::PointCloud<pcl::PointXYZ> c0;
00925   c0.points.resize(1);
00926   c0.points[0].x = 9.5;
00927   c0.points[0].y = 9.5;
00928   c0.points[0].z = MAX_Z;
00929 
00930   geometry_msgs::Point p;
00931   p.x = 0.5;
00932   p.y = 0.5;
00933   p.z = MAX_Z;
00934 
00935   Observation obs(p, c0, 100.0, 100.0);
00936   std::vector<Observation> obsBuf;
00937   obsBuf.push_back(obs);
00938 
00939   std::vector<unsigned int> obstacles;
00940 
00941   for(unsigned int i = 0; i < 10; ++i){
00942     for(unsigned int j = 0; j < 10; ++j){
00943       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00944         obstacles.push_back(map.getIndex(i, j));
00945       }
00946     }
00947   }
00948 
00949   unsigned int obs_before = obstacles.size();
00950 
00951   map.updateWorld(0, 0, obsBuf, obsBuf);
00952 
00953   obstacles.clear();
00954   for(unsigned int i = 0; i < 10; ++i){
00955     for(unsigned int j = 0; j < 10; ++j){
00956       if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
00957         obstacles.push_back(map.getIndex(i, j));
00958       }
00959     }
00960   }
00961 
00962   //Two obstacles shoulb be removed from the map by raytracing
00963   ASSERT_EQ(obstacles.size(), obs_before - 2);
00964 
00965 
00966   // many cells will have been switched to free space along the diagonal except
00967   // for those inflated in the update.. tests that inflation happens properly
00968   // after raytracing
00969   unsigned char test[10]= {0, 0, 0, 253, 253, 0, 0, 253, 253, 254};
00970   for(unsigned int i=0; i < 10; i++)
00971     ASSERT_EQ(map.getCost(i, i), test[i]);
00972 }
00973 
00980 TEST(costmap, testTrickyPropagation){
00981   const unsigned char MAP_HALL_CHAR[10 * 10] = {
00982     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
00983     254, 0, 0,   0,   0, 0,   0, 0, 0, 0,
00984     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
00985     0,   0, 0,   254, 0, 0,   0, 0, 0, 0,
00986     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
00987     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
00988     0,   0, 0,   0,   0, 254, 0, 0, 0, 0,
00989     0,   0, 0,   0,   0, 254, 0, 0, 0, 0,
00990     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
00991     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
00992   };
00993   std::vector<unsigned char> MAP_HALL;
00994   for (int i = 0; i < 10 * 10; i++) {
00995     MAP_HALL.push_back(MAP_HALL_CHAR[i]);
00996   }
00997 
00998   Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS, 
00999       100.0, MAX_Z, 100.0, 1, MAP_HALL, THRESHOLD);
01000 
01001 
01002   //Add a dynamic obstacle
01003   pcl::PointCloud<pcl::PointXYZ> c2;
01004   c2.points.resize(3);
01005   //Dynamic obstacle that raytaces.
01006   c2.points[0].x = 7.0;
01007   c2.points[0].y = 8.0;
01008   c2.points[0].z = 1.0;
01009   //Dynamic obstacle that should not be raytraced the
01010   //first update, but should on the second.
01011   c2.points[1].x = 3.0;
01012   c2.points[1].y = 4.0;
01013   c2.points[1].z = 1.0;
01014   //Dynamic obstacle that should not be erased.
01015   c2.points[2].x = 6.0;
01016   c2.points[2].y = 3.0;
01017   c2.points[2].z = 1.0;
01018 
01019   geometry_msgs::Point p2;
01020   p2.x = 0.5;
01021   p2.y = 0.5;
01022   p2.z = MAX_Z;
01023 
01024   Observation obs2(p2, c2, 100.0, 100.0);
01025   std::vector<Observation> obsBuf2;
01026   obsBuf2.push_back(obs2);
01027 
01028   map.updateWorld(0, 0, obsBuf2, obsBuf2);
01029 
01030   const unsigned char MAP_HALL_CHAR_TEST[10 * 10] = { 
01031     253, 254, 253,   0,   0,   0,   0,   0,   0,   0,
01032       0, 253,   0,   0,   0,   0,   0,   0,   0,   0,
01033       0,   0,   0,   0, 253,   0,   0,   0,   0,   0,
01034       0,   0,   0, 253, 254, 253,   0,   0,   0,   0,
01035       0,   0,   0,   0, 253,   0,   0, 253,   0,   0,
01036       0,   0,   0, 253,   0,   0, 253, 254, 253,   0,
01037       0,   0, 253, 254, 253,   0,   0, 253, 253,   0,
01038       0,   0,   0, 253,   0,   0,   0, 253, 254, 253,
01039       0,   0,   0,   0,   0,   0,   0,   0, 253,   0,
01040       0,   0,   0,   0,   0,   0,   0,   0,   0,   0,
01041   };
01042 
01043   
01044   for (int i = 0; i < 10 * 10; i++) {
01045     ASSERT_EQ(map.getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST[i]);
01046   }
01047 
01048   pcl::PointCloud<pcl::PointXYZ> c;
01049   c.points.resize(1);
01050   //Dynamic obstacle that raytaces the one at (3.0, 4.0).
01051   c.points[0].x = 4.0;
01052   c.points[0].y = 5.0;
01053   c.points[0].z = 1.0;
01054 
01055   geometry_msgs::Point p3;
01056   p3.x = 0.5;
01057   p3.y = 0.5;
01058   p3.z = MAX_Z;
01059 
01060   Observation obs3(p3, c, 100.0, 100.0);
01061   std::vector<Observation> obsBuf3;
01062   obsBuf3.push_back(obs3);
01063 
01064   map.updateWorld(0, 0, obsBuf3, obsBuf3);
01065 
01066   const unsigned char MAP_HALL_CHAR_TEST2[10 * 10] = { 
01067     253, 254, 253,   0,   0,   0,   0,   0,   0,   0,
01068       0, 253,   0,   0,   0,   0,   0,   0,   0,   0,
01069       0,   0,   0,   0,   0,   0,   0,   0,   0,   0,
01070       0,   0,   0,   0,   0, 253,   0,   0,   0,   0,
01071       0,   0,   0,   0, 253, 254, 253, 253,   0,   0,
01072       0,   0,   0, 253,   0, 253, 253, 254, 253,   0,
01073       0,   0, 253, 254, 253,   0,   0, 253, 253,   0,
01074       0,   0,   0, 253,   0,   0,   0, 253, 254, 253,
01075       0,   0,   0,   0,   0,   0,   0,   0, 253,   0,
01076       0,   0,   0,   0,   0,   0,   0,   0,   0,   0,
01077   };
01078 
01079   
01080   for (int i = 0; i < 10 * 10; i++) {
01081     ASSERT_EQ(map.getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST2[i]);
01082   }
01083 }
01084 
01085 
01086 
01087 int main(int argc, char** argv){
01088   for(unsigned int i = 0; i< GRID_WIDTH * GRID_HEIGHT; i++){
01089     EMPTY_10_BY_10.push_back(0);
01090     MAP_10_BY_10.push_back(MAP_10_BY_10_CHAR[i]);
01091   }
01092 
01093   for(unsigned int i = 0; i< 5 * 5; i++){
01094     MAP_5_BY_5.push_back(MAP_10_BY_10_CHAR[i]);
01095   }
01096 
01097   for(unsigned int i = 0; i< 100 * 100; i++)
01098     EMPTY_100_BY_100.push_back(0);
01099 
01100   testing::InitGoogleTest(&argc, argv);
01101   return RUN_ALL_TESTS();
01102 }


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:13:40