2 #include <gtest/gtest.h> 4 #include <sys/socket.h> 6 #include <netinet/in.h> 17 virtual void SetUp()=0;
18 virtual void TearDown()=0;
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));
30 ASSERT_TRUE((pty_name = ptsname(fd)) != NULL);
33 symlink(pty_name, symlink_name.c_str());
36 unlink(symlink_name.c_str());
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);
53 for (
int attempt = 0; attempt < 10; attempt++)
55 fd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
57 if (connect(fd, (
struct sockaddr *)&serv_addr,
sizeof(serv_addr)) >= 0)
60 fcntl(fd, F_SETFL, O_NONBLOCK);
66 FAIL() <<
"Unable to connect to rosserial socket server.";
71 struct sockaddr_in serv_addr;
81 if (mode ==
"socket") {
83 }
else if (mode ==
"serial") {
86 FAIL() <<
"Mode specified other than 'serial' or 'socket'.";
90 if (
setup == NULL) SetModeFromParam();
92 rosserial::ClientComms::fd =
setup->fd;
ROSCPP_DECL bool get(const std::string &key, std::string &s)
#define ROS_INFO_STREAM(args)
NodeHandle_< ClientComms, 5, 5, 200, 200 > NodeHandle
rosserial::ros::NodeHandle client_nh
static AbstractSetup * setup
static void SetModeFromParam()