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>
116 template<
class F0,
class F1>
118 : Base(Policy(queue_size))
123 template<
class F0,
class F1,
class F2>
125 : Base(Policy(queue_size))
130 template<
class F0,
class F1,
class F2,
class F3>
132 : Base(Policy(queue_size))
137 template<
class F0,
class F1,
class F2,
class F3,
class F4>
139 : Base(Policy(queue_size))
144 template<
class F0,
class F1,
class F2,
class F3,
class F4,
class F5>
146 : Base(Policy(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)
153 : Base(Policy(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)
160 : Base(Policy(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)
167 : Base(Policy(queue_size))
173 : Base(Policy(queue_size))
180 void add0(
const M0ConstPtr& msg)
182 this->
template add<0>(
M0Event(msg));
185 void add1(
const M1ConstPtr& msg)
187 this->
template add<1>(
M1Event(msg));
190 void add2(
const M2ConstPtr& msg)
192 this->
template add<2>(
M2Event(msg));
195 void add3(
const M3ConstPtr& msg)
197 this->
template add<3>(
M3Event(msg));
200 void add4(
const M4ConstPtr& msg)
202 this->
template add<4>(
M4Event(msg));
205 void add5(
const M5ConstPtr& msg)
207 this->
template add<5>(
M5Event(msg));
210 void add6(
const M6ConstPtr& msg)
212 this->
template add<6>(
M6Event(msg));
215 void add7(
const M7ConstPtr& msg)
217 this->
template add<7>(
M7Event(msg));
220 void add8(
const M8ConstPtr& msg)
222 this->
template add<8>(
M8Event(msg));
228 #endif // MESSAGE_FILTERS_TIME_SYNCHRONIZER_H
boost::shared_ptr< M6 const > M6ConstPtr
void add1(const M1ConstPtr &msg)
void setName(const std::string &name)
boost::shared_ptr< M7 const > M7ConstPtr
void add(const boost::shared_ptr< typename mpl::at_c< Messages, i >::type const > &msg)
boost::shared_ptr< M8 const > M8ConstPtr
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, uint32_t queue_size)
boost::shared_ptr< M2 const > M2ConstPtr
mpl::at_c< Events, 6 >::type M6Event
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, uint32_t queue_size)
void add3(const M3ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, uint32_t queue_size)
mpl::at_c< Events, 7 >::type M7Event
void add5(const M5ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, uint32_t queue_size)
mpl::at_c< Events, 3 >::type M3Event
mpl::at_c< Events, 5 >::type M5Event
const std::string & getName()
boost::shared_ptr< M3 const > M3ConstPtr
void add4(const M4ConstPtr &msg)
Connection registerDropCallback(const C &callback)
void add2(const M2ConstPtr &msg)
boost::shared_ptr< M5 const > M5ConstPtr
sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Policy
Connection registerCallback(C &callback)
boost::shared_ptr< M1 const > M1ConstPtr
TimeSynchronizer(uint32_t queue_size)
void add0(const M0ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, uint32_t queue_size)
boost::shared_ptr< M0 const > M0ConstPtr
mpl::at_c< Events, 0 >::type M0Event
void add8(const M8ConstPtr &msg)
void add7(const M7ConstPtr &msg)
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, uint32_t queue_size)
void connectInput(F0 &f0, F1 &f1)
void add6(const M6ConstPtr &msg)
boost::shared_ptr< M4 const > M4ConstPtr
mpl::at_c< Events, 4 >::type M4Event
mpl::at_c< Events, 1 >::type M1Event
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, uint32_t queue_size)
mpl::at_c< Events, 8 >::type M8Event
Synchronizes up to 9 messages by their timestamps.
Synchronizer< Policy > Base
mpl::at_c< Events, 2 >::type M2Event
TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8, uint32_t queue_size)