bond.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef BONDCPP__BOND_H_
33 #define BONDCPP__BOND_H_
34 
35 #include <boost/scoped_ptr.hpp>
36 #include <boost/thread/mutex.hpp>
37 #include <boost/thread/condition.hpp>
38 
39 #include <ros/ros.h>
40 #include <ros/macros.h>
41 
42 #include <bondcpp/timeout.h>
43 #include <bond/Constants.h>
44 #include <bond/Status.h>
45 #include "BondSM_sm.h"
46 
47 #include <string>
48 #include <vector>
49 
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
55  #endif
56 #else // ros is being built around static libraries
57  #define BONDCPP_DECL
58 #endif
59 
60 namespace bond {
61 
69 {
70 public:
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)>());
82 
85  ~Bond();
86 
87  double getConnectTimeout() const { return connect_timeout_; }
88  void setConnectTimeout(double dur);
89  double getDisconnectTimeout() const { return disconnect_timeout_; }
90  void setDisconnectTimeout(double dur);
91  double getHeartbeatTimeout() const { return heartbeat_timeout_; }
92  void setHeartbeatTimeout(double dur);
93  double getHeartbeatPeriod() const { return heartbeat_period_; }
94  void setHeartbeatPeriod(double dur);
95 
96  void setCallbackQueue(ros::CallbackQueueInterface *queue);
97 
100  void start();
101 
104  void setFormedCallback(boost::function<void(void)> on_formed);
105 
108  void setBrokenCallback(boost::function<void(void)> on_broken);
109 
115  bool waitUntilFormed(ros::Duration timeout = ros::Duration(-1));
116 
122  bool waitUntilFormed(ros::WallDuration timeout = ros::WallDuration(-1));
123 
129  bool waitUntilBroken(ros::Duration timeout = ros::Duration(-1));
130 
136  bool waitUntilBroken(ros::WallDuration timeout = ros::WallDuration(-1));
137 
141  bool isBroken();
142 
145  void breakBond();
146 
147  std::string getTopic() { return topic_; }
148  std::string getId() { return id_; }
149  std::string getInstanceId() { return instance_id_; }
150 
151 private:
152  friend class ::BondSM;
153 
155  boost::scoped_ptr<BondSM> bondsm_;
157 
158  std::string topic_;
159  std::string id_;
160  std::string instance_id_;
161  std::string sister_instance_id_;
162  boost::function<void(void)> on_broken_;
163  boost::function<void(void)> on_formed_;
165  bool started_;
166 
167  boost::mutex mutex_;
168  boost::condition condition_;
169 
174 
178 
182 
183  void onConnectTimeout();
184  void onHeartbeatTimeout();
185  void onDisconnectTimeout();
186 
187  void bondStatusCB(const bond::Status::ConstPtr &msg);
188 
189  void doPublishing(const ros::SteadyTimerEvent &e);
190  void publishStatus(bool active);
191 
192  std::vector<boost::function<void(void)> > pending_callbacks_;
193  void flushPendingCallbacks();
194 };
195 
196 } // namespace bond
197 
198 
199 // Internal use only
200 struct BondSM
201 {
202  BondSM(bond::Bond *b_) : b(b_) {}
203  void Connected();
204  void SisterDied();
205  void Death();
206  void Heartbeat();
207  void StartDying();
208 
209 private:
211 };
212 
213 #endif // BONDCPP__BOND_H_
bond::Bond::sm_
BondSMContext sm_
Definition: bond.h:156
ros::Publisher
bond::Bond::getHeartbeatTimeout
double getHeartbeatTimeout() const
Definition: bond.h:91
bond::Bond::getInstanceId
std::string getInstanceId()
Definition: bond.h:149
ros.h
bond::Bond::sisterDiedFirst_
bool sisterDiedFirst_
Definition: bond.h:164
BondSM::Heartbeat
void Heartbeat()
Definition: bond.cpp:409
bond::Bond::pending_callbacks_
std::vector< boost::function< void(void)> > pending_callbacks_
Definition: bond.h:192
timeout.h
BondSM::SisterDied
void SisterDied()
Definition: bond.cpp:394
BONDCPP_DECL
#define BONDCPP_DECL
Definition: bond.h:57
bond::Bond::getId
std::string getId()
Definition: bond.h:148
BondSM::BondSM
BondSM(bond::Bond *b_)
Definition: bond.h:202
bond::Bond::getTopic
std::string getTopic()
Definition: bond.h:147
bond::Bond::disconnect_timeout_
double disconnect_timeout_
Definition: bond.h:172
bond::Bond::on_broken_
boost::function< void(void)> on_broken_
Definition: bond.h:162
bond::Bond::connect_timer_
Timeout connect_timer_
Definition: bond.h:175
BondSM::Connected
void Connected()
Definition: bond.cpp:385
bond::Bond::heartbeat_timeout_
double heartbeat_timeout_
Definition: bond.h:171
BondSM::b
bond::Bond * b
Definition: bond.h:210
BondSM
Definition: bond.h:200
bond::Bond
Forms a bond to monitor another process.
Definition: bond.h:68
ros::SteadyTimer
bond::Bond::mutex_
boost::mutex mutex_
Definition: bond.h:167
bond::Bond::on_formed_
boost::function< void(void)> on_formed_
Definition: bond.h:163
bond::Timeout
Definition: timeout.h:37
bond::Bond::pub_
ros::Publisher pub_
Definition: bond.h:180
bond::Bond::sub_
ros::Subscriber sub_
Definition: bond.h:179
bond::Bond::getHeartbeatPeriod
double getHeartbeatPeriod() const
Definition: bond.h:93
ros::SteadyTimerEvent
BondSM::StartDying
void StartDying()
Definition: bond.cpp:414
bond
Definition: bond.h:60
bond::Bond::connect_timeout_
double connect_timeout_
Definition: bond.h:170
bond::Bond::heartbeat_period_
double heartbeat_period_
Definition: bond.h:173
bond::Bond::nh_
ros::NodeHandle nh_
Definition: bond.h:154
bond::Bond::getDisconnectTimeout
double getDisconnectTimeout() const
Definition: bond.h:89
start
ROSCPP_DECL void start()
bond::Bond::getConnectTimeout
double getConnectTimeout() const
Definition: bond.h:87
bond::Bond::started_
bool started_
Definition: bond.h:165
BondSM_sm.h
bond::Bond::topic_
std::string topic_
Definition: bond.h:158
bond::Bond::id_
std::string id_
Definition: bond.h:159
bond::Bond::disconnect_timer_
Timeout disconnect_timer_
Definition: bond.h:177
bond::Bond::sister_instance_id_
std::string sister_instance_id_
Definition: bond.h:161
BondSM::Death
void Death()
Definition: bond.cpp:399
ros::WallDuration
bond::Bond::instance_id_
std::string instance_id_
Definition: bond.h:160
macros.h
bond::Bond::heartbeat_timer_
Timeout heartbeat_timer_
Definition: bond.h:176
ros::Duration
bond::Bond::bondsm_
boost::scoped_ptr< BondSM > bondsm_
Definition: bond.h:155
bond::Bond::condition_
boost::condition condition_
Definition: bond.h:168
bond::Bond::publishingTimer_
ros::SteadyTimer publishingTimer_
Definition: bond.h:181
ros::CallbackQueueInterface
ros::NodeHandle
ros::Subscriber
BondSMContext
Definition: BondSM_sm.h:126


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