Template Class Synchronizer

Inheritance Relationships

Base Types

Class Documentation

template<class Policy>
class Synchronizer : public message_filters::noncopyable, public Policy

Public Types

typedef Policy::Messages Messages
typedef Policy::Events Events
typedef Policy::Signal Signal
typedef std::tuple_element<0, Messages>::type M0
typedef std::tuple_element<1, Messages>::type M1
typedef std::tuple_element<2, Messages>::type M2
typedef std::tuple_element<3, Messages>::type M3
typedef std::tuple_element<4, Messages>::type M4
typedef std::tuple_element<5, Messages>::type M5
typedef std::tuple_element<6, Messages>::type M6
typedef std::tuple_element<7, Messages>::type M7
typedef std::tuple_element<8, Messages>::type M8
typedef std::tuple_element<0, Events>::type M0Event
typedef std::tuple_element<1, Events>::type M1Event
typedef std::tuple_element<2, Events>::type M2Event
typedef std::tuple_element<3, Events>::type M3Event
typedef std::tuple_element<4, Events>::type M4Event
typedef std::tuple_element<5, Events>::type M5Event
typedef std::tuple_element<6, Events>::type M6Event
typedef std::tuple_element<7, Events>::type M7Event
typedef std::tuple_element<8, Events>::type M8Event

Public Functions

template<class F0, class F1>
inline Synchronizer(F0 &f0, F1 &f1)
template<class F0, class F1, class F2>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2)
template<class F0, class F1, class F2, class F3>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3)
template<class F0, class F1, class F2, class F3, class F4>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4)
template<class F0, class F1, class F2, class F3, class F4, class F5>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
inline Synchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8)
inline Synchronizer()
template<class F0, class F1>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1)
template<class F0, class F1, class F2>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2)
template<class F0, class F1, class F2, class F3>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3)
template<class F0, class F1, class F2, class F3, class F4>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4)
template<class F0, class F1, class F2, class F3, class F4, class F5>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
inline Synchronizer(const Policy &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8)
inline Synchronizer(const Policy &policy)
inline ~Synchronizer()
inline void init()
template<class F0, class F1>
inline void connectInput(F0 &f0, F1 &f1)
template<class F0, class F1, class F2>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2)
template<class F0, class F1, class F2, class F3>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2, F3 &f3)
template<class F0, class F1, class F2, class F3, class F4>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4)
template<class F0, class F1, class F2, class F3, class F4, class F5>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
inline void connectInput(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8)
template<class C>
inline Connection registerCallback(C &callback)
template<class C>
inline Connection registerCallback(const C &callback)
template<class C, typename T>
inline Connection registerCallback(const C &callback, T *t)
template<class C, typename T>
inline Connection registerCallback(C &callback, T *t)
inline void setName(const std::string &name)
inline const std::string &getName()
inline void signal(const M0Event &e0, const M1Event &e1, const M2Event &e2, const M3Event &e3, const M4Event &e4, const M5Event &e5, const M6Event &e6, const M7Event &e7, const M8Event &e8)
inline Policy *getPolicy()
template<int i>
inline void add(const std::shared_ptr<typename std::tuple_element<i, Messages>::type const> &msg)

Public Static Attributes

static const uint8_t MAX_MESSAGES = 9