Go to the documentation of this file.00001
00002 #include <gtest/gtest.h>
00003
00004 #include <sys/socket.h>
00005 #include <sys/fcntl.h>
00006 #include <netinet/in.h>
00007 #include <arpa/inet.h>
00008
00009 #include "ros/ros.h"
00010
00011 namespace rosserial {
00012 #include "rosserial_test/ros.h"
00013 }
00014
00015 class AbstractSetup {
00016 public:
00017 virtual void SetUp()=0;
00018 virtual void TearDown()=0;
00019 int fd;
00020 };
00021
00022 class SerialSetup : public AbstractSetup {
00023 public:
00024 virtual void SetUp() {
00025 ASSERT_NE(-1, fd = posix_openpt( O_RDWR | O_NOCTTY | O_NDELAY ));
00026 ASSERT_NE(-1, grantpt(fd));
00027 ASSERT_NE(-1, unlockpt(fd));
00028
00029 char* pty_name;
00030 ASSERT_TRUE((pty_name = ptsname(fd)) != NULL);
00031
00032 ros::param::get("~port", symlink_name);
00033 symlink(pty_name, symlink_name.c_str());
00034 }
00035 virtual void TearDown() {
00036 unlink(symlink_name.c_str());
00037 close(fd);
00038 }
00039 std::string symlink_name;
00040 };
00041
00042 class SocketSetup : public AbstractSetup {
00043 public:
00044 virtual void SetUp() {
00045 ros::param::get("~tcp_port", tcp_port);
00046 memset(&serv_addr, 0, sizeof(serv_addr));
00047 serv_addr.sin_family = AF_INET;
00048 serv_addr.sin_port = htons(tcp_port);
00049 ASSERT_GE(inet_pton(AF_INET, "127.0.0.1", &serv_addr.sin_addr), 0);
00050
00051
00052
00053 for (int attempt = 0; attempt < 10; attempt++)
00054 {
00055 fd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
00056 ASSERT_GE(fd, 0);
00057 if (connect(fd, (struct sockaddr *)&serv_addr, sizeof(serv_addr)) >= 0)
00058 {
00059
00060 fcntl(fd, F_SETFL, O_NONBLOCK);
00061 return;
00062 }
00063 close(fd);
00064 ros::Duration(0.5).sleep();
00065 }
00066 FAIL() << "Unable to connect to rosserial socket server.";
00067 }
00068 virtual void TearDown() {
00069 close(fd);
00070 }
00071 struct sockaddr_in serv_addr;
00072 int tcp_port;
00073 };
00074
00075 class SingleClientFixture : public ::testing::Test {
00076 protected:
00077 static void SetModeFromParam() {
00078 std::string mode;
00079 ros::param::get("~mode", mode);
00080 ROS_INFO_STREAM("Using test mode [" << mode << "]");
00081 if (mode == "socket") {
00082 setup = new SocketSetup();
00083 } else if (mode == "serial") {
00084 setup = new SerialSetup();
00085 } else {
00086 FAIL() << "Mode specified other than 'serial' or 'socket'.";
00087 }
00088 }
00089 virtual void SetUp() {
00090 if (setup == NULL) SetModeFromParam();
00091 setup->SetUp();
00092 rosserial::ClientComms::fd = setup->fd;
00093 }
00094 virtual void TearDown() {
00095 setup->TearDown();
00096 }
00097
00098 rosserial::ros::NodeHandle client_nh;
00099 ros::NodeHandle nh;
00100 static AbstractSetup* setup;
00101 };
00102 AbstractSetup* SingleClientFixture::setup = NULL;
00103
00104