rgbd
connection_shm_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_shm.h>
7 #include <rgbd/client_shm.h>
8 
9 #include <ros/duration.h>
10 #include <ros/init.h>
11 
12 
13 class SHM : public testing::Test
14 {
15 protected:
16  void SetUp() override
17  {
20  }
21 
22  const std::string test_server_name = "/test_ns/rgbd";
23 
27 };
28 
29 class SHMInitialized : public SHM
30 {
31 protected:
32  void SetUp() override
33  {
34  SHM::SetUp();
35  server.send(image);
36  ros::Duration(0.01).sleep();
37  EXPECT_TRUE(client.initialize(test_server_name));
38  EXPECT_TRUE(client.initialized());
39  EXPECT_TRUE(static_cast<bool>(client.nextImage()));
40  std::string old_frame_id = image.getFrameId();
42  image.setFrameId(old_frame_id); // As FrameId is assumed to be constant in the SHM communication
43  }
44 };
45 
46 TEST_F(SHM, InitializeBeforeSend)
47 {
48  EXPECT_FALSE(ros::isShuttingDown());
49  EXPECT_FALSE(client.initialized());
50  EXPECT_FALSE(client.initialize(test_server_name, 1.));
51  EXPECT_FALSE(client.initialized());
52  EXPECT_FALSE(ros::isShuttingDown());
53 }
54 
55 TEST_F(SHM, InitializeAfterSend)
56 {
57  EXPECT_FALSE(ros::isShuttingDown());
58  server.send(image);
59  ros::Duration(0.01).sleep();
60  EXPECT_FALSE(client.initialized());
61  EXPECT_TRUE(client.initialize(test_server_name));
62  EXPECT_TRUE(client.initialized());
63  EXPECT_FALSE(ros::isShuttingDown());
64 }
65 
66 TEST_F(SHM, DeInitialize)
67 {
68  EXPECT_FALSE(ros::isShuttingDown());
69  server.send(image);
70  ros::Duration(0.01).sleep();
71  EXPECT_FALSE(client.initialized());
72  EXPECT_TRUE(client.initialize(test_server_name));
73  EXPECT_TRUE(client.initialized());
74  EXPECT_TRUE(client.deinitialize());
75  EXPECT_FALSE(client.initialized());
76  EXPECT_FALSE(ros::isShuttingDown());
77 }
78 
80 {
81  EXPECT_FALSE(ros::isShuttingDown());
82  server.send(image);
83  ros::Duration(0.01).sleep();
84  rgbd::Image image2;
85  EXPECT_TRUE(client.nextImage(image2));
86  EXPECT_EQ(image, image2);
87  EXPECT_FALSE(ros::isShuttingDown());
88 }
89 
90 TEST_F(SHMInitialized, NextImagePtr)
91 {
92  EXPECT_FALSE(ros::isShuttingDown());
93  server.send(image);
94  ros::Duration(0.01).sleep();
95  rgbd::ImagePtr image2 = client.nextImage();
96  EXPECT_TRUE(image2);
97  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
98  {
99  EXPECT_EQ(image, *image2);
100  }
101  EXPECT_FALSE(ros::isShuttingDown());
102 }
103 
104 TEST_F(SHMInitialized, NextImageTwice)
105 {
106  EXPECT_FALSE(ros::isShuttingDown());
107  server.send(image);
108  ros::Duration(0.01).sleep();
109  rgbd::Image image2;
110  EXPECT_TRUE(client.nextImage(image2));
111  EXPECT_EQ(image, image2);
112  EXPECT_FALSE(ros::isShuttingDown());
113  image.setTimestamp(image.getTimestamp()+10.);
114  server.send(image);
115  ros::Duration(0.01).sleep();
116  EXPECT_TRUE(client.nextImage(image2));
117  EXPECT_EQ(image, image2);
118  EXPECT_FALSE(ros::isShuttingDown());
119 }
120 
121 TEST_F(SHMInitialized, NextImageTwiceWithoutSend)
122 {
123  EXPECT_FALSE(ros::isShuttingDown());
124  server.send(image);
125  ros::Duration(0.01).sleep();
126  rgbd::Image image2;
127  EXPECT_TRUE(client.nextImage(image2));
128  EXPECT_EQ(image, image2);
129  EXPECT_FALSE(ros::isShuttingDown());
130  EXPECT_FALSE(client.nextImage(image2));
131  EXPECT_FALSE(ros::isShuttingDown());
132 }
133 
134 TEST_F(SHMInitialized, NextImagePtrTwice)
135 {
136  EXPECT_FALSE(ros::isShuttingDown());
137  server.send(image);
138  ros::Duration(0.01).sleep();
139  rgbd::ImagePtr image2 = client.nextImage();
140  EXPECT_TRUE(image2);
141  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
142  {
143  EXPECT_EQ(image, *image2);
144  }
145  EXPECT_FALSE(ros::isShuttingDown());
146  image.setTimestamp(image.getTimestamp()+10.);
147  image2.reset();
148  server.send(image);
149  ros::Duration(0.01).sleep();
150  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 }
158 
159 TEST_F(SHMInitialized, NextImagePtrTwiceWithoutSend)
160 {
161  EXPECT_FALSE(ros::isShuttingDown());
162  server.send(image);
163  ros::Duration(0.01).sleep();
164  rgbd::ImagePtr image2 = client.nextImage();
165  EXPECT_TRUE(image2);
166  if (image2) // This prevents a crash of the node. Test will still fail because of previous line
167  {
168  EXPECT_EQ(image, *image2);
169  }
170  EXPECT_FALSE(ros::isShuttingDown());
171  image2.reset();
172  image2 = client.nextImage();
173  EXPECT_FALSE(image2);
174  EXPECT_FALSE(ros::isShuttingDown());
175 }
176 
177 // Run all the tests that were declared with TEST()
178 int main(int argc, char **argv)
179 {
180  ros::init(argc, argv, "shm_connection");
181  testing::InitGoogleTest(&argc, argv);
182  return RUN_ALL_TESTS();
183 }
rgbd::ClientSHM::initialized
bool initialized()
Check if the client is initialized. nextImage shouldn't be called if client is not initialized.
Definition: client_shm.h:53
std::string
std::shared_ptr
test_utils.h
SHM::test_server_name
const std::string test_server_name
Definition: connection_shm_gtest.cpp:22
client_shm.h
SHM::server
rgbd::ServerSHM server
Definition: connection_shm_gtest.cpp:25
main
int main(int argc, char **argv)
Definition: connection_shm_gtest.cpp:178
std::shared_ptr::reset
T reset(T... args)
SHM::client
rgbd::ClientSHM client
Definition: connection_shm_gtest.cpp:26
rgbd::Image::setFrameId
void setFrameId(const std::string &frame_id)
Set the frame_id.
Definition: image.h:117
rgbd::Image
Definition: image.h:43
rgbd::ClientSHM::initialize
bool initialize(const std::string &server_name, float timeout=5.0)
Initialize shared memory client.
Definition: client_shm.cpp:33
rgbd::ServerSHM::send
void send(const Image &image)
send Write a new image to the shared memory
Definition: server_shm.cpp:48
SHM::image
rgbd::Image image
Definition: connection_shm_gtest.cpp:24
image.h
rgbd::ClientSHM::nextImage
bool nextImage(Image &image)
Get a new Image. If no new image has been received, the sequence nummer is still the same as the prev...
Definition: client_shm.cpp:89
TEST_F
TEST_F(SHM, InitializeBeforeSend)
Definition: connection_shm_gtest.cpp:46
SHMInitialized
Definition: connection_shm_gtest.cpp:29
rgbd::ServerSHM::initialize
void initialize(const std::string &name)
initialize Initialize shared memory server
Definition: server_shm.cpp:40
rgbd::Image::getFrameId
const std::string & getFrameId() const
Get the frame_id.
Definition: image.h:84
SHM::SetUp
void SetUp() override
Definition: connection_shm_gtest.cpp:16
SHMInitialized::SetUp
void SetUp() override
Definition: connection_shm_gtest.cpp:32
rgbd::generateRandomImage
rgbd::Image generateRandomImage()
Definition: test_utils.h:36
SHM
Definition: connection_shm_gtest.cpp:13
rgbd::ClientSHM
Client which uses shared memory, requires a server on the same machine.
Definition: client_shm.h:16
rgbd::ServerSHM
Server which uses shared memory, this only works for clients on the same machine.
Definition: server_shm.h:22
server_shm.h