Public Member Functions | Private Member Functions | Private Attributes | Friends
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 setCallbackQueue (ros::CallbackQueueInterface *queue)
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 waitUntilBroken (ros::WallDuration timeout=ros::WallDuration(-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'.
bool waitUntilFormed (ros::WallDuration timeout=ros::WallDuration(-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 54 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:
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 63 of file bond.cpp.

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

Definition at line 88 of file bond.cpp.


Member Function Documentation

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

Definition at line 299 of file bond.cpp.

Breaks the bond, notifying the other process.

Definition at line 251 of file bond.cpp.

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

Definition at line 333 of file bond.cpp.

Definition at line 365 of file bond.cpp.

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

Definition at line 73 of file bond.h.

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

Definition at line 75 of file bond.h.

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

Definition at line 79 of file bond.h.

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

Definition at line 77 of file bond.h.

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

Definition at line 134 of file bond.h.

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

Definition at line 135 of file bond.h.

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

Definition at line 133 of file bond.h.

Indicates if the bond is broken.

Returns:
true iff the bond has been broken.

Definition at line 245 of file bond.cpp.

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

Definition at line 265 of file bond.cpp.

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

Definition at line 290 of file bond.cpp.

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

Definition at line 273 of file bond.cpp.

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

Definition at line 352 of file bond.cpp.

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

Sets the broken callback.

Definition at line 187 of file bond.cpp.

Definition at line 159 of file bond.cpp.

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

Definition at line 116 of file bond.cpp.

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

Definition at line 127 of file bond.cpp.

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

Sets the formed callback.

Definition at line 181 of file bond.cpp.

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

Definition at line 149 of file bond.cpp.

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

Definition at line 138 of file bond.cpp.

Starts the bond and connects to the sister process.

Definition at line 170 of file bond.cpp.

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 219 of file bond.cpp.

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 223 of file bond.cpp.

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 193 of file bond.cpp.

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 197 of file bond.cpp.


Friends And Related Function Documentation

friend class ::BondSM [friend]

Definition at line 138 of file bond.h.


Member Data Documentation

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

Definition at line 141 of file bond.h.

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

Definition at line 154 of file bond.h.

double bond::Bond::connect_timeout_ [private]

Definition at line 156 of file bond.h.

Definition at line 161 of file bond.h.

Definition at line 158 of file bond.h.

Definition at line 163 of file bond.h.

Definition at line 159 of file bond.h.

Definition at line 157 of file bond.h.

Definition at line 162 of file bond.h.

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

Definition at line 145 of file bond.h.

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

Definition at line 146 of file bond.h.

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

Definition at line 153 of file bond.h.

Definition at line 140 of file bond.h.

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

Definition at line 148 of file bond.h.

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

Definition at line 149 of file bond.h.

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

Definition at line 178 of file bond.h.

Definition at line 166 of file bond.h.

Definition at line 167 of file bond.h.

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

Definition at line 147 of file bond.h.

Definition at line 150 of file bond.h.

Definition at line 142 of file bond.h.

bool bond::Bond::started_ [private]

Definition at line 151 of file bond.h.

Definition at line 165 of file bond.h.

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

Definition at line 144 of file bond.h.


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


bondcpp
Author(s): Stuart Glaser
autogenerated on Sun Oct 5 2014 22:32:30