topic_synchronizer.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00039 #ifndef TOPIC_SYNCHRONIZER2_HH
00040 #define TOPIC_SYNCHRONIZER2_HH
00041 
00042 #include "ros/ros.h"
00043 #include <boost/thread/mutex.hpp>
00044 
00046 
00061 class TopicSynchronizer
00062 {
00063         int expected_count_;
00064         int count_;
00065         ros::Time time_;
00066         boost::function<void ()> callback_;
00067         boost::mutex mutex_;
00068 
00069 public:
00070 
00071         template <typename T>
00072         TopicSynchronizer(void(T::*fp)(), T* obj) : callback_(boost::bind(fp,obj))
00073         {
00074                 reset();
00075         }
00076 
00077         TopicSynchronizer(void (*fp)()) : callback_(fp)
00078         {
00079                 reset();
00080         }
00081 
00082 
00083         template <typename T, typename M>
00084         class CallbackFunctor {
00085                 TopicSynchronizer* synchronizer_;
00086                 const boost::function<void (const boost::shared_ptr<M const>&)> callback_;
00087 
00088         public:
00089 
00090                 CallbackFunctor(TopicSynchronizer* synchronizer, const boost::function<void (const boost::shared_ptr<M const>&)>& callback) :
00091                         synchronizer_(synchronizer), callback_(callback)
00092                 {
00093                 }
00094 
00095                 void operator()(const boost::shared_ptr<M const>& message)
00096                 {
00097                         callback_(message);
00098                         synchronizer_->update(message->header.stamp);
00099                 }
00100         };
00101 
00102         template <typename T, typename M>
00103         const boost::function<void (const boost::shared_ptr<M const>&)> synchronize(void(T::*fp)(const boost::shared_ptr<M const>&), T* obj)
00104         {
00105           boost::mutex::scoped_lock lock(mutex_);
00106 
00107                 expected_count_++;
00108                 return CallbackFunctor<T,M>(this, boost::bind(fp, obj, _1));
00109         }
00110 
00111         template <typename T, typename M>
00112         const boost::function<void (const boost::shared_ptr<M const>&)> synchronize(void(T::*fp)(const boost::shared_ptr<M const>&), const boost::shared_ptr<T>& obj)
00113         {
00114           boost::mutex::scoped_lock lock(mutex_);
00115 
00116                 expected_count_++;
00117                 return CallbackFunctor<T,M>(this, boost::bind(fp, obj.get(), _1));
00118         }
00119 
00120         template <typename T, typename M>
00121         const boost::function<void (const boost::shared_ptr<M const>&)> synchronize(void(*fp)(const boost::shared_ptr<M const>&))
00122         {
00123           boost::mutex::scoped_lock lock(mutex_);
00124 
00125                 expected_count_++;
00126                 return CallbackFunctor<T,M>(this, boost::function<void(const boost::shared_ptr<M>&)>(fp));
00127         }
00128 
00129         template <typename T, typename M>
00130         const boost::function<void (const boost::shared_ptr<M const>&)> synchronize(const boost::function<void (const boost::shared_ptr<M const>&)>& callback)
00131         {
00132           boost::mutex::scoped_lock lock(mutex_);
00133                 expected_count_++;
00134                 return CallbackFunctor<T,M>(this, callback);
00135         }
00136 
00137         void reset()
00138         {
00139           boost::mutex::scoped_lock lock(mutex_);
00140                 expected_count_ = 0;
00141         }
00142 
00143         void update(const ros::Time& time)
00144         {
00145           boost::mutex::scoped_lock lock(mutex_);
00146                 if (count_==0 || time>time_) {
00147                         time_ = time;
00148                         count_ = 0;
00149                 }
00150 
00151                 if (time==time_) {
00152                         count_++;
00153                 }
00154 
00155                 if (count_==expected_count_) {
00156                         callback_();
00157                 }
00158         }
00159 };
00160 
00161 #endif


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Wed Dec 11 2013 14:17:01