bond.h
Go to the documentation of this file.
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 #include <string>
00047 #include <vector>
00048 
00049 namespace bond {
00050 
00057 class Bond
00058 {
00059 public:
00068   Bond(const std::string &topic, const std::string &id,
00069        boost::function<void(void)> on_broken = boost::function<void(void)>(),
00070        boost::function<void(void)> on_formed = boost::function<void(void)>());
00071 
00074   ~Bond();
00075 
00076   double getConnectTimeout() const { return connect_timeout_; }
00077   void setConnectTimeout(double dur);
00078   double getDisconnectTimeout() const { return disconnect_timeout_; }
00079   void setDisconnectTimeout(double dur);
00080   double getHeartbeatTimeout() const { return heartbeat_timeout_; }
00081   void setHeartbeatTimeout(double dur);
00082   double getHeartbeatPeriod() const { return heartbeat_period_; }
00083   void setHeartbeatPeriod(double dur);
00084 
00085   void setCallbackQueue(ros::CallbackQueueInterface *queue);
00086 
00089   void start();
00090 
00093   void setFormedCallback(boost::function<void(void)> on_formed);
00094 
00097   void setBrokenCallback(boost::function<void(void)> on_broken);
00098 
00104   bool waitUntilFormed(ros::Duration timeout = ros::Duration(-1));
00105 
00111   bool waitUntilFormed(ros::WallDuration timeout = ros::WallDuration(-1));
00112 
00118   bool waitUntilBroken(ros::Duration timeout = ros::Duration(-1));
00119 
00125   bool waitUntilBroken(ros::WallDuration timeout = ros::WallDuration(-1));
00126 
00130   bool isBroken();
00131 
00134   void breakBond();
00135 
00136   std::string getTopic() { return topic_; }
00137   std::string getId() { return id_; }
00138   std::string getInstanceId() { return instance_id_; }
00139 
00140 private:
00141   friend class ::BondSM;
00142 
00143   ros::NodeHandle nh_;
00144   boost::scoped_ptr<BondSM> bondsm_;
00145   BondSMContext sm_;
00146 
00147   std::string topic_;
00148   std::string id_;
00149   std::string instance_id_;
00150   std::string sister_instance_id_;
00151   boost::function<void(void)> on_broken_;
00152   boost::function<void(void)> on_formed_;
00153   bool sisterDiedFirst_;
00154   bool started_;
00155 
00156   boost::mutex mutex_;
00157   boost::condition condition_;
00158 
00159   double connect_timeout_;
00160   double heartbeat_timeout_;
00161   double disconnect_timeout_;
00162   double heartbeat_period_;
00163 
00164   Timeout connect_timer_;
00165   Timeout heartbeat_timer_;
00166   Timeout disconnect_timer_;
00167 
00168   ros::Subscriber sub_;
00169   ros::Publisher pub_;
00170   ros::WallTimer publishingTimer_;
00171 
00172   void onConnectTimeout();
00173   void onHeartbeatTimeout();
00174   void onDisconnectTimeout();
00175 
00176   void bondStatusCB(const bond::Status::ConstPtr &msg);
00177 
00178   void doPublishing(const ros::WallTimerEvent &e);
00179   void publishStatus(bool active);
00180 
00181   std::vector<boost::function<void(void)> > pending_callbacks_;
00182   void flushPendingCallbacks();
00183 };
00184 
00185 }  // namespace bond
00186 
00187 
00188 // Internal use only
00189 struct BondSM
00190 {
00191   BondSM(bond::Bond *b_) : b(b_) {}
00192   void Connected();
00193   void SisterDied();
00194   void Death();
00195   void Heartbeat();
00196   void StartDying();
00197 
00198 private:
00199   bond::Bond *b;
00200 };
00201 
00202 #endif  // BONDCPP__BOND_H_


bondcpp
Author(s): Stuart Glaser
autogenerated on Thu Aug 17 2017 03:12:47