|
typedef Synchronizer< Policy > | Base |
|
typedef boost::shared_ptr< M0 const > | M0ConstPtr |
|
typedef Base::M0Event | M0Event |
|
typedef boost::shared_ptr< M1 const > | M1ConstPtr |
|
typedef Base::M1Event | M1Event |
|
typedef boost::shared_ptr< M2 const > | M2ConstPtr |
|
typedef Base::M2Event | M2Event |
|
typedef boost::shared_ptr< M3 const > | M3ConstPtr |
|
typedef Base::M3Event | M3Event |
|
typedef boost::shared_ptr< M4 const > | M4ConstPtr |
|
typedef Base::M4Event | M4Event |
|
typedef boost::shared_ptr< M5 const > | M5ConstPtr |
|
typedef Base::M5Event | M5Event |
|
typedef boost::shared_ptr< M6 const > | M6ConstPtr |
|
typedef Base::M6Event | M6Event |
|
typedef boost::shared_ptr< M7 const > | M7ConstPtr |
|
typedef Base::M7Event | M7Event |
|
typedef boost::shared_ptr< M8 const > | M8ConstPtr |
|
typedef Base::M8Event | M8Event |
|
typedef sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > | Policy |
|
typedef sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > ::Events | Events |
|
typedef mpl::at_c< Messages, 0 >::type | M0 |
|
typedef mpl::at_c< Events, 0 >::type | M0Event |
|
typedef mpl::at_c< Messages, 1 >::type | M1 |
|
typedef mpl::at_c< Events, 1 >::type | M1Event |
|
typedef mpl::at_c< Messages, 2 >::type | M2 |
|
typedef mpl::at_c< Events, 2 >::type | M2Event |
|
typedef mpl::at_c< Messages, 3 >::type | M3 |
|
typedef mpl::at_c< Events, 3 >::type | M3Event |
|
typedef mpl::at_c< Messages, 4 >::type | M4 |
|
typedef mpl::at_c< Events, 4 >::type | M4Event |
|
typedef mpl::at_c< Messages, 5 >::type | M5 |
|
typedef mpl::at_c< Events, 5 >::type | M5Event |
|
typedef mpl::at_c< Messages, 6 >::type | M6 |
|
typedef mpl::at_c< Events, 6 >::type | M6Event |
|
typedef mpl::at_c< Messages, 7 >::type | M7 |
|
typedef mpl::at_c< Events, 7 >::type | M7Event |
|
typedef mpl::at_c< Messages, 8 >::type | M8 |
|
typedef mpl::at_c< Events, 8 >::type | M8Event |
|
typedef sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > ::Messages | Messages |
|
typedef sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > ::Signal | Signal |
|
typedef Super::Events | Events |
|
typedef Super::M0Event | M0Event |
|
typedef Super::M1Event | M1Event |
|
typedef Super::M2Event | M2Event |
|
typedef Super::M3Event | M3Event |
|
typedef Super::M4Event | M4Event |
|
typedef Super::M5Event | M5Event |
|
typedef Super::M6Event | M6Event |
|
typedef Super::M7Event | M7Event |
|
typedef Super::M8Event | M8Event |
|
typedef Super::Messages | Messages |
|
typedef Super::RealTypeCount | RealTypeCount |
|
typedef Super::Signal | Signal |
|
typedef PolicyBase< M0, M1, M2, M3, M4, M5, M6, M7, M8 > | Super |
|
typedef Synchronizer< ExactTime > | Sync |
|
typedef boost::tuple< M0Event, M1Event, M2Event, M3Event, M4Event, M5Event, M6Event, M7Event, M8Event > | Tuple |
|
typedef mpl::vector< ros::MessageEvent< M0 const >, ros::MessageEvent< M1 const >, ros::MessageEvent< M2 const >, ros::MessageEvent< M3 const >, ros::MessageEvent< M4 const >, ros::MessageEvent< M5 const >, ros::MessageEvent< M6 const >, ros::MessageEvent< M7 const >, ros::MessageEvent< M8 const > > | Events |
|
typedef mpl::at_c< Events, 0 >::type | M0Event |
|
typedef mpl::at_c< Events, 1 >::type | M1Event |
|
typedef mpl::at_c< Events, 2 >::type | M2Event |
|
typedef mpl::at_c< Events, 3 >::type | M3Event |
|
typedef mpl::at_c< Events, 4 >::type | M4Event |
|
typedef mpl::at_c< Events, 5 >::type | M5Event |
|
typedef mpl::at_c< Events, 6 >::type | M6Event |
|
typedef mpl::at_c< Events, 7 >::type | M7Event |
|
typedef mpl::at_c< Events, 8 >::type | M8Event |
|
typedef mpl::vector< M0, M1, M2, M3, M4, M5, M6, M7, M8 > | Messages |
|
typedef mpl::fold< Messages, mpl::int_< 0 >, mpl::if_< mpl::not_< boost::is_same< mpl::_2, NullType > >, mpl::next< mpl::_1 >, mpl::_1 > >::type | RealTypeCount |
|
typedef Signal9< M0, M1, M2, M3, M4, M5, M6, M7, M8 > | Signal |
|
|
void | add0 (const M0ConstPtr &msg) |
|
void | add1 (const M1ConstPtr &msg) |
|
void | add2 (const M2ConstPtr &msg) |
|
void | add3 (const M3ConstPtr &msg) |
|
void | add4 (const M4ConstPtr &msg) |
|
void | add5 (const M5ConstPtr &msg) |
|
void | add6 (const M6ConstPtr &msg) |
|
void | add7 (const M7ConstPtr &msg) |
|
void | add8 (const M8ConstPtr &msg) |
|
template<class F0 , class F1 > |
| TimeSynchronizer (F0 &f0, F1 &f1, uint32_t queue_size) |
|
template<class F0 , class F1 , class F2 > |
| TimeSynchronizer (F0 &f0, F1 &f1, F2 &f2, uint32_t queue_size) |
|
template<class F0 , class F1 , class F2 , class F3 > |
| TimeSynchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, uint32_t queue_size) |
|
template<class F0 , class F1 , class F2 , class F3 , class F4 > |
| 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 > |
| 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 > |
| 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 > |
| 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 > |
| TimeSynchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8, uint32_t queue_size) |
|
| TimeSynchronizer (uint32_t queue_size) |
|
void | add (const boost::shared_ptr< typename mpl::at_c< Messages, i >::type const > &msg) |
|
void | connectInput (F0 &f0, F1 &f1) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7) |
|
void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8) |
|
const std::string & | getName () |
|
sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > * | getPolicy () |
|
void | init () |
|
Connection | registerCallback (C &callback) |
|
Connection | registerCallback (const C &callback) |
|
Connection | registerCallback (const C &callback, T *t) |
|
Connection | registerCallback (C &callback, T *t) |
|
void | setName (const std::string &name) |
|
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) |
|
| Synchronizer (F0 &f0, F1 &f1) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7) |
|
| Synchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8) |
|
| Synchronizer () |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy, F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8) |
|
| Synchronizer (const sync_policies::ExactTime< M0, M1, M2, M3, M4, M5, M6, M7, M8 > &policy) |
|
| ~Synchronizer () |
|
template<int i> |
void | add (const typename mpl::at_c< Events, i >::type &evt) |
|
| ExactTime (uint32_t queue_size) |
|
| ExactTime (const ExactTime &e) |
|
void | initParent (Sync *parent) |
|
ExactTime & | operator= (const ExactTime &rhs) |
|
template<class C > |
Connection | registerDropCallback (const C &callback) |
|
template<class C > |
Connection | registerDropCallback (C &callback) |
|
template<class C , typename T > |
Connection | registerDropCallback (const C &callback, T *t) |
|
template<class C , typename T > |
Connection | registerDropCallback (C &callback, T *t) |
|
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 message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >
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 roscpp subscription callbacks, ie.
void callback(const boost::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 boost::shared_ptr<M0 const>&, const boost::shared_ptr<M1 const>&, const boost::shared_ptr<M2 const>&);
USAGE
Example usage would be:
TimeSynchronizer<sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::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::CameraInfo::ConstPtr&, const sensor_msgs::Image::ConstPtr&, const sensor_msgs::Image::ConstPtr&);
Definition at line 85 of file time_synchronizer.h.