33                 const sensor_msgs::LaserScanConstPtr& scanMsg)
    36         rtabmap_ros::UserDataConstPtr userDataMsg; 
    37         nav_msgs::OdometryConstPtr odomMsg; 
    38         sensor_msgs::PointCloud2 scan3dMsg; 
    39         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    43                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
    46         rtabmap_ros::UserDataConstPtr userDataMsg; 
    47         nav_msgs::OdometryConstPtr odomMsg; 
    48         sensor_msgs::LaserScan scan2dMsg; 
    49         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    53                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
    56         rtabmap_ros::UserDataConstPtr userDataMsg; 
    57         nav_msgs::OdometryConstPtr odomMsg; 
    58         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    59         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
    61 void CommonDataSubscriber::scan2dInfoCallback(
    62                 const sensor_msgs::LaserScanConstPtr& scanMsg,
    63                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    66         rtabmap_ros::UserDataConstPtr userDataMsg; 
    67         nav_msgs::OdometryConstPtr odomMsg; 
    68         sensor_msgs::PointCloud2 scan3dMsg; 
    71 void CommonDataSubscriber::scan3dInfoCallback(
    72                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
    73                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    76         rtabmap_ros::UserDataConstPtr userDataMsg; 
    77         nav_msgs::OdometryConstPtr odomMsg; 
    78         sensor_msgs::LaserScan scan2dMsg; 
    81 void CommonDataSubscriber::scanDescInfoCallback(
    82                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
    83                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    86         rtabmap_ros::UserDataConstPtr userDataMsg; 
    87         nav_msgs::OdometryConstPtr odomMsg; 
    88         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
    91 void CommonDataSubscriber::odomScan2dCallback(
    92                 const nav_msgs::OdometryConstPtr & odomMsg,
    93                 const sensor_msgs::LaserScanConstPtr& scanMsg)
    96         rtabmap_ros::UserDataConstPtr userDataMsg; 
    97         sensor_msgs::PointCloud2 scan3dMsg; 
    98         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   101 void CommonDataSubscriber::odomScan3dCallback(
   102                 const nav_msgs::OdometryConstPtr & odomMsg,
   103                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   106         rtabmap_ros::UserDataConstPtr userDataMsg; 
   107         sensor_msgs::LaserScan scan2dMsg; 
   108         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   111 void CommonDataSubscriber::odomScanDescCallback(
   112                 const nav_msgs::OdometryConstPtr & odomMsg,
   113                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   116         rtabmap_ros::UserDataConstPtr userDataMsg; 
   117         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   118         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
   120 void CommonDataSubscriber::odomScan2dInfoCallback(
   121                 const nav_msgs::OdometryConstPtr & odomMsg,
   122                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   123                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   126         rtabmap_ros::UserDataConstPtr userDataMsg; 
   127         sensor_msgs::PointCloud2 scan3dMsg; 
   130 void CommonDataSubscriber::odomScan3dInfoCallback(
   131                 const nav_msgs::OdometryConstPtr & odomMsg,
   132                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   133                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   136         rtabmap_ros::UserDataConstPtr userDataMsg; 
   137         sensor_msgs::LaserScan scan2dMsg; 
   140 void CommonDataSubscriber::odomScanDescInfoCallback(
   141                 const nav_msgs::OdometryConstPtr & odomMsg,
   142                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   143                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   146         rtabmap_ros::UserDataConstPtr userDataMsg; 
   147         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
   150 #ifdef RTABMAP_SYNC_USER_DATA   151 void CommonDataSubscriber::dataScan2dCallback(
   152                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   153                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   156         nav_msgs::OdometryConstPtr odomMsg; 
   157         sensor_msgs::PointCloud2 scan3dMsg; 
   158         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   161 void CommonDataSubscriber::dataScan3dCallback(
   162                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   163                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   166         nav_msgs::OdometryConstPtr odomMsg; 
   167         sensor_msgs::LaserScan scan2dMsg; 
   168         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   171 void CommonDataSubscriber::dataScanDescCallback(
   172                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   173                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   176         nav_msgs::OdometryConstPtr odomMsg; 
   177         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   178         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
   180 void CommonDataSubscriber::dataScan2dInfoCallback(
   181                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   182                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   183                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   186         nav_msgs::OdometryConstPtr odomMsg; 
   187         sensor_msgs::PointCloud2 scan3dMsg; 
   190 void CommonDataSubscriber::dataScan3dInfoCallback(
   191                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   192                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   193                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   196         nav_msgs::OdometryConstPtr odomMsg; 
   197         sensor_msgs::LaserScan scan2dMsg; 
   200 void CommonDataSubscriber::dataScanDescInfoCallback(
   201                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   202                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   203                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   206         nav_msgs::OdometryConstPtr odomMsg; 
   207         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
   210 void CommonDataSubscriber::odomDataScan2dCallback(
   211                 const nav_msgs::OdometryConstPtr & odomMsg,
   212                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   213                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   216         sensor_msgs::PointCloud2 scan3dMsg; 
   217         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   220 void CommonDataSubscriber::odomDataScan3dCallback(
   221                 const nav_msgs::OdometryConstPtr & odomMsg,
   222                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   223                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   226         sensor_msgs::LaserScan scan2dMsg; 
   227         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   230 void CommonDataSubscriber::odomDataScanDescCallback(
   231                 const nav_msgs::OdometryConstPtr & odomMsg,
   232                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   233                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   236         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   237         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
   239 void CommonDataSubscriber::odomDataScan2dInfoCallback(
   240                 const nav_msgs::OdometryConstPtr & odomMsg,
   241                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   242                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   243                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   246         sensor_msgs::PointCloud2 scan3dMsg; 
   249 void CommonDataSubscriber::odomDataScan3dInfoCallback(
   250                 const nav_msgs::OdometryConstPtr & odomMsg,
   251                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   252                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   253                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   256         sensor_msgs::LaserScan scan2dMsg; 
   259 void CommonDataSubscriber::odomDataScanDescInfoCallback(
   260                 const nav_msgs::OdometryConstPtr & odomMsg,
   261                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   262                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   263                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   266         commonLaserScanCallback(odomMsg, userDataMsg, scanMsg->scan, scanMsg->scan_cloud, odomInfoMsg, scanMsg->global_descriptor);
   276                 bool subscribeUserData,
   277                 bool subscribeOdomInfo,
   283         if(subscribeOdom || subscribeUserData || subscribeOdomInfo)
   301 #ifdef RTABMAP_SYNC_USER_DATA   302                 if(subscribeOdom && subscribeUserData)
   309                                 if(subscribeOdomInfo)
   322                                 if(subscribeOdomInfo)
   335                                 if(subscribeOdomInfo)
   355                                 if(subscribeOdomInfo)
   368                                 if(subscribeOdomInfo)
   381                                 if(subscribeOdomInfo)
   393 #ifdef RTABMAP_SYNC_USER_DATA   394                 else if(subscribeUserData)
   400                                 if(subscribeOdomInfo)
   413                                 if(subscribeOdomInfo)
   426                                 if(subscribeOdomInfo)
   439                 else if(subscribeOdomInfo)
   464                                         uFormat(
"\n%s subscribed to:\n   %s",
   473                                         uFormat(
"\n%s subscribed to:\n   %s",
   482                                         uFormat(
"\n%s subscribed to:\n   %s",
 std::string uFormat(const char *fmt,...)
std::string getTopic() const
void scanDescCallback(const rtabmap_ros::ScanDescriptorConstPtr &)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
ROSCPP_DECL const std::string & getName()
message_filters::Subscriber< rtabmap_ros::UserData > userDataSub_
bool subscribedToOdomInfo_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const rtabmap_ros::GlobalDescriptor &globalDescriptor=rtabmap_ros::GlobalDescriptor())=0
ros::Subscriber scanDescSubOnly_
void setupScanCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeScan2d, bool subscribeScanDesc, bool subscribeOdom, bool subscribeUserData, bool subscribeOdomInfo, int queueSize, bool approxSync)
void scan3dCallback(const sensor_msgs::PointCloud2ConstPtr &)
bool subscribedToScanDescriptor_
void scan2dCallback(const sensor_msgs::LaserScanConstPtr &)
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > scan3dSub_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
ros::Subscriber scan3dSubOnly_
ros::Subscriber scan2dSubOnly_
std::string subscribedTopicsMsg_
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)