rgbd
connection_rgbd_gtest.cpp
Go to the documentation of this file.
1 #include "test_utils.h"
2 
3 #include <gtest/gtest.h>
4 
5 #include <rgbd/image.h>
6 #include <rgbd/server_rgbd.h>
7 #include <rgbd/client_rgbd.h>
8 
9 #include <ros/init.h>
10 #include <ros/node_handle.h>
11 
12 
13 class RGBD : public testing::Test
14 {
15 protected:
16  RGBD() : server(nh)
17  {
18  }
19 
20  virtual ~RGBD()
21  {
23  nh.shutdown();
24  }
25 
26  void SetUp() override
27  {
30  }
31 
32  const std::string test_server_name = "/test_ns/rgbd";
33 
34  ros::NodeHandle nh;
38 };
39 
40 TEST_F(RGBD, Initialize)
41 {
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());
47 }
48 
49 TEST_F(RGBD, DeInitialize)
50 {
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());
58 }
59 
60 TEST_F(RGBD, NextImageBeforeSend)
61 {
62  EXPECT_FALSE(ros::isShuttingDown());
63  EXPECT_TRUE(client.initialize(test_server_name));
64  EXPECT_TRUE(client.initialized());
65  rgbd::Image image2;
66  EXPECT_FALSE(client.nextImage(image2));
67  EXPECT_FALSE(ros::isShuttingDown());
68 }
69 
70 TEST_F(RGBD, NextImagePtrBeforeSend)
71 {
72  EXPECT_FALSE(ros::isShuttingDown());
73  EXPECT_TRUE(client.initialize(test_server_name));
74  EXPECT_TRUE(client.initialized());
75  rgbd::ImagePtr image2 = client.nextImage();
76  EXPECT_FALSE(image2);
77  EXPECT_FALSE(ros::isShuttingDown());
78 }
79 
80 TEST_F(RGBD, NextImage)
81 {
82  EXPECT_FALSE(ros::isShuttingDown());
83  EXPECT_TRUE(client.initialize(test_server_name));
84  EXPECT_TRUE(client.initialized());
85  server.send(image);
86  ros::Duration(0.01).sleep();
87  rgbd::Image image2;
88  EXPECT_TRUE(client.nextImage(image2));
89  EXPECT_EQ(image, image2);
90  EXPECT_FALSE(ros::isShuttingDown());
91 }
92 
93 TEST_F(RGBD, NextImagePtr)
94 {
95  EXPECT_FALSE(ros::isShuttingDown());
96  EXPECT_TRUE(client.initialize(test_server_name));
97  EXPECT_TRUE(client.initialized());
98  server.send(image);
99  ros::Duration(0.01).sleep();
100  rgbd::ImagePtr image2 = client.nextImage();
101  EXPECT_TRUE(image2);
102  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
103  {
104  EXPECT_EQ(image, *image2);
105  }
106  EXPECT_FALSE(ros::isShuttingDown());
107 }
108 
109 TEST_F(RGBD, NextImageTwice)
110 {
111  EXPECT_FALSE(ros::isShuttingDown());
112  EXPECT_TRUE(client.initialize(test_server_name));
113  EXPECT_TRUE(client.initialized());
114  server.send(image);
115  ros::Duration(0.01).sleep();
116  rgbd::Image image2;
117  EXPECT_TRUE(client.nextImage(image2));
118  EXPECT_EQ(image, image2);
119  EXPECT_FALSE(ros::isShuttingDown());
120  image.setTimestamp(image.getTimestamp()+10.);
121  server.send(image);
122  ros::Duration(0.01).sleep();
123  EXPECT_TRUE(client.nextImage(image2));
124  EXPECT_EQ(image, image2);
125  EXPECT_FALSE(ros::isShuttingDown());
126 }
127 
128 TEST_F(RGBD, NextImageTwiceWithoutSend)
129 {
130  EXPECT_FALSE(ros::isShuttingDown());
131  EXPECT_TRUE(client.initialize(test_server_name));
132  EXPECT_TRUE(client.initialized());
133  server.send(image);
134  ros::Duration(0.01).sleep();
135  rgbd::Image image2;
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());
141 }
142 
143 TEST_F(RGBD, NextImagePtrTwice)
144 {
145  EXPECT_FALSE(ros::isShuttingDown());
146  EXPECT_TRUE(client.initialize(test_server_name));
147  EXPECT_TRUE(client.initialized());
148  server.send(image);
149  ros::Duration(0.01).sleep();
150  rgbd::ImagePtr image2 = client.nextImage();
151  EXPECT_TRUE(image2);
152  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
153  {
154  EXPECT_EQ(image, *image2);
155  }
156  EXPECT_FALSE(ros::isShuttingDown());
157  image.setTimestamp(image.getTimestamp()+10.);
158  image2.reset();
159  server.send(image);
160  ros::Duration(0.01).sleep();
161  image2 = client.nextImage();
162  EXPECT_TRUE(image2);
163  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
164  {
165  EXPECT_EQ(image, *image2);
166  }
167  EXPECT_FALSE(ros::isShuttingDown());
168 }
169 
170 TEST_F(RGBD, NextImagePtrTwiceWithoutSend)
171 {
172  EXPECT_FALSE(ros::isShuttingDown());
173  EXPECT_TRUE(client.initialize(test_server_name));
174  EXPECT_TRUE(client.initialized());
175  server.send(image);
176  ros::Duration(0.01).sleep();
177  rgbd::ImagePtr image2 = client.nextImage();
178  EXPECT_TRUE(image2);
179  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
180  {
181  EXPECT_EQ(image, *image2);
182  }
183  EXPECT_FALSE(ros::isShuttingDown());
184  image2.reset();
185  image2 = client.nextImage();
186  EXPECT_FALSE(image2);
187  EXPECT_FALSE(ros::isShuttingDown());
188 }
189 
190 // Run all the tests that were declared with TEST()
191 int main(int argc, char **argv)
192 {
193  ros::init(argc, argv, "rgbd_connection");
194  testing::InitGoogleTest(&argc, argv);
195  return RUN_ALL_TESTS();
196 }
RGBD::image
rgbd::Image image
Definition: connection_rgbd_gtest.cpp:35
main
int main(int argc, char **argv)
Definition: connection_rgbd_gtest.cpp:191
RGBD::client
rgbd::ClientRGBD client
Definition: connection_rgbd_gtest.cpp:37
rgbd::ServerRGBD::initialize
void initialize(const std::string &name, RGBStorageType rgb_type=RGB_STORAGE_LOSSLESS, DepthStorageType depth_type=DEPTH_STORAGE_LOSSLESS, const float service_freq=10)
Initialize server.
Definition: server_rgbd.cpp:43
std::string
std::shared_ptr
RGBD::nh
ros::NodeHandle nh
Definition: connection_rgbd_gtest.cpp:34
test_utils.h
client_rgbd.h
std::shared_ptr::reset
T reset(T... args)
RGBD::~RGBD
virtual ~RGBD()
Definition: connection_rgbd_gtest.cpp:20
rgbd::Image
Definition: image.h:43
RGBD::RGBD
RGBD()
Definition: connection_rgbd_gtest.cpp:16
TEST_F
TEST_F(RGBD, Initialize)
Definition: connection_rgbd_gtest.cpp:40
rgbd::ClientRGBD::deinitialize
bool deinitialize()
Clears the subscriber. initialized will now return false.
Definition: client_rgbd.cpp:36
server_rgbd.h
RGBD::SetUp
void SetUp() override
Definition: connection_rgbd_gtest.cpp:26
image.h
rgbd::ClientRGBD
Client which subscribes to RGBD topic.
Definition: client_rgbd.h:22
RGBD::test_server_name
const std::string test_server_name
Definition: connection_rgbd_gtest.cpp:32
RGBD
Definition: connection_rgbd_gtest.cpp:13
RGBD::server
rgbd::ServerRGBD server
Definition: connection_rgbd_gtest.cpp:36
rgbd::ServerRGBD
Server which provides RGBD topic and RGBD service.
Definition: server_rgbd.h:20
rgbd::generateRandomImage
rgbd::Image generateRandomImage()
Definition: test_utils.h:36