bond::Bond Class Reference

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

#include <bond.h>

List of all members.

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.
void breakBond ()
 Breaks the bond, notifying the other process.
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.
void setBrokenCallback (boost::function< void(void)> on_broken)
 Sets the broken callback.
void setConnectTimeout (double dur)
void setDisconnectTimeout (double dur)
void setFormedCallback (boost::function< void(void)> on_formed)
 Sets the formed callback.
void setHeartbeatPeriod (double dur)
void setHeartbeatTimeout (double dur)
void start ()
 Starts the bond and connects to the sister process.
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'.
 ~Bond ()
 Destructs the object, breaking the bond if it is still formed.

Private Member Functions

void bondStatusCB (const bond::Status::ConstPtr &msg)
void doPublishing (const ros::WallTimerEvent &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::WallTimer 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 53 of file bond.h.


Constructor & Destructor Documentation

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:
topic The topic used to exchange the bond status messages.
id The ID of the bond, which should match the ID used on the sister's end.
on_broken callback that will be called when the bond is broken.
on_formed callback that will be called when the bond is formed.

Definition at line 44 of file bond.cpp.

bond::Bond::~Bond (  ) 

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

Definition at line 70 of file bond.cpp.


Member Function Documentation

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

Definition at line 259 of file bond.cpp.

void bond::Bond::breakBond (  ) 

Breaks the bond, notifying the other process.

Definition at line 211 of file bond.cpp.

void bond::Bond::doPublishing ( const ros::WallTimerEvent &  e  )  [private]

Definition at line 293 of file bond.cpp.

void bond::Bond::flushPendingCallbacks (  )  [private]

Definition at line 325 of file bond.cpp.

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

Definition at line 63 of file bond.h.

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

Definition at line 65 of file bond.h.

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

Definition at line 69 of file bond.h.

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

Definition at line 67 of file bond.h.

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

Definition at line 108 of file bond.h.

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

Definition at line 109 of file bond.h.

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

Definition at line 107 of file bond.h.

bool bond::Bond::isBroken (  ) 

Indicates if the bond is broken.

Returns:
true iff the bond has been broken.

Definition at line 205 of file bond.cpp.

void bond::Bond::onConnectTimeout (  )  [private]

Definition at line 225 of file bond.cpp.

void bond::Bond::onDisconnectTimeout (  )  [private]

Definition at line 250 of file bond.cpp.

void bond::Bond::onHeartbeatTimeout (  )  [private]

Definition at line 233 of file bond.cpp.

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

Definition at line 312 of file bond.cpp.

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

Sets the broken callback.

Definition at line 155 of file bond.cpp.

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

Definition at line 95 of file bond.cpp.

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

Definition at line 106 of file bond.cpp.

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

Sets the formed callback.

Definition at line 149 of file bond.cpp.

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

Definition at line 128 of file bond.cpp.

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

Definition at line 117 of file bond.cpp.

void bond::Bond::start (  ) 

Starts the bond and connects to the sister process.

Definition at line 139 of file bond.cpp.

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

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

Parameters:
timeout Maximum 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 183 of file bond.cpp.

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

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

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

Definition at line 161 of file bond.cpp.


Friends And Related Function Documentation

friend class ::BondSM [friend]

Definition at line 112 of file bond.h.


Member Data Documentation

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

Definition at line 115 of file bond.h.

boost::condition bond::Bond::condition_ [private]

Definition at line 128 of file bond.h.

double bond::Bond::connect_timeout_ [private]

Definition at line 130 of file bond.h.

Definition at line 135 of file bond.h.

Definition at line 132 of file bond.h.

Definition at line 137 of file bond.h.

Definition at line 133 of file bond.h.

Definition at line 131 of file bond.h.

Definition at line 136 of file bond.h.

std::string bond::Bond::id_ [private]

Definition at line 119 of file bond.h.

std::string bond::Bond::instance_id_ [private]

Definition at line 120 of file bond.h.

boost::mutex bond::Bond::mutex_ [private]

Definition at line 127 of file bond.h.

ros::NodeHandle bond::Bond::nh_ [private]

Definition at line 114 of file bond.h.

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

Definition at line 122 of file bond.h.

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

Definition at line 123 of file bond.h.

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

Definition at line 152 of file bond.h.

ros::Publisher bond::Bond::pub_ [private]

Definition at line 140 of file bond.h.

ros::WallTimer bond::Bond::publishingTimer_ [private]

Definition at line 141 of file bond.h.

std::string bond::Bond::sister_instance_id_ [private]

Definition at line 121 of file bond.h.

Definition at line 124 of file bond.h.

Definition at line 116 of file bond.h.

bool bond::Bond::started_ [private]

Definition at line 125 of file bond.h.

ros::Subscriber bond::Bond::sub_ [private]

Definition at line 139 of file bond.h.

std::string bond::Bond::topic_ [private]

Definition at line 118 of file bond.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Friends Defines


bondcpp
Author(s): Stuart Glaser
autogenerated on Fri Jan 11 09:53:59 2013