Skip to content

Commit

Permalink
Merge pull request #381 from ros/switch_to_boost_signals2
Browse files Browse the repository at this point in the history
update API to use boost::signals2 (#267)
  • Loading branch information
dirk-thomas committed Mar 31, 2014
2 parents 01093b4 + c82fb18 commit b49afac
Show file tree
Hide file tree
Showing 14 changed files with 23 additions and 89 deletions.
16 changes: 4 additions & 12 deletions clients/roscpp/include/ros/connection.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,15 +38,7 @@
#include "ros/header.h"
#include "common.h"

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals2.hpp>

#include <boost/function.hpp>
#include <boost/shared_ptr.hpp>
Expand Down Expand Up @@ -152,13 +144,13 @@ class ROSCPP_DECL Connection : public boost::enable_shared_from_this<Connection>
*/
void write(const boost::shared_array<uint8_t>& buffer, uint32_t size, const WriteFinishedFunc& finished_callback, bool immedate = true);

typedef boost::signal<void(const ConnectionPtr&, DropReason reason)> DropSignal;
typedef boost::signals2::signal<void(const ConnectionPtr&, DropReason reason)> DropSignal;
typedef boost::function<void(const ConnectionPtr&, DropReason reason)> DropFunc;
/**
* \brief Add a callback to be called when this connection has dropped
*/
boost::signals::connection addDropListener(const DropFunc& slot);
void removeDropListener(const boost::signals::connection& c);
boost::signals2::connection addDropListener(const DropFunc& slot);
void removeDropListener(const boost::signals2::connection& c);

/**
* \brief Set the header receipt callback
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/connection_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include "common.h"

#include <boost/thread/mutex.hpp>
#include <boost/signals/connection.hpp>
#include <boost/signals2/connection.hpp>

namespace ros
{
Expand Down Expand Up @@ -94,7 +94,7 @@ class ROSCPP_DECL ConnectionManager
uint32_t connection_id_counter_;
boost::mutex connection_id_counter_mutex_;

boost::signals::connection poll_conn_;
boost::signals2::connection poll_conn_;

TransportTCPPtr tcpserver_transport_;
TransportUDPPtr udpserver_transport_;
Expand Down
16 changes: 4 additions & 12 deletions clients/roscpp/include/ros/poll_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,7 @@
#include "poll_set.h"
#include "common.h"

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals2.hpp>

#include <boost/thread/recursive_mutex.hpp>
#include <boost/thread/thread.hpp>
Expand All @@ -50,7 +42,7 @@ namespace ros

class PollManager;
typedef boost::shared_ptr<PollManager> PollManagerPtr;
typedef boost::signal<void(void)> VoidSignal;
typedef boost::signals2::signal<void(void)> VoidSignal;
typedef boost::function<void(void)> VoidFunc;

class ROSCPP_DECL PollManager
Expand All @@ -63,8 +55,8 @@ class ROSCPP_DECL PollManager

PollSet& getPollSet() { return poll_set_; }

boost::signals::connection addPollThreadListener(const VoidFunc& func);
void removePollThreadListener(boost::signals::connection c);
boost::signals2::connection addPollThreadListener(const VoidFunc& func);
void removePollThreadListener(boost::signals2::connection c);

void start();
void shutdown();
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/service_client_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
#include <boost/thread/mutex.hpp>
#include <boost/shared_array.hpp>
#include <boost/enable_shared_from_this.hpp>
#include <boost/signals/connection.hpp>
#include <boost/signals2/connection.hpp>

#include <queue>

Expand Down Expand Up @@ -79,7 +79,7 @@ class ROSCPP_DECL ServiceClientLink : public boost::enable_shared_from_this<Serv
ConnectionPtr connection_;
ServicePublicationWPtr parent_;
bool persistent_;
boost::signals::connection dropped_conn_;
boost::signals2::connection dropped_conn_;
};
typedef boost::shared_ptr<ServiceClientLink> ServiceClientLinkPtr;

Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/transport_subscriber_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include "common.h"
#include "subscriber_link.h"

#include <boost/signals/connection.hpp>
#include <boost/signals2/connection.hpp>

namespace ros
{
Expand Down Expand Up @@ -66,7 +66,7 @@ class ROSCPP_DECL TransportSubscriberLink : public SubscriberLink
bool header_written_;

ConnectionPtr connection_;
boost::signals::connection dropped_conn_;
boost::signals2::connection dropped_conn_;

std::queue<SerializedMessage> outbox_;
boost::mutex outbox_mutex_;
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,13 +84,13 @@ void Connection::initialize(const TransportPtr& transport, bool is_server, const
}
}

boost::signals::connection Connection::addDropListener(const DropFunc& slot)
boost::signals2::connection Connection::addDropListener(const DropFunc& slot)
{
boost::recursive_mutex::scoped_lock lock(drop_mutex_);
return drop_signal_.connect(slot);
}

void Connection::removeDropListener(const boost::signals::connection& c)
void Connection::removeDropListener(const boost::signals2::connection& c)
{
boost::recursive_mutex::scoped_lock lock(drop_mutex_);
c.disconnect();
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/poll_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,13 +98,13 @@ void PollManager::threadFunc()
}
}

boost::signals::connection PollManager::addPollThreadListener(const VoidFunc& func)
boost::signals2::connection PollManager::addPollThreadListener(const VoidFunc& func)
{
boost::recursive_mutex::scoped_lock lock(signal_mutex_);
return poll_signal_.connect(func);
}

void PollManager::removePollThreadListener(boost::signals::connection c)
void PollManager::removePollThreadListener(boost::signals2::connection c)
{
boost::recursive_mutex::scoped_lock lock(signal_mutex_);
c.disconnect();
Expand Down
10 changes: 0 additions & 10 deletions utilities/message_filters/include/message_filters/cache.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,16 +39,6 @@
#include "boost/thread.hpp"
#include "boost/shared_ptr.hpp"

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif

#include "ros/time.h"

#include "connection.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#define MESSAGE_FILTERS_CONNECTION_H

#include <boost/function.hpp>
#include <boost/signals/connection.hpp>
#include <boost/signals2/connection.hpp>
#include "macros.h"

namespace message_filters
Expand All @@ -52,19 +52,19 @@ class MESSAGE_FILTERS_DECL Connection
typedef boost::function<void(const Connection&)> WithConnectionDisconnectFunction;
Connection() {}
Connection(const VoidDisconnectFunction& func);
Connection(const WithConnectionDisconnectFunction& func, boost::signals::connection conn);
Connection(const WithConnectionDisconnectFunction& func, boost::signals2::connection conn);

/**
* \brief disconnects this connection
*/
void disconnect();

boost::signals::connection getBoostConnection() const { return connection_; }
boost::signals2::connection getBoostConnection() const { return connection_; }

private:
VoidDisconnectFunction void_disconnect_;
WithConnectionDisconnectFunction connection_disconnect_;
boost::signals::connection connection_;
boost::signals2::connection connection_;
};

}
Expand Down
10 changes: 0 additions & 10 deletions utilities/message_filters/include/message_filters/subscriber.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,16 +37,6 @@

#include <ros/ros.h>

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif

#include <boost/thread/mutex.hpp>

#include "connection.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,16 +45,6 @@
#include <boost/function.hpp>
#include <boost/thread/mutex.hpp>

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif

#include <boost/bind.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/noncopyable.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,16 +45,6 @@
#include <boost/function.hpp>
#include <boost/thread/mutex.hpp>

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif

#include <boost/bind.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/noncopyable.hpp>
Expand Down
10 changes: 0 additions & 10 deletions utilities/message_filters/include/message_filters/synchronizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,16 +40,6 @@
#include <boost/function.hpp>
#include <boost/thread/mutex.hpp>

#ifndef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define BOOST_SIGNALS_NO_DEPRECATION_WARNING
#define ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif
#include <boost/signals.hpp>
#ifdef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef ros_BOOST_SIGNALS_NO_DEPRECATION_WARNING
#undef BOOST_SIGNALS_NO_DEPRECATION_WARNING
#endif

#include <boost/bind.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/noncopyable.hpp>
Expand Down
2 changes: 1 addition & 1 deletion utilities/message_filters/src/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ Connection::Connection(const VoidDisconnectFunction& func)
{
}

Connection::Connection(const WithConnectionDisconnectFunction& func, boost::signals::connection c)
Connection::Connection(const WithConnectionDisconnectFunction& func, boost::signals2::connection c)
: connection_disconnect_(func)
, connection_(c)
{
Expand Down

0 comments on commit b49afac

Please sign in to comment.