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 issues when built or run on Windows #1466

Merged
merged 8 commits into from
Aug 9, 2018
Merged
Show file tree
Hide file tree
Changes from 6 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
8 changes: 8 additions & 0 deletions clients/roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -124,13 +124,21 @@ 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
${catkin_LIBRARIES}
${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}
Expand Down
17 changes: 10 additions & 7 deletions clients/roscpp/src/libros/init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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)
Expand All @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/internal_timer_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
4 changes: 3 additions & 1 deletion clients/roscpp/src/libros/steady_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand All @@ -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<SteadyTime, WallDuration, SteadyTimerEvent>::threadFunc()
Expand Down Expand Up @@ -111,6 +112,7 @@ void TimerManager<SteadyTime, WallDuration, SteadyTimerEvent>::threadFunc()
new_timer_ = false;
}
}
#endif

SteadyTimer::Impl::Impl()
: started_(false)
Expand Down
2 changes: 0 additions & 2 deletions clients/roscpp/src/libros/topic_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string> pubs;
Expand Down
8 changes: 6 additions & 2 deletions clients/roscpp/src/libros/transport/transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,15 @@

#include "ros/transport/transport.h"
#include "ros/console.h"
#if defined(WIN32)
#include <winsock2.h>
#else
#include <netinet/in.h>
#include <sys/socket.h>
#include <netdb.h>
#endif

#if !defined(__ANDROID__)
#if !defined(__ANDROID__) && !defined(WIN32)
#include <ifaddrs.h>
#endif

Expand Down Expand Up @@ -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 ?)
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag_storage/include/rosbag/bag.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag_storage/include/rosbag/buffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

namespace rosbag {

class ROSBAG_DECL Buffer
class ROSBAG_STORAGE_DECL Buffer
{
public:
Buffer();
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag_storage/include/rosbag/chunked_file.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
8 changes: 8 additions & 0 deletions tools/rosbag_storage/include/rosbag/macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -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_ */
2 changes: 1 addition & 1 deletion tools/rosbag_storage/include/rosbag/message_instance.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
14 changes: 7 additions & 7 deletions tools/rosbag_storage/include/rosbag/query.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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);
Expand All @@ -84,7 +84,7 @@ class ROSBAG_DECL TopicQuery
std::vector<std::string> topics_;
};

class ROSBAG_DECL TypeQuery
class ROSBAG_STORAGE_DECL TypeQuery
{
public:
TypeQuery(std::string const& type);
Expand All @@ -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);

Expand All @@ -106,7 +106,7 @@ struct ROSBAG_DECL BagQuery
uint32_t bag_revision;
};

struct ROSBAG_DECL MessageRange
struct ROSBAG_STORAGE_DECL MessageRange
{
MessageRange(std::multiset<IndexEntry>::const_iterator const& _begin,
std::multiset<IndexEntry>::const_iterator const& _end,
Expand All @@ -120,15 +120,15 @@ struct ROSBAG_DECL MessageRange
};

//! The actual iterator data structure
struct ROSBAG_DECL ViewIterHelper
struct ROSBAG_STORAGE_DECL ViewIterHelper
{
ViewIterHelper(std::multiset<IndexEntry>::const_iterator _iter, MessageRange const* _range);

std::multiset<IndexEntry>::const_iterator iter;
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);
};
Expand Down
10 changes: 5 additions & 5 deletions tools/rosbag_storage/include/rosbag/stream.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class ChunkedFile;

class FileAccessor;

class ROSBAG_DECL Stream
class ROSBAG_STORAGE_DECL Stream
{
friend class FileAccessor;
public:
Expand Down Expand Up @@ -100,7 +100,7 @@ class ROSBAG_DECL Stream
ChunkedFile* file_;
};

class ROSBAG_DECL StreamFactory
class ROSBAG_STORAGE_DECL StreamFactory
{
public:
StreamFactory(ChunkedFile* file);
Expand All @@ -120,7 +120,7 @@ class FileAccessor {
}
};

class ROSBAG_DECL UncompressedStream : public Stream
class ROSBAG_STORAGE_DECL UncompressedStream : public Stream
{
public:
UncompressedStream(ChunkedFile* file);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand Down
8 changes: 4 additions & 4 deletions tools/rosbag_storage/include/rosbag/structures.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@

namespace rosbag {

struct ROSBAG_DECL ConnectionInfo
struct ROSBAG_STORAGE_DECL ConnectionInfo
{
ConnectionInfo() : id(-1) { }

Expand All @@ -66,14 +66,14 @@ struct ChunkInfo
std::map<uint32_t, uint32_t> 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
Expand All @@ -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; }
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag_storage/include/rosbag/view.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@

namespace rosbag {

class ROSBAG_DECL View
class ROSBAG_STORAGE_DECL View
{
friend class Bag;

Expand Down
5 changes: 5 additions & 0 deletions tools/rosgraph/src/rosgraph/roslogging.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,12 @@ def findCaller(self, dummy=False): # Dummy second arg to match Python3 function
f = inspect.currentframe()
if f is not None:
f = f.f_back
else:
return file_name, lineno, func_name
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you please provide some context why this change was necesary? The same for the break a few lines below.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

without this, roscore won't run on Windows. I need to investigate more about this change, will revert it from this PR for now.


while hasattr(f, "f_code"):
if f.f_back is None:
break
# Search for the right frame using the data already found by parent class.
co = f.f_code
filename = os.path.normcase(co.co_filename)
Expand Down
9 changes: 8 additions & 1 deletion tools/roslaunch/src/roslaunch/nodeprocess.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Loading