Template Class TimeSynchronizer

Inheritance Relationships

Base Type

  • public message_filters::Synchronizer< sync_policies::ExactTime< M0, M1, NullType, NullType, NullType, NullType, NullType, NullType, NullType > > (Template Class Synchronizer)

Class Documentation

template<class M0, class M1, class M2 = NullType, class M3 = NullType, class M4 = NullType, class M5 = NullType, class M6 = NullType, class M7 = NullType, class M8 = NullType>
class TimeSynchronizer : public message_filters::Synchronizer<sync_policies::ExactTime<M0, M1, NullType, NullType, NullType, NullType, NullType, NullType, NullType>>

Synchronizes up to 9 messages by their timestamps.

TimeSynchronizer synchronizes up to 9 incoming channels by the timestamps contained in their messages’ headers. TimeSynchronizer takes anywhere from 2 to 9 message types as template parameters, and passes them through to a callback which takes a shared pointer of each.

The required queue size parameter when constructing the TimeSynchronizer tells it how many sets of messages it should store (by timestamp) while waiting for messages to arrive and complete their “set”

CONNECTIONS

The input connections for the TimeSynchronizer object is the same signature as for rclcpp subscription callbacks, ie.

void callback(const std::shared_ptr<M const>&);
The output connection for the TimeSynchronizer object is dependent on the number of messages being synchronized. For a 3-message synchronizer for example, it would be:
void callback(const std::shared_ptr<M0 const>&, const std::shared_ptr<M1 const>&, const std::shared_ptr<M2 const>&);

USAGE

Example usage would be:

TimeSynchronizer<sensor_msgs::msg::CameraInfo, sensor_msgs::msg::Image, sensor_msgs::msg::Image> sync_policies(caminfo_sub, limage_sub, rimage_sub, 3);
sync_policies.registerCallback(callback);

The callback is then of the form:

void callback(const sensor_msgs::msg::CameraInfo::SharedPtr, const sensor_msgs::msg::Image::SharedPtr, const sensor_msgs::msg::Image::SharedPtr);

Public Types

typedef sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8> Policy
typedef Synchronizer<Policy> Base
typedef std::shared_ptr<M0 const> M0ConstPtr
typedef std::shared_ptr<M1 const> M1ConstPtr
typedef std::shared_ptr<M2 const> M2ConstPtr
typedef std::shared_ptr<M3 const> M3ConstPtr
typedef std::shared_ptr<M4 const> M4ConstPtr
typedef std::shared_ptr<M5 const> M5ConstPtr
typedef std::shared_ptr<M6 const> M6ConstPtr
typedef std::shared_ptr<M7 const> M7ConstPtr
typedef std::shared_ptr<M8 const> M8ConstPtr
typedef Base::M0Event M0Event
typedef Base::M1Event M1Event
typedef Base::M2Event M2Event
typedef Base::M3Event M3Event
typedef Base::M4Event M4Event
typedef Base::M5Event M5Event
typedef Base::M6Event M6Event
typedef Base::M7Event M7Event
typedef Base::M8Event M8Event

Public Functions

template<class F0, class F1>
inline TimeSynchronizer(F0 &f0, F1 &f1, uint32_t queue_size)
template<class F0, class F1, class F2>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, uint32_t queue_size)
template<class F0, class F1, class F2, class F3>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, uint32_t queue_size)
template<class F0, class F1, class F2, class F3, class F4>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, uint32_t queue_size)
template<class F0, class F1, class F2, class F3, class F4, class F5>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, uint32_t queue_size)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, uint32_t queue_size)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, uint32_t queue_size)
template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7, class F8>
inline TimeSynchronizer(F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8, uint32_t queue_size)
inline TimeSynchronizer(uint32_t queue_size)
inline void add0(const M0ConstPtr &msg)
inline void add1(const M1ConstPtr &msg)
inline void add2(const M2ConstPtr &msg)
inline void add3(const M3ConstPtr &msg)
inline void add4(const M4ConstPtr &msg)
inline void add5(const M5ConstPtr &msg)
inline void add6(const M6ConstPtr &msg)
inline void add7(const M7ConstPtr &msg)
inline void add8(const M8ConstPtr &msg)
template<int i>
inline void add(const std::shared_ptr<typename std::tuple_element<i, Messages>::type const> &msg)
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()
template<class C>
inline Connection registerDropCallback(const C &callback)
template<class C>
inline Connection registerDropCallback(C &callback)
template<class C, typename T>
inline Connection registerDropCallback(const C &callback, T *t)
template<class C, typename T>
inline Connection registerDropCallback(C &callback, T *t)