00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
00036 #define MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
00037
00038 #include "synchronizer.h"
00039 #include "sync_policies/exact_time.h"
00040
00041 #include <boost/shared_ptr.hpp>
00042
00043 #include <ros/message_event.h>
00044
00045 namespace message_filters
00046 {
00047 namespace mpl = boost::mpl;
00048
00083 template<class M0, class M1, class M2 = NullType, class M3 = NullType, class M4 = NullType,
00084 class M5 = NullType, class M6 = NullType, class M7 = NullType, class M8 = NullType>
00085 class TimeSynchronizer : public Synchronizer<sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8> >
00086 {
00087 public:
00088 typedef sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8> Policy;
00089 typedef Synchronizer<Policy> Base;
00090 typedef boost::shared_ptr<M0 const> M0ConstPtr;
00091 typedef boost::shared_ptr<M1 const> M1ConstPtr;
00092 typedef boost::shared_ptr<M2 const> M2ConstPtr;
00093 typedef boost::shared_ptr<M3 const> M3ConstPtr;
00094 typedef boost::shared_ptr<M4 const> M4ConstPtr;
00095 typedef boost::shared_ptr<M5 const> M5ConstPtr;
00096 typedef boost::shared_ptr<M6 const> M6ConstPtr;
00097 typedef boost::shared_ptr<M7 const> M7ConstPtr;
00098 typedef boost::shared_ptr<M8 const> M8ConstPtr;
00099
00100 using Base::add;
00101 using Base::connectInput;
00102 using Base::registerCallback;
00103 using Base::setName;
00104 using Base::getName;
00105 using Policy::registerDropCallback;
00106 typedef typename Base::M0Event M0Event;
00107 typedef typename Base::M1Event M1Event;
00108 typedef typename Base::M2Event M2Event;
00109 typedef typename Base::M3Event M3Event;
00110 typedef typename Base::M4Event M4Event;
00111 typedef typename Base::M5Event M5Event;
00112 typedef typename Base::M6Event M6Event;
00113 typedef typename Base::M7Event M7Event;
00114 typedef typename Base::M8Event M8Event;
00115
00116 template<class F0, class F1>
00117 TimeSynchronizer(F0& f0, F1& f1, uint32_t queue_size)
00118 : Base(Policy(queue_size))
00119 {
00120 connectInput(f0, f1);
00121 }
00122
00123 template<class F0, class F1, class F2>
00124 TimeSynchronizer(F0& f0, F1& f1, F2& f2, uint32_t queue_size)
00125 : Base(Policy(queue_size))
00126 {
00127 connectInput(f0, f1, f2);
00128 }
00129
00130 template<class F0, class F1, class F2, class F3>
00131 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, uint32_t queue_size)
00132 : Base(Policy(queue_size))
00133 {
00134 connectInput(f0, f1, f2, f3);
00135 }
00136
00137 template<class F0, class F1, class F2, class F3, class F4>
00138 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, uint32_t queue_size)
00139 : Base(Policy(queue_size))
00140 {
00141 connectInput(f0, f1, f2, f3, f4);
00142 }
00143
00144 template<class F0, class F1, class F2, class F3, class F4, class F5>
00145 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, uint32_t queue_size)
00146 : Base(Policy(queue_size))
00147 {
00148 connectInput(f0, f1, f2, f3, f4, f5);
00149 }
00150
00151 template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
00152 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, uint32_t queue_size)
00153 : Base(Policy(queue_size))
00154 {
00155 connectInput(f0, f1, f2, f3, f4, f5, f6);
00156 }
00157
00158 template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
00159 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, uint32_t queue_size)
00160 : Base(Policy(queue_size))
00161 {
00162 connectInput(f0, f1, f2, f3, f4, f5, f6, f7);
00163 }
00164
00165 template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
00166 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8, uint32_t queue_size)
00167 : Base(Policy(queue_size))
00168 {
00169 connectInput(f0, f1, f2, f3, f4, f5, f6, f7, f8);
00170 }
00171
00172 TimeSynchronizer(uint32_t queue_size)
00173 : Base(Policy(queue_size))
00174 {
00175 }
00176
00178
00180 void add0(const M0ConstPtr& msg)
00181 {
00182 this->template add<0>(M0Event(msg));
00183 }
00184
00185 void add1(const M1ConstPtr& msg)
00186 {
00187 this->template add<1>(M1Event(msg));
00188 }
00189
00190 void add2(const M2ConstPtr& msg)
00191 {
00192 this->template add<2>(M2Event(msg));
00193 }
00194
00195 void add3(const M3ConstPtr& msg)
00196 {
00197 this->template add<3>(M3Event(msg));
00198 }
00199
00200 void add4(const M4ConstPtr& msg)
00201 {
00202 this->template add<4>(M4Event(msg));
00203 }
00204
00205 void add5(const M5ConstPtr& msg)
00206 {
00207 this->template add<5>(M5Event(msg));
00208 }
00209
00210 void add6(const M6ConstPtr& msg)
00211 {
00212 this->template add<6>(M6Event(msg));
00213 }
00214
00215 void add7(const M7ConstPtr& msg)
00216 {
00217 this->template add<7>(M7Event(msg));
00218 }
00219
00220 void add8(const M8ConstPtr& msg)
00221 {
00222 this->template add<8>(M8Event(msg));
00223 }
00224 };
00225
00226 }
00227
00228 #endif // MESSAGE_FILTERS_TIME_SYNCHRONIZER_H