rtest.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Brian Gerkey */
31 
32 #include <gtest/gtest.h>
33 #include <ros/service.h>
34 #include <ros/ros.h>
35 #include <ros/package.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>
40 
41 #include "test_constants.h"
42 
43 int g_argc;
44 char** g_argv;
45 
46 class MapClientTest : public testing::Test
47 {
48  public:
49  // A node is needed to make a service call
51 
53  {
54  ros::init(g_argc, g_argv, "map_client_test");
55  n_ = new ros::NodeHandle();
56  got_map_ = false;
57  got_map_metadata_ = false;
58  }
59 
61  {
62  delete n_;
63  }
64 
65  bool got_map_;
68  {
69  map_ = map;
70  got_map_ = true;
71  }
72 
76  {
77  map_metadata_ = map_metadata;
78  got_map_metadata_ = true;
79  }
80 };
81 
82 /* Try to retrieve the map via service, and compare to ground truth */
83 TEST_F(MapClientTest, call_service)
84 {
85  nav_msgs::GetMap::Request req;
86  nav_msgs::GetMap::Response resp;
87  ASSERT_TRUE(ros::service::waitForService("static_map", 5000));
88  ASSERT_TRUE(ros::service::call("static_map", req, resp));
89  ASSERT_FLOAT_EQ(resp.map.info.resolution, g_valid_image_res);
90  ASSERT_EQ(resp.map.info.width, g_valid_image_width);
91  ASSERT_EQ(resp.map.info.height, g_valid_image_height);
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++)
94  ASSERT_EQ(g_valid_image_content[i], resp.map.data[i]);
95 }
96 
97 /* Try to retrieve the map via topic, and compare to ground truth */
98 TEST_F(MapClientTest, subscribe_topic)
99 {
100  ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>("map", 1, [this](auto& map){ mapCallback(map); });
101 
102  // Try a few times, because the server may not be up yet.
103  int i=20;
104  while(!got_map_ && i > 0)
105  {
106  ros::spinOnce();
108  d.sleep();
109  i--;
110  }
111  ASSERT_TRUE(got_map_);
112  ASSERT_FLOAT_EQ(map_->info.resolution, g_valid_image_res);
113  ASSERT_EQ(map_->info.width, g_valid_image_width);
114  ASSERT_EQ(map_->info.height, g_valid_image_height);
115  ASSERT_STREQ(map_->header.frame_id.c_str(), "map");
116  for(unsigned int i=0; i < map_->info.width * map_->info.height; i++)
117  ASSERT_EQ(g_valid_image_content[i], map_->data[i]);
118 }
119 
120 /* Try to retrieve the metadata via topic, and compare to ground truth */
121 TEST_F(MapClientTest, subscribe_topic_metadata)
122 {
123  ros::Subscriber sub = n_->subscribe<nav_msgs::MapMetaData>("map_metadata", 1, [this](auto& map_metadata){ mapMetaDataCallback(map_metadata); });
124 
125  // Try a few times, because the server may not be up yet.
126  int i=20;
127  while(!got_map_metadata_ && i > 0)
128  {
129  ros::spinOnce();
131  d.sleep();
132  i--;
133  }
134  ASSERT_TRUE(got_map_metadata_);
135  ASSERT_FLOAT_EQ(map_metadata_->resolution, g_valid_image_res);
136  ASSERT_EQ(map_metadata_->width, g_valid_image_width);
137  ASSERT_EQ(map_metadata_->height, g_valid_image_height);
138 }
139 
140 /* Change the map, retrieve the map via topic, and compare to ground truth */
141 TEST_F(MapClientTest, change_map)
142 {
143  ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>("map", 1, [this](auto& map){ mapCallback(map); });
144 
145  // Try a few times, because the server may not be up yet.
146  for (int i = 20; i > 0 && !got_map_; i--)
147  {
148  ros::spinOnce();
150  d.sleep();
151  }
152  ASSERT_TRUE(got_map_);
153 
154  // Now change the map
155  got_map_ = false;
156  nav_msgs::LoadMap::Request req;
157  nav_msgs::LoadMap::Response resp;
158  req.map_url = ros::package::getPath("map_server") + "/test/testmap2.yaml";
159  ASSERT_TRUE(ros::service::waitForService("change_map", 5000));
160  ASSERT_TRUE(ros::service::call("change_map", req, resp));
161  ASSERT_EQ(0u, resp.result);
162  for (int i = 20; i > 0 && !got_map_; i--)
163  {
164  ros::spinOnce();
166  d.sleep();
167  }
168 
169  ASSERT_FLOAT_EQ(tmap2::g_valid_image_res, map_->info.resolution);
170  ASSERT_EQ(tmap2::g_valid_image_width, map_->info.width);
171  ASSERT_EQ(tmap2::g_valid_image_height, map_->info.height);
172  ASSERT_STREQ("map", map_->header.frame_id.c_str());
173  for(unsigned int i=0; i < map_->info.width * map_->info.height; i++)
174  ASSERT_EQ(tmap2::g_valid_image_content[i], map_->data[i]) << "idx:" << i;
175 
176  //Put the old map back so the next test isn't broken
177  got_map_ = false;
178  req.map_url = ros::package::getPath("map_server") + "/test/testmap.yaml";
179  ASSERT_TRUE(ros::service::call("change_map", req, resp));
180  ASSERT_EQ(0u, resp.result);
181  for (int i = 20; i > 0 && !got_map_; i--)
182  {
183  ros::spinOnce();
185  d.sleep();
186  }
187  ASSERT_TRUE(got_map_);
188 }
189 
190 int main(int argc, char **argv)
191 {
192  testing::InitGoogleTest(&argc, argv);
193 
194  g_argc = argc;
195  g_argv = argv;
196 
197  return RUN_ALL_TESTS();
198 }
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
DurationBase< Duration >::fromSec
Duration & fromSec(double t)
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
MapClientTest::map_
boost::shared_ptr< nav_msgs::OccupancyGrid const > map_
Definition: rtest.cpp:66
boost::shared_ptr
g_valid_image_width
const unsigned int g_valid_image_width
Definition: test_constants.cpp:38
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tmap2::g_valid_image_width
const unsigned int g_valid_image_width
Definition: test_constants.cpp:82
ros.h
tmap2::g_valid_image_content
const char g_valid_image_content[]
Definition: test_constants.cpp:67
MapClientTest
Definition: rtest.cpp:46
ros::spinOnce
ROSCPP_DECL void spinOnce()
service.h
g_argv
char ** g_argv
Definition: rtest.cpp:44
TEST_F
TEST_F(MapClientTest, call_service)
Definition: rtest.cpp:83
test_constants.h
tmap2::g_valid_image_res
const float g_valid_image_res
Definition: test_constants.cpp:81
g_valid_image_res
const float g_valid_image_res
Definition: test_constants.cpp:62
tmap2::g_valid_image_height
const unsigned int g_valid_image_height
Definition: test_constants.cpp:83
MapClientTest::n_
ros::NodeHandle * n_
Definition: rtest.cpp:50
d
d
MapClientTest::map_metadata_
boost::shared_ptr< nav_msgs::MapMetaData const > map_metadata_
Definition: rtest.cpp:74
MapClientTest::mapCallback
void mapCallback(const boost::shared_ptr< nav_msgs::OccupancyGrid const > &map)
Definition: rtest.cpp:67
package.h
g_valid_image_height
const unsigned int g_valid_image_height
Definition: test_constants.cpp:39
MapClientTest::~MapClientTest
~MapClientTest()
Definition: rtest.cpp:60
ros::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
MapClientTest::got_map_
bool got_map_
Definition: rtest.cpp:65
main
int main(int argc, char **argv)
Definition: rtest.cpp:190
g_valid_image_content
const char g_valid_image_content[]
Definition: test_constants.cpp:45
MapClientTest::got_map_metadata_
bool got_map_metadata_
Definition: rtest.cpp:73
MapClientTest::MapClientTest
MapClientTest()
Definition: rtest.cpp:52
ros::Duration
g_argc
int g_argc
Definition: rtest.cpp:43
MapClientTest::mapMetaDataCallback
void mapMetaDataCallback(const boost::shared_ptr< nav_msgs::MapMetaData const > &map_metadata)
Definition: rtest.cpp:75
ros::NodeHandle
ros::Subscriber


map_server
Author(s): Brian Gerkey, Tony Pratkanis, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:11