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< BondSM > | bondsm_ |
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 |
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.
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.
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. |
bond::Bond::~Bond | ( | ) |
|
private |
void bond::Bond::breakBond | ( | ) |
|
private |
bool bond::Bond::isBroken | ( | ) |
void bond::Bond::setBrokenCallback | ( | boost::function< void(void)> | on_broken | ) |
void bond::Bond::setCallbackQueue | ( | ros::CallbackQueueInterface * | queue | ) |
void bond::Bond::setFormedCallback | ( | boost::function< void(void)> | on_formed | ) |
void bond::Bond::start | ( | ) |
bool bond::Bond::waitUntilBroken | ( | ros::Duration | timeout = ros::Duration(-1) | ) |
bool bond::Bond::waitUntilBroken | ( | ros::WallDuration | timeout = ros::WallDuration(-1) | ) |
bool bond::Bond::waitUntilFormed | ( | ros::Duration | timeout = ros::Duration(-1) | ) |
bool bond::Bond::waitUntilFormed | ( | ros::WallDuration | timeout = ros::WallDuration(-1) | ) |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |