33 void CommonDataSubscriber::depthCallback(
    34                 const sensor_msgs::ImageConstPtr& imageMsg,
    35                 const sensor_msgs::ImageConstPtr& depthMsg,
    36                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
    38         rtabmap_ros::UserDataConstPtr userDataMsg; 
    39         nav_msgs::OdometryConstPtr odomMsg; 
    40         sensor_msgs::LaserScan scanMsg; 
    41         sensor_msgs::PointCloud2 scan3dMsg; 
    42         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    45 void CommonDataSubscriber::depthScan2dCallback(
    46                 const sensor_msgs::ImageConstPtr& imageMsg,
    47                 const sensor_msgs::ImageConstPtr& depthMsg,
    48                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    49                 const sensor_msgs::LaserScanConstPtr& scanMsg)
    51         rtabmap_ros::UserDataConstPtr userDataMsg; 
    52         nav_msgs::OdometryConstPtr odomMsg; 
    53         sensor_msgs::PointCloud2 scan3dMsg; 
    54         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    57 void CommonDataSubscriber::depthScan3dCallback(
    58                 const sensor_msgs::ImageConstPtr& imageMsg,
    59                 const sensor_msgs::ImageConstPtr& depthMsg,
    60                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    61                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
    63         rtabmap_ros::UserDataConstPtr userDataMsg; 
    64         nav_msgs::OdometryConstPtr odomMsg; 
    65         sensor_msgs::LaserScan scan2dMsg; 
    66         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    69 void CommonDataSubscriber::depthScanDescCallback(
    70                 const sensor_msgs::ImageConstPtr& imageMsg,
    71                 const sensor_msgs::ImageConstPtr& depthMsg,
    72                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    73                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
    75         rtabmap_ros::UserDataConstPtr userDataMsg; 
    76         nav_msgs::OdometryConstPtr odomMsg; 
    77         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    78         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
    79         if(!scanMsg->global_descriptor.data.empty())
    81                 globalDescriptor.push_back(scanMsg->global_descriptor);
    85 void CommonDataSubscriber::depthInfoCallback(
    86                 const sensor_msgs::ImageConstPtr& imageMsg,
    87                 const sensor_msgs::ImageConstPtr& depthMsg,
    88                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    89                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    91         rtabmap_ros::UserDataConstPtr userDataMsg; 
    92         nav_msgs::OdometryConstPtr odomMsg; 
    93         sensor_msgs::LaserScan scan2dMsg; 
    94         sensor_msgs::PointCloud2 scan3dMsg; 
    97 void CommonDataSubscriber::depthScan2dInfoCallback(
    98                 const sensor_msgs::ImageConstPtr& imageMsg,
    99                 const sensor_msgs::ImageConstPtr& depthMsg,
   100                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   101                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   102                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   104         rtabmap_ros::UserDataConstPtr userDataMsg; 
   105         nav_msgs::OdometryConstPtr odomMsg; 
   106         sensor_msgs::PointCloud2 scan3dMsg; 
   109 void CommonDataSubscriber::depthScan3dInfoCallback(
   110                 const sensor_msgs::ImageConstPtr& imageMsg,
   111                 const sensor_msgs::ImageConstPtr& depthMsg,
   112                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   113                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   114                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   116         rtabmap_ros::UserDataConstPtr userDataMsg; 
   117         nav_msgs::OdometryConstPtr odomMsg; 
   118         sensor_msgs::LaserScan scan2dMsg; 
   121 void CommonDataSubscriber::depthScanDescInfoCallback(
   122                 const sensor_msgs::ImageConstPtr& imageMsg,
   123                 const sensor_msgs::ImageConstPtr& depthMsg,
   124                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   125                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   126                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   128         rtabmap_ros::UserDataConstPtr userDataMsg; 
   129         nav_msgs::OdometryConstPtr odomMsg; 
   130         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   131         if(!scanMsg->global_descriptor.data.empty())
   133                 globalDescriptor.push_back(scanMsg->global_descriptor);
   139 void CommonDataSubscriber::depthOdomCallback(
   140                 const nav_msgs::OdometryConstPtr & odomMsg,
   141                 const sensor_msgs::ImageConstPtr& imageMsg,
   142                 const sensor_msgs::ImageConstPtr& depthMsg,
   143                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
   145         rtabmap_ros::UserDataConstPtr userDataMsg; 
   146         sensor_msgs::LaserScan scanMsg; 
   147         sensor_msgs::PointCloud2 scan3dMsg; 
   148         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   151 void CommonDataSubscriber::depthOdomScan2dCallback(
   152                 const nav_msgs::OdometryConstPtr & odomMsg,
   153                 const sensor_msgs::ImageConstPtr& imageMsg,
   154                 const sensor_msgs::ImageConstPtr& depthMsg,
   155                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   156                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   158         rtabmap_ros::UserDataConstPtr userDataMsg; 
   159         sensor_msgs::PointCloud2 scan3dMsg; 
   160         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   163 void CommonDataSubscriber::depthOdomScan3dCallback(
   164                 const nav_msgs::OdometryConstPtr & odomMsg,
   165                 const sensor_msgs::ImageConstPtr& imageMsg,
   166                 const sensor_msgs::ImageConstPtr& depthMsg,
   167                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   168                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   170         rtabmap_ros::UserDataConstPtr userDataMsg; 
   171         sensor_msgs::LaserScan scan2dMsg; 
   172         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   175 void CommonDataSubscriber::depthOdomScanDescCallback(
   176                 const nav_msgs::OdometryConstPtr & odomMsg,
   177                 const sensor_msgs::ImageConstPtr& imageMsg,
   178                 const sensor_msgs::ImageConstPtr& depthMsg,
   179                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   180                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   182         rtabmap_ros::UserDataConstPtr userDataMsg; 
   183         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   184         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   185         if(!scanMsg->global_descriptor.data.empty())
   187                 globalDescriptor.push_back(scanMsg->global_descriptor);
   191 void CommonDataSubscriber::depthOdomInfoCallback(
   192                 const nav_msgs::OdometryConstPtr & odomMsg,
   193                 const sensor_msgs::ImageConstPtr& imageMsg,
   194                 const sensor_msgs::ImageConstPtr& depthMsg,
   195                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   196                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   198         rtabmap_ros::UserDataConstPtr userDataMsg; 
   199         sensor_msgs::LaserScan scan2dMsg; 
   200         sensor_msgs::PointCloud2 scan3dMsg; 
   203 void CommonDataSubscriber::depthOdomScan2dInfoCallback(
   204                 const nav_msgs::OdometryConstPtr & odomMsg,
   205                 const sensor_msgs::ImageConstPtr& imageMsg,
   206                 const sensor_msgs::ImageConstPtr& depthMsg,
   207                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   208                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   209                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   211         rtabmap_ros::UserDataConstPtr userDataMsg; 
   212         sensor_msgs::PointCloud2 scan3dMsg; 
   215 void CommonDataSubscriber::depthOdomScan3dInfoCallback(
   216                 const nav_msgs::OdometryConstPtr & odomMsg,
   217                 const sensor_msgs::ImageConstPtr& imageMsg,
   218                 const sensor_msgs::ImageConstPtr& depthMsg,
   219                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   220                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   221                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   223         rtabmap_ros::UserDataConstPtr userDataMsg; 
   224         sensor_msgs::LaserScan scan2dMsg; 
   227 void CommonDataSubscriber::depthOdomScanDescInfoCallback(
   228                 const nav_msgs::OdometryConstPtr & odomMsg,
   229                 const sensor_msgs::ImageConstPtr& imageMsg,
   230                 const sensor_msgs::ImageConstPtr& depthMsg,
   231                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   232                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   233                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   235         rtabmap_ros::UserDataConstPtr userDataMsg; 
   236         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   237         if(!scanMsg->global_descriptor.data.empty())
   239                 globalDescriptor.push_back(scanMsg->global_descriptor);
   244 #ifdef RTABMAP_SYNC_USER_DATA   246 void CommonDataSubscriber::depthDataCallback(
   247                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   248                 const sensor_msgs::ImageConstPtr& imageMsg,
   249                 const sensor_msgs::ImageConstPtr& depthMsg,
   250                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
   252         nav_msgs::OdometryConstPtr odomMsg; 
   253         sensor_msgs::LaserScan scanMsg; 
   254         sensor_msgs::PointCloud2 scan3dMsg; 
   255         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   258 void CommonDataSubscriber::depthDataScan2dCallback(
   259                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   260                 const sensor_msgs::ImageConstPtr& imageMsg,
   261                 const sensor_msgs::ImageConstPtr& depthMsg,
   262                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   263                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   265         nav_msgs::OdometryConstPtr odomMsg; 
   266         sensor_msgs::PointCloud2 scan3dMsg; 
   267         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   270 void CommonDataSubscriber::depthDataScan3dCallback(
   271                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   272                 const sensor_msgs::ImageConstPtr& imageMsg,
   273                 const sensor_msgs::ImageConstPtr& depthMsg,
   274                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   275                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   277         nav_msgs::OdometryConstPtr odomMsg; 
   278         sensor_msgs::LaserScan scan2dMsg; 
   279         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   282 void CommonDataSubscriber::depthDataScanDescCallback(
   283                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   284                 const sensor_msgs::ImageConstPtr& imageMsg,
   285                 const sensor_msgs::ImageConstPtr& depthMsg,
   286                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   287                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   289         nav_msgs::OdometryConstPtr odomMsg; 
   290         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   291         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   292         if(!scanMsg->global_descriptor.data.empty())
   294                 globalDescriptor.push_back(scanMsg->global_descriptor);
   298 void CommonDataSubscriber::depthDataInfoCallback(
   299                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   300                 const sensor_msgs::ImageConstPtr& imageMsg,
   301                 const sensor_msgs::ImageConstPtr& depthMsg,
   302                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   303                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   305         nav_msgs::OdometryConstPtr odomMsg; 
   306         sensor_msgs::LaserScan scan2dMsg; 
   307         sensor_msgs::PointCloud2 scan3dMsg; 
   310 void CommonDataSubscriber::depthDataScan2dInfoCallback(
   311                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   312                 const sensor_msgs::ImageConstPtr& imageMsg,
   313                 const sensor_msgs::ImageConstPtr& depthMsg,
   314                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   315                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   316                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   318         nav_msgs::OdometryConstPtr odomMsg; 
   319         sensor_msgs::PointCloud2 scan3dMsg; 
   322 void CommonDataSubscriber::depthDataScan3dInfoCallback(
   323                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   324                 const sensor_msgs::ImageConstPtr& imageMsg,
   325                 const sensor_msgs::ImageConstPtr& depthMsg,
   326                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   327                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   328                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   330         nav_msgs::OdometryConstPtr odomMsg; 
   331         sensor_msgs::LaserScan scan2dMsg; 
   334 void CommonDataSubscriber::depthDataScanDescInfoCallback(
   335                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   336                 const sensor_msgs::ImageConstPtr& imageMsg,
   337                 const sensor_msgs::ImageConstPtr& depthMsg,
   338                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   339                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   340                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   342         nav_msgs::OdometryConstPtr odomMsg; 
   343         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   344         if(!scanMsg->global_descriptor.data.empty())
   346                 globalDescriptor.push_back(scanMsg->global_descriptor);
   352 void CommonDataSubscriber::depthOdomDataCallback(
   353                 const nav_msgs::OdometryConstPtr & odomMsg,
   354                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   355                 const sensor_msgs::ImageConstPtr& imageMsg,
   356                 const sensor_msgs::ImageConstPtr& depthMsg,
   357                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
   359         sensor_msgs::LaserScan scanMsg; 
   360         sensor_msgs::PointCloud2 scan3dMsg; 
   361         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   364 void CommonDataSubscriber::depthOdomDataScan2dCallback(
   365                 const nav_msgs::OdometryConstPtr & odomMsg,
   366                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   367                 const sensor_msgs::ImageConstPtr& imageMsg,
   368                 const sensor_msgs::ImageConstPtr& depthMsg,
   369                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   370                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   372         sensor_msgs::PointCloud2 scan3dMsg; 
   373         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   376 void CommonDataSubscriber::depthOdomDataScan3dCallback(
   377                 const nav_msgs::OdometryConstPtr & odomMsg,
   378                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   379                 const sensor_msgs::ImageConstPtr& imageMsg,
   380                 const sensor_msgs::ImageConstPtr& depthMsg,
   381                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   382                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   384         sensor_msgs::LaserScan scan2dMsg; 
   385         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   388 void CommonDataSubscriber::depthOdomDataScanDescCallback(
   389                 const nav_msgs::OdometryConstPtr & odomMsg,
   390                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   391                 const sensor_msgs::ImageConstPtr& imageMsg,
   392                 const sensor_msgs::ImageConstPtr& depthMsg,
   393                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   394                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   396         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   397         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   398         if(!scanMsg->global_descriptor.data.empty())
   400                 globalDescriptor.push_back(scanMsg->global_descriptor);
   404 void CommonDataSubscriber::depthOdomDataInfoCallback(
   405                 const nav_msgs::OdometryConstPtr & odomMsg,
   406                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   407                 const sensor_msgs::ImageConstPtr& imageMsg,
   408                 const sensor_msgs::ImageConstPtr& depthMsg,
   409                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   410                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   412         sensor_msgs::LaserScan scan2dMsg; 
   413         sensor_msgs::PointCloud2 scan3dMsg; 
   416 void CommonDataSubscriber::depthOdomDataScan2dInfoCallback(
   417                 const nav_msgs::OdometryConstPtr & odomMsg,
   418                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   419                 const sensor_msgs::ImageConstPtr& imageMsg,
   420                 const sensor_msgs::ImageConstPtr& depthMsg,
   421                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   422                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   423                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   425         sensor_msgs::PointCloud2 scan3dMsg; 
   428 void CommonDataSubscriber::depthOdomDataScan3dInfoCallback(
   429                 const nav_msgs::OdometryConstPtr & odomMsg,
   430                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   431                 const sensor_msgs::ImageConstPtr& imageMsg,
   432                 const sensor_msgs::ImageConstPtr& depthMsg,
   433                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   434                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   435                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   437         sensor_msgs::LaserScan scan2dMsg; 
   440 void CommonDataSubscriber::depthOdomDataScanDescInfoCallback(
   441                 const nav_msgs::OdometryConstPtr & odomMsg,
   442                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   443                 const sensor_msgs::ImageConstPtr& imageMsg,
   444                 const sensor_msgs::ImageConstPtr& depthMsg,
   445                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   446                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   447                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   449         std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptor;
   450         if(!scanMsg->global_descriptor.data.empty())
   452                 globalDescriptor.push_back(scanMsg->global_descriptor);
   462                 bool subscribeUserData,
   463                 bool subscribeScan2d,
   464                 bool subscribeScan3d,
   465                 bool subscribeScanDesc,
   466                 bool subscribeOdomInfo,
   472         std::string rgbPrefix = 
"rgb";
   473         std::string depthPrefix = 
"depth";
   487 #ifdef RTABMAP_SYNC_USER_DATA   488         if(subscribeOdom && subscribeUserData)
   493                 if(subscribeScanDesc)
   497                         if(subscribeOdomInfo)
   501                                 SYNC_DECL7(
CommonDataSubscriber, depthOdomDataScanDescInfo, approxSync, queueSize, 
odomSub_, 
userDataSub_, 
imageSub_, 
imageDepthSub_, 
cameraInfoSub_, 
scanDescSub_, 
odomInfoSub_);
   508                 else if(subscribeScan2d)
   512                         if(subscribeOdomInfo)
   516                                 SYNC_DECL7(
CommonDataSubscriber, depthOdomDataScan2dInfo, approxSync, queueSize, 
odomSub_, 
userDataSub_, 
imageSub_, 
imageDepthSub_, 
cameraInfoSub_, 
scanSub_, 
odomInfoSub_);
   523                 else if(subscribeScan3d)
   527                         if(subscribeOdomInfo)
   531                                 SYNC_DECL7(
CommonDataSubscriber, depthOdomDataScan3dInfo, approxSync, queueSize, 
odomSub_, 
userDataSub_, 
imageSub_, 
imageDepthSub_, 
cameraInfoSub_, 
scan3dSub_, 
odomInfoSub_);
   538                 else if(subscribeOdomInfo)
   555                 if(subscribeScanDesc)
   559                         if(subscribeOdomInfo)
   570                 else if(subscribeScan2d)
   574                         if(subscribeOdomInfo)
   585                 else if(subscribeScan3d)
   589                         if(subscribeOdomInfo)
   600                 else if(subscribeOdomInfo)
   611 #ifdef RTABMAP_SYNC_USER_DATA   612         else if(subscribeUserData)
   616                 if(subscribeScanDesc)
   621                         if(subscribeOdomInfo)
   632                 else if(subscribeScan2d)
   637                         if(subscribeOdomInfo)
   648                 else if(subscribeScan3d)
   652                         if(subscribeOdomInfo)
   663                 else if(subscribeOdomInfo)
   677                 if(subscribeScanDesc)
   681                         if(subscribeOdomInfo)
   692                 else if(subscribeScan2d)
   696                         if(subscribeOdomInfo)
   707                 else if(subscribeScan3d)
   711                         if(subscribeOdomInfo)
   722                 else if(subscribeOdomInfo)
 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
message_filters::Subscriber< rtabmap_ros::UserData > userDataSub_
bool subscribedToOdomInfo_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
image_transport::SubscriberFilter imageDepthSub_
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
bool subscribedToScanDescriptor_
image_transport::SubscriberFilter imageSub_
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
std::string resolveName(const std::string &name, bool remap=true) const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
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)
#define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo, int queueSize, bool approxSync)
void commonSingleCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &imageMsg, const cv_bridge::CvImageConstPtr &depthMsg, const sensor_msgs::CameraInfo &rgbCameraInfoMsg, const sensor_msgs::CameraInfo &depthCameraInfoMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())