32 #ifndef BONDCPP__BOND_H_ 33 #define BONDCPP__BOND_H_ 35 #include <boost/scoped_ptr.hpp> 36 #include <boost/thread/mutex.hpp> 37 #include <boost/thread/condition.hpp> 43 #include <bond/Constants.h> 44 #include <bond/Status.h> 50 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries 51 #ifdef bondcpp_EXPORTS // we are building a shared lib/dll 52 #define BONDCPP_DECL ROS_HELPER_EXPORT 53 #else // we are using shared lib/dll 54 #define BONDCPP_DECL ROS_HELPER_IMPORT 56 #else // ros is being built around static libraries 79 Bond(
const std::string &topic,
const std::string &
id,
80 boost::function<
void(
void)> on_broken = boost::function<
void(
void)>(),
81 boost::function<
void(
void)> on_formed = boost::function<
void(
void)>());
88 void setConnectTimeout(
double dur);
90 void setDisconnectTimeout(
double dur);
92 void setHeartbeatTimeout(
double dur);
94 void setHeartbeatPeriod(
double dur);
104 void setFormedCallback(boost::function<
void(
void)> on_formed);
108 void setBrokenCallback(boost::function<
void(
void)> on_broken);
152 friend class ::BondSM;
183 void onConnectTimeout();
184 void onHeartbeatTimeout();
185 void onDisconnectTimeout();
187 void bondStatusCB(
const bond::Status::ConstPtr &msg);
190 void publishStatus(
bool active);
193 void flushPendingCallbacks();
213 #endif // BONDCPP__BOND_H_
double heartbeat_timeout_
double getConnectTimeout() const
double getHeartbeatPeriod() const
boost::scoped_ptr< BondSM > bondsm_
double getDisconnectTimeout() const
double getHeartbeatTimeout() const
ros::SteadyTimer publishingTimer_
std::vector< boost::function< void(void)> > pending_callbacks_
boost::function< void(void)> on_broken_
boost::condition condition_
std::string sister_instance_id_
boost::function< void(void)> on_formed_
Forms a bond to monitor another process.
Timeout disconnect_timer_
double disconnect_timeout_
std::string getInstanceId()