fixture.h
Go to the documentation of this file.
1 
2 #include <gtest/gtest.h>
3 
4 #include <sys/socket.h>
5 #include <sys/fcntl.h>
6 #include <netinet/in.h>
7 #include <arpa/inet.h>
8 
9 #include "ros/ros.h"
10 
11 namespace rosserial {
12 #include "rosserial_test/ros.h"
13 }
14 
16 public:
17  virtual void SetUp()=0;
18  virtual void TearDown()=0;
19  int fd;
20 };
21 
22 class SerialSetup : public AbstractSetup {
23 public:
24  virtual void SetUp() {
25  ASSERT_NE(-1, fd = posix_openpt( O_RDWR | O_NOCTTY | O_NDELAY ));
26  ASSERT_NE(-1, grantpt(fd));
27  ASSERT_NE(-1, unlockpt(fd));
28 
29  char* pty_name;
30  ASSERT_TRUE((pty_name = ptsname(fd)) != NULL);
31 
32  ros::param::get("~port", symlink_name);
33  symlink(pty_name, symlink_name.c_str());
34  }
35  virtual void TearDown() {
36  unlink(symlink_name.c_str());
37  close(fd);
38  }
39  std::string symlink_name;
40 };
41 
42 class SocketSetup : public AbstractSetup {
43 public:
44  virtual void SetUp() {
45  ros::param::get("~tcp_port", tcp_port);
46  memset(&serv_addr, 0, sizeof(serv_addr));
47  serv_addr.sin_family = AF_INET;
48  serv_addr.sin_port = htons(tcp_port);
49  ASSERT_GE(inet_pton(AF_INET, "127.0.0.1", &serv_addr.sin_addr), 0);
50 
51  // Try a bunch of times; we don't know how long it will take for the
52  // server to come up.
53  for (int attempt = 0; attempt < 10; attempt++)
54  {
55  fd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
56  ASSERT_GE(fd, 0);
57  if (connect(fd, (struct sockaddr *)&serv_addr, sizeof(serv_addr)) >= 0)
58  {
59  // Connection successful, set nonblocking and return.
60  fcntl(fd, F_SETFL, O_NONBLOCK);
61  return;
62  }
63  close(fd);
64  ros::Duration(0.5).sleep();
65  }
66  FAIL() << "Unable to connect to rosserial socket server.";
67  }
68  virtual void TearDown() {
69  close(fd);
70  }
71  struct sockaddr_in serv_addr;
72  int tcp_port;
73 };
74 
75 class SingleClientFixture : public ::testing::Test {
76 protected:
77  static void SetModeFromParam() {
78  std::string mode;
79  ros::param::get("~mode", mode);
80  ROS_INFO_STREAM("Using test mode [" << mode << "]");
81  if (mode == "socket") {
82  setup = new SocketSetup();
83  } else if (mode == "serial") {
84  setup = new SerialSetup();
85  } else {
86  FAIL() << "Mode specified other than 'serial' or 'socket'.";
87  }
88  }
89  virtual void SetUp() {
90  if (setup == NULL) SetModeFromParam();
91  setup->SetUp();
92  rosserial::ClientComms::fd = setup->fd;
93  }
94  virtual void TearDown() {
95  setup->TearDown();
96  }
97 
101 };
103 
104 
ros::NodeHandle nh
Definition: fixture.h:99
virtual void TearDown()
Definition: fixture.h:35
bool sleep() const
virtual void SetUp()
Definition: fixture.h:24
virtual void TearDown()
Definition: fixture.h:94
int tcp_port
Definition: fixture.h:72
ROSCPP_DECL bool get(const std::string &key, std::string &s)
virtual void SetUp()
Definition: fixture.h:44
virtual void TearDown()
Definition: fixture.h:68
#define ROS_INFO_STREAM(args)
NodeHandle_< ClientComms, 5, 5, 200, 200 > NodeHandle
Definition: ros.h:38
rosserial::ros::NodeHandle client_nh
Definition: fixture.h:98
virtual void SetUp()
Definition: fixture.h:89
static AbstractSetup * setup
Definition: fixture.h:100
static void SetModeFromParam()
Definition: fixture.h:77
std::string symlink_name
Definition: fixture.h:39


rosserial_test
Author(s):
autogenerated on Fri Jun 7 2019 22:03:01