static_tests.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330
  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. /**
  30. * @author David Lu!!
  31. * Test harness for StaticMap Layer for Costmap2D
  32. */
  33. #include <costmap_2d/costmap_2d.h>
  34. #include <costmap_2d/layered_costmap.h>
  35. #include <costmap_2d/obstacle_layer.h>
  36. #include <costmap_2d/static_layer.h>
  37. #include <costmap_2d/observation_buffer.h>
  38. #include <costmap_2d/testing_helper.h>
  39. #include <set>
  40. #include <gtest/gtest.h>
  41. using namespace costmap_2d;
  42. /**
  43. * Tests the reset method
  44. *
  45. TEST(costmap, testResetForStaticMap){
  46. // Define a static map with a large object in the center
  47. std::vector<unsigned char> staticMap;
  48. for(unsigned int i=0; i<10; i++){
  49. for(unsigned int j=0; j<10; j++){
  50. staticMap.push_back(costmap_2d::LETHAL_OBSTACLE);
  51. }
  52. }
  53. // Allocate the cost map, with a inflation to 3 cells all around
  54. Costmap2D map(10, 10, RESOLUTION, 0.0, 0.0, 3, 3, 3, OBSTACLE_RANGE, MAX_Z, RAYTRACE_RANGE, 25, staticMap, THRESHOLD);
  55. // Populate the cost map with a wall around the perimeter. Free space should clear out the room.
  56. pcl::PointCloud<pcl::PointXYZ> cloud;
  57. cloud.points.resize(40);
  58. // Left wall
  59. unsigned int ind = 0;
  60. for (unsigned int i = 0; i < 10; i++){
  61. // Left
  62. cloud.points[ind].x = 0;
  63. cloud.points[ind].y = i;
  64. cloud.points[ind].z = MAX_Z;
  65. ind++;
  66. // Top
  67. cloud.points[ind].x = i;
  68. cloud.points[ind].y = 0;
  69. cloud.points[ind].z = MAX_Z;
  70. ind++;
  71. // Right
  72. cloud.points[ind].x = 9;
  73. cloud.points[ind].y = i;
  74. cloud.points[ind].z = MAX_Z;
  75. ind++;
  76. // Bottom
  77. cloud.points[ind].x = i;
  78. cloud.points[ind].y = 9;
  79. cloud.points[ind].z = MAX_Z;
  80. ind++;
  81. }
  82. double wx = 5.0, wy = 5.0;
  83. geometry_msgs::Point p;
  84. p.x = wx;
  85. p.y = wy;
  86. p.z = MAX_Z;
  87. Observation obs(p, cloud, OBSTACLE_RANGE, RAYTRACE_RANGE);
  88. std::vector<Observation> obsBuf;
  89. obsBuf.push_back(obs);
  90. // Update the cost map for this observation
  91. map.updateWorld(wx, wy, obsBuf, obsBuf);
  92. // Verify that we now have only 36 cells with lethal cost, thus provong that we have correctly cleared
  93. // free space
  94. int hitCount = 0;
  95. for(unsigned int i=0; i < 10; ++i){
  96. for(unsigned int j=0; j < 10; ++j){
  97. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  98. hitCount++;
  99. }
  100. }
  101. }
  102. ASSERT_EQ(hitCount, 36);
  103. // Veriy that we have 64 non-leathal
  104. hitCount = 0;
  105. for(unsigned int i=0; i < 10; ++i){
  106. for(unsigned int j=0; j < 10; ++j){
  107. if(map.getCost(i, j) != costmap_2d::LETHAL_OBSTACLE)
  108. hitCount++;
  109. }
  110. }
  111. ASSERT_EQ(hitCount, 64);
  112. // Now if we reset the cost map, we should have our map go back to being completely occupied
  113. map.resetMapOutsideWindow(wx, wy, 0.0, 0.0);
  114. //We should now go back to everything being occupied
  115. hitCount = 0;
  116. for(unsigned int i=0; i < 10; ++i){
  117. for(unsigned int j=0; j < 10; ++j){
  118. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE)
  119. hitCount++;
  120. }
  121. }
  122. ASSERT_EQ(hitCount, 100);
  123. }
  124. /** Test for copying a window of a costmap *
  125. TEST(costmap, testWindowCopy){
  126. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  127. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  128. /*
  129. for(unsigned int i = 0; i < 10; ++i){
  130. for(unsigned int j = 0; j < 10; ++j){
  131. printf("%3d ", map.getCost(i, j));
  132. }
  133. printf("\n");
  134. }
  135. printf("\n");
  136. *
  137. Costmap2D windowCopy;
  138. //first test that if we try to make a window that is too big, things fail
  139. windowCopy.copyCostmapWindow(map, 2.0, 2.0, 6.0, 12.0);
  140. ASSERT_EQ(windowCopy.getSizeInCellsX(), (unsigned int)0);
  141. ASSERT_EQ(windowCopy.getSizeInCellsY(), (unsigned int)0);
  142. //Next, test that trying to make a map window itself fails
  143. map.copyCostmapWindow(map, 2.0, 2.0, 6.0, 6.0);
  144. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)10);
  145. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)10);
  146. //Next, test that legal input generates the result that we expect
  147. windowCopy.copyCostmapWindow(map, 2.0, 2.0, 6.0, 6.0);
  148. ASSERT_EQ(windowCopy.getSizeInCellsX(), (unsigned int)6);
  149. ASSERT_EQ(windowCopy.getSizeInCellsY(), (unsigned int)6);
  150. //check that we actually get the windo that we expect
  151. for(unsigned int i = 0; i < windowCopy.getSizeInCellsX(); ++i){
  152. for(unsigned int j = 0; j < windowCopy.getSizeInCellsY(); ++j){
  153. ASSERT_EQ(windowCopy.getCost(i, j), map.getCost(i + 2, j + 2));
  154. //printf("%3d ", windowCopy.getCost(i, j));
  155. }
  156. //printf("\n");
  157. }
  158. }
  159. //test for updating costmaps with static data
  160. TEST(costmap, testFullyContainedStaticMapUpdate){
  161. Costmap2D map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  162. 10.0, MAX_Z, 10.0, 25, MAP_5_BY_5, THRESHOLD);
  163. Costmap2D static_map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  164. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  165. map.updateStaticMapWindow(0, 0, 10, 10, MAP_10_BY_10);
  166. for(unsigned int i = 0; i < map.getSizeInCellsX(); ++i){
  167. for(unsigned int j = 0; j < map.getSizeInCellsY(); ++j){
  168. ASSERT_EQ(map.getCost(i, j), static_map.getCost(i, j));
  169. }
  170. }
  171. }
  172. TEST(costmap, testOverlapStaticMapUpdate){
  173. Costmap2D map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  174. 10.0, MAX_Z, 10.0, 25, MAP_5_BY_5, THRESHOLD);
  175. Costmap2D static_map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  176. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  177. map.updateStaticMapWindow(-10, -10, 10, 10, MAP_10_BY_10);
  178. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  179. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  180. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)15);
  181. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)15);
  182. for(unsigned int i = 0; i < 10; ++i){
  183. for(unsigned int j = 0; j < 10; ++j){
  184. ASSERT_EQ(map.getCost(i, j), static_map.getCost(i, j));
  185. }
  186. }
  187. std::vector<unsigned char> blank(100);
  188. //check to make sure that inflation on updates are being done correctly
  189. map.updateStaticMapWindow(-10, -10, 10, 10, blank);
  190. for(unsigned int i = 0; i < map.getSizeInCellsX(); ++i){
  191. for(unsigned int j = 0; j < map.getSizeInCellsY(); ++j){
  192. ASSERT_EQ(map.getCost(i, j), 0);
  193. }
  194. }
  195. std::vector<unsigned char> fully_contained(25);
  196. fully_contained[0] = 254;
  197. fully_contained[4] = 254;
  198. fully_contained[5] = 254;
  199. fully_contained[9] = 254;
  200. Costmap2D small_static_map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  201. 10.0, MAX_Z, 10.0, 25, fully_contained, THRESHOLD);
  202. map.updateStaticMapWindow(0, 0, 5, 5, fully_contained);
  203. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  204. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  205. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)15);
  206. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)15);
  207. for(unsigned int j = 0; j < 5; ++j){
  208. for(unsigned int i = 0; i < 5; ++i){
  209. ASSERT_EQ(map.getCost(i + 10, j + 10), small_static_map.getCost(i, j));
  210. }
  211. }
  212. }
  213. TEST(costmap, testStaticMap){
  214. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  215. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  216. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)10);
  217. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)10);
  218. // Verify that obstacles correctly identified from the static map.
  219. std::vector<unsigned int> occupiedCells;
  220. for(unsigned int i = 0; i < 10; ++i){
  221. for(unsigned int j = 0; j < 10; ++j){
  222. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  223. occupiedCells.push_back(map.getIndex(i, j));
  224. }
  225. }
  226. }
  227. ASSERT_EQ(occupiedCells.size(), (unsigned int)20);
  228. // Iterate over all id's and verify that they are present according to their
  229. for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
  230. unsigned int ind = *it;
  231. unsigned int x, y;
  232. map.indexToCells(ind, x, y);
  233. ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
  234. ASSERT_EQ(MAP_10_BY_10[ind] >= 100, true);
  235. ASSERT_EQ(map.getCost(x, y) >= 100, true);
  236. }
  237. // Block of 200
  238. ASSERT_EQ(find(occupiedCells, map.getIndex(7, 2)), true);
  239. ASSERT_EQ(find(occupiedCells, map.getIndex(8, 2)), true);
  240. ASSERT_EQ(find(occupiedCells, map.getIndex(9, 2)), true);
  241. ASSERT_EQ(find(occupiedCells, map.getIndex(7, 3)), true);
  242. ASSERT_EQ(find(occupiedCells, map.getIndex(8, 3)), true);
  243. ASSERT_EQ(find(occupiedCells, map.getIndex(9, 3)), true);
  244. ASSERT_EQ(find(occupiedCells, map.getIndex(7, 4)), true);
  245. ASSERT_EQ(find(occupiedCells, map.getIndex(8, 4)), true);
  246. ASSERT_EQ(find(occupiedCells, map.getIndex(9, 4)), true);
  247. // Block of 100
  248. ASSERT_EQ(find(occupiedCells, map.getIndex(4, 3)), true);
  249. ASSERT_EQ(find(occupiedCells, map.getIndex(4, 4)), true);
  250. // Block of 200
  251. ASSERT_EQ(find(occupiedCells, map.getIndex(3, 7)), true);
  252. ASSERT_EQ(find(occupiedCells, map.getIndex(4, 7)), true);
  253. ASSERT_EQ(find(occupiedCells, map.getIndex(5, 7)), true);
  254. // Verify Coordinate Transformations, ROW MAJOR ORDER
  255. ASSERT_EQ(worldToIndex(map, 0.0, 0.0), (unsigned int)0);
  256. ASSERT_EQ(worldToIndex(map, 0.0, 0.99), (unsigned int)0);
  257. ASSERT_EQ(worldToIndex(map, 0.0, 1.0), (unsigned int)10);
  258. ASSERT_EQ(worldToIndex(map, 1.0, 0.99), (unsigned int)1);
  259. ASSERT_EQ(worldToIndex(map, 9.99, 9.99), (unsigned int)99);
  260. ASSERT_EQ(worldToIndex(map, 8.2, 3.4), (unsigned int)38);
  261. // Ensure we hit the middle of the cell for world co-ordinates
  262. double wx, wy;
  263. indexToWorld(map, 99, wx, wy);
  264. ASSERT_EQ(wx, 9.5);
  265. ASSERT_EQ(wy, 9.5);
  266. }
  267. //*/
  268. int main(int argc, char** argv){
  269. ros::init(argc, argv, "obstacle_tests");
  270. testing::InitGoogleTest(&argc, argv);
  271. return RUN_ALL_TESTS();
  272. }