Go to the documentation of this file.   28 #ifndef INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBERIMPL_H_    29 #define INCLUDE_RTABMAP_ROS_COMMONDATASUBSCRIBERIMPL_H_    33 #define DATA_SYNC2(PREFIX, SYNC_NAME, MSG0, MSG1) \    34         typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1> PREFIX##SYNC_NAME##SyncPolicy; \    35         message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    37 #define DATA_SYNCS2(PREFIX, MSG0, MSG1) \    38                 DATA_SYNC2(PREFIX, Approximate, MSG0, MSG1) \    39                 DATA_SYNC2(PREFIX, Exact, MSG0, MSG1) \    40                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&);    42 #define DATA_SYNC3(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2) \    43                 typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2> PREFIX##SYNC_NAME##SyncPolicy; \    44                 message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    46 #define DATA_SYNCS3(PREFIX, MSG0, MSG1, MSG2) \    47                 DATA_SYNC3(PREFIX, Approximate, MSG0, MSG1, MSG2) \    48                 DATA_SYNC3(PREFIX, Exact, MSG0, MSG1, MSG2) \    49                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&); \    51 #define DATA_SYNC4(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3) \    52                 typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3> PREFIX##SYNC_NAME##SyncPolicy; \    53                 message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    55 #define DATA_SYNCS4(PREFIX, MSG0, MSG1, MSG2, MSG3) \    56                 DATA_SYNC4(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3) \    57                 DATA_SYNC4(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3) \    58                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&); \    60 #define DATA_SYNC5(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4) \    61                 typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4> PREFIX##SYNC_NAME##SyncPolicy; \    62                 message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    64 #define DATA_SYNCS5(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4) \    65                 DATA_SYNC5(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4) \    66                 DATA_SYNC5(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4) \    67                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&); \    69 #define DATA_SYNC6(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5) \    70                 typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4, MSG5> PREFIX##SYNC_NAME##SyncPolicy; \    71                 message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    73 #define DATA_SYNCS6(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5) \    74                 DATA_SYNC6(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5) \    75                 DATA_SYNC6(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5) \    76                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&, const MSG5##ConstPtr&); \    78 #define DATA_SYNC7(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6) \    79                 typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6> PREFIX##SYNC_NAME##SyncPolicy; \    80                 message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    82 #define DATA_SYNCS7(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6) \    83                 DATA_SYNC7(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6) \    84                 DATA_SYNC7(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6) \    85                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&, const MSG5##ConstPtr&, const MSG6##ConstPtr&); \    87 #define DATA_SYNC8(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7) \    88                 typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7> PREFIX##SYNC_NAME##SyncPolicy; \    89                 message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;    91 #define DATA_SYNCS8(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7) \    92                 DATA_SYNC8(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7) \    93                 DATA_SYNC8(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7) \    94                 void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&, const MSG5##ConstPtr&, const MSG6##ConstPtr&, const MSG7##ConstPtr&); \    98 #define SYNC_INIT(PREFIX) \    99         PREFIX##ApproximateSync_(0), \   100         PREFIX##ExactSync_(0)   103 #define SYNC_DEL(PREFIX) \   104         if(PREFIX##ApproximateSync_) delete PREFIX##ApproximateSync_; \   105         if(PREFIX##ExactSync_) delete PREFIX##ExactSync_;   108 #define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1) \   111                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   112                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1); \   113                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2)); \   117                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   118                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1); \   119                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2)); \   121                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s", \   123                                 APPROX?"approx":"exact", \   124                                 SUB0.getTopic().c_str(), \   125                                 SUB1.getTopic().c_str());   127 #define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2) \   130                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   131                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2); \   132                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); \   136                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   137                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2); \   138                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); \   140                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s \\\n   %s", \   142                                 APPROX?"approx":"exact", \   143                                 SUB0.getTopic().c_str(), \   144                                 SUB1.getTopic().c_str(), \   145                                 SUB2.getTopic().c_str());   147 #define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3) \   150                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   151                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3); \   152                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); \   156                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   157                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3); \   158                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); \   160                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s \\\n   %s \\\n   %s", \   162                                 APPROX?"approx":"exact", \   163                                 SUB0.getTopic().c_str(), \   164                                 SUB1.getTopic().c_str(), \   165                                 SUB2.getTopic().c_str(), \   166                                 SUB3.getTopic().c_str());   168 #define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4) \   171                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   172                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4); \   173                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5)); \   177                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   178                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4); \   179                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5)); \   181                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s", \   183                                 approxSync?"approx":"exact", \   184                                 SUB0.getTopic().c_str(), \   185                                 SUB1.getTopic().c_str(), \   186                                 SUB2.getTopic().c_str(), \   187                                 SUB3.getTopic().c_str(), \   188                                 SUB4.getTopic().c_str());   190 #define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5) \   193                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   194                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5); \   195                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6)); \   199                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   200                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5); \   201                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6)); \   203                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s", \   205                                 APPROX?"approx":"exact", \   206                                 SUB0.getTopic().c_str(), \   207                                 SUB1.getTopic().c_str(), \   208                                 SUB2.getTopic().c_str(), \   209                                 SUB3.getTopic().c_str(), \   210                                 SUB4.getTopic().c_str(), \   211                                 SUB5.getTopic().c_str());   213 #define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6) \   216                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   217                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6); \   218                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7)); \   222                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   223                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6); \   224                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7)); \   226                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s", \   228                                 APPROX?"approx":"exact", \   229                                 SUB0.getTopic().c_str(), \   230                                 SUB1.getTopic().c_str(), \   231                                 SUB2.getTopic().c_str(), \   232                                 SUB3.getTopic().c_str(), \   233                                 SUB4.getTopic().c_str(), \   234                                 SUB5.getTopic().c_str(), \   235                                 SUB6.getTopic().c_str());   237 #define SYNC_DECL8(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7) \   240                         PREFIX##ApproximateSync_ = new message_filters::Synchronizer<PREFIX##ApproximateSyncPolicy>( \   241                                         PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7); \   242                         PREFIX##ApproximateSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8)); \   246                         PREFIX##ExactSync_ = new message_filters::Synchronizer<PREFIX##ExactSyncPolicy>( \   247                                         PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7); \   248                         PREFIX##ExactSync_->registerCallback(boost::bind(&CLASS::PREFIX##Callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8)); \   250                 subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s \\\n   %s", \   252                                 APPROX?"approx":"exact", \   253                                 SUB0.getTopic().c_str(), \   254                                 SUB1.getTopic().c_str(), \   255                                 SUB2.getTopic().c_str(), \   256                                 SUB3.getTopic().c_str(), \   257                                 SUB4.getTopic().c_str(), \   258                                 SUB5.getTopic().c_str(), \   259                                 SUB6.getTopic().c_str(), \   260                                 SUB7.getTopic().c_str()); 
 
rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40