35 #ifndef MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
36 #define MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
41 #include <boost/shared_ptr.hpp>
47 namespace mpl = boost::mpl;
83 template<
class M0,
class M1,
class M2 = NullType,
class M3 = NullType,
class M4 = NullType,
84 class M5 = NullType,
class M6 = NullType,
class M7 = NullType,
class M8 = NullType>
85 class TimeSynchronizer :
public Synchronizer<sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8> >
88 typedef sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8>
Policy;
89 typedef Synchronizer<Policy>
Base;
116 template<
class F0,
class F1>
123 template<
class F0,
class F1,
class F2>
130 template<
class F0,
class F1,
class F2,
class F3>
137 template<
class F0,
class F1,
class F2,
class F3,
class F4>
138 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, uint32_t queue_size)
144 template<
class F0,
class F1,
class F2,
class F3,
class F4,
class F5>
145 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, uint32_t queue_size)
151 template<
class F0,
class F1,
class F2,
class F3,
class F4,
class F5,
class F6>
152 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, uint32_t queue_size)
158 template<
class F0,
class F1,
class F2,
class F3,
class F4,
class F5,
class F6,
class F7>
159 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, uint32_t queue_size)
165 template<
class F0,
class F1,
class F2,
class F3,
class F4,
class F5,
class F6,
class F7,
class F8>
166 TimeSynchronizer(F0& f0, F1& f1, F2& f2, F3& f3, F4& f4, F5& f5, F6& f6, F7& f7, F8& f8, uint32_t queue_size)
182 this->
template add<0>(
M0Event(msg));
187 this->
template add<1>(
M1Event(msg));
192 this->
template add<2>(
M2Event(msg));
197 this->
template add<3>(
M3Event(msg));
207 this->
template add<5>(
M5Event(msg));
212 this->
template add<6>(
M6Event(msg));
217 this->
template add<7>(
M7Event(msg));
222 this->
template add<8>(
M8Event(msg));
228 #endif // MESSAGE_FILTERS_TIME_SYNCHRONIZER_H