Template Class TimeSynchronizer
Defined in File time_synchronizer.hpp
Inheritance Relationships
Base Type
public message_filters::Synchronizer< sync_policies::ExactTime< Ms... > >(Template Class Synchronizer)
Class Documentation
-
template<class ...Ms>
class TimeSynchronizer : public message_filters::Synchronizer<sync_policies::ExactTime<Ms...>> Synchronizes up to N messages by their timestamps.
TimeSynchronizer synchronizes up to N incoming channels by the timestamps contained in their messages’ headers. TimeSynchronizer takes anywhere from 2 to N 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.
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<M const>&);
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 Functions
-
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)
-
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)
-
template<class F0, class F1, class F2>