32 #include <gtest/gtest.h>
35 #include <nav_msgs/GetMap.h>
36 #include <nav_msgs/OccupancyGrid.h>
37 #include <nav_msgs/MapMetaData.h>
74 EXPECT_FLOAT_EQ(map_metadata.resolution,
g_res);
75 EXPECT_FLOAT_EQ(map_metadata.width,
g_width);
76 EXPECT_FLOAT_EQ(map_metadata.height,
g_height);
82 unsigned int free_cnt = 0;
83 for(i=0; i < map.info.width * map.info.height; i++)
88 double free_ratio = free_cnt / (double)(i);
98 nav_msgs::GetMap::Request req;
99 nav_msgs::GetMap::Response resp;
102 checkMapMetaData(resp.map.info);
103 checkMapData(resp.map);
113 while(!got_map_ && i > 0)
120 ASSERT_TRUE(got_map_);
121 checkMapMetaData(map_->info);
122 checkMapData(*(map_.get()));
132 while(!got_map_metadata_ && i > 0)
139 ASSERT_TRUE(got_map_metadata_);
140 checkMapMetaData(*(map_metadata_.get()));
143 int main(
int argc,
char **argv)
145 testing::InitGoogleTest(&argc, argv);
147 ros::init(argc, argv,
"map_client_test");
154 g_res = atof(argv[2]);
162 ROS_INFO(
"Waiting for initial time publication");
169 ROS_INFO(
"Waiting for delay expiration (%.3f - %.3f) < %.3f",
177 int result = RUN_ALL_TESTS();