|
Project: message_filters License: BSD Dependencies: Used by:
|
message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 > Class Template Reference#include <time_synchronizer.h>
Detailed Descriptiontemplate<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>
Synchronizes up to 9 messages by their timestamps.
| |||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
Public Types | |
| typedef boost::shared_ptr< M0 const > | M0ConstPtr |
| typedef boost::shared_ptr< M1 const > | M1ConstPtr |
| typedef boost::shared_ptr< M2 const > | M2ConstPtr |
| typedef boost::shared_ptr< M3 const > | M3ConstPtr |
| typedef boost::shared_ptr< M4 const > | M4ConstPtr |
| typedef boost::shared_ptr< M5 const > | M5ConstPtr |
| typedef boost::shared_ptr< M6 const > | M6ConstPtr |
| typedef boost::shared_ptr< M7 const > | M7ConstPtr |
| typedef boost::shared_ptr< M8 const > | M8ConstPtr |
| typedef boost::signal< void(const M0ConstPtr &, const M1ConstPtr &, const M2ConstPtr &, const M3ConstPtr &, const M4ConstPtr &, const M5ConstPtr &, const M6ConstPtr &, const M7ConstPtr &, const M8ConstPtr &)> | Signal |
| typedef boost::tuple < M0ConstPtr, M1ConstPtr, M2ConstPtr, M3ConstPtr, M4ConstPtr, M5ConstPtr, M6ConstPtr, M7ConstPtr, M8ConstPtr > | Tuple |
Public Member Functions | |
| 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, class F2, class F3, class F4, class F5, class F6, class F7, class F8> | |
| void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, F5 &f5, F6 &f6, F7 &f7, F8 &f8) |
| template<class F0, class F1, class F2, class F3, class F4, class F5, class F6, class F7> | |
| 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> | |
| 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> | |
| 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> | |
| void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4) |
| template<class F0, class F1, class F2, class F3> | |
| void | connectInput (F0 &f0, F1 &f1, F2 &f2, F3 &f3) |
| template<class F0, class F1, class F2> | |
| void | connectInput (F0 &f0, F1 &f1, F2 &f2) |
| template<class F0, class F1> | |
| void | connectInput (F0 &f0, F1 &f1) |
| const std::string & | getName () |
| template<class C> | |
| Connection | registerCallback (const C &callback) |
| void | setName (const std::string &name) |
| TimeSynchronizer (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) | |
| 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> | |
| 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> | |
| 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> | |
| TimeSynchronizer (F0 &f0, F1 &f1, F2 &f2, F3 &f3, F4 &f4, 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> | |
| TimeSynchronizer (F0 &f0, F1 &f1, F2 &f2, uint32_t queue_size) | |
| template<class F0, class F1> | |
| TimeSynchronizer (F0 &f0, F1 &f1, uint32_t queue_size) | |
| ~TimeSynchronizer () | |
Private Types | |
| typedef std::map< ros::Time, Tuple > | M_TimeToTuple |
Private Member Functions | |
| void | cb0 (const M0ConstPtr &msg) |
| void | cb1 (const M1ConstPtr &msg) |
| void | cb2 (const M2ConstPtr &msg) |
| void | cb3 (const M3ConstPtr &msg) |
| void | cb4 (const M4ConstPtr &msg) |
| void | cb5 (const M5ConstPtr &msg) |
| void | cb6 (const M6ConstPtr &msg) |
| void | cb7 (const M7ConstPtr &msg) |
| void | cb8 (const M8ConstPtr &msg) |
| void | checkTuple (Tuple &t) |
| void | clearOldTuples () |
| void | determineRealTypeCount () |
| void | disconnect (const Connection &c) |
| void | disconnectAll () |
Private Attributes | |
| Connection | input_connections_ [TIME_SYNCHRONIZER_MAX_MESSAGES] |
| ros::Time | last_signal_time_ |
| std::string | name_ |
| uint32_t | queue_size_ |
| uint32_t | real_type_count_ |
| Signal | signal_ |
| boost::mutex | signal_mutex_ |
| M_TimeToTuple | tuples_ |
| boost::mutex | tuples_mutex_ |
| typedef boost::shared_ptr<M0 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M0ConstPtr |
Definition at line 114 of file time_synchronizer.h.
| typedef boost::shared_ptr<M1 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M1ConstPtr |
Definition at line 115 of file time_synchronizer.h.
| typedef boost::shared_ptr<M2 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M2ConstPtr |
Definition at line 116 of file time_synchronizer.h.
| typedef boost::shared_ptr<M3 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M3ConstPtr |
Definition at line 117 of file time_synchronizer.h.
| typedef boost::shared_ptr<M4 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M4ConstPtr |
Definition at line 118 of file time_synchronizer.h.
| typedef boost::shared_ptr<M5 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M5ConstPtr |
Definition at line 119 of file time_synchronizer.h.
| typedef boost::shared_ptr<M6 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M6ConstPtr |
Definition at line 120 of file time_synchronizer.h.
| typedef boost::shared_ptr<M7 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M7ConstPtr |
Definition at line 121 of file time_synchronizer.h.
| typedef boost::shared_ptr<M8 const> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M8ConstPtr |
Definition at line 122 of file time_synchronizer.h.
typedef std::map<ros::Time, Tuple> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::M_TimeToTuple [private] |
Definition at line 527 of file time_synchronizer.h.
| typedef boost::signal<void(const M0ConstPtr&, const M1ConstPtr&, const M2ConstPtr&, const M3ConstPtr&, const M4ConstPtr&, const M5ConstPtr&, const M6ConstPtr&, const M7ConstPtr&, const M8ConstPtr&)> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::Signal |
Definition at line 124 of file time_synchronizer.h.
| typedef boost::tuple<M0ConstPtr, M1ConstPtr, M2ConstPtr, M3ConstPtr, M4ConstPtr, M5ConstPtr, M6ConstPtr, M7ConstPtr, M8ConstPtr> message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::Tuple |
Definition at line 123 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 127 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 135 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 143 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 151 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 159 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| F6 & | f6, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 167 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| F6 & | f6, | |||
| F7 & | f7, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 175 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| F6 & | f6, | |||
| F7 & | f7, | |||
| F8 & | f8, | |||
| uint32_t | queue_size | |||
| ) | [inline] |
Definition at line 183 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::TimeSynchronizer | ( | uint32_t | queue_size | ) | [inline] |
Definition at line 190 of file time_synchronizer.h.
| message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::~TimeSynchronizer | ( | ) | [inline] |
Definition at line 196 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add0 | ( | const M0ConstPtr & | msg | ) | [inline] |
Definition at line 273 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add1 | ( | const M1ConstPtr & | msg | ) | [inline] |
Definition at line 283 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add2 | ( | const M2ConstPtr & | msg | ) | [inline] |
Definition at line 293 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add3 | ( | const M3ConstPtr & | msg | ) | [inline] |
Definition at line 303 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add4 | ( | const M4ConstPtr & | msg | ) | [inline] |
Definition at line 313 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add5 | ( | const M5ConstPtr & | msg | ) | [inline] |
Definition at line 323 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add6 | ( | const M6ConstPtr & | msg | ) | [inline] |
Definition at line 333 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add7 | ( | const M7ConstPtr & | msg | ) | [inline] |
Definition at line 343 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::add8 | ( | const M8ConstPtr & | msg | ) | [inline] |
Definition at line 353 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb0 | ( | const M0ConstPtr & | msg | ) | [inline, private] |
Definition at line 416 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb1 | ( | const M1ConstPtr & | msg | ) | [inline, private] |
Definition at line 421 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb2 | ( | const M2ConstPtr & | msg | ) | [inline, private] |
Definition at line 426 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb3 | ( | const M3ConstPtr & | msg | ) | [inline, private] |
Definition at line 431 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb4 | ( | const M4ConstPtr & | msg | ) | [inline, private] |
Definition at line 436 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb5 | ( | const M5ConstPtr & | msg | ) | [inline, private] |
Definition at line 441 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb6 | ( | const M6ConstPtr & | msg | ) | [inline, private] |
Definition at line 446 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb7 | ( | const M7ConstPtr & | msg | ) | [inline, private] |
Definition at line 451 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::cb8 | ( | const M8ConstPtr & | msg | ) | [inline, private] |
Definition at line 456 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::checkTuple | ( | Tuple & | t | ) | [inline, private] |
Definition at line 462 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::clearOldTuples | ( | ) | [inline, private] |
Definition at line 499 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| F6 & | f6, | |||
| F7 & | f7, | |||
| F8 & | f8 | |||
| ) | [inline] |
Definition at line 251 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| F6 & | f6, | |||
| F7 & | f7 | |||
| ) | [inline] |
Definition at line 244 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5, | |||
| F6 & | f6 | |||
| ) | [inline] |
Definition at line 237 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4, | |||
| F5 & | f5 | |||
| ) | [inline] |
Definition at line 230 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3, | |||
| F4 & | f4 | |||
| ) | [inline] |
Definition at line 223 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2, | |||
| F3 & | f3 | |||
| ) | [inline] |
Definition at line 216 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1, | |||
| F2 & | f2 | |||
| ) | [inline] |
Definition at line 209 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::connectInput | ( | F0 & | f0, | |
| F1 & | f1 | |||
| ) | [inline] |
Definition at line 202 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::determineRealTypeCount | ( | ) | [inline, private] |
Definition at line 376 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::disconnect | ( | const Connection & | c | ) | [inline, private] |
Definition at line 519 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::disconnectAll | ( | ) | [inline, private] |
Definition at line 368 of file time_synchronizer.h.
| const std::string& message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::getName | ( | ) | [inline] |
Definition at line 364 of file time_synchronizer.h.
| Connection message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::registerCallback | ( | const C & | callback | ) | [inline] |
Definition at line 267 of file time_synchronizer.h.
| void message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::setName | ( | const std::string & | name | ) | [inline] |
Definition at line 363 of file time_synchronizer.h.
Connection message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::input_connections_[TIME_SYNCHRONIZER_MAX_MESSAGES] [private] |
Definition at line 535 of file time_synchronizer.h.
ros::Time message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::last_signal_time_ [private] |
Definition at line 533 of file time_synchronizer.h.
std::string message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::name_ [private] |
Definition at line 539 of file time_synchronizer.h.
uint32_t message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::queue_size_ [private] |
Definition at line 525 of file time_synchronizer.h.
uint32_t message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::real_type_count_ [private] |
Definition at line 537 of file time_synchronizer.h.
Signal message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::signal_ [private] |
Definition at line 531 of file time_synchronizer.h.
boost::mutex message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::signal_mutex_ [private] |
Definition at line 532 of file time_synchronizer.h.
M_TimeToTuple message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::tuples_ [private] |
Definition at line 528 of file time_synchronizer.h.
boost::mutex message_filters::TimeSynchronizer< M0, M1, M2, M3, M4, M5, M6, M7, M8 >::tuples_mutex_ [private] |
Definition at line 529 of file time_synchronizer.h.