32 #include <gtest/gtest.h>
36 #include <nav_msgs/GetMap.h>
37 #include <nav_msgs/OccupancyGrid.h>
38 #include <nav_msgs/MapMetaData.h>
39 #include <nav_msgs/LoadMap.h>
85 nav_msgs::GetMap::Request req;
86 nav_msgs::GetMap::Response resp;
92 ASSERT_STREQ(resp.map.header.frame_id.c_str(),
"map");
93 for(
unsigned int i=0; i < resp.map.info.width * resp.map.info.height; i++)
100 ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>(
"map", 1, [
this](
auto& map){ mapCallback(map); });
104 while(!got_map_ && i > 0)
111 ASSERT_TRUE(got_map_);
115 ASSERT_STREQ(map_->header.frame_id.c_str(),
"map");
116 for(
unsigned int i=0; i < map_->info.width * map_->info.height; i++)
123 ros::Subscriber sub = n_->subscribe<nav_msgs::MapMetaData>(
"map_metadata", 1, [
this](
auto& map_metadata){ mapMetaDataCallback(map_metadata); });
127 while(!got_map_metadata_ && i > 0)
134 ASSERT_TRUE(got_map_metadata_);
143 ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>(
"map", 1, [
this](
auto& map){ mapCallback(map); });
146 for (
int i = 20; i > 0 && !got_map_; i--)
152 ASSERT_TRUE(got_map_);
156 nav_msgs::LoadMap::Request req;
157 nav_msgs::LoadMap::Response resp;
161 ASSERT_EQ(0u, resp.result);
162 for (
int i = 20; i > 0 && !got_map_; i--)
172 ASSERT_STREQ(
"map", map_->header.frame_id.c_str());
173 for(
unsigned int i=0; i < map_->info.width * map_->info.height; i++)
180 ASSERT_EQ(0u, resp.result);
181 for (
int i = 20; i > 0 && !got_map_; i--)
187 ASSERT_TRUE(got_map_);
190 int main(
int argc,
char **argv)
192 testing::InitGoogleTest(&argc, argv);
197 return RUN_ALL_TESTS();