rgbd
connection_gtest.cpp
Go to the documentation of this file.
1 #include <boost/interprocess/shared_memory_object.hpp>
2 
3 #include <gtest/gtest.h>
4 
5 #include <rgbd/client.h>
6 #include <rgbd/image.h>
7 
8 #include <ros/duration.h>
9 #include <ros/init.h>
10 #include <ros/names.h>
11 #include <ros/rate.h>
12 #include <ros/time.h>
13 
14 
15 namespace ipc = boost::interprocess;
16 
17 class Connection : public testing::Test
18 {
19 protected:
20  void SetUp() override
21  {
22  client.initialize(ros::names::resolve(test_server_name));
23  ros::Time end_init = ros::Time::now() + ros::Duration(2);
24  ros::Rate r_init(10);
25  while(ros::Time::now() < end_init)
26  {
27  if (client.nextImage())
28  {
29  ros::Duration(0.5).sleep(); // Make sure there will be a new image when going to the actual test phase
30  break;
31  }
32  r_init.sleep();
33  }
34  }
35 
36  const std::string test_server_name = "rgbd";
38 
40 };
41 
42 TEST_F(Connection, ConsistentConnection)
43 {
44  rgbd::Image image;
45  double last_time_stamp = 0;
46  EXPECT_FALSE(ros::isShuttingDown());
47  ros::Time start = ros::Time::now();
48  ros::Time shm_kill_time = start + ros::Duration(5);
49  bool shm_killed = false;
50  ros::Time end = start + ros::Duration(20);
51  ros::Rate r(1);
52  int i=1;
53  while(ros::Time::now() < end)
54  {
55  if (!shm_killed && ros::Time::now() >= shm_kill_time)
56  {
57  ipc::shared_memory_object::remove(test_server_name_shm.c_str());
58  shm_killed = true;
59  ros::Duration(1.5).sleep(); // Wait for RGBD client to take over
60  /* Reset rate, otherwise first sleep is zero, because of the longer sleep above.
61  * Which eliminates any time between the two consecutive nextImage calls.
62  * The second call will fail then, because the elapsed time has been to short to receive any new image.
63  */
64  r.reset();
65  }
66  EXPECT_TRUE(client.nextImage(image)) << "i=" << i;
67  ++i;
68  EXPECT_GT(image.getTimestamp(), last_time_stamp);
69  last_time_stamp = image.getTimestamp();
70  r.sleep();
71  }
72  EXPECT_FALSE(ros::isShuttingDown());
73 }
74 
75 // Run all the tests that were declared with TEST()
76 int main(int argc, char **argv)
77 {
78  ros::init(argc, argv, "connection_client");
79  testing::InitGoogleTest(&argc, argv);
80  return RUN_ALL_TESTS();
81 }
Connection::client
rgbd::Client client
Definition: connection_gtest.cpp:39
std::string
main
int main(int argc, char **argv)
Definition: connection_gtest.cpp:76
rgbd::Image::getTimestamp
double getTimestamp() const
Get the timestamp.
Definition: image.h:90
TEST_F
TEST_F(Connection, ConsistentConnection)
Definition: connection_gtest.cpp:42
Connection
Definition: connection_gtest.cpp:17
rgbd::Image
Definition: image.h:43
rgbd::Client::initialize
bool initialize(const std::string &server_name, float timeout=5.0)
Initialize the client.
Definition: client.cpp:34
image.h
rgbd::Client
Client which uses the interfaces of ClientRGBD and ClientSHM.
Definition: client.h:29
Connection::test_server_name_shm
const std::string test_server_name_shm
Definition: connection_gtest.cpp:37
Connection::test_server_name
const std::string test_server_name
Definition: connection_gtest.cpp:36
Connection::SetUp
void SetUp() override
Definition: connection_gtest.cpp:20
client.h
rgbd::Client::nextImage
bool nextImage(Image &image)
Get a new Image. If no new image has been received since the last call, no image will be written and ...
Definition: client.cpp:76