Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <gtest/gtest.h>
00033 #include <ros/service.h>
00034 #include <ros/ros.h>
00035 #include <nav_msgs/GetMap.h>
00036 #include <nav_msgs/OccupancyGrid.h>
00037 #include <nav_msgs/MapMetaData.h>
00038
00039
00040 ros::NodeHandle* g_n=NULL;
00041 double g_res, g_width, g_height, g_min_free_ratio, g_max_free_ratio;
00042
00043 class MapClientTest : public testing::Test
00044 {
00045 public:
00046 MapClientTest()
00047 {
00048 got_map_ = false;
00049 got_map_metadata_ = false;
00050 }
00051
00052 ~MapClientTest()
00053 {
00054 }
00055
00056 bool got_map_;
00057 boost::shared_ptr<nav_msgs::OccupancyGrid const> map_;
00058 void mapCallback(const boost::shared_ptr<nav_msgs::OccupancyGrid const>& map)
00059 {
00060 map_ = map;
00061 got_map_ = true;
00062 }
00063
00064 bool got_map_metadata_;
00065 boost::shared_ptr<nav_msgs::MapMetaData const> map_metadata_;
00066 void mapMetaDataCallback(const boost::shared_ptr<nav_msgs::MapMetaData const>& map_metadata)
00067 {
00068 map_metadata_ = map_metadata;
00069 got_map_metadata_ = true;
00070 }
00071
00072 void checkMapMetaData(const nav_msgs::MapMetaData& map_metadata)
00073 {
00074 EXPECT_FLOAT_EQ(map_metadata.resolution, g_res);
00075 EXPECT_FLOAT_EQ(map_metadata.width, g_width);
00076 EXPECT_FLOAT_EQ(map_metadata.height, g_height);
00077 }
00078
00079 void checkMapData(const nav_msgs::OccupancyGrid& map)
00080 {
00081 unsigned int i;
00082 unsigned int free_cnt = 0;
00083 for(i=0; i < map.info.width * map.info.height; i++)
00084 {
00085 if(map.data[i] == 0)
00086 free_cnt++;
00087 }
00088 double free_ratio = free_cnt / (double)(i);
00089 ROS_INFO("Min / ratio / Max free ratio: %f / %f / %f", g_min_free_ratio, free_ratio, g_max_free_ratio);
00090 EXPECT_GE(free_ratio, g_min_free_ratio);
00091 EXPECT_LE(free_ratio, g_max_free_ratio);
00092 }
00093 };
00094
00095
00096 TEST_F(MapClientTest, call_service)
00097 {
00098 nav_msgs::GetMap::Request req;
00099 nav_msgs::GetMap::Response resp;
00100 ASSERT_TRUE(ros::service::waitForService("dynamic_map", 5000));
00101 ASSERT_TRUE(ros::service::call("dynamic_map", req, resp));
00102 checkMapMetaData(resp.map.info);
00103 checkMapData(resp.map);
00104 }
00105
00106
00107 TEST_F(MapClientTest, subscribe_topic)
00108 {
00109 ros::Subscriber sub = g_n->subscribe<nav_msgs::OccupancyGrid>("map", 1, boost::bind(&MapClientTest::mapCallback, this, _1));
00110
00111
00112 int i=20;
00113 while(!got_map_ && i > 0)
00114 {
00115 ros::spinOnce();
00116 ros::WallDuration d(0.25);
00117 d.sleep();
00118 i--;
00119 }
00120 ASSERT_TRUE(got_map_);
00121 checkMapMetaData(map_->info);
00122 checkMapData(*(map_.get()));
00123 }
00124
00125
00126 TEST_F(MapClientTest, subscribe_topic_metadata)
00127 {
00128 ros::Subscriber sub = g_n->subscribe<nav_msgs::MapMetaData>("map_metadata", 1, boost::bind(&MapClientTest::mapMetaDataCallback, this, _1));
00129
00130
00131 int i=20;
00132 while(!got_map_metadata_ && i > 0)
00133 {
00134 ros::spinOnce();
00135 ros::WallDuration d(0.25);
00136 d.sleep();
00137 i--;
00138 }
00139 ASSERT_TRUE(got_map_metadata_);
00140 checkMapMetaData(*(map_metadata_.get()));
00141 }
00142
00143 int main(int argc, char **argv)
00144 {
00145 testing::InitGoogleTest(&argc, argv);
00146
00147 ros::init(argc, argv, "map_client_test");
00148 g_n = new ros::NodeHandle();
00149
00150
00151
00152 ROS_ASSERT(argc == 7);
00153 ros::Duration delay = ros::Duration(atof(argv[1]));
00154 g_res = atof(argv[2]);
00155 g_width = atof(argv[3]);
00156 g_height = atof(argv[4]);
00157 g_min_free_ratio = atof(argv[5]);
00158 g_max_free_ratio = atof(argv[6]);
00159
00160 while(ros::Time::now().toSec() == 0.0)
00161 {
00162 ROS_INFO("Waiting for initial time publication");
00163 ros::Duration(0.25).sleep();
00164 ros::spinOnce();
00165 }
00166 ros::Time start_time = ros::Time::now();
00167 while((ros::Time::now() - start_time) < delay)
00168 {
00169 ROS_INFO("Waiting for delay expiration (%.3f - %.3f) < %.3f",
00170 ros::Time::now().toSec(),
00171 start_time.toSec(),
00172 delay.toSec());
00173 ros::Duration(0.25).sleep();
00174 ros::spinOnce();
00175 }
00176
00177 int result = RUN_ALL_TESTS();
00178 delete g_n;
00179 return result;
00180 }