33 #include <boost/thread/thread_time.hpp>    34 #include <boost/date_time/posix_time/posix_time_types.hpp>    39 #include <uuid/uuid.h>    54   UuidToStringA(&uuid, &str);
    55   std::string return_string(reinterpret_cast<char *>(str));
    60   uuid_generate_random(uuid);
    62   uuid_unparse(uuid, uuid_str);
    63   return std::string(uuid_str);
    67 Bond::Bond(
const std::string &topic, 
const std::string &
id,
    68            boost::function<
void(
void)> on_broken,
    69            boost::function<
void(
void)> on_formed)
    77   on_broken_(on_broken),
    78   on_formed_(on_formed),
    79   sisterDiedFirst_(false),
    82   connect_timer_(
ros::WallDuration(), 
boost::bind(&
Bond::onConnectTimeout, this)),
    83   heartbeat_timer_(
ros::WallDuration(), 
boost::bind(&
Bond::onHeartbeatTimeout, this)),
    84   disconnect_timer_(
ros::WallDuration(), 
boost::bind(&
Bond::onDisconnectTimeout, this))
   115   boost::mutex::scoped_lock lock(
mutex_);
   123     ROS_ERROR(
"Cannot set timeouts after calling start()");
   134     ROS_ERROR(
"Cannot set timeouts after calling start()");
   145     ROS_ERROR(
"Cannot set timeouts after calling start()");
   156     ROS_ERROR(
"Cannot set timeouts after calling start()");
   166     ROS_ERROR(
"Cannot set callback queue after calling start()");
   176   boost::mutex::scoped_lock lock(
mutex_);
   188   boost::mutex::scoped_lock lock(
mutex_);
   194   boost::mutex::scoped_lock lock(
mutex_);
   204   boost::mutex::scoped_lock lock(
mutex_);
   222       static_cast<int64_t>(wait_time.
toSec() * 1000.0f)));
   233   boost::mutex::scoped_lock lock(
mutex_);
   251       static_cast<int64_t>(wait_time.
toSec() * 1000.0f)));
   258   boost::mutex::scoped_lock lock(
mutex_);
   265     boost::mutex::scoped_lock lock(
mutex_);
   278     boost::mutex::scoped_lock lock(
mutex_);
   286   bool disable_heartbeat_timeout;
   287   nh_.
param(bond::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, disable_heartbeat_timeout, 
false);
   288   if (disable_heartbeat_timeout) {
   289     ROS_WARN(
"Heartbeat timeout is disabled.  Not breaking bond (topic: %s, id: %s)",
   295     boost::mutex::scoped_lock lock(
mutex_);
   303     boost::mutex::scoped_lock lock(
mutex_);
   314       boost::mutex::scoped_lock lock(
mutex_);
   321           "More than two locations are trying to use a single bond (topic: %s, id: %s).  "   322           "You should only instantiate at most two bond instances for each (topic, id) pair.",
   344   boost::mutex::scoped_lock lock(
mutex_);
   357   bond::Status::Ptr msg(
new bond::Status);
   361   msg->active = active;
   370   std::vector<boost::function<void(void)> > callbacks;
   372     boost::mutex::scoped_lock lock(
mutex_);
   377   for (
size_t i = 0; i < callbacks.size(); ++i) {
   387   b->connect_timer_.cancel();
   388   b->condition_.notify_all();
   390     b->pending_callbacks_.push_back(b->on_formed_);
   396   b->sisterDiedFirst_ = 
true;
   401   b->condition_.notify_all();
   402   b->heartbeat_timer_.cancel();
   403   b->disconnect_timer_.cancel();
   405     b->pending_callbacks_.push_back(b->on_broken_);
   411   b->heartbeat_timer_.reset();
   416   b->heartbeat_timer_.cancel();
   417   b->disconnect_timer_.reset();
   418   b->publishingTimer_.setPeriod(
ros::WallDuration(bond::Constants::DEAD_PUBLISH_PERIOD));
 
double heartbeat_timeout_
void setHeartbeatPeriod(double dur)
void breakBond()
Breaks the bond, notifying the other process. 
void publish(const boost::shared_ptr< M > &message) const 
Bond(const std::string &topic, const std::string &id, boost::function< void(void)> on_broken=boost::function< void(void)>(), boost::function< void(void)> on_formed=boost::function< void(void)>())
Constructs a bond, but does not connect. 
void setBrokenCallback(boost::function< void(void)> on_broken)
Sets the broken callback. 
void setCallbackQueue(ros::CallbackQueueInterface *queue)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setHeartbeatTimeout(double dur)
void bondStatusCB(const bond::Status::ConstPtr &msg)
~Bond()
Destructs the object, breaking the bond if it is still formed. 
void onDisconnectTimeout()
ros::SteadyTimer publishingTimer_
std::vector< boost::function< void(void)> > pending_callbacks_
static std::string makeUUID()
void setConnectTimeout(double dur)
void flushPendingCallbacks()
boost::function< void(void)> on_broken_
void publishStatus(bool active)
bool waitUntilBroken(ros::Duration timeout=ros::Duration(-1))
Blocks until the bond is broken for at most 'duration'. 
bool waitUntilFormed(ros::Duration timeout=ros::Duration(-1))
Blocks until the bond is formed for at most 'duration'. 
void start()
Starts the bond and connects to the sister process. 
static SM_WaitingForSister WaitingForSister
void setDisconnectTimeout(double dur)
SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const 
boost::condition condition_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
void setCallbackQueue(CallbackQueueInterface *queue)
std::string sister_instance_id_
static SM_AwaitSisterDeath AwaitSisterDeath
boost::function< void(void)> on_formed_
Forms a bond to monitor another process. 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Timeout disconnect_timer_
bool isBroken()
Indicates if the bond is broken. 
double disconnect_timeout_
BondSMState & getState() const 
void onHeartbeatTimeout()
void doPublishing(const ros::SteadyTimerEvent &e)
void setDuration(const ros::Duration &d)
void setFormedCallback(boost::function< void(void)> on_formed)
Sets the formed callback.