123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146 |
- #include <gtest/gtest.h>
- #include <ros/ros.h>
- #include <costmap_2d/costmap_2d_ros.h>
- #include <costmap_2d/cost_values.h>
- #include <tf2_ros/transform_listener.h>
- namespace costmap_2d {
- class CostmapTester : public testing::Test {
- public:
- CostmapTester(tf2_ros::Buffer& tf);
- void checkConsistentCosts();
- void compareCellToNeighbors(costmap_2d::Costmap2D& costmap, unsigned int x, unsigned int y);
- void compareCells(costmap_2d::Costmap2D& costmap,
- unsigned int x, unsigned int y, unsigned int nx, unsigned int ny);
- virtual void TestBody(){}
- private:
- costmap_2d::Costmap2DROS costmap_ros_;
- };
- CostmapTester::CostmapTester(tf2_ros::Buffer& tf): costmap_ros_("test_costmap", tf){}
- void CostmapTester::checkConsistentCosts(){
- costmap_2d::Costmap2D* costmap = costmap_ros_.getCostmap();
-
- costmap->saveMap("costmap_test.pgm");
-
- for(unsigned int i = 0; i < costmap->getSizeInCellsX(); ++i){
- for(unsigned int j = 0; j < costmap->getSizeInCellsY(); ++j){
- compareCellToNeighbors(*costmap, i, j);
- }
- }
- }
- void CostmapTester::compareCellToNeighbors(costmap_2d::Costmap2D& costmap, unsigned int x, unsigned int y){
-
- for(int offset_x = -1; offset_x <= 1; ++offset_x){
- for(int offset_y = -1; offset_y <= 1; ++offset_y){
- int nx = x + offset_x;
- int ny = y + offset_y;
-
- if(nx >= 0 && nx < (int)costmap.getSizeInCellsX() && ny >=0 && ny < (int)costmap.getSizeInCellsY()){
- compareCells(costmap, x, y, nx, ny);
- }
- }
- }
- }
- void CostmapTester::compareCells(costmap_2d::Costmap2D& costmap, unsigned int x, unsigned int y, unsigned int nx, unsigned int ny){
- double cell_distance = hypot(static_cast<int>(x-nx), static_cast<int>(y-ny));
- unsigned char cell_cost = costmap.getCost(x, y);
- unsigned char neighbor_cost = costmap.getCost(nx, ny);
- if(cell_cost == costmap_2d::LETHAL_OBSTACLE){
-
- unsigned char expected_lowest_cost = 0;
- EXPECT_TRUE(neighbor_cost >= expected_lowest_cost || (cell_distance > 0 && neighbor_cost == costmap_2d::FREE_SPACE));
- }
- else if(cell_cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
-
- double furthest_valid_distance = 0;
- unsigned char expected_lowest_cost = 0;
- if(neighbor_cost < expected_lowest_cost){
- ROS_ERROR("Cell cost (%d, %d): %d, neighbor cost (%d, %d): %d, expected lowest cost: %d, cell distance: %.2f, furthest valid distance: %.2f",
- x, y, cell_cost, nx, ny, neighbor_cost, expected_lowest_cost, cell_distance, furthest_valid_distance);
- ROS_ERROR("Cell: (%d, %d), Neighbor: (%d, %d)", x, y, nx, ny);
- costmap.saveMap("failing_costmap.pgm");
- }
- EXPECT_TRUE(neighbor_cost >= expected_lowest_cost || (furthest_valid_distance > 0&& neighbor_cost == costmap_2d::FREE_SPACE));
- }
- }
- };
- costmap_2d::CostmapTester* map_tester = NULL;
- TEST(CostmapTester, checkConsistentCosts){
- map_tester->checkConsistentCosts();
- }
- void testCallback(const ros::TimerEvent& e){
- int test_result = RUN_ALL_TESTS();
- ROS_INFO("gtest return value: %d", test_result);
- ros::shutdown();
- }
- int main(int argc, char** argv){
- ros::init(argc, argv, "costmap_tester_node");
- testing::InitGoogleTest(&argc, argv);
- ros::NodeHandle n;
- ros::NodeHandle private_nh("~");
- tf2_ros::Buffer tf(ros::Duration(10));
- tf2_ros::TransformListener tfl(tf);
- map_tester = new costmap_2d::CostmapTester(tf);
- double wait_time;
- private_nh.param("wait_time", wait_time, 30.0);
- ros::Timer timer = n.createTimer(ros::Duration(wait_time), testCallback);
- ros::spin();
- return(0);
- }
|