module_tests.cpp 35 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176
  1. /*
  2. * Copyright (c) 2008, 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 Conor McGann
  31. * Test harness for Costmap2D
  32. */
  33. #include <costmap_2d/costmap_2d.h>
  34. #include <costmap_2d/observation_buffer.h>
  35. #include <set>
  36. #include <gtest/gtest.h>
  37. using namespace costmap_2d;
  38. const unsigned char MAP_10_BY_10_CHAR[] = {
  39. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  40. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  41. 0, 0, 0, 0, 0, 0, 0, 200, 200, 200,
  42. 0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
  43. 0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
  44. 70, 70, 0, 0, 0, 0, 0, 0, 0, 0,
  45. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  46. 0, 0, 0, 200, 200, 200, 0, 0, 0, 0,
  47. 0, 0, 0, 0, 0, 0, 0, 255, 255, 255,
  48. 0, 0, 0, 0, 0, 0, 0, 255, 255, 255
  49. };
  50. const unsigned char MAP_5_BY_5_CHAR[] = {
  51. 0, 0, 0, 0, 0,
  52. 0, 0, 0, 0, 0,
  53. 0, 0, 0, 0, 0,
  54. 0, 0, 0, 0, 0,
  55. 0, 0, 0, 0, 0,
  56. };
  57. std::vector<unsigned char> MAP_5_BY_5;
  58. std::vector<unsigned char> MAP_10_BY_10;
  59. std::vector<unsigned char> EMPTY_10_BY_10;
  60. std::vector<unsigned char> EMPTY_100_BY_100;
  61. const unsigned int GRID_WIDTH(10);
  62. const unsigned int GRID_HEIGHT(10);
  63. const double RESOLUTION(1);
  64. const double WINDOW_LENGTH(10);
  65. const unsigned char THRESHOLD(100);
  66. const double MAX_Z(1.0);
  67. const double RAYTRACE_RANGE(20.0);
  68. const double OBSTACLE_RANGE(20.0);
  69. const double ROBOT_RADIUS(1.0);
  70. bool find(const std::vector<unsigned int>& l, unsigned int n){
  71. for(std::vector<unsigned int>::const_iterator it = l.begin(); it != l.end(); ++it){
  72. if(*it == n)
  73. return true;
  74. }
  75. return false;
  76. }
  77. /**
  78. * Tests the reset method
  79. */
  80. TEST(costmap, testResetForStaticMap){
  81. // Define a static map with a large object in the center
  82. std::vector<unsigned char> staticMap;
  83. for(unsigned int i=0; i<10; i++){
  84. for(unsigned int j=0; j<10; j++){
  85. staticMap.push_back(costmap_2d::LETHAL_OBSTACLE);
  86. }
  87. }
  88. // Allocate the cost map, with a inflation to 3 cells all around
  89. Costmap2D map(10, 10, RESOLUTION, 0.0, 0.0, 3, 3, 3, OBSTACLE_RANGE, MAX_Z, RAYTRACE_RANGE, 25, staticMap, THRESHOLD);
  90. // Populate the cost map with a wall around the perimeter. Free space should clear out the room.
  91. pcl::PointCloud<pcl::PointXYZ> cloud;
  92. cloud.points.resize(40);
  93. // Left wall
  94. unsigned int ind = 0;
  95. for (unsigned int i = 0; i < 10; i++){
  96. // Left
  97. cloud.points[ind].x = 0;
  98. cloud.points[ind].y = i;
  99. cloud.points[ind].z = MAX_Z;
  100. ind++;
  101. // Top
  102. cloud.points[ind].x = i;
  103. cloud.points[ind].y = 0;
  104. cloud.points[ind].z = MAX_Z;
  105. ind++;
  106. // Right
  107. cloud.points[ind].x = 9;
  108. cloud.points[ind].y = i;
  109. cloud.points[ind].z = MAX_Z;
  110. ind++;
  111. // Bottom
  112. cloud.points[ind].x = i;
  113. cloud.points[ind].y = 9;
  114. cloud.points[ind].z = MAX_Z;
  115. ind++;
  116. }
  117. double wx = 5.0, wy = 5.0;
  118. geometry_msgs::Point p;
  119. p.x = wx;
  120. p.y = wy;
  121. p.z = MAX_Z;
  122. Observation obs(p, cloud, OBSTACLE_RANGE, RAYTRACE_RANGE);
  123. std::vector<Observation> obsBuf;
  124. obsBuf.push_back(obs);
  125. // Update the cost map for this observation
  126. map.updateWorld(wx, wy, obsBuf, obsBuf);
  127. // Verify that we now have only 36 cells with lethal cost, thus provong that we have correctly cleared
  128. // free space
  129. int hitCount = 0;
  130. for(unsigned int i=0; i < 10; ++i){
  131. for(unsigned int j=0; j < 10; ++j){
  132. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  133. hitCount++;
  134. }
  135. }
  136. }
  137. ASSERT_EQ(hitCount, 36);
  138. // Veriy that we have 64 non-leathal
  139. hitCount = 0;
  140. for(unsigned int i=0; i < 10; ++i){
  141. for(unsigned int j=0; j < 10; ++j){
  142. if(map.getCost(i, j) != costmap_2d::LETHAL_OBSTACLE)
  143. hitCount++;
  144. }
  145. }
  146. ASSERT_EQ(hitCount, 64);
  147. // Now if we reset the cost map, we should have our map go back to being completely occupied
  148. map.resetMapOutsideWindow(wx, wy, 0.0, 0.0);
  149. //We should now go back to everything being occupied
  150. hitCount = 0;
  151. for(unsigned int i=0; i < 10; ++i){
  152. for(unsigned int j=0; j < 10; ++j){
  153. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE)
  154. hitCount++;
  155. }
  156. }
  157. ASSERT_EQ(hitCount, 100);
  158. }
  159. /**
  160. * Test for the cost function correctness with a larger range and different values
  161. */
  162. TEST(costmap, testCostFunctionCorrectness){
  163. Costmap2D map(100, 100, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS * 5.0, ROBOT_RADIUS * 8.0, ROBOT_RADIUS * 10.5,
  164. 100.0, MAX_Z, 100.0, 25, EMPTY_100_BY_100, THRESHOLD);
  165. // Verify that the circumscribed cost lower bound is as expected: based on the cost function.
  166. unsigned char c = map.computeCost((ROBOT_RADIUS * 8.0 / RESOLUTION));
  167. ASSERT_EQ(map.getCircumscribedCost(), c);
  168. // Add a point in the center
  169. pcl::PointCloud<pcl::PointXYZ> cloud;
  170. cloud.points.resize(1);
  171. cloud.points[0].x = 50;
  172. cloud.points[0].y = 50;
  173. cloud.points[0].z = MAX_Z;
  174. geometry_msgs::Point p;
  175. p.x = 0.0;
  176. p.y = 0.0;
  177. p.z = MAX_Z;
  178. Observation obs(p, cloud, 100.0, 100.0);
  179. std::vector<Observation> obsBuf;
  180. obsBuf.push_back(obs);
  181. map.updateWorld(0, 0, obsBuf, obsBuf);
  182. for(unsigned int i = 0; i <= (unsigned int)ceil(ROBOT_RADIUS * 5.0); i++){
  183. // To the right
  184. ASSERT_EQ(map.getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  185. ASSERT_EQ(map.getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  186. // To the left
  187. ASSERT_EQ(map.getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  188. ASSERT_EQ(map.getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  189. // Down
  190. ASSERT_EQ(map.getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  191. ASSERT_EQ(map.getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  192. // Up
  193. ASSERT_EQ(map.getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  194. ASSERT_EQ(map.getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  195. }
  196. // Verify the normalized cost attenuates as expected
  197. for(unsigned int i = (unsigned int)(ceil(ROBOT_RADIUS * 5.0) + 1); i <= (unsigned int)ceil(ROBOT_RADIUS * 10.5); i++){
  198. unsigned char expectedValue = map.computeCost(i / RESOLUTION);
  199. ASSERT_EQ(map.getCost(50 + i, 50), expectedValue);
  200. }
  201. // Update with no hits. Should clear (revert to the static map
  202. map.resetMapOutsideWindow(0, 0, 0.0, 0.0);
  203. cloud.points.resize(0);
  204. p.x = 0.0;
  205. p.y = 0.0;
  206. p.z = MAX_Z;
  207. Observation obs2(p, cloud, 100.0, 100.0);
  208. std::vector<Observation> obsBuf2;
  209. obsBuf2.push_back(obs2);
  210. map.updateWorld(0, 0, obsBuf2, obsBuf2);
  211. for(unsigned int i = 0; i < 100; i++)
  212. for(unsigned int j = 0; j < 100; j++)
  213. ASSERT_EQ(map.getCost(i, j), costmap_2d::FREE_SPACE);
  214. }
  215. char printableCost( unsigned char cost )
  216. {
  217. switch( cost )
  218. {
  219. case NO_INFORMATION: return '?';
  220. case LETHAL_OBSTACLE: return 'L';
  221. case INSCRIBED_INFLATED_OBSTACLE: return 'I';
  222. case FREE_SPACE: return '.';
  223. default: return '0' + (unsigned char) (10 * cost / 255);
  224. }
  225. }
  226. /**
  227. * Test for wave interference
  228. */
  229. TEST(costmap, testWaveInterference){
  230. // Start with an empty map
  231. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS * 2, ROBOT_RADIUS * 3.01,
  232. 10.0, MAX_Z * 2, 10.0, 1, EMPTY_10_BY_10, THRESHOLD);
  233. // Lay out 3 obstacles in a line - along the diagonal, separated by a cell.
  234. pcl::PointCloud<pcl::PointXYZ> cloud;
  235. cloud.points.resize(3);
  236. cloud.points[0].x = 3;
  237. cloud.points[0].y = 3;
  238. cloud.points[0].z = MAX_Z;
  239. cloud.points[1].x = 5;
  240. cloud.points[1].y = 5;
  241. cloud.points[1].z = MAX_Z;
  242. cloud.points[2].x = 7;
  243. cloud.points[2].y = 7;
  244. cloud.points[2].z = MAX_Z;
  245. geometry_msgs::Point p;
  246. p.x = 0.0;
  247. p.y = 0.0;
  248. p.z = MAX_Z;
  249. Observation obs(p, cloud, 100.0, 100.0);
  250. std::vector<Observation> obsBuf;
  251. obsBuf.push_back(obs);
  252. map.updateWorld(0, 0, obsBuf, obsBuf);
  253. int update_count = 0;
  254. // Expect to see a union of obstacles
  255. printf("map:\n");
  256. for(unsigned int i = 0; i < 10; ++i){
  257. for(unsigned int j = 0; j < 10; ++j){
  258. if(map.getCost(i, j) != costmap_2d::FREE_SPACE){
  259. update_count++;
  260. }
  261. printf("%c", printableCost( map.getCost( i, j )));
  262. }
  263. printf("\n");
  264. }
  265. ASSERT_EQ(update_count, 79);
  266. }
  267. /** Test for copying a window of a costmap */
  268. TEST(costmap, testWindowCopy){
  269. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  270. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  271. /*
  272. for(unsigned int i = 0; i < 10; ++i){
  273. for(unsigned int j = 0; j < 10; ++j){
  274. printf("%3d ", map.getCost(i, j));
  275. }
  276. printf("\n");
  277. }
  278. printf("\n");
  279. */
  280. Costmap2D windowCopy;
  281. //first test that if we try to make a window that is too big, things fail
  282. windowCopy.copyCostmapWindow(map, 2.0, 2.0, 6.0, 12.0);
  283. ASSERT_EQ(windowCopy.getSizeInCellsX(), (unsigned int)0);
  284. ASSERT_EQ(windowCopy.getSizeInCellsY(), (unsigned int)0);
  285. //Next, test that trying to make a map window itself fails
  286. map.copyCostmapWindow(map, 2.0, 2.0, 6.0, 6.0);
  287. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)10);
  288. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)10);
  289. //Next, test that legal input generates the result that we expect
  290. windowCopy.copyCostmapWindow(map, 2.0, 2.0, 6.0, 6.0);
  291. ASSERT_EQ(windowCopy.getSizeInCellsX(), (unsigned int)6);
  292. ASSERT_EQ(windowCopy.getSizeInCellsY(), (unsigned int)6);
  293. //check that we actually get the windo that we expect
  294. for(unsigned int i = 0; i < windowCopy.getSizeInCellsX(); ++i){
  295. for(unsigned int j = 0; j < windowCopy.getSizeInCellsY(); ++j){
  296. ASSERT_EQ(windowCopy.getCost(i, j), map.getCost(i + 2, j + 2));
  297. //printf("%3d ", windowCopy.getCost(i, j));
  298. }
  299. //printf("\n");
  300. }
  301. }
  302. //test for updating costmaps with static data
  303. TEST(costmap, testFullyContainedStaticMapUpdate){
  304. Costmap2D map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  305. 10.0, MAX_Z, 10.0, 25, MAP_5_BY_5, THRESHOLD);
  306. Costmap2D static_map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  307. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  308. map.updateStaticMapWindow(0, 0, 10, 10, MAP_10_BY_10);
  309. for(unsigned int i = 0; i < map.getSizeInCellsX(); ++i){
  310. for(unsigned int j = 0; j < map.getSizeInCellsY(); ++j){
  311. ASSERT_EQ(map.getCost(i, j), static_map.getCost(i, j));
  312. }
  313. }
  314. }
  315. TEST(costmap, testOverlapStaticMapUpdate){
  316. Costmap2D map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  317. 10.0, MAX_Z, 10.0, 25, MAP_5_BY_5, THRESHOLD);
  318. Costmap2D static_map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  319. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  320. map.updateStaticMapWindow(-10, -10, 10, 10, MAP_10_BY_10);
  321. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  322. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  323. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)15);
  324. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)15);
  325. for(unsigned int i = 0; i < 10; ++i){
  326. for(unsigned int j = 0; j < 10; ++j){
  327. ASSERT_EQ(map.getCost(i, j), static_map.getCost(i, j));
  328. }
  329. }
  330. std::vector<unsigned char> blank(100);
  331. //check to make sure that inflation on updates are being done correctly
  332. map.updateStaticMapWindow(-10, -10, 10, 10, blank);
  333. for(unsigned int i = 0; i < map.getSizeInCellsX(); ++i){
  334. for(unsigned int j = 0; j < map.getSizeInCellsY(); ++j){
  335. ASSERT_EQ(map.getCost(i, j), 0);
  336. }
  337. }
  338. std::vector<unsigned char> fully_contained(25);
  339. fully_contained[0] = 254;
  340. fully_contained[4] = 254;
  341. fully_contained[5] = 254;
  342. fully_contained[9] = 254;
  343. Costmap2D small_static_map(5, 5, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  344. 10.0, MAX_Z, 10.0, 25, fully_contained, THRESHOLD);
  345. map.updateStaticMapWindow(0, 0, 5, 5, fully_contained);
  346. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  347. ASSERT_FLOAT_EQ(map.getOriginX(), -10);
  348. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)15);
  349. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)15);
  350. for(unsigned int j = 0; j < 5; ++j){
  351. for(unsigned int i = 0; i < 5; ++i){
  352. ASSERT_EQ(map.getCost(i + 10, j + 10), small_static_map.getCost(i, j));
  353. }
  354. }
  355. }
  356. /**
  357. * Test for ray tracing free space
  358. */
  359. TEST(costmap, testRaytracing){
  360. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  361. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  362. // Add a point cloud, should not affect the map
  363. pcl::PointCloud<pcl::PointXYZ> cloud;
  364. cloud.points.resize(1);
  365. cloud.points[0].x = 0;
  366. cloud.points[0].y = 0;
  367. cloud.points[0].z = MAX_Z;
  368. geometry_msgs::Point p;
  369. p.x = 0.0;
  370. p.y = 0.0;
  371. p.z = MAX_Z;
  372. Observation obs(p, cloud, 100.0, 100.0);
  373. std::vector<Observation> obsBuf;
  374. obsBuf.push_back(obs);
  375. map.updateWorld(0, 0, obsBuf, obsBuf);
  376. int lethal_count = 0;
  377. for(unsigned int i = 0; i < 10; ++i){
  378. for(unsigned int j = 0; j < 10; ++j){
  379. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  380. lethal_count++;
  381. }
  382. }
  383. }
  384. //we expect just one obstacle to be added
  385. ASSERT_EQ(lethal_count, 21);
  386. }
  387. TEST(costmap, testAdjacentToObstacleCanStillMove){
  388. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, 2.1, 3.1, 4.1,
  389. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  390. pcl::PointCloud<pcl::PointXYZ> cloud;
  391. cloud.points.resize(1);
  392. cloud.points[0].x = 0;
  393. cloud.points[0].y = 0;
  394. cloud.points[0].z = MAX_Z;
  395. geometry_msgs::Point p;
  396. p.x = 0.0;
  397. p.y = 0.0;
  398. p.z = MAX_Z;
  399. Observation obs(p, cloud, 100.0, 100.0);
  400. std::vector<Observation> obsBuf;
  401. obsBuf.push_back(obs);
  402. map.updateWorld(9, 9, obsBuf, obsBuf);
  403. EXPECT_EQ( LETHAL_OBSTACLE, map.getCost( 0, 0 ));
  404. EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, map.getCost( 1, 0 ));
  405. EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, map.getCost( 2, 0 ));
  406. EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > map.getCost( 3, 0 ));
  407. EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > map.getCost( 2, 1 ));
  408. EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, map.getCost( 1, 1 ));
  409. }
  410. TEST(costmap, testInflationShouldNotCreateUnknowns){
  411. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, 2.1, 3.1, 4.1,
  412. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  413. pcl::PointCloud<pcl::PointXYZ> cloud;
  414. cloud.points.resize(1);
  415. cloud.points[0].x = 0;
  416. cloud.points[0].y = 0;
  417. cloud.points[0].z = MAX_Z;
  418. geometry_msgs::Point p;
  419. p.x = 0.0;
  420. p.y = 0.0;
  421. p.z = MAX_Z;
  422. Observation obs(p, cloud, 100.0, 100.0);
  423. std::vector<Observation> obsBuf;
  424. obsBuf.push_back(obs);
  425. map.updateWorld(9, 9, obsBuf, obsBuf);
  426. int unknown_count = 0;
  427. for(unsigned int i = 0; i < 10; ++i){
  428. for(unsigned int j = 0; j < 10; ++j){
  429. if(map.getCost(i, j) == costmap_2d::NO_INFORMATION){
  430. unknown_count++;
  431. }
  432. }
  433. }
  434. EXPECT_EQ( 0, unknown_count );
  435. }
  436. unsigned int worldToIndex(Costmap2D& map, double wx, double wy){
  437. unsigned int mx, my;
  438. map.worldToMap(wx, wy, mx, my);
  439. return map.getIndex(mx, my);
  440. }
  441. void indexToWorld(Costmap2D& map, unsigned int index, double& wx, double& wy){
  442. unsigned int mx, my;
  443. map.indexToCells(index, mx, my);
  444. map.mapToWorld(mx, my, wx, wy);
  445. }
  446. TEST(costmap, testStaticMap){
  447. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  448. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  449. ASSERT_EQ(map.getSizeInCellsX(), (unsigned int)10);
  450. ASSERT_EQ(map.getSizeInCellsY(), (unsigned int)10);
  451. // Verify that obstacles correctly identified from the static map.
  452. std::vector<unsigned int> occupiedCells;
  453. for(unsigned int i = 0; i < 10; ++i){
  454. for(unsigned int j = 0; j < 10; ++j){
  455. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  456. occupiedCells.push_back(map.getIndex(i, j));
  457. }
  458. }
  459. }
  460. ASSERT_EQ(occupiedCells.size(), (unsigned int)20);
  461. // Iterate over all id's and verify that they are present according to their
  462. for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
  463. unsigned int ind = *it;
  464. unsigned int x, y;
  465. map.indexToCells(ind, x, y);
  466. ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
  467. ASSERT_EQ(MAP_10_BY_10[ind] >= 100, true);
  468. ASSERT_EQ(map.getCost(x, y) >= 100, true);
  469. }
  470. // Block of 200
  471. ASSERT_EQ(find(occupiedCells, map.getIndex(7, 2)), true);
  472. ASSERT_EQ(find(occupiedCells, map.getIndex(8, 2)), true);
  473. ASSERT_EQ(find(occupiedCells, map.getIndex(9, 2)), true);
  474. ASSERT_EQ(find(occupiedCells, map.getIndex(7, 3)), true);
  475. ASSERT_EQ(find(occupiedCells, map.getIndex(8, 3)), true);
  476. ASSERT_EQ(find(occupiedCells, map.getIndex(9, 3)), true);
  477. ASSERT_EQ(find(occupiedCells, map.getIndex(7, 4)), true);
  478. ASSERT_EQ(find(occupiedCells, map.getIndex(8, 4)), true);
  479. ASSERT_EQ(find(occupiedCells, map.getIndex(9, 4)), true);
  480. // Block of 100
  481. ASSERT_EQ(find(occupiedCells, map.getIndex(4, 3)), true);
  482. ASSERT_EQ(find(occupiedCells, map.getIndex(4, 4)), true);
  483. // Block of 200
  484. ASSERT_EQ(find(occupiedCells, map.getIndex(3, 7)), true);
  485. ASSERT_EQ(find(occupiedCells, map.getIndex(4, 7)), true);
  486. ASSERT_EQ(find(occupiedCells, map.getIndex(5, 7)), true);
  487. // Verify Coordinate Transformations, ROW MAJOR ORDER
  488. ASSERT_EQ(worldToIndex(map, 0.0, 0.0), (unsigned int)0);
  489. ASSERT_EQ(worldToIndex(map, 0.0, 0.99), (unsigned int)0);
  490. ASSERT_EQ(worldToIndex(map, 0.0, 1.0), (unsigned int)10);
  491. ASSERT_EQ(worldToIndex(map, 1.0, 0.99), (unsigned int)1);
  492. ASSERT_EQ(worldToIndex(map, 9.99, 9.99), (unsigned int)99);
  493. ASSERT_EQ(worldToIndex(map, 8.2, 3.4), (unsigned int)38);
  494. // Ensure we hit the middle of the cell for world co-ordinates
  495. double wx, wy;
  496. indexToWorld(map, 99, wx, wy);
  497. ASSERT_EQ(wx, 9.5);
  498. ASSERT_EQ(wy, 9.5);
  499. }
  500. /**
  501. * Verify that dynamic obstacles are added
  502. */
  503. TEST(costmap, testDynamicObstacles){
  504. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  505. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  506. // Add a point cloud and verify its insertion. There should be only one new one
  507. pcl::PointCloud<pcl::PointXYZ> cloud;
  508. cloud.points.resize(3);
  509. cloud.points[0].x = 0;
  510. cloud.points[0].y = 0;
  511. cloud.points[1].x = 0;
  512. cloud.points[1].y = 0;
  513. cloud.points[2].x = 0;
  514. cloud.points[2].y = 0;
  515. geometry_msgs::Point p;
  516. p.x = 0.0;
  517. p.y = 0.0;
  518. p.z = MAX_Z;
  519. Observation obs(p, cloud, 100.0, 100.0);
  520. std::vector<Observation> obsBuf;
  521. obsBuf.push_back(obs);
  522. map.updateWorld(0, 0, obsBuf, obsBuf);
  523. std::vector<unsigned int> ids;
  524. for(unsigned int i = 0; i < 10; ++i){
  525. for(unsigned int j = 0; j < 10; ++j){
  526. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  527. ids.push_back(map.getIndex(i, j));
  528. }
  529. }
  530. }
  531. // Should now have 1 insertion and no deletions
  532. ASSERT_EQ(ids.size(), (unsigned int)21);
  533. // Repeating the call - we should see no insertions or deletions
  534. map.updateWorld(0, 0, obsBuf, obsBuf);
  535. ASSERT_EQ(ids.size(), (unsigned int)21);
  536. }
  537. /**
  538. * Verify that if we add a point that is already a static obstacle we do not end up with a new ostacle
  539. */
  540. TEST(costmap, testMultipleAdditions){
  541. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  542. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  543. // A point cloud with one point that falls within an existing obstacle
  544. pcl::PointCloud<pcl::PointXYZ> cloud;
  545. cloud.points.resize(1);
  546. cloud.points[0].x = 7;
  547. cloud.points[0].y = 2;
  548. geometry_msgs::Point p;
  549. p.x = 0.0;
  550. p.y = 0.0;
  551. p.z = MAX_Z;
  552. Observation obs(p, cloud, 100.0, 100.0);
  553. std::vector<Observation> obsBuf;
  554. obsBuf.push_back(obs);
  555. map.updateWorld(0, 0, obsBuf, obsBuf);
  556. std::vector<unsigned int> ids;
  557. for(unsigned int i = 0; i < 10; ++i){
  558. for(unsigned int j = 0; j < 10; ++j){
  559. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  560. ids.push_back(map.getIndex(i, j));
  561. }
  562. }
  563. }
  564. ASSERT_EQ(ids.size(), (unsigned int)20);
  565. }
  566. /**
  567. * Make sure we ignore points outside of our z threshold
  568. */
  569. TEST(costmap, testZThreshold){
  570. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  571. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  572. // A point cloud with 2 points falling in a cell with a non-lethal cost
  573. pcl::PointCloud<pcl::PointXYZ> c0;
  574. c0.points.resize(2);
  575. c0.points[0].x = 0;
  576. c0.points[0].y = 5;
  577. c0.points[0].z = 0.4;
  578. c0.points[1].x = 1;
  579. c0.points[1].y = 5;
  580. c0.points[1].z = 1.2;
  581. geometry_msgs::Point p;
  582. p.x = 0.0;
  583. p.y = 0.0;
  584. p.z = MAX_Z;
  585. Observation obs(p, c0, 100.0, 100.0);
  586. std::vector<Observation> obsBuf;
  587. obsBuf.push_back(obs);
  588. map.updateWorld(0, 0, obsBuf, obsBuf);
  589. std::vector<unsigned int> ids;
  590. for(unsigned int i = 0; i < 10; ++i){
  591. for(unsigned int j = 0; j < 10; ++j){
  592. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  593. ids.push_back(map.getIndex(i, j));
  594. }
  595. }
  596. }
  597. ASSERT_EQ(ids.size(), (unsigned int)21);
  598. }
  599. /**
  600. * Test inflation for both static and dynamic obstacles
  601. */
  602. TEST(costmap, testInflation){
  603. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  604. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  605. // Verify that obstacles correctly identified
  606. std::vector<unsigned int> occupiedCells;
  607. for(unsigned int i = 0; i < 10; ++i){
  608. for(unsigned int j = 0; j < 10; ++j){
  609. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
  610. occupiedCells.push_back(map.getIndex(i, j));
  611. }
  612. }
  613. }
  614. // There should be no duplicates
  615. std::set<unsigned int> setOfCells;
  616. for(unsigned int i=0;i<occupiedCells.size(); i++)
  617. setOfCells.insert(i);
  618. ASSERT_EQ(setOfCells.size(), occupiedCells.size());
  619. ASSERT_EQ(setOfCells.size(), (unsigned int)48);
  620. // Iterate over all id's and verify they are obstacles
  621. for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
  622. unsigned int ind = *it;
  623. unsigned int x, y;
  624. map.indexToCells(ind, x, y);
  625. ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
  626. ASSERT_EQ(map.getCost(x, y) == costmap_2d::LETHAL_OBSTACLE || map.getCost(x, y) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  627. }
  628. // Set an obstacle at the origin and observe insertions for it and its neighbors
  629. pcl::PointCloud<pcl::PointXYZ> c0;
  630. c0.points.resize(1);
  631. c0.points[0].x = 0;
  632. c0.points[0].y = 0;
  633. c0.points[0].z = 0.4;
  634. geometry_msgs::Point p;
  635. p.x = 0.0;
  636. p.y = 0.0;
  637. p.z = MAX_Z;
  638. Observation obs(p, c0, 100.0, 100.0);
  639. std::vector<Observation> obsBuf, empty;
  640. obsBuf.push_back(obs);
  641. map.updateWorld(0, 0, obsBuf, empty);
  642. occupiedCells.clear();
  643. for(unsigned int i = 0; i < 10; ++i){
  644. for(unsigned int j = 0; j < 10; ++j){
  645. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
  646. occupiedCells.push_back(map.getIndex(i, j));
  647. }
  648. }
  649. }
  650. // It and its 2 neighbors makes 3 obstacles
  651. ASSERT_EQ(occupiedCells.size(), (unsigned int)51);
  652. // @todo Rewrite
  653. // Add an obstacle at <2,0> which will inflate and refresh to of the other inflated cells
  654. pcl::PointCloud<pcl::PointXYZ> c1;
  655. c1.points.resize(1);
  656. c1.points[0].x = 2;
  657. c1.points[0].y = 0;
  658. c1.points[0].z = 0.0;
  659. geometry_msgs::Point p1;
  660. p1.x = 0.0;
  661. p1.y = 0.0;
  662. p1.z = MAX_Z;
  663. Observation obs1(p1, c1, 100.0, 100.0);
  664. std::vector<Observation> obsBuf1;
  665. obsBuf1.push_back(obs1);
  666. map.updateWorld(0, 0, obsBuf1, empty);
  667. occupiedCells.clear();
  668. for(unsigned int i = 0; i < 10; ++i){
  669. for(unsigned int j = 0; j < 10; ++j){
  670. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
  671. occupiedCells.push_back(map.getIndex(i, j));
  672. }
  673. }
  674. }
  675. // Now we expect insertions for it, and 2 more neighbors, but not all 5. Free space will propagate from
  676. // the origin to the target, clearing the point at <0, 0>, but not over-writing the inflation of the obstacle
  677. // at <0, 1>
  678. ASSERT_EQ(occupiedCells.size(), (unsigned int)54);
  679. // Add an obstacle at <1, 9>. This will inflate obstacles around it
  680. pcl::PointCloud<pcl::PointXYZ> c2;
  681. c2.points.resize(1);
  682. c2.points[0].x = 1;
  683. c2.points[0].y = 9;
  684. c2.points[0].z = 0.0;
  685. geometry_msgs::Point p2;
  686. p2.x = 0.0;
  687. p2.y = 0.0;
  688. p2.z = MAX_Z;
  689. Observation obs2(p2, c2, 100.0, 100.0);
  690. std::vector<Observation> obsBuf2;
  691. obsBuf2.push_back(obs2);
  692. map.updateWorld(0, 0, obsBuf2, empty);
  693. ASSERT_EQ(map.getCost(1, 9), costmap_2d::LETHAL_OBSTACLE);
  694. ASSERT_EQ(map.getCost(0, 9), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
  695. ASSERT_EQ(map.getCost(2, 9), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
  696. // Add an obstacle and verify that it over-writes its inflated status
  697. pcl::PointCloud<pcl::PointXYZ> c3;
  698. c3.points.resize(1);
  699. c3.points[0].x = 0;
  700. c3.points[0].y = 9;
  701. c3.points[0].z = 0.0;
  702. geometry_msgs::Point p3;
  703. p3.x = 0.0;
  704. p3.y = 0.0;
  705. p3.z = MAX_Z;
  706. Observation obs3(p3, c3, 100.0, 100.0);
  707. std::vector<Observation> obsBuf3;
  708. obsBuf3.push_back(obs3);
  709. map.updateWorld(0, 0, obsBuf3, empty);
  710. ASSERT_EQ(map.getCost(0, 9), costmap_2d::LETHAL_OBSTACLE);
  711. }
  712. /**
  713. * Test specific inflation scenario to ensure we do not set inflated obstacles to be raw obstacles.
  714. */
  715. TEST(costmap, testInflation2){
  716. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  717. 10.0, MAX_Z, 10.0, 25, MAP_10_BY_10, THRESHOLD);
  718. // Creat a small L-Shape all at once
  719. pcl::PointCloud<pcl::PointXYZ> c0;
  720. c0.points.resize(3);
  721. c0.points[0].x = 1;
  722. c0.points[0].y = 1;
  723. c0.points[0].z = MAX_Z;
  724. c0.points[1].x = 1;
  725. c0.points[1].y = 2;
  726. c0.points[1].z = MAX_Z;
  727. c0.points[2].x = 2;
  728. c0.points[2].y = 2;
  729. c0.points[2].z = MAX_Z;
  730. geometry_msgs::Point p;
  731. p.x = 0.0;
  732. p.y = 0.0;
  733. p.z = MAX_Z;
  734. Observation obs(p, c0, 100.0, 100.0);
  735. std::vector<Observation> obsBuf;
  736. obsBuf.push_back(obs);
  737. map.updateWorld(0, 0, obsBuf, obsBuf);
  738. ASSERT_EQ(map.getCost(3, 2), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
  739. ASSERT_EQ(map.getCost(3, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
  740. }
  741. /**
  742. * Test inflation behavior, starting with an empty map
  743. */
  744. TEST(costmap, testInflation3){
  745. std::vector<unsigned char> mapData;
  746. for(unsigned int i=0; i< GRID_WIDTH; i++){
  747. for(unsigned int j = 0; j < GRID_HEIGHT; j++){
  748. mapData.push_back(0);
  749. }
  750. }
  751. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS * 2, ROBOT_RADIUS * 3,
  752. 10.0, MAX_Z, 10.0, 1, mapData, THRESHOLD);
  753. // There should be no occupied cells
  754. std::vector<unsigned int> ids;
  755. for(unsigned int i = 0; i < 10; ++i){
  756. for(unsigned int j = 0; j < 10; ++j){
  757. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
  758. ids.push_back(map.getIndex(i, j));
  759. }
  760. }
  761. }
  762. ASSERT_EQ(ids.size(), (unsigned int)0);
  763. // Add an obstacle at 5,5
  764. pcl::PointCloud<pcl::PointXYZ> c0;
  765. c0.points.resize(1);
  766. c0.points[0].x = 5;
  767. c0.points[0].y = 5;
  768. c0.points[0].z = MAX_Z;
  769. geometry_msgs::Point p;
  770. p.x = 0.0;
  771. p.y = 0.0;
  772. p.z = MAX_Z;
  773. Observation obs(p, c0, 100.0, 100.0);
  774. std::vector<Observation> obsBuf;
  775. obsBuf.push_back(obs);
  776. map.updateWorld(0, 0, obsBuf, obsBuf);
  777. for(unsigned int i = 0; i < 10; ++i){
  778. for(unsigned int j = 0; j < 10; ++j){
  779. if(map.getCost(i, j) != costmap_2d::FREE_SPACE){
  780. ids.push_back(map.getIndex(i, j));
  781. }
  782. }
  783. }
  784. ASSERT_EQ(ids.size(), (unsigned int)29);
  785. ids.clear();
  786. for(unsigned int i = 0; i < 10; ++i){
  787. for(unsigned int j = 0; j < 10; ++j){
  788. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE || map.getCost(i, j) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
  789. ids.push_back(map.getIndex(i, j));
  790. }
  791. }
  792. }
  793. ASSERT_EQ(ids.size(), (unsigned int)5);
  794. // Update again - should see no change
  795. map.updateWorld(0, 0, obsBuf, obsBuf);
  796. ids.clear();
  797. for(unsigned int i = 0; i < 10; ++i){
  798. for(unsigned int j = 0; j < 10; ++j){
  799. if(map.getCost(i, j) != costmap_2d::FREE_SPACE){
  800. ids.push_back(map.getIndex(i, j));
  801. }
  802. }
  803. }
  804. ASSERT_EQ(ids.size(), (unsigned int)29);
  805. }
  806. /**
  807. * Test for ray tracing free space
  808. */
  809. TEST(costmap, testRaytracing2){
  810. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  811. 100.0, MAX_Z, 100.0, 1, MAP_10_BY_10, THRESHOLD);
  812. // The sensor origin will be <0,0>. So if we add an obstacle at 9,9, we would expect cells
  813. // <0, 0> thru <8, 8> to be traced through
  814. pcl::PointCloud<pcl::PointXYZ> c0;
  815. c0.points.resize(1);
  816. c0.points[0].x = 9.5;
  817. c0.points[0].y = 9.5;
  818. c0.points[0].z = MAX_Z;
  819. geometry_msgs::Point p;
  820. p.x = 0.5;
  821. p.y = 0.5;
  822. p.z = MAX_Z;
  823. Observation obs(p, c0, 100.0, 100.0);
  824. std::vector<Observation> obsBuf;
  825. obsBuf.push_back(obs);
  826. std::vector<unsigned int> obstacles;
  827. for(unsigned int i = 0; i < 10; ++i){
  828. for(unsigned int j = 0; j < 10; ++j){
  829. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  830. obstacles.push_back(map.getIndex(i, j));
  831. }
  832. }
  833. }
  834. unsigned int obs_before = obstacles.size();
  835. map.updateWorld(0, 0, obsBuf, obsBuf);
  836. obstacles.clear();
  837. for(unsigned int i = 0; i < 10; ++i){
  838. for(unsigned int j = 0; j < 10; ++j){
  839. if(map.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE){
  840. obstacles.push_back(map.getIndex(i, j));
  841. }
  842. }
  843. }
  844. //Two obstacles shoulb be removed from the map by raytracing
  845. ASSERT_EQ(obstacles.size(), obs_before - 2);
  846. // many cells will have been switched to free space along the diagonal except
  847. // for those inflated in the update.. tests that inflation happens properly
  848. // after raytracing
  849. unsigned char test[10]= {0, 0, 0, 253, 253, 0, 0, 253, 253, 254};
  850. for(unsigned int i=0; i < 10; i++)
  851. ASSERT_EQ(map.getCost(i, i), test[i]);
  852. }
  853. /**
  854. * Within a certian radius of the robot, the cost map most propagate obstacles. This
  855. * is to avoid a case where a hit on a far obstacle clears inscribed radius around a
  856. * near one.
  857. */
  858. TEST(costmap, testTrickyPropagation){
  859. const unsigned char MAP_HALL_CHAR[10 * 10] = {
  860. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  861. 254, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  862. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  863. 0, 0, 0, 254, 0, 0, 0, 0, 0, 0,
  864. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  865. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  866. 0, 0, 0, 0, 0, 254, 0, 0, 0, 0,
  867. 0, 0, 0, 0, 0, 254, 0, 0, 0, 0,
  868. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  869. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  870. };
  871. std::vector<unsigned char> MAP_HALL;
  872. for (int i = 0; i < 10 * 10; i++) {
  873. MAP_HALL.push_back(MAP_HALL_CHAR[i]);
  874. }
  875. Costmap2D map(GRID_WIDTH, GRID_HEIGHT, RESOLUTION, 0.0, 0.0, ROBOT_RADIUS, ROBOT_RADIUS, ROBOT_RADIUS,
  876. 100.0, MAX_Z, 100.0, 1, MAP_HALL, THRESHOLD);
  877. //Add a dynamic obstacle
  878. pcl::PointCloud<pcl::PointXYZ> c2;
  879. c2.points.resize(3);
  880. //Dynamic obstacle that raytaces.
  881. c2.points[0].x = 7.0;
  882. c2.points[0].y = 8.0;
  883. c2.points[0].z = 1.0;
  884. //Dynamic obstacle that should not be raytraced the
  885. //first update, but should on the second.
  886. c2.points[1].x = 3.0;
  887. c2.points[1].y = 4.0;
  888. c2.points[1].z = 1.0;
  889. //Dynamic obstacle that should not be erased.
  890. c2.points[2].x = 6.0;
  891. c2.points[2].y = 3.0;
  892. c2.points[2].z = 1.0;
  893. geometry_msgs::Point p2;
  894. p2.x = 0.5;
  895. p2.y = 0.5;
  896. p2.z = MAX_Z;
  897. Observation obs2(p2, c2, 100.0, 100.0);
  898. std::vector<Observation> obsBuf2;
  899. obsBuf2.push_back(obs2);
  900. map.updateWorld(0, 0, obsBuf2, obsBuf2);
  901. const unsigned char MAP_HALL_CHAR_TEST[10 * 10] = {
  902. 253, 254, 253, 0, 0, 0, 0, 0, 0, 0,
  903. 0, 253, 0, 0, 0, 0, 0, 0, 0, 0,
  904. 0, 0, 0, 0, 253, 0, 0, 0, 0, 0,
  905. 0, 0, 0, 253, 254, 253, 0, 0, 0, 0,
  906. 0, 0, 0, 0, 253, 0, 0, 253, 0, 0,
  907. 0, 0, 0, 253, 0, 0, 253, 254, 253, 0,
  908. 0, 0, 253, 254, 253, 0, 0, 253, 253, 0,
  909. 0, 0, 0, 253, 0, 0, 0, 253, 254, 253,
  910. 0, 0, 0, 0, 0, 0, 0, 0, 253, 0,
  911. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  912. };
  913. for (int i = 0; i < 10 * 10; i++) {
  914. ASSERT_EQ(map.getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST[i]);
  915. }
  916. pcl::PointCloud<pcl::PointXYZ> c;
  917. c.points.resize(1);
  918. //Dynamic obstacle that raytaces the one at (3.0, 4.0).
  919. c.points[0].x = 4.0;
  920. c.points[0].y = 5.0;
  921. c.points[0].z = 1.0;
  922. geometry_msgs::Point p3;
  923. p3.x = 0.5;
  924. p3.y = 0.5;
  925. p3.z = MAX_Z;
  926. Observation obs3(p3, c, 100.0, 100.0);
  927. std::vector<Observation> obsBuf3;
  928. obsBuf3.push_back(obs3);
  929. map.updateWorld(0, 0, obsBuf3, obsBuf3);
  930. const unsigned char MAP_HALL_CHAR_TEST2[10 * 10] = {
  931. 253, 254, 253, 0, 0, 0, 0, 0, 0, 0,
  932. 0, 253, 0, 0, 0, 0, 0, 0, 0, 0,
  933. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  934. 0, 0, 0, 0, 0, 253, 0, 0, 0, 0,
  935. 0, 0, 0, 0, 253, 254, 253, 253, 0, 0,
  936. 0, 0, 0, 253, 0, 253, 253, 254, 253, 0,
  937. 0, 0, 253, 254, 253, 0, 0, 253, 253, 0,
  938. 0, 0, 0, 253, 0, 0, 0, 253, 254, 253,
  939. 0, 0, 0, 0, 0, 0, 0, 0, 253, 0,
  940. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  941. };
  942. for (int i = 0; i < 10 * 10; i++) {
  943. ASSERT_EQ(map.getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST2[i]);
  944. }
  945. }
  946. int main(int argc, char** argv){
  947. for(unsigned int i = 0; i< GRID_WIDTH * GRID_HEIGHT; i++){
  948. EMPTY_10_BY_10.push_back(0);
  949. MAP_10_BY_10.push_back(MAP_10_BY_10_CHAR[i]);
  950. }
  951. for(unsigned int i = 0; i< 5 * 5; i++){
  952. MAP_5_BY_5.push_back(MAP_10_BY_10_CHAR[i]);
  953. }
  954. for(unsigned int i = 0; i< 100 * 100; i++)
  955. EMPTY_100_BY_100.push_back(0);
  956. testing::InitGoogleTest(&argc, argv);
  957. return RUN_ALL_TESTS();
  958. }