Macros
CommonDataSubscriberDefines.h File Reference
#include <rtabmap/utilite/UConversion.h>
Include dependency graph for CommonDataSubscriberDefines.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Macros

#define DATA_SYNC2(PREFIX, SYNC_NAME, MSG0, MSG1)
 
#define DATA_SYNC3(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2)
 
#define DATA_SYNC4(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3)
 
#define DATA_SYNC5(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4)
 
#define DATA_SYNC6(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5)
 
#define DATA_SYNC7(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6)
 
#define DATA_SYNC8(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7)
 
#define DATA_SYNCS2(PREFIX, MSG0, MSG1)
 
#define DATA_SYNCS3(PREFIX, MSG0, MSG1, MSG2)
 
#define DATA_SYNCS4(PREFIX, MSG0, MSG1, MSG2, MSG3)
 
#define DATA_SYNCS5(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4)
 
#define DATA_SYNCS6(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5)
 
#define DATA_SYNCS7(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6)
 
#define DATA_SYNCS8(PREFIX, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7)
 
#define SYNC_DECL2(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
 
#define SYNC_DECL3(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
 
#define SYNC_DECL4(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
 
#define SYNC_DECL5(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
 
#define SYNC_DECL6(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
 
#define SYNC_DECL7(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
 
#define SYNC_DECL8(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7)
 
#define SYNC_DEL(PREFIX)
 
#define SYNC_INIT(PREFIX)
 

Macro Definition Documentation

#define DATA_SYNC2 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 33 of file CommonDataSubscriberDefines.h.

#define DATA_SYNC3 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1,
  MSG2 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 42 of file CommonDataSubscriberDefines.h.

#define DATA_SYNC4 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1,
  MSG2,
  MSG3 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 51 of file CommonDataSubscriberDefines.h.

#define DATA_SYNC5 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 60 of file CommonDataSubscriberDefines.h.

#define DATA_SYNC6 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4,
  MSG5 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4, MSG5> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 69 of file CommonDataSubscriberDefines.h.

#define DATA_SYNC7 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4,
  MSG5,
  MSG6 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 78 of file CommonDataSubscriberDefines.h.

#define DATA_SYNC8 (   PREFIX,
  SYNC_NAME,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4,
  MSG5,
  MSG6,
  MSG7 
)
Value:
typedef message_filters::sync_policies::SYNC_NAME##Time<MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7> PREFIX##SYNC_NAME##SyncPolicy; \
message_filters::Synchronizer<PREFIX##SYNC_NAME##SyncPolicy> * PREFIX##SYNC_NAME##Sync_;

Definition at line 87 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS2 (   PREFIX,
  MSG0,
  MSG1 
)
Value:
DATA_SYNC2(PREFIX, Approximate, MSG0, MSG1) \
DATA_SYNC2(PREFIX, Exact, MSG0, MSG1) \
void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&);
#define DATA_SYNC2(PREFIX, SYNC_NAME, MSG0, MSG1)

Definition at line 37 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS3 (   PREFIX,
  MSG0,
  MSG1,
  MSG2 
)
Value:
DATA_SYNC3(PREFIX, Approximate, MSG0, MSG1, MSG2) \
DATA_SYNC3(PREFIX, Exact, MSG0, MSG1, MSG2) \
void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&); \
#define DATA_SYNC3(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2)

Definition at line 46 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS4 (   PREFIX,
  MSG0,
  MSG1,
  MSG2,
  MSG3 
)
Value:
DATA_SYNC4(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3) \
DATA_SYNC4(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3) \
void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&); \
#define DATA_SYNC4(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3)

Definition at line 55 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS5 (   PREFIX,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4 
)
Value:
DATA_SYNC5(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4) \
DATA_SYNC5(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4) \
void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&); \
#define DATA_SYNC5(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4)

Definition at line 64 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS6 (   PREFIX,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4,
  MSG5 
)
Value:
DATA_SYNC6(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5) \
DATA_SYNC6(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5) \
void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&, const MSG5##ConstPtr&); \
#define DATA_SYNC6(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5)

Definition at line 73 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS7 (   PREFIX,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4,
  MSG5,
  MSG6 
)
Value:
DATA_SYNC7(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6) \
DATA_SYNC7(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6) \
void PREFIX##Callback(const MSG0##ConstPtr&, const MSG1##ConstPtr&, const MSG2##ConstPtr&, const MSG3##ConstPtr&, const MSG4##ConstPtr&, const MSG5##ConstPtr&, const MSG6##ConstPtr&); \
#define DATA_SYNC7(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6)

Definition at line 82 of file CommonDataSubscriberDefines.h.

#define DATA_SYNCS8 (   PREFIX,
  MSG0,
  MSG1,
  MSG2,
  MSG3,
  MSG4,
  MSG5,
  MSG6,
  MSG7 
)
Value:
DATA_SYNC8(PREFIX, Approximate, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7) \
DATA_SYNC8(PREFIX, Exact, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7) \
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&); \
#define DATA_SYNC8(PREFIX, SYNC_NAME, MSG0, MSG1, MSG2, MSG3, MSG4, MSG5, MSG6, MSG7)

Definition at line 91 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL2 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s", \
name_.c_str(), \
APPROX?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 108 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL3 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1,
  SUB2 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s", \
name_.c_str(), \
APPROX?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str(), \
SUB2.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 127 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL4 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1,
  SUB2,
  SUB3 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s", \
name_.c_str(), \
APPROX?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str(), \
SUB2.getTopic().c_str(), \
SUB3.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 147 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL5 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1,
  SUB2,
  SUB3,
  SUB4 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s \\\n %s", \
name_.c_str(), \
approxSync?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str(), \
SUB2.getTopic().c_str(), \
SUB3.getTopic().c_str(), \
SUB4.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 168 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL6 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1,
  SUB2,
  SUB3,
  SUB4,
  SUB5 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5, _6)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5, _6)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s \\\n %s \\\n %s", \
name_.c_str(), \
APPROX?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str(), \
SUB2.getTopic().c_str(), \
SUB3.getTopic().c_str(), \
SUB4.getTopic().c_str(), \
SUB5.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 190 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL7 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1,
  SUB2,
  SUB3,
  SUB4,
  SUB5,
  SUB6 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5, _6, _7)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5, _6, _7)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s \\\n %s \\\n %s \\\n %s", \
name_.c_str(), \
APPROX?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str(), \
SUB2.getTopic().c_str(), \
SUB3.getTopic().c_str(), \
SUB4.getTopic().c_str(), \
SUB5.getTopic().c_str(), \
SUB6.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 213 of file CommonDataSubscriberDefines.h.

#define SYNC_DECL8 (   PREFIX,
  APPROX,
  QUEUE_SIZE,
  SUB0,
  SUB1,
  SUB2,
  SUB3,
  SUB4,
  SUB5,
  SUB6,
  SUB7 
)
Value:
if(APPROX) \
{ \
PREFIX##ApproximateSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7); \
PREFIX##ApproximateSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5, _6, _7, _8)); \
} \
else \
{ \
PREFIX##ExactSyncPolicy(QUEUE_SIZE), SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7); \
PREFIX##ExactSync_->registerCallback(boost::bind(&CommonDataSubscriber::PREFIX##Callback, this, _1, _2, _3, _4, _5, _6, _7, _8)); \
} \
subscribedTopicsMsg_ = uFormat("\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s \\\n %s \\\n %s \\\n %s \\\n %s", \
name_.c_str(), \
APPROX?"approx":"exact", \
SUB0.getTopic().c_str(), \
SUB1.getTopic().c_str(), \
SUB2.getTopic().c_str(), \
SUB3.getTopic().c_str(), \
SUB4.getTopic().c_str(), \
SUB5.getTopic().c_str(), \
SUB6.getTopic().c_str(), \
SUB7.getTopic().c_str());
std::string uFormat(const char *fmt,...)
Connection registerCallback(C &callback)

Definition at line 237 of file CommonDataSubscriberDefines.h.

#define SYNC_DEL (   PREFIX)
Value:
if(PREFIX##ApproximateSync_) delete PREFIX##ApproximateSync_; \
if(PREFIX##ExactSync_) delete PREFIX##ExactSync_;

Definition at line 103 of file CommonDataSubscriberDefines.h.

#define SYNC_INIT (   PREFIX)
Value:
PREFIX##ApproximateSync_(0), \
PREFIX##ExactSync_(0)

Definition at line 98 of file CommonDataSubscriberDefines.h.



rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19