00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00032 #ifndef BONDCPP_BOND_H 00033 #define BONDCPP_BOND_H 00034 00035 #include <boost/scoped_ptr.hpp> 00036 #include <boost/thread/mutex.hpp> 00037 #include <boost/thread/condition.hpp> 00038 00039 #include <ros/ros.h> 00040 00041 #include <bondcpp/timeout.h> 00042 #include <bond/Constants.h> 00043 #include <bond/Status.h> 00044 #include <BondSM_sm.h> 00045 00046 namespace bond { 00047 00054 class Bond 00055 { 00056 public: 00065 Bond(const std::string &topic, const std::string &id, 00066 boost::function<void(void)> on_broken = boost::function<void(void)>(), 00067 boost::function<void(void)> on_formed = boost::function<void(void)>()); 00068 00071 ~Bond(); 00072 00073 double getConnectTimeout() const { return connect_timeout_; } 00074 void setConnectTimeout(double dur); 00075 double getDisconnectTimeout() const { return disconnect_timeout_; } 00076 void setDisconnectTimeout(double dur); 00077 double getHeartbeatTimeout() const { return heartbeat_timeout_; } 00078 void setHeartbeatTimeout(double dur); 00079 double getHeartbeatPeriod() const { return heartbeat_period_; } 00080 void setHeartbeatPeriod(double dur); 00081 00084 void start(); 00085 00088 void setFormedCallback(boost::function<void(void)> on_formed); 00089 00092 void setBrokenCallback(boost::function<void(void)> on_broken); 00093 00099 bool waitUntilFormed(ros::Duration timeout = ros::Duration(-1)); 00100 00106 bool waitUntilBroken(ros::Duration timeout = ros::Duration(-1)); 00107 00111 bool isBroken(); 00112 00115 void breakBond(); 00116 00117 std::string getTopic() { return topic_; } 00118 std::string getId() { return id_; } 00119 std::string getInstanceId() { return instance_id_; } 00120 00121 private: 00122 friend class ::BondSM; 00123 00124 ros::NodeHandle nh_; 00125 boost::scoped_ptr<BondSM> bondsm_; 00126 BondSMContext sm_; 00127 00128 std::string topic_; 00129 std::string id_; 00130 std::string instance_id_; 00131 std::string sister_instance_id_; 00132 boost::function<void(void)> on_broken_; 00133 boost::function<void(void)> on_formed_; 00134 bool sisterDiedFirst_; 00135 bool started_; 00136 00137 boost::mutex mutex_; 00138 boost::condition condition_; 00139 00140 double connect_timeout_; 00141 double heartbeat_timeout_; 00142 double disconnect_timeout_; 00143 double heartbeat_period_; 00144 00145 Timeout connect_timer_; 00146 Timeout heartbeat_timer_; 00147 Timeout disconnect_timer_; 00148 00149 ros::Subscriber sub_; 00150 ros::Publisher pub_; 00151 ros::WallTimer publishingTimer_; 00152 00153 void onConnectTimeout(); 00154 void onHeartbeatTimeout(); 00155 void onDisconnectTimeout(); 00156 00157 void bondStatusCB(const bond::Status::ConstPtr &msg); 00158 00159 void doPublishing(const ros::WallTimerEvent &e); 00160 void publishStatus(bool active); 00161 00162 std::vector<boost::function<void(void)> > pending_callbacks_; 00163 void flushPendingCallbacks(); 00164 }; 00165 00166 }// namespace 00167 00168 00169 // Internal use only 00170 struct BondSM 00171 { 00172 BondSM(bond::Bond *b_) : b(b_) {} 00173 void Connected(); 00174 void SisterDied(); 00175 void Death(); 00176 void Heartbeat(); 00177 void StartDying(); 00178 00179 private: 00180 bond::Bond *b; 00181 }; 00182 00183 #endif