obstacle_tests.cpp 8.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251
  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 ObstacleLayer for Costmap2D
  32. */
  33. #include <costmap_2d/costmap_2d.h>
  34. #include <costmap_2d/layered_costmap.h>
  35. #include <costmap_2d/observation_buffer.h>
  36. #include <costmap_2d/testing_helper.h>
  37. #include <set>
  38. #include <gtest/gtest.h>
  39. using namespace costmap_2d;
  40. /*
  41. * For reference, the static map looks like this:
  42. *
  43. * 0 0 0 0 0 0 0 254 254 254
  44. *
  45. * 0 0 0 0 0 0 0 254 254 254
  46. *
  47. * 0 0 0 254 254 254 0 0 0 0
  48. *
  49. * 0 0 0 0 0 0 0 0 0 0
  50. *
  51. * 0 0 0 0 0 0 0 0 0 0
  52. *
  53. * 0 0 0 0 254 0 0 254 254 254
  54. *
  55. * 0 0 0 0 254 0 0 254 254 254
  56. *
  57. * 0 0 0 0 0 0 0 254 254 254
  58. *
  59. * 0 0 0 0 0 0 0 0 0 0
  60. *
  61. * 0 0 0 0 0 0 0 0 0 0
  62. *
  63. * upper left is 0,0, lower right is 9,9
  64. */
  65. /**
  66. * Test for ray tracing free space
  67. */
  68. TEST(costmap, testRaytracing){
  69. tf2_ros::Buffer tf;
  70. LayeredCostmap layers("frame", false, false); // Not rolling window, not tracking unknown
  71. addStaticLayer(layers, tf); // This adds the static map
  72. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  73. // Add a point at 0, 0, 0
  74. addObservation(olayer, 0.0, 0.0, MAX_Z/2, 0, 0, MAX_Z/2);
  75. // This actually puts the LETHAL (254) point in the costmap at (0,0)
  76. layers.updateMap(0,0,0); // 0, 0, 0 is robot pose
  77. //printMap(*(layers.getCostmap()));
  78. int lethal_count = countValues(*(layers.getCostmap()), LETHAL_OBSTACLE);
  79. // We expect just one obstacle to be added (20 in static map)
  80. ASSERT_EQ(lethal_count, 21);
  81. }
  82. /**
  83. * Test for ray tracing free space
  84. */
  85. TEST(costmap, testRaytracing2){
  86. tf2_ros::Buffer tf;
  87. LayeredCostmap layers("frame", false, false);
  88. addStaticLayer(layers, tf);
  89. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  90. //If we print map now, it is 10x10 all value 0
  91. //printMap(*(layers.getCostmap()));
  92. // Update will fill in the costmap with the static map
  93. layers.updateMap(0,0,0);
  94. //If we print the map now, we get the static map
  95. //printMap(*(layers.getCostmap()));
  96. // Static map has 20 LETHAL cells (see diagram above)
  97. int obs_before = countValues(*(layers.getCostmap()), LETHAL_OBSTACLE);
  98. ASSERT_EQ(obs_before, 20);
  99. // The sensor origin will be <0,0>. So if we add an obstacle at 9,9,
  100. // we would expect cells <0, 0> thru <8, 8> to be traced through
  101. // however the static map is not cleared by obstacle layer
  102. addObservation(olayer, 9.5, 9.5, MAX_Z/2, 0.5, 0.5, MAX_Z/2);
  103. layers.updateMap(0, 0, 0);
  104. // If we print map now, we have static map + <9,9> is LETHAL
  105. //printMap(*(layers.getCostmap()));
  106. int obs_after = countValues(*(layers.getCostmap()), LETHAL_OBSTACLE);
  107. // Change from previous test:
  108. // No obstacles from the static map will be cleared, so the
  109. // net change is +1.
  110. ASSERT_EQ(obs_after, obs_before + 1);
  111. // Fill in the diagonal, <7,7> and <9,9> already filled in, <0,0> is robot
  112. for(int i = 0; i < olayer->getSizeInCellsY(); ++i)
  113. {
  114. olayer->setCost(i, i, LETHAL_OBSTACLE);
  115. }
  116. // This will updateBounds, which will raytrace the static observation added
  117. // above, thus clearing out the diagonal again!
  118. layers.updateMap(0, 0, 0);
  119. // Map now has diagonal except <0,0> filled with LETHAL (254)
  120. //printMap(*(layers.getCostmap()));
  121. int with_static = countValues(*(layers.getCostmap()), LETHAL_OBSTACLE);
  122. // Should thus be the same
  123. ASSERT_EQ(with_static, obs_after);
  124. // If 21 are filled, 79 should be free
  125. ASSERT_EQ(79, countValues(*(layers.getCostmap()), costmap_2d::FREE_SPACE));
  126. }
  127. /**
  128. * Test for wave interference
  129. */
  130. TEST(costmap, testWaveInterference){
  131. tf2_ros::Buffer tf;
  132. // Start with an empty map, no rolling window, tracking unknown
  133. LayeredCostmap layers("frame", false, true);
  134. layers.resizeMap(10, 10, 1, 0, 0);
  135. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  136. // If we print map now, it is 10x10, all cells are 255 (NO_INFORMATION)
  137. //printMap(*(layers.getCostmap()));
  138. // Lay out 3 obstacles in a line - along the diagonal, separated by a cell.
  139. addObservation(olayer, 3.0, 3.0, MAX_Z);
  140. addObservation(olayer, 5.0, 5.0, MAX_Z);
  141. addObservation(olayer, 7.0, 7.0, MAX_Z);
  142. layers.updateMap(0,0,0);
  143. Costmap2D* costmap = layers.getCostmap();
  144. // 3 obstacle cells are filled, <1,1>,<2,2>,<4,4> and <6,6> are now free
  145. // <0,0> is footprint and is free
  146. //printMap(*costmap);
  147. ASSERT_EQ(3, countValues(*costmap, costmap_2d::LETHAL_OBSTACLE));
  148. ASSERT_EQ(92, countValues(*costmap, costmap_2d::NO_INFORMATION));
  149. ASSERT_EQ(5, countValues(*costmap, costmap_2d::FREE_SPACE));
  150. }
  151. /**
  152. * Make sure we ignore points outside of our z threshold
  153. */
  154. TEST(costmap, testZThreshold){
  155. tf2_ros::Buffer tf;
  156. // Start with an empty map
  157. LayeredCostmap layers("frame", false, true);
  158. layers.resizeMap(10, 10, 1, 0, 0);
  159. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  160. // A point cloud with 2 points falling in a cell with a non-lethal cost
  161. addObservation(olayer, 0.0, 5.0, 0.4);
  162. addObservation(olayer, 1.0, 5.0, 2.2);
  163. layers.updateMap(0,0,0);
  164. Costmap2D* costmap = layers.getCostmap();
  165. ASSERT_EQ(countValues(*costmap, costmap_2d::LETHAL_OBSTACLE), 1);
  166. }
  167. /**
  168. * Verify that dynamic obstacles are added
  169. */
  170. TEST(costmap, testDynamicObstacles){
  171. tf2_ros::Buffer tf;
  172. LayeredCostmap layers("frame", false, false);
  173. addStaticLayer(layers, tf);
  174. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  175. // Add a point cloud and verify its insertion. There should be only one new one
  176. addObservation(olayer, 0.0, 0.0);
  177. addObservation(olayer, 0.0, 0.0);
  178. addObservation(olayer, 0.0, 0.0);
  179. layers.updateMap(0,0,0);
  180. Costmap2D* costmap = layers.getCostmap();
  181. // Should now have 1 insertion and no deletions
  182. ASSERT_EQ(countValues(*costmap, costmap_2d::LETHAL_OBSTACLE), 21);
  183. // Repeating the call - we should see no insertions or deletions
  184. ASSERT_EQ(countValues(*costmap, costmap_2d::LETHAL_OBSTACLE), 21);
  185. }
  186. /**
  187. * Verify that if we add a point that is already a static obstacle we do not end up with a new ostacle
  188. */
  189. TEST(costmap, testMultipleAdditions){
  190. tf2_ros::Buffer tf;
  191. LayeredCostmap layers("frame", false, false);
  192. addStaticLayer(layers, tf);
  193. ObstacleLayer* olayer = addObstacleLayer(layers, tf);
  194. // A point cloud with one point that falls within an existing obstacle
  195. addObservation(olayer, 9.5, 0.0);
  196. layers.updateMap(0,0,0);
  197. Costmap2D* costmap = layers.getCostmap();
  198. //printMap(*costmap);
  199. ASSERT_EQ(countValues(*costmap, costmap_2d::LETHAL_OBSTACLE), 20);
  200. }
  201. int main(int argc, char** argv){
  202. ros::init(argc, argv, "obstacle_tests");
  203. testing::InitGoogleTest(&argc, argv);
  204. return RUN_ALL_TESTS();
  205. }