costmap_tester.cpp 6.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146
  1. /*********************************************************************
  2. *
  3. * Software License Agreement (BSD License)
  4. *
  5. * Copyright (c) 2009, Willow Garage, Inc.
  6. * All rights reserved.
  7. *
  8. * Redistribution and use in source and binary forms, with or without
  9. * modification, are permitted provided that the following conditions
  10. * are met:
  11. *
  12. * * Redistributions of source code must retain the above copyright
  13. * notice, this list of conditions and the following disclaimer.
  14. * * Redistributions in binary form must reproduce the above
  15. * copyright notice, this list of conditions and the following
  16. * disclaimer in the documentation and/or other materials provided
  17. * with the distribution.
  18. * * Neither the name of Willow Garage, Inc. nor the names of its
  19. * contributors may be used to endorse or promote products derived
  20. * from this software without specific prior written permission.
  21. *
  22. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  23. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  24. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  25. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  26. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  27. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  28. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  29. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  30. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  31. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  32. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  33. * POSSIBILITY OF SUCH DAMAGE.
  34. *
  35. * Author: Eitan Marder-Eppstein
  36. *********************************************************************/
  37. #include <gtest/gtest.h>
  38. #include <ros/ros.h>
  39. #include <costmap_2d/costmap_2d_ros.h>
  40. #include <costmap_2d/cost_values.h>
  41. #include <tf2_ros/transform_listener.h>
  42. namespace costmap_2d {
  43. class CostmapTester : public testing::Test {
  44. public:
  45. CostmapTester(tf2_ros::Buffer& tf);
  46. void checkConsistentCosts();
  47. void compareCellToNeighbors(costmap_2d::Costmap2D& costmap, unsigned int x, unsigned int y);
  48. void compareCells(costmap_2d::Costmap2D& costmap,
  49. unsigned int x, unsigned int y, unsigned int nx, unsigned int ny);
  50. virtual void TestBody(){}
  51. private:
  52. costmap_2d::Costmap2DROS costmap_ros_;
  53. };
  54. CostmapTester::CostmapTester(tf2_ros::Buffer& tf): costmap_ros_("test_costmap", tf){}
  55. void CostmapTester::checkConsistentCosts(){
  56. costmap_2d::Costmap2D* costmap = costmap_ros_.getCostmap();
  57. //get a copy of the costmap contained by our ros wrapper
  58. costmap->saveMap("costmap_test.pgm");
  59. //loop through the costmap and check for any unexpected drop-offs in costs
  60. for(unsigned int i = 0; i < costmap->getSizeInCellsX(); ++i){
  61. for(unsigned int j = 0; j < costmap->getSizeInCellsY(); ++j){
  62. compareCellToNeighbors(*costmap, i, j);
  63. }
  64. }
  65. }
  66. void CostmapTester::compareCellToNeighbors(costmap_2d::Costmap2D& costmap, unsigned int x, unsigned int y){
  67. //we'll compare the cost of this cell with that of its eight neighbors to see if they're reasonable
  68. for(int offset_x = -1; offset_x <= 1; ++offset_x){
  69. for(int offset_y = -1; offset_y <= 1; ++offset_y){
  70. int nx = x + offset_x;
  71. int ny = y + offset_y;
  72. //check to make sure that the neighbor cell is a legal one
  73. if(nx >= 0 && nx < (int)costmap.getSizeInCellsX() && ny >=0 && ny < (int)costmap.getSizeInCellsY()){
  74. compareCells(costmap, x, y, nx, ny);
  75. }
  76. }
  77. }
  78. }
  79. //for all lethal and inscribed costs, we'll make sure that their neighbors have the cost values we'd expect
  80. void CostmapTester::compareCells(costmap_2d::Costmap2D& costmap, unsigned int x, unsigned int y, unsigned int nx, unsigned int ny){
  81. double cell_distance = hypot(static_cast<int>(x-nx), static_cast<int>(y-ny));
  82. unsigned char cell_cost = costmap.getCost(x, y);
  83. unsigned char neighbor_cost = costmap.getCost(nx, ny);
  84. if(cell_cost == costmap_2d::LETHAL_OBSTACLE){
  85. //if the cell is a lethal obstacle, then we know that all its neighbors should have equal or slighlty less cost
  86. unsigned char expected_lowest_cost = 0; // ################costmap.computeCost(cell_distance);
  87. EXPECT_TRUE(neighbor_cost >= expected_lowest_cost || (cell_distance > 0 /*costmap.cell_inflation_radius_*/ && neighbor_cost == costmap_2d::FREE_SPACE));
  88. }
  89. else if(cell_cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
  90. //the furthest valid distance from an obstacle is the inscribed radius plus the cell distance away
  91. double furthest_valid_distance = 0; // ################costmap.cell_inscribed_radius_ + cell_distance + 1;
  92. unsigned char expected_lowest_cost = 0; // ################costmap.computeCost(furthest_valid_distance);
  93. if(neighbor_cost < expected_lowest_cost){
  94. ROS_ERROR("Cell cost (%d, %d): %d, neighbor cost (%d, %d): %d, expected lowest cost: %d, cell distance: %.2f, furthest valid distance: %.2f",
  95. x, y, cell_cost, nx, ny, neighbor_cost, expected_lowest_cost, cell_distance, furthest_valid_distance);
  96. ROS_ERROR("Cell: (%d, %d), Neighbor: (%d, %d)", x, y, nx, ny);
  97. costmap.saveMap("failing_costmap.pgm");
  98. }
  99. EXPECT_TRUE(neighbor_cost >= expected_lowest_cost || (furthest_valid_distance > 0/* costmap.cell_inflation_radius_ */&& neighbor_cost == costmap_2d::FREE_SPACE));
  100. }
  101. }
  102. };
  103. costmap_2d::CostmapTester* map_tester = NULL;
  104. TEST(CostmapTester, checkConsistentCosts){
  105. map_tester->checkConsistentCosts();
  106. }
  107. void testCallback(const ros::TimerEvent& e){
  108. int test_result = RUN_ALL_TESTS();
  109. ROS_INFO("gtest return value: %d", test_result);
  110. ros::shutdown();
  111. }
  112. int main(int argc, char** argv){
  113. ros::init(argc, argv, "costmap_tester_node");
  114. testing::InitGoogleTest(&argc, argv);
  115. ros::NodeHandle n;
  116. ros::NodeHandle private_nh("~");
  117. tf2_ros::Buffer tf(ros::Duration(10));
  118. tf2_ros::TransformListener tfl(tf);
  119. map_tester = new costmap_2d::CostmapTester(tf);
  120. double wait_time;
  121. private_nh.param("wait_time", wait_time, 30.0);
  122. ros::Timer timer = n.createTimer(ros::Duration(wait_time), testCallback);
  123. ros::spin();
  124. return(0);
  125. }