32 #include <gtest/gtest.h> 35 #include <nav_msgs/GetMap.h> 36 #include <nav_msgs/OccupancyGrid.h> 37 #include <nav_msgs/MapMetaData.h> 68 map_metadata_ = map_metadata;
69 got_map_metadata_ =
true;
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;
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();
void checkMapMetaData(const nav_msgs::MapMetaData &map_metadata)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< nav_msgs::MapMetaData const > map_metadata_
int main(int argc, char **argv)
void checkMapData(const nav_msgs::OccupancyGrid &map)
boost::shared_ptr< nav_msgs::OccupancyGrid const > map_
void mapCallback(const boost::shared_ptr< nav_msgs::OccupancyGrid const > &map)
void mapMetaDataCallback(const boost::shared_ptr< nav_msgs::MapMetaData const > &map_metadata)
ROSCPP_DECL void spinOnce()
TEST_F(MapClientTest, call_service)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)