3 #include <gtest/gtest.h>
10 #include <ros/node_handle.h>
13 class RGBD :
public testing::Test
42 EXPECT_FALSE(ros::isShuttingDown());
43 EXPECT_FALSE(client.initialized());
44 EXPECT_TRUE(client.initialize(test_server_name));
45 EXPECT_TRUE(client.initialized());
46 EXPECT_FALSE(ros::isShuttingDown());
51 EXPECT_FALSE(ros::isShuttingDown());
52 EXPECT_FALSE(client.initialized());
53 EXPECT_TRUE(client.initialize(test_server_name));
54 EXPECT_TRUE(client.initialized());
55 EXPECT_TRUE(client.deinitialize());
56 EXPECT_FALSE(client.initialized());
57 EXPECT_FALSE(ros::isShuttingDown());
62 EXPECT_FALSE(ros::isShuttingDown());
63 EXPECT_TRUE(client.initialize(test_server_name));
64 EXPECT_TRUE(client.initialized());
66 EXPECT_FALSE(client.nextImage(image2));
67 EXPECT_FALSE(ros::isShuttingDown());
72 EXPECT_FALSE(ros::isShuttingDown());
73 EXPECT_TRUE(client.initialize(test_server_name));
74 EXPECT_TRUE(client.initialized());
77 EXPECT_FALSE(ros::isShuttingDown());
82 EXPECT_FALSE(ros::isShuttingDown());
83 EXPECT_TRUE(client.initialize(test_server_name));
84 EXPECT_TRUE(client.initialized());
86 ros::Duration(0.01).sleep();
88 EXPECT_TRUE(client.nextImage(image2));
89 EXPECT_EQ(image, image2);
90 EXPECT_FALSE(ros::isShuttingDown());
95 EXPECT_FALSE(ros::isShuttingDown());
96 EXPECT_TRUE(client.initialize(test_server_name));
97 EXPECT_TRUE(client.initialized());
99 ros::Duration(0.01).sleep();
104 EXPECT_EQ(image, *image2);
106 EXPECT_FALSE(ros::isShuttingDown());
111 EXPECT_FALSE(ros::isShuttingDown());
112 EXPECT_TRUE(client.initialize(test_server_name));
113 EXPECT_TRUE(client.initialized());
115 ros::Duration(0.01).sleep();
117 EXPECT_TRUE(client.nextImage(image2));
118 EXPECT_EQ(image, image2);
119 EXPECT_FALSE(ros::isShuttingDown());
120 image.setTimestamp(image.getTimestamp()+10.);
122 ros::Duration(0.01).sleep();
123 EXPECT_TRUE(client.nextImage(image2));
124 EXPECT_EQ(image, image2);
125 EXPECT_FALSE(ros::isShuttingDown());
130 EXPECT_FALSE(ros::isShuttingDown());
131 EXPECT_TRUE(client.initialize(test_server_name));
132 EXPECT_TRUE(client.initialized());
134 ros::Duration(0.01).sleep();
136 EXPECT_TRUE(client.nextImage(image2));
137 EXPECT_EQ(image, image2);
138 EXPECT_FALSE(ros::isShuttingDown());
139 EXPECT_FALSE(client.nextImage(image2));
140 EXPECT_FALSE(ros::isShuttingDown());
145 EXPECT_FALSE(ros::isShuttingDown());
146 EXPECT_TRUE(client.initialize(test_server_name));
147 EXPECT_TRUE(client.initialized());
149 ros::Duration(0.01).sleep();
154 EXPECT_EQ(image, *image2);
156 EXPECT_FALSE(ros::isShuttingDown());
157 image.setTimestamp(image.getTimestamp()+10.);
160 ros::Duration(0.01).sleep();
161 image2 = client.nextImage();
165 EXPECT_EQ(image, *image2);
167 EXPECT_FALSE(ros::isShuttingDown());
172 EXPECT_FALSE(ros::isShuttingDown());
173 EXPECT_TRUE(client.initialize(test_server_name));
174 EXPECT_TRUE(client.initialized());
176 ros::Duration(0.01).sleep();
181 EXPECT_EQ(image, *image2);
183 EXPECT_FALSE(ros::isShuttingDown());
185 image2 = client.nextImage();
186 EXPECT_FALSE(image2);
187 EXPECT_FALSE(ros::isShuttingDown());
191 int main(
int argc,
char **argv)
193 ros::init(argc, argv,
"rgbd_connection");
194 testing::InitGoogleTest(&argc, argv);
195 return RUN_ALL_TESTS();