Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
bond::Bond Class Reference

Forms a bond to monitor another process. More...

#include <bond.h>

Public Member Functions

 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. More...
 
void breakBond ()
 Breaks the bond, notifying the other process. More...
 
double getConnectTimeout () const
 
double getDisconnectTimeout () const
 
double getHeartbeatPeriod () const
 
double getHeartbeatTimeout () const
 
std::string getId ()
 
std::string getInstanceId ()
 
std::string getTopic ()
 
bool isBroken ()
 Indicates if the bond is broken. More...
 
void setBrokenCallback (boost::function< void(void)> on_broken)
 Sets the broken callback. More...
 
void setCallbackQueue (ros::CallbackQueueInterface *queue)
 
void setConnectTimeout (double dur)
 
void setDisconnectTimeout (double dur)
 
void setFormedCallback (boost::function< void(void)> on_formed)
 Sets the formed callback. More...
 
void setHeartbeatPeriod (double dur)
 
void setHeartbeatTimeout (double dur)
 
void start ()
 Starts the bond and connects to the sister process. More...
 
bool waitUntilBroken (ros::Duration timeout=ros::Duration(-1))
 Blocks until the bond is broken for at most 'duration'. More...
 
bool waitUntilBroken (ros::WallDuration timeout=ros::WallDuration(-1))
 Blocks until the bond is broken for at most 'duration'. More...
 
bool waitUntilFormed (ros::Duration timeout=ros::Duration(-1))
 Blocks until the bond is formed for at most 'duration'. More...
 
bool waitUntilFormed (ros::WallDuration timeout=ros::WallDuration(-1))
 Blocks until the bond is formed for at most 'duration'. More...
 
 ~Bond ()
 Destructs the object, breaking the bond if it is still formed. More...
 

Private Member Functions

void bondStatusCB (const bond::Status::ConstPtr &msg)
 
void doPublishing (const ros::SteadyTimerEvent &e)
 
void flushPendingCallbacks ()
 
void onConnectTimeout ()
 
void onDisconnectTimeout ()
 
void onHeartbeatTimeout ()
 
void publishStatus (bool active)
 

Private Attributes

boost::scoped_ptr< BondSMbondsm_
 
boost::condition condition_
 
double connect_timeout_
 
Timeout connect_timer_
 
double disconnect_timeout_
 
Timeout disconnect_timer_
 
double heartbeat_period_
 
double heartbeat_timeout_
 
Timeout heartbeat_timer_
 
std::string id_
 
std::string instance_id_
 
boost::mutex mutex_
 
ros::NodeHandle nh_
 
boost::function< void(void)> on_broken_
 
boost::function< void(void)> on_formed_
 
std::vector< boost::function< void(void)> > pending_callbacks_
 
ros::Publisher pub_
 
ros::SteadyTimer publishingTimer_
 
std::string sister_instance_id_
 
bool sisterDiedFirst_
 
BondSMContext sm_
 
bool started_
 
ros::Subscriber sub_
 
std::string topic_
 

Friends

class ::BondSM
 

Detailed Description

Forms a bond to monitor another process.

The bond::Bond class implements a bond, allowing you to monitor another process and be notified when it dies. In turn, it will be notified when you die.

Definition at line 68 of file bond.h.

Constructor & Destructor Documentation

◆ Bond()

bond::Bond::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.

Parameters
topicThe topic used to exchange the bond status messages.
idThe ID of the bond, which should match the ID used on the sister's end.
on_brokencallback that will be called when the bond is broken.
on_formedcallback that will be called when the bond is formed.

Definition at line 67 of file bond.cpp.

◆ ~Bond()

bond::Bond::~Bond ( )

Destructs the object, breaking the bond if it is still formed.

Definition at line 92 of file bond.cpp.

Member Function Documentation

◆ bondStatusCB()

void bond::Bond::bondStatusCB ( const bond::Status::ConstPtr &  msg)
private

Definition at line 309 of file bond.cpp.

◆ breakBond()

void bond::Bond::breakBond ( )

Breaks the bond, notifying the other process.

Definition at line 262 of file bond.cpp.

◆ doPublishing()

void bond::Bond::doPublishing ( const ros::SteadyTimerEvent e)
private

Definition at line 342 of file bond.cpp.

◆ flushPendingCallbacks()

void bond::Bond::flushPendingCallbacks ( )
private

Definition at line 368 of file bond.cpp.

◆ getConnectTimeout()

double bond::Bond::getConnectTimeout ( ) const
inline

Definition at line 87 of file bond.h.

◆ getDisconnectTimeout()

double bond::Bond::getDisconnectTimeout ( ) const
inline

Definition at line 89 of file bond.h.

◆ getHeartbeatPeriod()

double bond::Bond::getHeartbeatPeriod ( ) const
inline

Definition at line 93 of file bond.h.

◆ getHeartbeatTimeout()

double bond::Bond::getHeartbeatTimeout ( ) const
inline

Definition at line 91 of file bond.h.

◆ getId()

std::string bond::Bond::getId ( )
inline

Definition at line 148 of file bond.h.

◆ getInstanceId()

std::string bond::Bond::getInstanceId ( )
inline

Definition at line 149 of file bond.h.

◆ getTopic()

std::string bond::Bond::getTopic ( )
inline

Definition at line 147 of file bond.h.

◆ isBroken()

bool bond::Bond::isBroken ( )

Indicates if the bond is broken.

Returns
true iff the bond has been broken.

Definition at line 256 of file bond.cpp.

◆ onConnectTimeout()

void bond::Bond::onConnectTimeout ( )
private

Definition at line 275 of file bond.cpp.

◆ onDisconnectTimeout()

void bond::Bond::onDisconnectTimeout ( )
private

Definition at line 300 of file bond.cpp.

◆ onHeartbeatTimeout()

void bond::Bond::onHeartbeatTimeout ( )
private

Definition at line 283 of file bond.cpp.

◆ publishStatus()

void bond::Bond::publishStatus ( bool  active)
private

Definition at line 355 of file bond.cpp.

◆ setBrokenCallback()

void bond::Bond::setBrokenCallback ( boost::function< void(void)>  on_broken)

Sets the broken callback.

Definition at line 192 of file bond.cpp.

◆ setCallbackQueue()

void bond::Bond::setCallbackQueue ( ros::CallbackQueueInterface queue)

Definition at line 163 of file bond.cpp.

◆ setConnectTimeout()

void bond::Bond::setConnectTimeout ( double  dur)

Definition at line 120 of file bond.cpp.

◆ setDisconnectTimeout()

void bond::Bond::setDisconnectTimeout ( double  dur)

Definition at line 131 of file bond.cpp.

◆ setFormedCallback()

void bond::Bond::setFormedCallback ( boost::function< void(void)>  on_formed)

Sets the formed callback.

Definition at line 186 of file bond.cpp.

◆ setHeartbeatPeriod()

void bond::Bond::setHeartbeatPeriod ( double  dur)

Definition at line 153 of file bond.cpp.

◆ setHeartbeatTimeout()

void bond::Bond::setHeartbeatTimeout ( double  dur)

Definition at line 142 of file bond.cpp.

◆ start()

void bond::Bond::start ( )

Starts the bond and connects to the sister process.

Definition at line 174 of file bond.cpp.

◆ waitUntilBroken() [1/2]

bool bond::Bond::waitUntilBroken ( ros::Duration  timeout = ros::Duration(-1))

Blocks until the bond is broken for at most 'duration'.

Parameters
timeoutMaximum duration to wait. If -1 then this call will not timeout.
Returns
true iff the bond has been broken, even if it has never been formed.

Definition at line 227 of file bond.cpp.

◆ waitUntilBroken() [2/2]

bool bond::Bond::waitUntilBroken ( ros::WallDuration  timeout = ros::WallDuration(-1))

Blocks until the bond is broken for at most 'duration'.

Parameters
timeoutMaximum duration to wait. If -1 then this call will not timeout.
Returns
true iff the bond has been broken, even if it has never been formed.

Definition at line 231 of file bond.cpp.

◆ waitUntilFormed() [1/2]

bool bond::Bond::waitUntilFormed ( ros::Duration  timeout = ros::Duration(-1))

Blocks until the bond is formed for at most 'duration'.

Parameters
timeoutMaximum duration to wait. If -1 then this call will not timeout.
Returns
true iff the bond has been formed.

Definition at line 198 of file bond.cpp.

◆ waitUntilFormed() [2/2]

bool bond::Bond::waitUntilFormed ( ros::WallDuration  timeout = ros::WallDuration(-1))

Blocks until the bond is formed for at most 'duration'.

Parameters
timeoutMaximum duration to wait. If -1 then this call will not timeout.
Returns
true iff the bond has been formed.

Definition at line 202 of file bond.cpp.

Friends And Related Function Documentation

◆ ::BondSM

friend class ::BondSM
friend

Definition at line 152 of file bond.h.

Member Data Documentation

◆ bondsm_

boost::scoped_ptr<BondSM> bond::Bond::bondsm_
private

Definition at line 155 of file bond.h.

◆ condition_

boost::condition bond::Bond::condition_
private

Definition at line 168 of file bond.h.

◆ connect_timeout_

double bond::Bond::connect_timeout_
private

Definition at line 170 of file bond.h.

◆ connect_timer_

Timeout bond::Bond::connect_timer_
private

Definition at line 175 of file bond.h.

◆ disconnect_timeout_

double bond::Bond::disconnect_timeout_
private

Definition at line 172 of file bond.h.

◆ disconnect_timer_

Timeout bond::Bond::disconnect_timer_
private

Definition at line 177 of file bond.h.

◆ heartbeat_period_

double bond::Bond::heartbeat_period_
private

Definition at line 173 of file bond.h.

◆ heartbeat_timeout_

double bond::Bond::heartbeat_timeout_
private

Definition at line 171 of file bond.h.

◆ heartbeat_timer_

Timeout bond::Bond::heartbeat_timer_
private

Definition at line 176 of file bond.h.

◆ id_

std::string bond::Bond::id_
private

Definition at line 159 of file bond.h.

◆ instance_id_

std::string bond::Bond::instance_id_
private

Definition at line 160 of file bond.h.

◆ mutex_

boost::mutex bond::Bond::mutex_
private

Definition at line 167 of file bond.h.

◆ nh_

ros::NodeHandle bond::Bond::nh_
private

Definition at line 154 of file bond.h.

◆ on_broken_

boost::function<void(void)> bond::Bond::on_broken_
private

Definition at line 162 of file bond.h.

◆ on_formed_

boost::function<void(void)> bond::Bond::on_formed_
private

Definition at line 163 of file bond.h.

◆ pending_callbacks_

std::vector<boost::function<void(void)> > bond::Bond::pending_callbacks_
private

Definition at line 192 of file bond.h.

◆ pub_

ros::Publisher bond::Bond::pub_
private

Definition at line 180 of file bond.h.

◆ publishingTimer_

ros::SteadyTimer bond::Bond::publishingTimer_
private

Definition at line 181 of file bond.h.

◆ sister_instance_id_

std::string bond::Bond::sister_instance_id_
private

Definition at line 161 of file bond.h.

◆ sisterDiedFirst_

bool bond::Bond::sisterDiedFirst_
private

Definition at line 164 of file bond.h.

◆ sm_

BondSMContext bond::Bond::sm_
private

Definition at line 156 of file bond.h.

◆ started_

bool bond::Bond::started_
private

Definition at line 165 of file bond.h.

◆ sub_

ros::Subscriber bond::Bond::sub_
private

Definition at line 179 of file bond.h.

◆ topic_

std::string bond::Bond::topic_
private

Definition at line 158 of file bond.h.


The documentation for this class was generated from the following files:


bondcpp
Author(s): Stuart Glaser
autogenerated on Tue Mar 1 2022 23:53:37