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 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 
00082   void setCallbackQueue(ros::CallbackQueueInterface *queue);
00083 
00086   void start();
00087 
00090   void setFormedCallback(boost::function<void(void)> on_formed);
00091 
00094   void setBrokenCallback(boost::function<void(void)> on_broken);
00095 
00101   bool waitUntilFormed(ros::Duration timeout = ros::Duration(-1));
00102 
00108   bool waitUntilFormed(ros::WallDuration timeout = ros::WallDuration(-1));
00109 
00115   bool waitUntilBroken(ros::Duration timeout = ros::Duration(-1));
00116 
00122   bool waitUntilBroken(ros::WallDuration timeout = ros::WallDuration(-1));
00123 
00127   bool isBroken();
00128 
00131   void breakBond();
00132 
00133   std::string getTopic() { return topic_; }
00134   std::string getId() { return id_; }
00135   std::string getInstanceId() { return instance_id_; }
00136 
00137 private:
00138   friend class ::BondSM;
00139 
00140   ros::NodeHandle nh_;
00141   boost::scoped_ptr<BondSM> bondsm_;
00142   BondSMContext sm_;
00143 
00144   std::string topic_;
00145   std::string id_;
00146   std::string instance_id_;
00147   std::string sister_instance_id_;
00148   boost::function<void(void)> on_broken_;
00149   boost::function<void(void)> on_formed_;
00150   bool sisterDiedFirst_;
00151   bool started_;
00152 
00153   boost::mutex mutex_;
00154   boost::condition condition_;
00155 
00156   double connect_timeout_;
00157   double heartbeat_timeout_;
00158   double disconnect_timeout_;
00159   double heartbeat_period_;
00160 
00161   Timeout connect_timer_;
00162   Timeout heartbeat_timer_;
00163   Timeout disconnect_timer_;
00164 
00165   ros::Subscriber sub_;
00166   ros::Publisher pub_;
00167   ros::WallTimer publishingTimer_;
00168 
00169   void onConnectTimeout();
00170   void onHeartbeatTimeout();
00171   void onDisconnectTimeout();
00172 
00173   void bondStatusCB(const bond::Status::ConstPtr &msg);
00174 
00175   void doPublishing(const ros::WallTimerEvent &e);
00176   void publishStatus(bool active);
00177 
00178   std::vector<boost::function<void(void)> > pending_callbacks_;
00179   void flushPendingCallbacks();
00180 };
00181 
00182 }// namespace
00183 
00184 
00185 // Internal use only
00186 struct BondSM
00187 {
00188   BondSM(bond::Bond *b_) : b(b_) {}
00189   void Connected();
00190   void SisterDied();
00191   void Death();
00192   void Heartbeat();
00193   void StartDying();
00194 
00195 private:
00196   bond::Bond *b;
00197 };
00198 
00199 #endif


bondcpp
Author(s): Stuart Glaser
autogenerated on Fri Aug 28 2015 10:10:53