inflation_tests.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417
  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 InflationLayer for Costmap2D
  32. */
  33. #include <map>
  34. #include <cmath>
  35. #include <costmap_2d/costmap_2d.h>
  36. #include <costmap_2d/layered_costmap.h>
  37. #include <costmap_2d/obstacle_layer.h>
  38. #include <costmap_2d/inflation_layer.h>
  39. #include <costmap_2d/observation_buffer.h>
  40. #include <costmap_2d/testing_helper.h>
  41. #include <gtest/gtest.h>
  42. using namespace costmap_2d;
  43. using geometry_msgs::Point;
  44. std::vector<Point> setRadii(LayeredCostmap& layers, double length, double width, double inflation_radius)
  45. {
  46. std::vector<Point> polygon;
  47. Point p;
  48. p.x = width;
  49. p.y = length;
  50. polygon.push_back(p);
  51. p.x = width;
  52. p.y = -length;
  53. polygon.push_back(p);
  54. p.x = -width;
  55. p.y = -length;
  56. polygon.push_back(p);
  57. p.x = -width;
  58. p.y = length;
  59. polygon.push_back(p);
  60. layers.setFootprint(polygon);
  61. ros::NodeHandle nh;
  62. nh.setParam("/inflation_tests/inflation/inflation_radius", inflation_radius);
  63. return polygon;
  64. }
  65. // Test that a single point gets inflated properly
  66. void validatePointInflation(unsigned int mx, unsigned int my, Costmap2D* costmap, InflationLayer* ilayer, double inflation_radius)
  67. {
  68. bool* seen = new bool[costmap->getSizeInCellsX() * costmap->getSizeInCellsY()];
  69. memset(seen, false, costmap->getSizeInCellsX() * costmap->getSizeInCellsY() * sizeof(bool));
  70. std::map<double, std::vector<CellData> > m;
  71. CellData initial(costmap->getIndex(mx, my), mx, my, mx, my);
  72. m[0].push_back(initial);
  73. for (std::map<double, std::vector<CellData> >::iterator bin = m.begin(); bin != m.end(); ++bin)
  74. {
  75. for (int i = 0; i < bin->second.size(); ++i)
  76. {
  77. const CellData& cell = bin->second[i];
  78. if (!seen[cell.index_])
  79. {
  80. seen[cell.index_] = true;
  81. unsigned int dx = (cell.x_ > cell.src_x_) ? cell.x_ - cell.src_x_ : cell.src_x_ - cell.x_;
  82. unsigned int dy = (cell.y_ > cell.src_y_) ? cell.y_ - cell.src_y_ : cell.src_y_ - cell.y_;
  83. double dist = hypot(dx, dy);
  84. unsigned char expected_cost = ilayer->computeCost(dist);
  85. ASSERT_TRUE(costmap->getCost(cell.x_, cell.y_) >= expected_cost);
  86. if (dist > inflation_radius)
  87. {
  88. continue;
  89. }
  90. if (dist == bin->first)
  91. {
  92. // Adding to our current bin could cause a reallocation
  93. // Which appears to cause the iterator to get messed up
  94. dist += 0.001;
  95. }
  96. if (cell.x_ > 0)
  97. {
  98. CellData data(costmap->getIndex(cell.x_-1, cell.y_),
  99. cell.x_-1, cell.y_, cell.src_x_, cell.src_y_);
  100. m[dist].push_back(data);
  101. }
  102. if (cell.y_ > 0)
  103. {
  104. CellData data(costmap->getIndex(cell.x_, cell.y_-1),
  105. cell.x_, cell.y_-1, cell.src_x_, cell.src_y_);
  106. m[dist].push_back(data);
  107. }
  108. if (cell.x_ < costmap->getSizeInCellsX() - 1)
  109. {
  110. CellData data(costmap->getIndex(cell.x_+1, cell.y_),
  111. cell.x_+1, cell.y_, cell.src_x_, cell.src_y_);
  112. m[dist].push_back(data);
  113. }
  114. if (cell.y_ < costmap->getSizeInCellsY() - 1)
  115. {
  116. CellData data(costmap->getIndex(cell.x_, cell.y_+1),
  117. cell.x_, cell.y_+1, cell.src_x_, cell.src_y_);
  118. m[dist].push_back(data);
  119. }
  120. }
  121. }
  122. }
  123. delete[] seen;
  124. }
  125. TEST(costmap, testAdjacentToObstacleCanStillMove){
  126. tf2_ros::Buffer tf;
  127. LayeredCostmap layers("frame", false, false);
  128. layers.resizeMap(10, 10, 1, 0, 0);
  129. // Footprint with inscribed radius = 2.1
  130. // circumscribed radius = 3.1
  131. std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
  132. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  133. InflationLayer* ilayer = addInflationLayer(layers, tf);
  134. layers.setFootprint(polygon);
  135. addObservation(olayer, 0, 0, MAX_Z);
  136. layers.updateMap(0,0,0);
  137. Costmap2D* costmap = layers.getCostmap();
  138. //printMap(*costmap);
  139. EXPECT_EQ( LETHAL_OBSTACLE, costmap->getCost( 0, 0 ));
  140. EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 0 ));
  141. EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 2, 0 ));
  142. EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 3, 0 ));
  143. EXPECT_TRUE( INSCRIBED_INFLATED_OBSTACLE > costmap->getCost( 2, 1 ));
  144. EXPECT_EQ( INSCRIBED_INFLATED_OBSTACLE, costmap->getCost( 1, 1 ));
  145. }
  146. TEST(costmap, testInflationShouldNotCreateUnknowns){
  147. tf2_ros::Buffer tf;
  148. LayeredCostmap layers("frame", false, false);
  149. layers.resizeMap(10, 10, 1, 0, 0);
  150. // Footprint with inscribed radius = 2.1
  151. // circumscribed radius = 3.1
  152. std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, 4.1);
  153. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  154. InflationLayer* ilayer = addInflationLayer(layers, tf);
  155. layers.setFootprint(polygon);
  156. addObservation(olayer, 0, 0, MAX_Z);
  157. layers.updateMap(0,0,0);
  158. Costmap2D* costmap = layers.getCostmap();
  159. EXPECT_EQ( countValues(*costmap, NO_INFORMATION), 0 );
  160. }
  161. /**
  162. * Test for the cost function correctness with a larger range and different values
  163. */
  164. TEST(costmap, testCostFunctionCorrectness){
  165. tf2_ros::Buffer tf;
  166. LayeredCostmap layers("frame", false, false);
  167. layers.resizeMap(100, 100, 1, 0, 0);
  168. // Footprint with inscribed radius = 5.0
  169. // circumscribed radius = 8.0
  170. std::vector<Point> polygon = setRadii(layers, 5.0, 6.25, 10.5);
  171. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  172. InflationLayer* ilayer = addInflationLayer(layers, tf);
  173. layers.setFootprint(polygon);
  174. addObservation(olayer, 50, 50, MAX_Z);
  175. layers.updateMap(0,0,0);
  176. Costmap2D* map = layers.getCostmap();
  177. // Verify that the circumscribed cost lower bound is as expected: based on the cost function.
  178. //unsigned char c = ilayer->computeCost(8.0);
  179. //ASSERT_EQ(ilayer->getCircumscribedCost(), c);
  180. for(unsigned int i = 0; i <= (unsigned int)ceil(5.0); i++){
  181. // To the right
  182. ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  183. ASSERT_EQ(map->getCost(50 + i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  184. // To the left
  185. ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  186. ASSERT_EQ(map->getCost(50 - i, 50) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  187. // Down
  188. ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  189. ASSERT_EQ(map->getCost(50, 50 + i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  190. // Up
  191. ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  192. ASSERT_EQ(map->getCost(50, 50 - i) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  193. }
  194. // Verify the normalized cost attenuates as expected
  195. for(unsigned int i = (unsigned int)(ceil(5.0) + 1); i <= (unsigned int)ceil(10.5); i++){
  196. unsigned char expectedValue = ilayer->computeCost(i/1.0);
  197. ASSERT_EQ(map->getCost(50 + i, 50), expectedValue);
  198. }
  199. // Update with no hits. Should clear (revert to the static map
  200. /*map->resetMapOutsideWindow(0, 0, 0.0, 0.0);
  201. cloud.points.resize(0);
  202. p.x = 0.0;
  203. p.y = 0.0;
  204. p.z = MAX_Z;
  205. Observation obs2(p, cloud, 100.0, 100.0);
  206. std::vector<Observation> obsBuf2;
  207. obsBuf2.push_back(obs2);
  208. map->updateWorld(0, 0, obsBuf2, obsBuf2);
  209. for(unsigned int i = 0; i < 100; i++)
  210. for(unsigned int j = 0; j < 100; j++)
  211. ASSERT_EQ(map->getCost(i, j), costmap_2d::FREE_SPACE);*/
  212. }
  213. /**
  214. * Test that there is no regression and that costs do not get
  215. * underestimated with the distance-as-key map used to replace
  216. * the previously used priority queue. This is a more thorough
  217. * test of the cost function being correctly applied.
  218. */
  219. TEST(costmap, testInflationOrderCorrectness){
  220. tf2_ros::Buffer tf;
  221. LayeredCostmap layers("frame", false, false);
  222. layers.resizeMap(10, 10, 1, 0, 0);
  223. // Footprint with inscribed radius = 2.1
  224. // circumscribed radius = 3.1
  225. const double inflation_radius = 4.1;
  226. std::vector<Point> polygon = setRadii(layers, 2.1, 2.3, inflation_radius);
  227. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  228. InflationLayer* ilayer = addInflationLayer(layers, tf);
  229. layers.setFootprint(polygon);
  230. // Add two diagonal cells, they would induce problems under the
  231. // previous implementations
  232. addObservation(olayer, 4, 4, MAX_Z);
  233. addObservation(olayer, 5, 5, MAX_Z);
  234. layers.updateMap(0, 0, 0);
  235. validatePointInflation(4, 4, layers.getCostmap(), ilayer, inflation_radius);
  236. validatePointInflation(5, 5, layers.getCostmap(), ilayer, inflation_radius);
  237. }
  238. /**
  239. * Test inflation for both static and dynamic obstacles
  240. */
  241. TEST(costmap, testInflation){
  242. tf2_ros::Buffer tf;
  243. LayeredCostmap layers("frame", false, false);
  244. // Footprint with inscribed radius = 2.1
  245. // circumscribed radius = 3.1
  246. std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
  247. addStaticLayer(layers, tf);
  248. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  249. InflationLayer* ilayer = addInflationLayer(layers, tf);
  250. layers.setFootprint(polygon);
  251. Costmap2D* costmap = layers.getCostmap();
  252. layers.updateMap(0,0,0);
  253. //printMap(*costmap);
  254. ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)20);
  255. ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)28);
  256. /*/ Iterate over all id's and verify they are obstacles
  257. for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
  258. unsigned int ind = *it;
  259. unsigned int x, y;
  260. map.indexToCells(ind, x, y);
  261. ASSERT_EQ(find(occupiedCells, map.getIndex(x, y)), true);
  262. ASSERT_EQ(map.getCost(x, y) == costmap_2d::LETHAL_OBSTACLE || map.getCost(x, y) == costmap_2d::INSCRIBED_INFLATED_OBSTACLE, true);
  263. }*/
  264. addObservation(olayer, 0, 0, 0.4);
  265. layers.updateMap(0,0,0);
  266. // It and its 2 neighbors makes 3 obstacles
  267. ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)51);
  268. // @todo Rewrite
  269. // Add an obstacle at <2,0> which will inflate and refresh to of the other inflated cells
  270. addObservation(olayer, 2, 0);
  271. layers.updateMap(0,0,0);
  272. // Now we expect insertions for it, and 2 more neighbors, but not all 5. Free space will propagate from
  273. // the origin to the target, clearing the point at <0, 0>, but not over-writing the inflation of the obstacle
  274. // at <0, 1>
  275. ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE) + countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)54);
  276. // Add an obstacle at <1, 9>. This will inflate obstacles around it
  277. addObservation(olayer, 1, 9);
  278. layers.updateMap(0,0,0);
  279. ASSERT_EQ(costmap->getCost(1, 9), LETHAL_OBSTACLE);
  280. ASSERT_EQ(costmap->getCost(0, 9), INSCRIBED_INFLATED_OBSTACLE);
  281. ASSERT_EQ(costmap->getCost(2, 9), INSCRIBED_INFLATED_OBSTACLE);
  282. // Add an obstacle and verify that it over-writes its inflated status
  283. addObservation(olayer, 0, 9);
  284. layers.updateMap(0,0,0);
  285. ASSERT_EQ(costmap->getCost(0, 9), LETHAL_OBSTACLE);
  286. }
  287. /**
  288. * Test specific inflation scenario to ensure we do not set inflated obstacles to be raw obstacles.
  289. */
  290. TEST(costmap, testInflation2){
  291. tf2_ros::Buffer tf;
  292. LayeredCostmap layers("frame", false, false);
  293. // Footprint with inscribed radius = 2.1
  294. // circumscribed radius = 3.1
  295. std::vector<Point> polygon = setRadii(layers, 1, 1, 1);
  296. addStaticLayer(layers, tf);
  297. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  298. InflationLayer* ilayer = addInflationLayer(layers, tf);
  299. layers.setFootprint(polygon);
  300. // Creat a small L-Shape all at once
  301. addObservation(olayer, 1, 1, MAX_Z);
  302. addObservation(olayer, 2, 1, MAX_Z);
  303. addObservation(olayer, 2, 2, MAX_Z);
  304. layers.updateMap(0,0,0);
  305. Costmap2D* costmap = layers.getCostmap();
  306. //printMap(*costmap);
  307. ASSERT_EQ(costmap->getCost(2, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
  308. ASSERT_EQ(costmap->getCost(3, 3), costmap_2d::INSCRIBED_INFLATED_OBSTACLE);
  309. }
  310. /**
  311. * Test inflation behavior, starting with an empty map
  312. */
  313. TEST(costmap, testInflation3){
  314. tf2_ros::Buffer tf;
  315. LayeredCostmap layers("frame", false, false);
  316. layers.resizeMap(10, 10, 1, 0, 0);
  317. // 1 2 3
  318. std::vector<Point> polygon = setRadii(layers, 1, 1.75, 3);
  319. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  320. InflationLayer* ilayer = addInflationLayer(layers, tf);
  321. layers.setFootprint(polygon);
  322. // There should be no occupied cells
  323. Costmap2D* costmap = layers.getCostmap();
  324. ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)0);
  325. ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)0);
  326. printMap(*costmap);
  327. // Add an obstacle at 5,5
  328. addObservation(olayer, 5, 5, MAX_Z);
  329. layers.updateMap(0,0,0);
  330. printMap(*costmap);
  331. // Test fails because updated cell value is 0
  332. ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
  333. ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
  334. ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
  335. // Update again - should see no change
  336. layers.updateMap(0,0,0);
  337. ASSERT_EQ(countValues(*costmap, FREE_SPACE, false), (unsigned int)29);
  338. ASSERT_EQ(countValues(*costmap, LETHAL_OBSTACLE), (unsigned int)1);
  339. ASSERT_EQ(countValues(*costmap, INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4);
  340. }
  341. int main(int argc, char** argv){
  342. ros::init(argc, argv, "inflation_tests");
  343. testing::InitGoogleTest(&argc, argv);
  344. return RUN_ALL_TESTS();
  345. }