exact_time.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, 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 
00035 #ifndef MESSAGE_FILTERS_SYNC_EXACT_TIME_H
00036 #define MESSAGE_FILTERS_SYNC_EXACT_TIME_H
00037 
00038 #include "message_filters/synchronizer.h"
00039 #include "message_filters/connection.h"
00040 #include "message_filters/null_types.h"
00041 #include "message_filters/signal9.h"
00042 
00043 #include <boost/tuple/tuple.hpp>
00044 #include <boost/shared_ptr.hpp>
00045 #include <boost/function.hpp>
00046 #include <boost/thread/mutex.hpp>
00047 
00048 #include <boost/bind.hpp>
00049 #include <boost/type_traits/is_same.hpp>
00050 #include <boost/noncopyable.hpp>
00051 #include <boost/mpl/or.hpp>
00052 #include <boost/mpl/at.hpp>
00053 #include <boost/mpl/vector.hpp>
00054 
00055 #include <ros/assert.h>
00056 #include <ros/message_traits.h>
00057 #include <ros/message_event.h>
00058 
00059 #include <deque>
00060 #include <vector>
00061 #include <string>
00062 
00063 namespace message_filters
00064 {
00065 namespace sync_policies
00066 {
00067 
00068 namespace mpl = boost::mpl;
00069 
00070 
00071 template<typename M0, typename M1, typename M2 = NullType, typename M3 = NullType, typename M4 = NullType,
00072          typename M5 = NullType, typename M6 = NullType, typename M7 = NullType, typename M8 = NullType>
00073 struct ExactTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
00074 {
00075   typedef Synchronizer<ExactTime> Sync;
00076   typedef PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8> Super;
00077   typedef typename Super::Messages Messages;
00078   typedef typename Super::Signal Signal;
00079   typedef typename Super::Events Events;
00080   typedef typename Super::RealTypeCount RealTypeCount;
00081   typedef typename Super::M0Event M0Event;
00082   typedef typename Super::M1Event M1Event;
00083   typedef typename Super::M2Event M2Event;
00084   typedef typename Super::M3Event M3Event;
00085   typedef typename Super::M4Event M4Event;
00086   typedef typename Super::M5Event M5Event;
00087   typedef typename Super::M6Event M6Event;
00088   typedef typename Super::M7Event M7Event;
00089   typedef typename Super::M8Event M8Event;
00090   typedef boost::tuple<M0Event, M1Event, M2Event, M3Event, M4Event, M5Event, M6Event, M7Event, M8Event> Tuple;
00091 
00092   ExactTime(uint32_t queue_size)
00093   : parent_(0)
00094   , queue_size_(queue_size)
00095   {
00096   }
00097 
00098   ExactTime(const ExactTime& e)
00099   {
00100     *this = e;
00101   }
00102 
00103   ExactTime& operator=(const ExactTime& rhs)
00104   {
00105     parent_ = rhs.parent_;
00106     queue_size_ = rhs.queue_size_;
00107     last_signal_time_ = rhs.last_signal_time_;
00108     tuples_ = rhs.tuples_;
00109 
00110     return *this;
00111   }
00112 
00113   void initParent(Sync* parent)
00114   {
00115     parent_ = parent;
00116   }
00117 
00118   template<int i>
00119   void add(const typename mpl::at_c<Events, i>::type& evt)
00120   {
00121     ROS_ASSERT(parent_);
00122 
00123     namespace mt = ros::message_traits;
00124 
00125     boost::mutex::scoped_lock lock(mutex_);
00126 
00127     Tuple& t = tuples_[mt::TimeStamp<typename mpl::at_c<Messages, i>::type>::value(*evt.getMessage())];
00128     boost::get<i>(t) = evt;
00129 
00130     checkTuple(t);
00131   }
00132 
00133   template<class C>
00134   Connection registerDropCallback(const C& callback)
00135   {
00136     return drop_signal_.template addCallback(callback);
00137   }
00138 
00139   template<class C>
00140   Connection registerDropCallback(C& callback)
00141   {
00142     return drop_signal_.template addCallback(callback);
00143   }
00144 
00145   template<class C, typename T>
00146   Connection registerDropCallback(const C& callback, T* t)
00147   {
00148     return drop_signal_.template addCallback(callback, t);
00149   }
00150 
00151   template<class C, typename T>
00152   Connection registerDropCallback(C& callback, T* t)
00153   {
00154     return drop_signal_.template addCallback(callback, t);
00155   }
00156 
00157 private:
00158 
00159   // assumes mutex_ is already locked
00160   void checkTuple(Tuple& t)
00161   {
00162     namespace mt = ros::message_traits;
00163 
00164     bool full = true;
00165     full = full && (bool)boost::get<0>(t).getMessage();
00166     full = full && (bool)boost::get<1>(t).getMessage();
00167     full = full && (RealTypeCount::value > 2 ? (bool)boost::get<2>(t).getMessage() : true);
00168     full = full && (RealTypeCount::value > 3 ? (bool)boost::get<3>(t).getMessage() : true);
00169     full = full && (RealTypeCount::value > 4 ? (bool)boost::get<4>(t).getMessage() : true);
00170     full = full && (RealTypeCount::value > 5 ? (bool)boost::get<5>(t).getMessage() : true);
00171     full = full && (RealTypeCount::value > 6 ? (bool)boost::get<6>(t).getMessage() : true);
00172     full = full && (RealTypeCount::value > 7 ? (bool)boost::get<7>(t).getMessage() : true);
00173     full = full && (RealTypeCount::value > 8 ? (bool)boost::get<8>(t).getMessage() : true);
00174 
00175     if (full)
00176     {
00177       parent_->signal(boost::get<0>(t), boost::get<1>(t), boost::get<2>(t),
00178                        boost::get<3>(t), boost::get<4>(t), boost::get<5>(t),
00179                        boost::get<6>(t), boost::get<7>(t), boost::get<8>(t));
00180 
00181       last_signal_time_ = mt::TimeStamp<M0>::value(*boost::get<0>(t).getMessage());
00182 
00183       tuples_.erase(last_signal_time_);
00184 
00185       clearOldTuples();
00186     }
00187 
00188     if (queue_size_ > 0)
00189     {
00190       while (tuples_.size() > queue_size_)
00191       {
00192         Tuple& t2 = tuples_.begin()->second;
00193         drop_signal_.call(boost::get<0>(t2), boost::get<1>(t2), boost::get<2>(t2),
00194                           boost::get<3>(t2), boost::get<4>(t2), boost::get<5>(t2),
00195                           boost::get<6>(t2), boost::get<7>(t2), boost::get<8>(t2));
00196         tuples_.erase(tuples_.begin());
00197       }
00198     }
00199   }
00200 
00201   // assumes mutex_ is already locked
00202   void clearOldTuples()
00203   {
00204     typename M_TimeToTuple::iterator it = tuples_.begin();
00205     typename M_TimeToTuple::iterator end = tuples_.end();
00206     for (; it != end;)
00207     {
00208       if (it->first <= last_signal_time_)
00209       {
00210         typename M_TimeToTuple::iterator old = it;
00211         ++it;
00212 
00213         Tuple& t = old->second;
00214         drop_signal_.call(boost::get<0>(t), boost::get<1>(t), boost::get<2>(t),
00215                           boost::get<3>(t), boost::get<4>(t), boost::get<5>(t),
00216                           boost::get<6>(t), boost::get<7>(t), boost::get<8>(t));
00217         tuples_.erase(old);
00218       }
00219       else
00220       {
00221         // the map is sorted by time, so we can ignore anything after this if this one's time is ok
00222         break;
00223       }
00224     }
00225   }
00226 
00227 private:
00228   Sync* parent_;
00229 
00230   uint32_t queue_size_;
00231   typedef std::map<ros::Time, Tuple> M_TimeToTuple;
00232   M_TimeToTuple tuples_;
00233   ros::Time last_signal_time_;
00234 
00235   Signal drop_signal_;
00236 
00237   boost::mutex mutex_;
00238 };
00239 
00240 } // namespace sync
00241 } // namespace message_filters
00242 
00243 #endif // MESSAGE_FILTERS_SYNC_EXACT_TIME_H
00244 


message_filters
Author(s): Josh Faust, Vijay Pradeep
autogenerated on Tue Mar 7 2017 03:45:14