38 #include <gtest/gtest.h>    43   0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    44   0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    45   0, 0, 0, 0, 0, 0, 0, 200, 200, 200,
    46   0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
    47   0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
    48   70, 70, 0, 0, 0, 0, 0, 0, 0, 0,
    49   0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    50   0, 0, 0, 200, 200, 200, 0, 0, 0, 0,
    51   0, 0, 0, 0, 0, 0, 0, 255, 255, 255,
    52   0, 0, 0, 0, 0, 0, 0, 255, 255, 255
    73 const double MAX_Z(1.0);
    78 bool find(
const std::vector<unsigned int>& l, 
unsigned int n){
    79   for(std::vector<unsigned int>::const_iterator it = l.begin(); it != l.end(); ++it){
    90 TEST(costmap, testResetForStaticMap){
    92   std::vector<unsigned char> staticMap;
    93   for(
unsigned int i=0; i<10; i++){
    94     for(
unsigned int j=0; j<10; j++){
   100   Costmap2D map(10, 10, 
RESOLUTION, 0.0, 0.0, 3, 3, 3, 
OBSTACLE_RANGE, 
MAX_Z, 
RAYTRACE_RANGE, 25, staticMap, 
THRESHOLD);
   103   pcl::PointCloud<pcl::PointXYZ> cloud;
   104   cloud.points.resize(40);
   107   unsigned int ind = 0;
   108   for (
unsigned int i = 0; i < 10; i++){
   110     cloud.points[ind].x = 0;
   111     cloud.points[ind].y = i;
   112     cloud.points[ind].z = 
MAX_Z;
   116     cloud.points[ind].x = i;
   117     cloud.points[ind].y = 0;
   118     cloud.points[ind].z = 
MAX_Z;
   122     cloud.points[ind].x = 9;
   123     cloud.points[ind].y = i;
   124     cloud.points[ind].z = 
MAX_Z;
   128     cloud.points[ind].x = i;
   129     cloud.points[ind].y = 9;
   130     cloud.points[ind].z = 
MAX_Z;
   134   double wx = 5.0, wy = 5.0;
   135   geometry_msgs::Point p;
   140   std::vector<Observation> obsBuf;
   141   obsBuf.push_back(obs);
   144   map.updateWorld(wx, wy, obsBuf, obsBuf);
   149   for(
unsigned int i=0; i < 10; ++i){
   150     for(
unsigned int j=0; j < 10; ++j){
   156   ASSERT_EQ(hitCount, 36);
   160   for(
unsigned int i=0; i < 10; ++i){
   161     for(
unsigned int j=0; j < 10; ++j){
   166   ASSERT_EQ(hitCount, 64);
   169   map.resetMapOutsideWindow(wx, wy, 0.0, 0.0);
   173   for(
unsigned int i=0; i < 10; ++i){
   174     for(
unsigned int j=0; j < 10; ++j){
   179   ASSERT_EQ(hitCount, 100);
   186 TEST(costmap, testCostFunctionCorrectness){
   192   ASSERT_EQ(map.getCircumscribedCost(), c);
   195   pcl::PointCloud<pcl::PointXYZ> cloud;
   196   cloud.points.resize(1);
   197   cloud.points[0].x = 50;
   198   cloud.points[0].y = 50;
   199   cloud.points[0].z = 
MAX_Z;
   201   geometry_msgs::Point p;
   207   std::vector<Observation> obsBuf;
   208   obsBuf.push_back(obs);
   210   map.updateWorld(0, 0, obsBuf, obsBuf);
   212   for(
unsigned int i = 0; i <= (
unsigned int)ceil(
ROBOT_RADIUS * 5.0); i++){
   228   for(
unsigned int i = (
unsigned int)(ceil(
ROBOT_RADIUS * 5.0) + 1); i <= (
unsigned int)ceil(
ROBOT_RADIUS * 10.5); i++){
   229     unsigned char expectedValue = map.computeCost(i / 
RESOLUTION);
   230     ASSERT_EQ(map.
getCost(50 + i, 50), expectedValue);
   234   map.resetMapOutsideWindow(0, 0, 0.0, 0.0);
   235   cloud.points.resize(0);
   242   std::vector<Observation> obsBuf2;
   243   obsBuf2.push_back(obs2);
   245   map.updateWorld(0, 0, obsBuf2, obsBuf2);
   247   for(
unsigned int i = 0; i < 100; i++)
   248     for(
unsigned int j = 0; j < 100; j++)
   260   default: 
return '0' + (
unsigned char) (10 * cost / 255);
   267 TEST(costmap, testWaveInterference){
   273   pcl::PointCloud<pcl::PointXYZ> cloud;
   274   cloud.points.resize(3);
   275   cloud.points[0].x = 3;
   276   cloud.points[0].y = 3;
   277   cloud.points[0].z = 
MAX_Z;
   278   cloud.points[1].x = 5;
   279   cloud.points[1].y = 5;
   280   cloud.points[1].z = 
MAX_Z;
   281   cloud.points[2].x = 7;
   282   cloud.points[2].y = 7;
   283   cloud.points[2].z = 
MAX_Z;
   285   geometry_msgs::Point p;
   291   std::vector<Observation> obsBuf;
   292   obsBuf.push_back(obs);
   294   map.updateWorld(0, 0, obsBuf, obsBuf);
   296   int update_count = 0;
   300   for(
unsigned int i = 0; i < 10; ++i){
   301     for(
unsigned int j = 0; j < 10; ++j){
   310   ASSERT_EQ(update_count, 79);
   357 TEST(costmap, testFullyContainedStaticMapUpdate){
   373 TEST(costmap, testOverlapStaticMapUpdate){
   380   map.updateStaticMapWindow(-10, -10, 10, 10, 
MAP_10_BY_10);
   386   for(
unsigned int i = 0; i < 10; ++i){
   387     for(
unsigned int j = 0; j < 10; ++j){
   392   std::vector<unsigned char> blank(100);
   395   map.updateStaticMapWindow(-10, -10, 10, 10, blank);
   399       ASSERT_EQ(map.
getCost(i, j), 0);
   403   std::vector<unsigned char> fully_contained(25);
   404   fully_contained[0] = 254;
   405   fully_contained[4] = 254;
   406   fully_contained[5] = 254;
   407   fully_contained[9] = 254;
   412   map.updateStaticMapWindow(0, 0, 5, 5, fully_contained);
   418   for(
unsigned int j = 0; j < 5; ++j){
   419     for(
unsigned int i = 0; i < 5; ++i){
   420       ASSERT_EQ(map.
getCost(i + 10, j + 10), small_static_map.
getCost(i, j));
   434   pcl::PointCloud<pcl::PointXYZ> cloud;
   435   cloud.points.resize(1);
   436   cloud.points[0].x = 0;
   437   cloud.points[0].y = 0;
   438   cloud.points[0].z = 
MAX_Z;
   440   geometry_msgs::Point p;
   446   std::vector<Observation> obsBuf;
   447   obsBuf.push_back(obs);
   449   map.updateWorld(0, 0, obsBuf, obsBuf);
   451   int lethal_count = 0;
   453   for(
unsigned int i = 0; i < 10; ++i){
   454     for(
unsigned int j = 0; j < 10; ++j){
   462   ASSERT_EQ(lethal_count, 21);
   465 TEST(costmap, testAdjacentToObstacleCanStillMove){
   468   pcl::PointCloud<pcl::PointXYZ> cloud;
   469   cloud.points.resize(1);
   470   cloud.points[0].x = 0;
   471   cloud.points[0].y = 0;
   472   cloud.points[0].z = 
MAX_Z;
   474   geometry_msgs::Point p;
   480   std::vector<Observation> obsBuf;
   481   obsBuf.push_back(obs);
   483   map.updateWorld(9, 9, obsBuf, obsBuf);
   493 TEST(costmap, testInflationShouldNotCreateUnknowns){
   496   pcl::PointCloud<pcl::PointXYZ> cloud;
   497   cloud.points.resize(1);
   498   cloud.points[0].x = 0;
   499   cloud.points[0].y = 0;
   500   cloud.points[0].z = 
MAX_Z;
   502   geometry_msgs::Point p;
   508   std::vector<Observation> obsBuf;
   509   obsBuf.push_back(obs);
   511   map.updateWorld(9, 9, obsBuf, obsBuf);
   513   int unknown_count = 0;
   515   for(
unsigned int i = 0; i < 10; ++i){
   516     for(
unsigned int j = 0; j < 10; ++j){
   522   EXPECT_EQ( 0, unknown_count );
   545   std::vector<unsigned int> occupiedCells;
   547   for(
unsigned int i = 0; i < 10; ++i){
   548     for(
unsigned int j = 0; j < 10; ++j){
   550         occupiedCells.push_back(map.
getIndex(i, j));
   555   ASSERT_EQ(occupiedCells.size(), (
unsigned int)20);
   558   for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
   559     unsigned int ind = *it;
   562     ASSERT_EQ(
find(occupiedCells, map.
getIndex(x, y)), 
true);
   564     ASSERT_EQ(map.
getCost(x, y) >= 100, 
true);
   568   ASSERT_EQ(
find(occupiedCells, map.
getIndex(7, 2)), 
true);
   569   ASSERT_EQ(
find(occupiedCells, map.
getIndex(8, 2)), 
true);
   570   ASSERT_EQ(
find(occupiedCells, map.
getIndex(9, 2)), 
true);
   571   ASSERT_EQ(
find(occupiedCells, map.
getIndex(7, 3)), 
true);
   572   ASSERT_EQ(
find(occupiedCells, map.
getIndex(8, 3)), 
true);
   573   ASSERT_EQ(
find(occupiedCells, map.
getIndex(9, 3)), 
true);
   574   ASSERT_EQ(
find(occupiedCells, map.
getIndex(7, 4)), 
true);
   575   ASSERT_EQ(
find(occupiedCells, map.
getIndex(8, 4)), 
true);
   576   ASSERT_EQ(
find(occupiedCells, map.
getIndex(9, 4)), 
true);
   579   ASSERT_EQ(
find(occupiedCells, map.
getIndex(4, 3)), 
true);
   580   ASSERT_EQ(
find(occupiedCells, map.
getIndex(4, 4)), 
true);
   583   ASSERT_EQ(
find(occupiedCells, map.
getIndex(3, 7)), 
true);
   584   ASSERT_EQ(
find(occupiedCells, map.
getIndex(4, 7)), 
true);
   585   ASSERT_EQ(
find(occupiedCells, map.
getIndex(5, 7)), 
true);
   589   ASSERT_EQ(
worldToIndex(map, 0.0, 0.0), (
unsigned int)0);
   590   ASSERT_EQ(
worldToIndex(map, 0.0, 0.99), (
unsigned int)0);
   591   ASSERT_EQ(
worldToIndex(map, 0.0, 1.0), (
unsigned int)10);
   592   ASSERT_EQ(
worldToIndex(map, 1.0, 0.99), (
unsigned int)1);
   593   ASSERT_EQ(
worldToIndex(map, 9.99, 9.99), (
unsigned int)99);
   594   ASSERT_EQ(
worldToIndex(map, 8.2, 3.4), (
unsigned int)38);
   608 TEST(costmap, testDynamicObstacles){
   613   pcl::PointCloud<pcl::PointXYZ> cloud;
   614   cloud.points.resize(3);
   615   cloud.points[0].x = 0;
   616   cloud.points[0].y = 0;
   617   cloud.points[1].x = 0;
   618   cloud.points[1].y = 0;
   619   cloud.points[2].x = 0;
   620   cloud.points[2].y = 0;
   622   geometry_msgs::Point p;
   628   std::vector<Observation> obsBuf;
   629   obsBuf.push_back(obs);
   631   map.updateWorld(0, 0, obsBuf, obsBuf);
   633   std::vector<unsigned int> ids;
   635   for(
unsigned int i = 0; i < 10; ++i){
   636     for(
unsigned int j = 0; j < 10; ++j){
   644   ASSERT_EQ(ids.size(), (
unsigned int)21);
   647   map.updateWorld(0, 0, obsBuf, obsBuf);
   648   ASSERT_EQ(ids.size(), (
unsigned int)21);
   654 TEST(costmap, testMultipleAdditions){
   659   pcl::PointCloud<pcl::PointXYZ> cloud;
   660   cloud.points.resize(1);
   661   cloud.points[0].x = 7;
   662   cloud.points[0].y = 2;
   664   geometry_msgs::Point p;
   670   std::vector<Observation> obsBuf;
   671   obsBuf.push_back(obs);
   673   map.updateWorld(0, 0, obsBuf, obsBuf);
   675   std::vector<unsigned int> ids;
   677   for(
unsigned int i = 0; i < 10; ++i){
   678     for(
unsigned int j = 0; j < 10; ++j){
   685   ASSERT_EQ(ids.size(), (
unsigned int)20);
   696   pcl::PointCloud<pcl::PointXYZ> c0;
   700   c0.points[0].z = 0.4;
   703   c0.points[1].z = 1.2;
   705   geometry_msgs::Point p;
   711   std::vector<Observation> obsBuf;
   712   obsBuf.push_back(obs);
   714   map.updateWorld(0, 0, obsBuf, obsBuf);
   716   std::vector<unsigned int> ids;
   718   for(
unsigned int i = 0; i < 10; ++i){
   719     for(
unsigned int j = 0; j < 10; ++j){
   726   ASSERT_EQ(ids.size(), (
unsigned int)21);
   738   std::vector<unsigned int> occupiedCells;
   740   for(
unsigned int i = 0; i < 10; ++i){
   741     for(
unsigned int j = 0; j < 10; ++j){
   743         occupiedCells.push_back(map.
getIndex(i, j));
   749   std::set<unsigned int> setOfCells;
   750   for(
unsigned int i=0;i<occupiedCells.size(); i++)
   751     setOfCells.insert(i);
   753   ASSERT_EQ(setOfCells.size(), occupiedCells.size());
   754   ASSERT_EQ(setOfCells.size(), (
unsigned int)48);
   757   for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
   758     unsigned int ind = *it;
   761     ASSERT_EQ(
find(occupiedCells, map.
getIndex(x, y)), 
true);
   766   pcl::PointCloud<pcl::PointXYZ> c0;
   770   c0.points[0].z = 0.4;
   772   geometry_msgs::Point p;
   778   std::vector<Observation> obsBuf, empty;
   779   obsBuf.push_back(obs);
   781   map.updateWorld(0, 0, obsBuf, empty);
   783   occupiedCells.clear();
   784   for(
unsigned int i = 0; i < 10; ++i){
   785     for(
unsigned int j = 0; j < 10; ++j){
   787         occupiedCells.push_back(map.
getIndex(i, j));
   793   ASSERT_EQ(occupiedCells.size(), (
unsigned int)51);
   797   pcl::PointCloud<pcl::PointXYZ> c1;
   801   c1.points[0].z = 0.0;
   803   geometry_msgs::Point p1;
   809   std::vector<Observation> obsBuf1;
   810   obsBuf1.push_back(obs1);
   812   map.updateWorld(0, 0, obsBuf1, empty);
   814   occupiedCells.clear();
   815   for(
unsigned int i = 0; i < 10; ++i){
   816     for(
unsigned int j = 0; j < 10; ++j){
   818         occupiedCells.push_back(map.
getIndex(i, j));
   826   ASSERT_EQ(occupiedCells.size(), (
unsigned int)54);
   830   pcl::PointCloud<pcl::PointXYZ> c2;
   834   c2.points[0].z = 0.0;
   836   geometry_msgs::Point p2;
   842   std::vector<Observation> obsBuf2;
   843   obsBuf2.push_back(obs2);
   845   map.updateWorld(0, 0, obsBuf2, empty);
   852   pcl::PointCloud<pcl::PointXYZ> c3;
   856   c3.points[0].z = 0.0;
   858   geometry_msgs::Point p3;
   864   std::vector<Observation> obsBuf3;
   865   obsBuf3.push_back(obs3);
   867   map.updateWorld(0, 0, obsBuf3, empty);
   880   pcl::PointCloud<pcl::PointXYZ> c0;
   884   c0.points[0].z = 
MAX_Z;
   887   c0.points[1].z = 
MAX_Z;
   890   c0.points[2].z = 
MAX_Z;
   892   geometry_msgs::Point p;
   898   std::vector<Observation> obsBuf;
   899   obsBuf.push_back(obs);
   901   map.updateWorld(0, 0, obsBuf, obsBuf);
   911   std::vector<unsigned char> mapData;
   914       mapData.push_back(0);
   922   std::vector<unsigned int> ids;
   924   for(
unsigned int i = 0; i < 10; ++i){
   925     for(
unsigned int j = 0; j < 10; ++j){
   932   ASSERT_EQ(ids.size(), (
unsigned int)0);
   935   pcl::PointCloud<pcl::PointXYZ> c0;
   939   c0.points[0].z = 
MAX_Z;
   941   geometry_msgs::Point p;
   947   std::vector<Observation> obsBuf;
   948   obsBuf.push_back(obs);
   950   map.updateWorld(0, 0, obsBuf, obsBuf);
   952   for(
unsigned int i = 0; i < 10; ++i){
   953     for(
unsigned int j = 0; j < 10; ++j){
   960   ASSERT_EQ(ids.size(), (
unsigned int)29);
   963   for(
unsigned int i = 0; i < 10; ++i){
   964     for(
unsigned int j = 0; j < 10; ++j){
   971   ASSERT_EQ(ids.size(), (
unsigned int)5);
   974   map.updateWorld(0, 0, obsBuf, obsBuf);
   977   for(
unsigned int i = 0; i < 10; ++i){
   978     for(
unsigned int j = 0; j < 10; ++j){
   985   ASSERT_EQ(ids.size(), (
unsigned int)29);
   992 TEST(costmap, testRaytracing2){
   998   pcl::PointCloud<pcl::PointXYZ> c0;
  1000   c0.points[0].x = 9.5;
  1001   c0.points[0].y = 9.5;
  1002   c0.points[0].z = 
MAX_Z;
  1004   geometry_msgs::Point p;
  1010   std::vector<Observation> obsBuf;
  1011   obsBuf.push_back(obs);
  1013   std::vector<unsigned int> obstacles;
  1015   for(
unsigned int i = 0; i < 10; ++i){
  1016     for(
unsigned int j = 0; j < 10; ++j){
  1018         obstacles.push_back(map.
getIndex(i, j));
  1023   unsigned int obs_before = obstacles.size();
  1025   map.updateWorld(0, 0, obsBuf, obsBuf);
  1028   for(
unsigned int i = 0; i < 10; ++i){
  1029     for(
unsigned int j = 0; j < 10; ++j){
  1031         obstacles.push_back(map.
getIndex(i, j));
  1037   ASSERT_EQ(obstacles.size(), obs_before - 2);
  1043   unsigned char test[10]= {0, 0, 0, 253, 253, 0, 0, 253, 253, 254};
  1044   for(
unsigned int i=0; i < 10; i++)
  1045     ASSERT_EQ(map.
getCost(i, i), test[i]);
  1054 TEST(costmap, testTrickyPropagation){
  1055   const unsigned char MAP_HALL_CHAR[10 * 10] = {
  1056     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
  1057     254, 0, 0,   0,   0, 0,   0, 0, 0, 0,
  1058     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
  1059     0,   0, 0,   254, 0, 0,   0, 0, 0, 0,
  1060     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
  1061     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
  1062     0,   0, 0,   0,   0, 254, 0, 0, 0, 0,
  1063     0,   0, 0,   0,   0, 254, 0, 0, 0, 0,
  1064     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
  1065     0,   0, 0,   0,   0, 0,   0, 0, 0, 0,
  1067   std::vector<unsigned char> MAP_HALL;
  1068   for (
int i = 0; i < 10 * 10; i++) {
  1069     MAP_HALL.push_back(MAP_HALL_CHAR[i]);
  1077   pcl::PointCloud<pcl::PointXYZ> c2;
  1078   c2.points.resize(3);
  1080   c2.points[0].x = 7.0;
  1081   c2.points[0].y = 8.0;
  1082   c2.points[0].z = 1.0;
  1085   c2.points[1].x = 3.0;
  1086   c2.points[1].y = 4.0;
  1087   c2.points[1].z = 1.0;
  1089   c2.points[2].x = 6.0;
  1090   c2.points[2].y = 3.0;
  1091   c2.points[2].z = 1.0;
  1093   geometry_msgs::Point p2;
  1099   std::vector<Observation> obsBuf2;
  1100   obsBuf2.push_back(obs2);
  1102   map.updateWorld(0, 0, obsBuf2, obsBuf2);
  1104   const unsigned char MAP_HALL_CHAR_TEST[10 * 10] = { 
  1105     253, 254, 253,   0,   0,   0,   0,   0,   0,   0,
  1106       0, 253,   0,   0,   0,   0,   0,   0,   0,   0,
  1107       0,   0,   0,   0, 253,   0,   0,   0,   0,   0,
  1108       0,   0,   0, 253, 254, 253,   0,   0,   0,   0,
  1109       0,   0,   0,   0, 253,   0,   0, 253,   0,   0,
  1110       0,   0,   0, 253,   0,   0, 253, 254, 253,   0,
  1111       0,   0, 253, 254, 253,   0,   0, 253, 253,   0,
  1112       0,   0,   0, 253,   0,   0,   0, 253, 254, 253,
  1113       0,   0,   0,   0,   0,   0,   0,   0, 253,   0,
  1114       0,   0,   0,   0,   0,   0,   0,   0,   0,   0,
  1118   for (
int i = 0; i < 10 * 10; i++) {
  1119     ASSERT_EQ(map.
getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST[i]);
  1122   pcl::PointCloud<pcl::PointXYZ> c;
  1125   c.points[0].x = 4.0;
  1126   c.points[0].y = 5.0;
  1127   c.points[0].z = 1.0;
  1129   geometry_msgs::Point p3;
  1135   std::vector<Observation> obsBuf3;
  1136   obsBuf3.push_back(obs3);
  1138   map.updateWorld(0, 0, obsBuf3, obsBuf3);
  1140   const unsigned char MAP_HALL_CHAR_TEST2[10 * 10] = { 
  1141     253, 254, 253,   0,   0,   0,   0,   0,   0,   0,
  1142       0, 253,   0,   0,   0,   0,   0,   0,   0,   0,
  1143       0,   0,   0,   0,   0,   0,   0,   0,   0,   0,
  1144       0,   0,   0,   0,   0, 253,   0,   0,   0,   0,
  1145       0,   0,   0,   0, 253, 254, 253, 253,   0,   0,
  1146       0,   0,   0, 253,   0, 253, 253, 254, 253,   0,
  1147       0,   0, 253, 254, 253,   0,   0, 253, 253,   0,
  1148       0,   0,   0, 253,   0,   0,   0, 253, 254, 253,
  1149       0,   0,   0,   0,   0,   0,   0,   0, 253,   0,
  1150       0,   0,   0,   0,   0,   0,   0,   0,   0,   0,
  1154   for (
int i = 0; i < 10 * 10; i++) {
  1155     ASSERT_EQ(map.
getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST2[i]);
  1167   for(
unsigned int i = 0; i< 5 * 5; i++){
  1171   for(
unsigned int i = 0; i< 100 * 100; i++)
  1174   testing::InitGoogleTest(&argc, argv);
  1175   return RUN_ALL_TESTS();
 unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells. 
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates. 
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells. 
const double OBSTACLE_RANGE(20.0)
TEST(costmap, testResetForStaticMap)
void indexToWorld(Costmap2D &map, unsigned int index, double &wx, double &wy)
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index. 
Stores an observation in terms of a point cloud and the origin of the source. 
static const unsigned char FREE_SPACE
int main(int argc, char **argv)
std::vector< unsigned char > MAP_10_BY_10
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
const double RESOLUTION(1)
char printableCost(unsigned char cost)
const unsigned int GRID_WIDTH(10)
const unsigned char MAP_10_BY_10_CHAR[]
std::vector< unsigned char > MAP_5_BY_5
double getOriginX() const
Accessor for the x origin of the costmap. 
bool copyCostmapWindow(const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
Turn this costmap into a copy of a window of a costmap passed in. 
const double WINDOW_LENGTH(10)
static const unsigned char LETHAL_OBSTACLE
const double ROBOT_RADIUS(1.0)
static const unsigned char NO_INFORMATION
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates. 
const double RAYTRACE_RANGE(20.0)
bool find(const std::vector< unsigned int > &l, unsigned int n)
A 2D costmap provides a mapping between points in the world and their associated "costs". 
std::vector< unsigned char > EMPTY_100_BY_100
unsigned int worldToIndex(Costmap2D &map, double wx, double wy)
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates. 
const unsigned char MAP_5_BY_5_CHAR[]
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap. 
std::vector< unsigned char > EMPTY_10_BY_10
const unsigned char THRESHOLD(100)
const unsigned int GRID_HEIGHT(10)