Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix test_roscpp build issues on Windows #1482

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions test/test_roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@ if(CATKIN_ENABLE_TESTING)

include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})

if(WIN32)
add_definitions(-DNOGDI)
endif()

# Testing message and service files. See comment below about subdirectory support.
add_message_files(
NOINSTALL
Expand Down
3 changes: 3 additions & 0 deletions test/test_roscpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,9 @@ endif()
catkin_add_gtest(${PROJECT_NAME}-test_poll_set test_poll_set.cpp)
if(TARGET ${PROJECT_NAME}-test_poll_set)
target_link_libraries(${PROJECT_NAME}-test_poll_set ${catkin_LIBRARIES})
if(WIN32)
target_link_libraries(${PROJECT_NAME}-test_poll_set ws2_32)
endif()
endif()

catkin_add_gtest(${PROJECT_NAME}-test_transport_tcp test_transport_tcp.cpp)
Expand Down
14 changes: 14 additions & 0 deletions test/test_roscpp/test/src/check_master.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,20 @@ using namespace XmlRpc;

bool g_should_exist = true;

#ifdef _WIN32
int setenv(const char *name, const char *value, int overwrite)
{
if(!overwrite)
{
size_t envsize = 0;
const errno_t errcode = getenv_s(&envsize, NULL, 0, name);
if(errcode || envsize)
return errcode;
}
return _putenv_s(name, value);
}
#endif

TEST(CheckMaster, checkMaster)
{
ASSERT_EQ(ros::master::check(), g_should_exist);
Expand Down
7 changes: 0 additions & 7 deletions test/test_roscpp/test/src/service_adv_a.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,6 @@
#include "ros/ros.h"
#include <test_roscpp/TestStringString.h>

#include <unistd.h>
#include <errno.h>
#include <signal.h>
#include <sys/types.h>
#include <sys/wait.h>
#include <cstdlib>

bool srvCallback(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &res)
{
Expand Down
5 changes: 5 additions & 0 deletions test/test_roscpp/test/src/service_adv_zombie.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,12 @@ int main(int argc, char** argv)
for(int i = 0; i < 10; ++i)
{
ros::spinOnce();

#ifndef _WIN32
usleep(100*1000);
#else
Sleep(100);
#endif
}

// Exit immediately without calling any atexit hooks
Expand Down
4 changes: 4 additions & 0 deletions test/test_roscpp/test/src/service_call_zombie.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,11 @@ main(int argc, char** argv)
ros::init(argc, argv, "service_call");
ros::NodeHandle nh;

#ifndef _WIN32
sleep(10);
#else
Sleep(10 * 1000);
#endif

int ret = RUN_ALL_TESTS();

Expand Down
9 changes: 9 additions & 0 deletions test/test_roscpp/test/src/service_exception.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
#include "ros/ros.h"
#include "std_srvs/Empty.h"
#include <log4cxx/appenderskeleton.h>
#ifdef _MSC_VER
// Have to be able to encode wchar LogStrings on windows.
# include <log4cxx/helpers/transcoder.h>
#endif
#include <ros/console.h>
#include <ros/poll_manager.h>

Expand Down Expand Up @@ -72,7 +76,12 @@ TEST(roscpp, ServiceThrowingException)
const std::list<log4cxx::spi::LoggingEventPtr>& list = appender->getList();
for (std::list<log4cxx::spi::LoggingEventPtr>::const_iterator it = list.begin(); it != list.end(); it++)
{
#ifdef _MSC_VER
LOG4CXX_ENCODE_CHAR(tmpstr, (*it)->getMessage()); // has to handle LogString with wchar types.
const std::string& msg = tmpstr; // tmpstr gets instantiated inside the LOG4CXX_ENCODE_CHAR macro
#else
const log4cxx::LogString& msg = (*it)->getMessage();
#endif
size_t pos_error = msg.find("Service call failed:");
size_t pos_exception = msg.find(EXCEPTION);
if (pos_error != std::string::npos && pos_exception != std::string::npos)
Expand Down
139 changes: 133 additions & 6 deletions test/test_roscpp/test/test_poll_set.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@

#include <gtest/gtest.h>
#include "ros/poll_set.h"
#include <sys/socket.h>
#ifndef _WIN32
# include <sys/socket.h>
#endif

#include <fcntl.h>

Expand All @@ -44,22 +46,145 @@

using namespace ros;

int set_nonblocking(int &socket)
{
#ifndef _WIN32
if (fcntl(socket, F_SETFL, O_NONBLOCK) == -1)
{
return errno;
}
#else
u_long non_blocking = 1;
if (ioctlsocket(socket, FIONBIO, &non_blocking) != 0)
{
return WSAGetLastError();
}
#endif
return 0;
}

int create_socket_pair(int socket_pair[2])
{
#ifndef _WIN32
return socketpair(AF_UNIX, SOCK_STREAM, 0, socket_pair);
#else
socket_pair[0] = INVALID_SOCKET;
socket_pair[1] = INVALID_SOCKET;

/*********************
** Listen Socket
**********************/
socket_fd_t listen_socket = INVALID_SOCKET;
listen_socket = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
if (listen_socket == INVALID_SOCKET)
{
return WSAGetLastError();
}

// allow it to be bound to an address already in use - do we actually need this?
int reuse = 1;
if (setsockopt(listen_socket, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast<const char*>(&reuse), static_cast<socklen_t>(sizeof(reuse))) == SOCKET_ERROR)
{
::closesocket(listen_socket);
return WSAGetLastError();
}

union
{
struct sockaddr_in inaddr;
struct sockaddr addr;
} a;

memset(&a, 0, sizeof(a));
a.inaddr.sin_family = AF_INET;
a.inaddr.sin_addr.s_addr = htonl(INADDR_LOOPBACK);
// For TCP/IP, if the port is specified as zero, the service provider assigns
// a unique port to the application from the dynamic client port range.
a.inaddr.sin_port = 0;

if (bind(listen_socket, &a.addr, sizeof(a.inaddr)) == SOCKET_ERROR)
{
::closesocket(listen_socket);
return WSAGetLastError();
}

// we need this below because the system auto filled in some entries, e.g. port #
socklen_t addrlen = static_cast<socklen_t>(sizeof(a.inaddr));
if (getsockname(listen_socket, &a.addr, &addrlen) == SOCKET_ERROR)
{
::closesocket(listen_socket);
return WSAGetLastError();
}
// max 1 connection permitted
if (listen(listen_socket, 1) == SOCKET_ERROR)
{
::closesocket(listen_socket);
return WSAGetLastError();
}

/*********************
** Connection
**********************/
DWORD overlapped_flag = 0;
socket_pair[0] = WSASocket(AF_INET, SOCK_STREAM, 0, NULL, 0, overlapped_flag);
if (socket_pair[0] == INVALID_SOCKET)
{
::closesocket(listen_socket);
::closesocket(socket_pair[0]);
return WSAGetLastError();
}

// reusing the information from above to connect to the listener
if (connect(socket_pair[0], &a.addr, sizeof(a.inaddr)) == SOCKET_ERROR)
{
::closesocket(listen_socket);
::closesocket(socket_pair[0]);
return WSAGetLastError();
}

/*********************
** Accept
**********************/
socket_pair[1] = accept(listen_socket, NULL, NULL);
if (socket_pair[1] == INVALID_SOCKET)
{
::closesocket(listen_socket);
::closesocket(socket_pair[0]);
return WSAGetLastError();
}

/*********************
** Cleanup
**********************/
::closesocket(listen_socket); // the listener has done its job.
return 0;
#endif
}

class Poller : public testing::Test
{
public:
Poller()
{
#ifdef _WIN32
WSADATA wsaData;
WSAStartup(MAKEWORD(2, 0), &wsaData);
#endif
}

~Poller()
{
::close(sockets_[0]);
::close(sockets_[1]);

#ifdef _WIN32
WSACleanup();
#endif
}

void waitThenSignal()
{
usleep(100000);
boost::this_thread::sleep(boost::posix_time::microseconds(100000));

poll_set_.signal();
}
Expand All @@ -68,15 +193,15 @@ class Poller : public testing::Test

virtual void SetUp()
{
if(socketpair(AF_UNIX, SOCK_STREAM, 0, sockets_) != 0)
if (create_socket_pair(sockets_) != 0)
{
FAIL();
}
if(fcntl(sockets_[0], F_SETFL, O_NONBLOCK) == -1)
if(set_nonblocking(sockets_[0]) != 0)
{
FAIL();
}
if(fcntl(sockets_[1], F_SETFL, O_NONBLOCK) == -1)
if(set_nonblocking(sockets_[1]) != 0)
{
FAIL();
}
Expand Down Expand Up @@ -390,15 +515,17 @@ TEST_F(Poller, signal)
poll_set_.update(-1);

// wait for poll_set_.signal_mutex_ to be unlocked after invoking signal()
usleep(50000);
boost::this_thread::sleep(boost::posix_time::microseconds(50000));
}


int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);

#ifndef _WIN32
signal(SIGPIPE, SIG_IGN);
#endif

return RUN_ALL_TESTS();
}
Expand Down
2 changes: 2 additions & 0 deletions test/test_roscpp/test/test_transport_tcp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -417,7 +417,9 @@ int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);

#ifndef _WIN32
signal(SIGPIPE, SIG_IGN);
#endif

return RUN_ALL_TESTS();
}