diff --git a/clients/roscpp/CMakeLists.txt b/clients/roscpp/CMakeLists.txt index af68f8e13a..9fc475643b 100644 --- a/clients/roscpp/CMakeLists.txt +++ b/clients/roscpp/CMakeLists.txt @@ -124,6 +124,10 @@ add_library(roscpp src/libros/steady_timer.cpp ) +if(WIN32) + add_definitions(-DNOGDI) +endif() + add_dependencies(roscpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(roscpp @@ -131,6 +135,10 @@ target_link_libraries(roscpp ${Boost_LIBRARIES} ) +if(WIN32) + target_link_libraries(roscpp ws2_32) +endif() + #explicitly install library and includes install(TARGETS roscpp ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/clients/roscpp/src/libros/init.cpp b/clients/roscpp/src/libros/init.cpp index fa3a0430d8..61782462e4 100644 --- a/clients/roscpp/src/libros/init.cpp +++ b/clients/roscpp/src/libros/init.cpp @@ -316,13 +316,6 @@ void start() } } -#ifdef _MSC_VER - if (env_ipv6) - { - free(env_ipv6); - } -#endif - param::param("/tcp_keepalive", TransportTCP::s_use_keepalive_, TransportTCP::s_use_keepalive_); PollManager::instance()->addPollThreadListener(checkForShutdown); @@ -430,6 +423,13 @@ void check_ipv6_environment() { bool use_ipv6 = (env_ipv6 && strcmp(env_ipv6,"on") == 0); TransportTCP::s_use_ipv6_ = use_ipv6; XmlRpc::XmlRpcSocket::s_use_ipv6_ = use_ipv6; + +#ifdef _MSC_VER + if (env_ipv6) + { + free(env_ipv6); + } +#endif } void init(const M_string& remappings, const std::string& name, uint32_t options) @@ -454,6 +454,9 @@ void init(const M_string& remappings, const std::string& name, uint32_t options) // Disable SIGPIPE #ifndef WIN32 signal(SIGPIPE, SIG_IGN); +#else + WSADATA wsaData; + WSAStartup(MAKEWORD(2, 0), &wsaData); #endif check_ipv6_environment(); network::init(remappings); diff --git a/clients/roscpp/src/libros/internal_timer_manager.cpp b/clients/roscpp/src/libros/internal_timer_manager.cpp index 564c2bfbe0..4f5f751412 100644 --- a/clients/roscpp/src/libros/internal_timer_manager.cpp +++ b/clients/roscpp/src/libros/internal_timer_manager.cpp @@ -26,7 +26,7 @@ */ // Make sure we use CLOCK_MONOTONIC for the condition variable if not Apple. -#ifndef __APPLE__ +#if !defined(__APPLE__) && !defined(WIN32) #define BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC #endif diff --git a/clients/roscpp/src/libros/steady_timer.cpp b/clients/roscpp/src/libros/steady_timer.cpp index 69af3ac9b5..fac976a263 100644 --- a/clients/roscpp/src/libros/steady_timer.cpp +++ b/clients/roscpp/src/libros/steady_timer.cpp @@ -26,7 +26,7 @@ */ // Make sure we use CLOCK_MONOTONIC for the condition variable if not Apple. -#ifndef __APPLE__ +#if !defined(__APPLE__) && !defined(WIN32) #define BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC #endif @@ -44,6 +44,7 @@ namespace ros { +#if !defined(WIN32) // specialization for SteadyTimer, to make sure we use a version with wait_until that uses the monotonic clock template<> void TimerManager::threadFunc() @@ -111,6 +112,7 @@ void TimerManager::threadFunc() new_timer_ = false; } } +#endif SteadyTimer::Impl::Impl() : started_(false) diff --git a/clients/roscpp/src/libros/topic_manager.cpp b/clients/roscpp/src/libros/topic_manager.cpp index 363fb05e10..e4725b1cd2 100644 --- a/clients/roscpp/src/libros/topic_manager.cpp +++ b/clients/roscpp/src/libros/topic_manager.cpp @@ -1000,8 +1000,6 @@ void TopicManager::getPublications(XmlRpcValue &pubs) } } -extern std::string console::g_last_error_message; - void TopicManager::pubUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result) { std::vector pubs; diff --git a/clients/roscpp/src/libros/transport/transport.cpp b/clients/roscpp/src/libros/transport/transport.cpp index b4c3fbb30b..1fdda36f86 100644 --- a/clients/roscpp/src/libros/transport/transport.cpp +++ b/clients/roscpp/src/libros/transport/transport.cpp @@ -34,11 +34,15 @@ #include "ros/transport/transport.h" #include "ros/console.h" +#if defined(WIN32) +#include +#else #include #include #include +#endif -#if !defined(__ANDROID__) +#if !defined(__ANDROID__) && !defined(WIN32) #include #endif @@ -71,7 +75,7 @@ Transport::Transport() gethostname(our_hostname, sizeof(our_hostname)-1); allowed_hosts_.push_back(std::string(our_hostname)); allowed_hosts_.push_back("localhost"); -#if !defined(__ANDROID__) +#if !defined(__ANDROID__) && !defined(WIN32) // for ipv4 loopback, we'll explicitly search for 127.* in isHostAllowed() // now we need to iterate all local interfaces and add their addresses // from the getifaddrs manpage: (maybe something similar for windows ?) diff --git a/tools/rosbag_storage/include/rosbag/bag.h b/tools/rosbag_storage/include/rosbag/bag.h index ebb2ae263f..c65533011e 100644 --- a/tools/rosbag_storage/include/rosbag/bag.h +++ b/tools/rosbag_storage/include/rosbag/bag.h @@ -96,7 +96,7 @@ class MessageInstance; class View; class Query; -class ROSBAG_DECL Bag +class ROSBAG_STORAGE_DECL Bag { friend class MessageInstance; friend class View; diff --git a/tools/rosbag_storage/include/rosbag/buffer.h b/tools/rosbag_storage/include/rosbag/buffer.h index aef6c99e4b..cdf5af01e8 100644 --- a/tools/rosbag_storage/include/rosbag/buffer.h +++ b/tools/rosbag_storage/include/rosbag/buffer.h @@ -40,7 +40,7 @@ namespace rosbag { -class ROSBAG_DECL Buffer +class ROSBAG_STORAGE_DECL Buffer { public: Buffer(); diff --git a/tools/rosbag_storage/include/rosbag/chunked_file.h b/tools/rosbag_storage/include/rosbag/chunked_file.h index 722aeca3ea..dc0310c8e3 100644 --- a/tools/rosbag_storage/include/rosbag/chunked_file.h +++ b/tools/rosbag_storage/include/rosbag/chunked_file.h @@ -48,7 +48,7 @@ namespace rosbag { //! ChunkedFile reads and writes files which contain interleaved chunks of compressed and uncompressed data. -class ROSBAG_DECL ChunkedFile +class ROSBAG_STORAGE_DECL ChunkedFile { friend class Stream; diff --git a/tools/rosbag_storage/include/rosbag/macros.h b/tools/rosbag_storage/include/rosbag/macros.h index 967465f4ec..5ddc9059eb 100644 --- a/tools/rosbag_storage/include/rosbag/macros.h +++ b/tools/rosbag_storage/include/rosbag/macros.h @@ -38,8 +38,16 @@ #else // we are using shared lib/dll #define ROSBAG_DECL ROS_HELPER_IMPORT #endif + + #ifdef rosbag_storage_EXPORTS // we are building a shared lib/dll + #define ROSBAG_STORAGE_DECL ROS_HELPER_EXPORT + #else // we are using shared lib/dll + #define ROSBAG_STORAGE_DECL ROS_HELPER_IMPORT + #endif + #else // ros is being built around static libraries #define ROSBAG_DECL + #define ROSBAG_STORAGE_DECL #endif #endif /* ROSBAG_MACROS_H_ */ diff --git a/tools/rosbag_storage/include/rosbag/message_instance.h b/tools/rosbag_storage/include/rosbag/message_instance.h index 7f18ec6fdc..299ce65fc6 100644 --- a/tools/rosbag_storage/include/rosbag/message_instance.h +++ b/tools/rosbag_storage/include/rosbag/message_instance.h @@ -56,7 +56,7 @@ class Bag; * It adheres to the necessary ros::message_traits to be directly * serializable. */ -class ROSBAG_DECL MessageInstance +class ROSBAG_STORAGE_DECL MessageInstance { friend class View; diff --git a/tools/rosbag_storage/include/rosbag/query.h b/tools/rosbag_storage/include/rosbag/query.h index fd43214c2f..2c8c56900b 100644 --- a/tools/rosbag_storage/include/rosbag/query.h +++ b/tools/rosbag_storage/include/rosbag/query.h @@ -49,7 +49,7 @@ namespace rosbag { class Bag; -class ROSBAG_DECL Query +class ROSBAG_STORAGE_DECL Query { public: //! The base query takes an optional time-range @@ -72,7 +72,7 @@ class ROSBAG_DECL Query ros::Time end_time_; }; -class ROSBAG_DECL TopicQuery +class ROSBAG_STORAGE_DECL TopicQuery { public: TopicQuery(std::string const& topic); @@ -84,7 +84,7 @@ class ROSBAG_DECL TopicQuery std::vector topics_; }; -class ROSBAG_DECL TypeQuery +class ROSBAG_STORAGE_DECL TypeQuery { public: TypeQuery(std::string const& type); @@ -97,7 +97,7 @@ class ROSBAG_DECL TypeQuery }; //! Pairs of queries and the bags they come from (used internally by View) -struct ROSBAG_DECL BagQuery +struct ROSBAG_STORAGE_DECL BagQuery { BagQuery(Bag const* _bag, Query const& _query, uint32_t _bag_revision); @@ -106,7 +106,7 @@ struct ROSBAG_DECL BagQuery uint32_t bag_revision; }; -struct ROSBAG_DECL MessageRange +struct ROSBAG_STORAGE_DECL MessageRange { MessageRange(std::multiset::const_iterator const& _begin, std::multiset::const_iterator const& _end, @@ -120,7 +120,7 @@ struct ROSBAG_DECL MessageRange }; //! The actual iterator data structure -struct ROSBAG_DECL ViewIterHelper +struct ROSBAG_STORAGE_DECL ViewIterHelper { ViewIterHelper(std::multiset::const_iterator _iter, MessageRange const* _range); @@ -128,7 +128,7 @@ struct ROSBAG_DECL ViewIterHelper MessageRange const* range; //!< pointer to vector of ranges in View }; -struct ROSBAG_DECL ViewIterHelperCompare +struct ROSBAG_STORAGE_DECL ViewIterHelperCompare { bool operator()(ViewIterHelper const& a, ViewIterHelper const& b); }; diff --git a/tools/rosbag_storage/include/rosbag/stream.h b/tools/rosbag_storage/include/rosbag/stream.h index 2ef7fac3ea..e9a0ca0557 100644 --- a/tools/rosbag_storage/include/rosbag/stream.h +++ b/tools/rosbag_storage/include/rosbag/stream.h @@ -65,7 +65,7 @@ class ChunkedFile; class FileAccessor; -class ROSBAG_DECL Stream +class ROSBAG_STORAGE_DECL Stream { friend class FileAccessor; public: @@ -100,7 +100,7 @@ class ROSBAG_DECL Stream ChunkedFile* file_; }; -class ROSBAG_DECL StreamFactory +class ROSBAG_STORAGE_DECL StreamFactory { public: StreamFactory(ChunkedFile* file); @@ -120,7 +120,7 @@ class FileAccessor { } }; -class ROSBAG_DECL UncompressedStream : public Stream +class ROSBAG_STORAGE_DECL UncompressedStream : public Stream { public: UncompressedStream(ChunkedFile* file); @@ -136,7 +136,7 @@ class ROSBAG_DECL UncompressedStream : public Stream /*! * BZ2Stream uses libbzip2 (http://www.bzip.org) for reading/writing compressed data in the BZ2 format. */ -class ROSBAG_DECL BZ2Stream : public Stream +class ROSBAG_STORAGE_DECL BZ2Stream : public Stream { public: BZ2Stream(ChunkedFile* file); @@ -164,7 +164,7 @@ class ROSBAG_DECL BZ2Stream : public Stream // LZ4Stream reads/writes compressed datat in the LZ4 format // https://code.google.com/p/lz4/ -class ROSBAG_DECL LZ4Stream : public Stream +class ROSBAG_STORAGE_DECL LZ4Stream : public Stream { public: LZ4Stream(ChunkedFile* file); diff --git a/tools/rosbag_storage/include/rosbag/structures.h b/tools/rosbag_storage/include/rosbag/structures.h index ad75b1ee95..72db0e3c1e 100644 --- a/tools/rosbag_storage/include/rosbag/structures.h +++ b/tools/rosbag_storage/include/rosbag/structures.h @@ -44,7 +44,7 @@ namespace rosbag { -struct ROSBAG_DECL ConnectionInfo +struct ROSBAG_STORAGE_DECL ConnectionInfo { ConnectionInfo() : id(-1) { } @@ -66,14 +66,14 @@ struct ChunkInfo std::map connection_counts; //! number of messages in each connection stored in the chunk }; -struct ROSBAG_DECL ChunkHeader +struct ROSBAG_STORAGE_DECL ChunkHeader { std::string compression; //! chunk compression type, e.g. "none" or "bz2" (see constants.h) uint32_t compressed_size; //! compressed size of the chunk in bytes uint32_t uncompressed_size; //! uncompressed size of the chunk in bytes }; -struct ROSBAG_DECL IndexEntry +struct ROSBAG_STORAGE_DECL IndexEntry { ros::Time time; //! timestamp of the message uint64_t chunk_pos; //! absolute byte offset of the chunk record containing the message @@ -82,7 +82,7 @@ struct ROSBAG_DECL IndexEntry bool operator<(IndexEntry const& b) const { return time < b.time; } }; -struct ROSBAG_DECL IndexEntryCompare +struct ROSBAG_STORAGE_DECL IndexEntryCompare { bool operator()(ros::Time const& a, IndexEntry const& b) const { return a < b.time; } bool operator()(IndexEntry const& a, ros::Time const& b) const { return a.time < b; } diff --git a/tools/rosbag_storage/include/rosbag/view.h b/tools/rosbag_storage/include/rosbag/view.h index ea9048adb9..9cdcee98a3 100644 --- a/tools/rosbag_storage/include/rosbag/view.h +++ b/tools/rosbag_storage/include/rosbag/view.h @@ -45,7 +45,7 @@ namespace rosbag { -class ROSBAG_DECL View +class ROSBAG_STORAGE_DECL View { friend class Bag; diff --git a/tools/roslaunch/src/roslaunch/nodeprocess.py b/tools/roslaunch/src/roslaunch/nodeprocess.py index 27cc62b377..bbe92ff4e4 100644 --- a/tools/roslaunch/src/roslaunch/nodeprocess.py +++ b/tools/roslaunch/src/roslaunch/nodeprocess.py @@ -306,7 +306,14 @@ def start(self): _logger.info("process[%s]: cwd will be [%s]", self.name, cwd) try: - self.popen = subprocess.Popen(self.args, cwd=cwd, stdout=logfileout, stderr=logfileerr, env=full_env, close_fds=True, preexec_fn=os.setsid) + preexec_function = os.setsid + close_file_descriptor = True + except AttributeError: + preexec_function = None + close_file_descriptor = False + + try: + self.popen = subprocess.Popen(self.args, cwd=cwd, stdout=logfileout, stderr=logfileerr, env=full_env, close_fds=close_file_descriptor, preexec_fn=preexec_function) except OSError as e: self.started = True # must set so is_alive state is correct _logger.error("OSError(%d, %s)", e.errno, e.strerror) diff --git a/utilities/roslz4/CMakeLists.txt b/utilities/roslz4/CMakeLists.txt index ae9d75f370..e56584a65f 100644 --- a/utilities/roslz4/CMakeLists.txt +++ b/utilities/roslz4/CMakeLists.txt @@ -6,7 +6,7 @@ if(NOT WIN32) set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Wextra") endif() -find_package(catkin REQUIRED) +find_package(catkin REQUIRED COMPONENTS cpp_common) find_path(lz4_INCLUDE_DIRS NAMES lz4.h) if (NOT lz4_INCLUDE_DIRS) @@ -28,9 +28,11 @@ catkin_package( include_directories(include ${lz4_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS}) add_library(roslz4 src/lz4s.c src/xxhash.c) -set_source_files_properties( - src/lz4s.c -PROPERTIES COMPILE_FLAGS "-Wno-sign-compare") +if (NOT WIN32) + set_source_files_properties( + src/lz4s.c + PROPERTIES COMPILE_FLAGS "-Wno-sign-compare") +endif() set_source_files_properties( src/lz4s.c src/xxhash.c PROPERTIES COMPILE_DEFINITIONS "XXH_NAMESPACE=ROSLZ4_") @@ -43,12 +45,18 @@ find_package(PythonLibs "${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" REQUIR include_directories(${PYTHON_INCLUDE_PATH}) add_library(roslz4_py src/_roslz4module.c) -set_source_files_properties( - src/_roslz4module.c -PROPERTIES COMPILE_FLAGS "-Wno-missing-field-initializers -Wno-unused-variable -Wno-strict-aliasing") -set_target_properties( - roslz4_py PROPERTIES OUTPUT_NAME roslz4 PREFIX "_" SUFFIX ".so" +if (NOT WIN32) + set_source_files_properties( + src/_roslz4module.c + PROPERTIES COMPILE_FLAGS "-Wno-missing-field-initializers -Wno-unused-variable -Wno-strict-aliasing") +endif() +set_target_properties(roslz4_py PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${CATKIN_DEVEL_PREFIX}/${PYTHON_INSTALL_DIR}/roslz4) +if (NOT WIN32) + set_target_properties(roslz4_py PROPERTIES OUTPUT_NAME roslz4 PREFIX "_" SUFFIX ".so") +else() + set_target_properties(roslz4_py PROPERTIES OUTPUT_NAME _roslz4 SUFFIX ".pyd") +endif() target_link_libraries(roslz4_py roslz4 ${catkin_LIBRARIES} ${PYTHON_LIBRARIES}) endif() @@ -60,7 +68,9 @@ install(TARGETS roslz4 if(NOT ANDROID) install(TARGETS roslz4_py - LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) endif() install(DIRECTORY include/${PROJECT_NAME} diff --git a/utilities/roslz4/include/roslz4/lz4s.h b/utilities/roslz4/include/roslz4/lz4s.h index 6d8dd271c0..ece489ca72 100644 --- a/utilities/roslz4/include/roslz4/lz4s.h +++ b/utilities/roslz4/include/roslz4/lz4s.h @@ -36,6 +36,18 @@ #define ROSLZ4_LZ4S_H #include +#include + +// Import/export for windows dll's and visibility for gcc shared libraries. +#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries + #ifdef roslz4_EXPORTS // we are building a shared lib/dll + #define ROSLZ4S_DECL ROS_HELPER_EXPORT + #else // we are using shared lib/dll + #define ROSLZ4S_DECL ROS_HELPER_IMPORT + #endif +#else // ros is being built around static libraries + #define ROSLZ4S_DECL +#endif #ifdef __cplusplus extern "C" { @@ -71,22 +83,22 @@ typedef struct { } roslz4_stream; // Low level functions -int roslz4_blockSizeFromIndex(int block_id); +ROSLZ4S_DECL int roslz4_blockSizeFromIndex(int block_id); -int roslz4_compressStart(roslz4_stream *stream, int block_size_id); -int roslz4_compress(roslz4_stream *stream, int action); -void roslz4_compressEnd(roslz4_stream *stream); +ROSLZ4S_DECL int roslz4_compressStart(roslz4_stream *stream, int block_size_id); +ROSLZ4S_DECL int roslz4_compress(roslz4_stream *stream, int action); +ROSLZ4S_DECL void roslz4_compressEnd(roslz4_stream *stream); -int roslz4_decompressStart(roslz4_stream *stream); -int roslz4_decompress(roslz4_stream *stream); -void roslz4_decompressEnd(roslz4_stream *str); +ROSLZ4S_DECL int roslz4_decompressStart(roslz4_stream *stream); +ROSLZ4S_DECL int roslz4_decompress(roslz4_stream *stream); +ROSLZ4S_DECL void roslz4_decompressEnd(roslz4_stream *str); // Oneshot compression / decompression -int roslz4_buffToBuffCompress(char *input, unsigned int input_size, - char *output, unsigned int *output_size, - int block_size_id); -int roslz4_buffToBuffDecompress(char *input, unsigned int input_size, - char *output, unsigned int *output_size); +ROSLZ4S_DECL int roslz4_buffToBuffCompress(char *input, unsigned int input_size, + char *output, unsigned int *output_size, + int block_size_id); +ROSLZ4S_DECL int roslz4_buffToBuffDecompress(char *input, unsigned int input_size, + char *output, unsigned int *output_size); #ifdef __cplusplus } diff --git a/utilities/roslz4/package.xml b/utilities/roslz4/package.xml index b2cc5754b0..24127a6eb7 100644 --- a/utilities/roslz4/package.xml +++ b/utilities/roslz4/package.xml @@ -15,6 +15,7 @@ catkin lz4 + cpp_common lz4 diff --git a/utilities/roslz4/src/lz4s.c b/utilities/roslz4/src/lz4s.c index 85e46c72d7..e7c804e6a4 100644 --- a/utilities/roslz4/src/lz4s.c +++ b/utilities/roslz4/src/lz4s.c @@ -80,9 +80,11 @@ void writeUInt32(unsigned char *buffer, uint32_t val) { buffer[3] = (val >> 24) & 0xFF; } +#ifndef _MSC_VER int min(int a, int b) { return a < b ? a : b; } +#endif /*========================== Low level compression ==========================*/ diff --git a/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcDispatch.h b/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcDispatch.h index 3177fdb907..441ccd8596 100644 --- a/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcDispatch.h +++ b/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcDispatch.h @@ -12,6 +12,7 @@ #ifndef MAKEDEPEND # include +# include #endif namespace XmlRpc { diff --git a/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcServer.h b/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcServer.h index 1069755aac..4b40794930 100644 --- a/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcServer.h +++ b/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcServer.h @@ -15,7 +15,11 @@ # include # include # include -# include +# if defined(_WINDOWS) +# include +# else +# include +# endif #endif #include "xmlrpcpp/XmlRpcDispatch.h" diff --git a/utilities/xmlrpcpp/src/XmlRpcDispatch.cpp b/utilities/xmlrpcpp/src/XmlRpcDispatch.cpp index a47666b5a5..c211a430a4 100644 --- a/utilities/xmlrpcpp/src/XmlRpcDispatch.cpp +++ b/utilities/xmlrpcpp/src/XmlRpcDispatch.cpp @@ -8,7 +8,6 @@ #include #include #include -#include #if defined(_WINDOWS) # include @@ -23,6 +22,7 @@ static inline int poll( struct pollfd *pfd, int nfds, int timeout) # define ftime _ftime_s # endif #else +# include # include #endif // _WINDOWS @@ -87,8 +87,13 @@ XmlRpcDispatch::work(double timeout) const unsigned POLLIN_CHK = (POLLIN | POLLHUP | POLLERR); // Readable or connection lost const unsigned POLLOUT_REQ = POLLOUT; // Request write const unsigned POLLOUT_CHK = (POLLOUT | POLLERR); // Writable or connection lost +#if !defined(_WINDOWS) const unsigned POLLEX_REQ = POLLPRI; // Out-of-band data received const unsigned POLLEX_CHK = (POLLPRI | POLLNVAL); // Out-of-band data or invalid fd +#else + const unsigned POLLEX_REQ = POLLRDBAND; // Out-of-band data received + const unsigned POLLEX_CHK = (POLLRDBAND | POLLNVAL); // Out-of-band data or invalid fd +#endif // Compute end time _endTime = (timeout < 0.0) ? -1.0 : (getTime() + timeout); @@ -101,8 +106,8 @@ XmlRpcDispatch::work(double timeout) // Construct the sets of descriptors we are interested in const unsigned source_cnt = _sources.size(); - pollfd fds[source_cnt]; - XmlRpcSource * sources[source_cnt]; + std::vector fds(source_cnt); + std::vector sources(source_cnt); SourceList::iterator it; std::size_t i = 0; @@ -117,12 +122,16 @@ XmlRpcDispatch::work(double timeout) } // Check for events - int nEvents = poll(fds, source_cnt, (timeout_ms < 0) ? -1 : timeout_ms); + int nEvents = poll(&fds[0], source_cnt, (timeout_ms < 0) ? -1 : timeout_ms); if (nEvents < 0) { +#if defined(_WINDOWS) + XmlRpcUtil::error("Error in XmlRpcDispatch::work: error in poll (%d).", WSAGetLastError()); +#else if(errno != EINTR) XmlRpcUtil::error("Error in XmlRpcDispatch::work: error in poll (%d).", nEvents); +#endif _inWork = false; return; } diff --git a/utilities/xmlrpcpp/src/XmlRpcServer.cpp b/utilities/xmlrpcpp/src/XmlRpcServer.cpp index 3b84286780..bd252c27b7 100644 --- a/utilities/xmlrpcpp/src/XmlRpcServer.cpp +++ b/utilities/xmlrpcpp/src/XmlRpcServer.cpp @@ -11,7 +11,9 @@ #include #include -#include +#if !defined(_WINDOWS) +# include +#endif using namespace XmlRpc; @@ -26,6 +28,7 @@ XmlRpcServer::XmlRpcServer() _accept_error(false), _accept_retry_time_sec(0.0) { +#if !defined(_WINDOWS) struct rlimit limit = { .rlim_cur = 0, .rlim_max = 0 }; unsigned int max_files = 1024; @@ -43,6 +46,7 @@ XmlRpcServer::XmlRpcServer() pollfds[i].fd = i; pollfds[i].events = POLLIN | POLLPRI | POLLOUT; } +#endif // Ask dispatch not to close this socket if it becomes unreadable. setKeepOpen(true); @@ -215,6 +219,8 @@ int XmlRpcServer::countFreeFDs() { // // If the underlying system calls here fail, this will print an error and // return 0 + +#if !defined(_WINDOWS) int free_fds = 0; struct rlimit limit = { .rlim_cur = 0, .rlim_max = 0 }; @@ -253,6 +259,9 @@ int XmlRpcServer::countFreeFDs() { } return free_fds; +#else + return FREE_FD_BUFFER; +#endif } diff --git a/utilities/xmlrpcpp/src/XmlRpcSocket.cpp b/utilities/xmlrpcpp/src/XmlRpcSocket.cpp index 8c5fce05df..7cbfc7567f 100644 --- a/utilities/xmlrpcpp/src/XmlRpcSocket.cpp +++ b/utilities/xmlrpcpp/src/XmlRpcSocket.cpp @@ -209,9 +209,13 @@ XmlRpcSocket::connect(int fd, const std::string& host, int port) hints.ai_family = AF_UNSPEC; int getaddr_err = getaddrinfo(host.c_str(), NULL, &hints, &addr); if (0 != getaddr_err) { +#if !defined(_WINDOWS) if(getaddr_err == EAI_SYSTEM) { XmlRpcUtil::error("Couldn't find an %s address for [%s]: %s\n", s_use_ipv6_ ? "AF_INET6" : "AF_INET", host.c_str(), XmlRpcSocket::getErrorMsg().c_str()); } else { +#else + { +#endif XmlRpcUtil::error("Couldn't find an %s address for [%s]: %s\n", s_use_ipv6_ ? "AF_INET6" : "AF_INET", host.c_str(), gai_strerror(getaddr_err)); } return false;