33 void CommonDataSubscriber::rgbCallback(
    34                 const sensor_msgs::ImageConstPtr& imageMsg,
    35                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
    37         rtabmap_ros::UserDataConstPtr userDataMsg; 
    38         nav_msgs::OdometryConstPtr odomMsg; 
    39         sensor_msgs::LaserScan scanMsg; 
    40         sensor_msgs::PointCloud2 scan3dMsg; 
    41         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    45 void CommonDataSubscriber::rgbScan2dCallback(
    46                 const sensor_msgs::ImageConstPtr& imageMsg,
    47                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    48                 const sensor_msgs::LaserScanConstPtr& scanMsg)
    50         rtabmap_ros::UserDataConstPtr userDataMsg; 
    51         nav_msgs::OdometryConstPtr odomMsg; 
    52         sensor_msgs::PointCloud2 scan3dMsg; 
    53         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    57 void CommonDataSubscriber::rgbScan3dCallback(
    58                 const sensor_msgs::ImageConstPtr& imageMsg,
    59                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    60                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
    62         rtabmap_ros::UserDataConstPtr userDataMsg; 
    63         nav_msgs::OdometryConstPtr odomMsg; 
    64         sensor_msgs::LaserScan scan2dMsg; 
    65         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    69 void CommonDataSubscriber::rgbScanDescCallback(
    70                 const sensor_msgs::ImageConstPtr& imageMsg,
    71                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    72                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
    74         rtabmap_ros::UserDataConstPtr userDataMsg; 
    75         nav_msgs::OdometryConstPtr odomMsg; 
    76         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::rgbInfoCallback(
    86                 const sensor_msgs::ImageConstPtr& imageMsg,
    87                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
    88                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    90         rtabmap_ros::UserDataConstPtr userDataMsg; 
    91         nav_msgs::OdometryConstPtr odomMsg; 
    92         sensor_msgs::LaserScan scan2dMsg; 
    93         sensor_msgs::PointCloud2 scan3dMsg; 
    97 void CommonDataSubscriber::rgbScan2dInfoCallback(
    98                 const sensor_msgs::ImageConstPtr& imageMsg,
    99                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   100                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   101                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   103         rtabmap_ros::UserDataConstPtr userDataMsg; 
   104         nav_msgs::OdometryConstPtr odomMsg; 
   105         sensor_msgs::PointCloud2 scan3dMsg; 
   109 void CommonDataSubscriber::rgbScan3dInfoCallback(
   110                 const sensor_msgs::ImageConstPtr& imageMsg,
   111                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   112                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   113                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   115         rtabmap_ros::UserDataConstPtr userDataMsg; 
   116         nav_msgs::OdometryConstPtr odomMsg; 
   117         sensor_msgs::LaserScan scan2dMsg; 
   121 void CommonDataSubscriber::rgbScanDescInfoCallback(
   122                 const sensor_msgs::ImageConstPtr& imageMsg,
   123                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   124                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   125                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   127         rtabmap_ros::UserDataConstPtr userDataMsg; 
   128         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::rgbOdomCallback(
   140                 const nav_msgs::OdometryConstPtr & odomMsg,
   141                 const sensor_msgs::ImageConstPtr& imageMsg,
   142                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
   144         rtabmap_ros::UserDataConstPtr userDataMsg; 
   145         sensor_msgs::LaserScan scanMsg; 
   146         sensor_msgs::PointCloud2 scan3dMsg; 
   147         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   151 void CommonDataSubscriber::rgbOdomScan2dCallback(
   152                 const nav_msgs::OdometryConstPtr & odomMsg,
   153                 const sensor_msgs::ImageConstPtr& imageMsg,
   154                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   155                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   157         rtabmap_ros::UserDataConstPtr userDataMsg; 
   158         sensor_msgs::PointCloud2 scan3dMsg; 
   159         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   163 void CommonDataSubscriber::rgbOdomScan3dCallback(
   164                 const nav_msgs::OdometryConstPtr & odomMsg,
   165                 const sensor_msgs::ImageConstPtr& imageMsg,
   166                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   167                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   169         rtabmap_ros::UserDataConstPtr userDataMsg; 
   170         sensor_msgs::LaserScan scan2dMsg; 
   171         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   175 void CommonDataSubscriber::rgbOdomScanDescCallback(
   176                 const nav_msgs::OdometryConstPtr & odomMsg,
   177                 const sensor_msgs::ImageConstPtr& imageMsg,
   178                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   179                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   181         rtabmap_ros::UserDataConstPtr userDataMsg; 
   182         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::rgbOdomInfoCallback(
   192                 const nav_msgs::OdometryConstPtr & odomMsg,
   193                 const sensor_msgs::ImageConstPtr& imageMsg,
   194                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   195                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   197         rtabmap_ros::UserDataConstPtr userDataMsg; 
   198         sensor_msgs::LaserScan scan2dMsg; 
   199         sensor_msgs::PointCloud2 scan3dMsg; 
   203 void CommonDataSubscriber::rgbOdomScan2dInfoCallback(
   204                 const nav_msgs::OdometryConstPtr & odomMsg,
   205                 const sensor_msgs::ImageConstPtr& imageMsg,
   206                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   207                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   208                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   210         rtabmap_ros::UserDataConstPtr userDataMsg; 
   211         sensor_msgs::PointCloud2 scan3dMsg; 
   215 void CommonDataSubscriber::rgbOdomScan3dInfoCallback(
   216                 const nav_msgs::OdometryConstPtr & odomMsg,
   217                 const sensor_msgs::ImageConstPtr& imageMsg,
   218                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   219                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   220                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   222         rtabmap_ros::UserDataConstPtr userDataMsg; 
   223         sensor_msgs::LaserScan scan2dMsg; 
   227 void CommonDataSubscriber::rgbOdomScanDescInfoCallback(
   228                 const nav_msgs::OdometryConstPtr & odomMsg,
   229                 const sensor_msgs::ImageConstPtr& imageMsg,
   230                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   231                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   232                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   234         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::rgbDataCallback(
   247                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   248                 const sensor_msgs::ImageConstPtr& imageMsg,
   249                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
   251         nav_msgs::OdometryConstPtr odomMsg; 
   252         sensor_msgs::LaserScan scanMsg; 
   253         sensor_msgs::PointCloud2 scan3dMsg; 
   254         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   258 void CommonDataSubscriber::rgbDataScan2dCallback(
   259                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   260                 const sensor_msgs::ImageConstPtr& imageMsg,
   261                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   262                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   264         nav_msgs::OdometryConstPtr odomMsg; 
   265         sensor_msgs::PointCloud2 scan3dMsg; 
   266         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   270 void CommonDataSubscriber::rgbDataScan3dCallback(
   271                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   272                 const sensor_msgs::ImageConstPtr& imageMsg,
   273                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   274                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   276         nav_msgs::OdometryConstPtr odomMsg; 
   277         sensor_msgs::LaserScan scan2dMsg; 
   278         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   282 void CommonDataSubscriber::rgbDataScanDescCallback(
   283                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   284                 const sensor_msgs::ImageConstPtr& imageMsg,
   285                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   286                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   288         nav_msgs::OdometryConstPtr odomMsg; 
   289         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::rgbDataInfoCallback(
   299                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   300                 const sensor_msgs::ImageConstPtr& imageMsg,
   301                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   302                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   304         nav_msgs::OdometryConstPtr odomMsg; 
   305         sensor_msgs::LaserScan scan2dMsg; 
   306         sensor_msgs::PointCloud2 scan3dMsg; 
   310 void CommonDataSubscriber::rgbDataScan2dInfoCallback(
   311                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   312                 const sensor_msgs::ImageConstPtr& imageMsg,
   313                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   314                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   315                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   317         nav_msgs::OdometryConstPtr odomMsg; 
   318         sensor_msgs::PointCloud2 scan3dMsg; 
   322 void CommonDataSubscriber::rgbDataScan3dInfoCallback(
   323                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   324                 const sensor_msgs::ImageConstPtr& imageMsg,
   325                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   326                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   327                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   329         nav_msgs::OdometryConstPtr odomMsg; 
   330         sensor_msgs::LaserScan scan2dMsg; 
   334 void CommonDataSubscriber::rgbDataScanDescInfoCallback(
   335                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   336                 const sensor_msgs::ImageConstPtr& imageMsg,
   337                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   338                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   339                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   341         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::rgbOdomDataCallback(
   353                 const nav_msgs::OdometryConstPtr & odomMsg,
   354                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   355                 const sensor_msgs::ImageConstPtr& imageMsg,
   356                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg)
   358         sensor_msgs::LaserScan scanMsg; 
   359         sensor_msgs::PointCloud2 scan3dMsg; 
   360         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   364 void CommonDataSubscriber::rgbOdomDataScan2dCallback(
   365                 const nav_msgs::OdometryConstPtr & odomMsg,
   366                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   367                 const sensor_msgs::ImageConstPtr& imageMsg,
   368                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   369                 const sensor_msgs::LaserScanConstPtr& scanMsg)
   371         sensor_msgs::PointCloud2 scan3dMsg; 
   372         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   376 void CommonDataSubscriber::rgbOdomDataScan3dCallback(
   377                 const nav_msgs::OdometryConstPtr & odomMsg,
   378                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   379                 const sensor_msgs::ImageConstPtr& imageMsg,
   380                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   381                 const sensor_msgs::PointCloud2ConstPtr& scanMsg)
   383         sensor_msgs::LaserScan scan2dMsg; 
   384         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
   388 void CommonDataSubscriber::rgbOdomDataScanDescCallback(
   389                 const nav_msgs::OdometryConstPtr & odomMsg,
   390                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   391                 const sensor_msgs::ImageConstPtr& imageMsg,
   392                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   393                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg)
   395         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::rgbOdomDataInfoCallback(
   405                 const nav_msgs::OdometryConstPtr & odomMsg,
   406                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   407                 const sensor_msgs::ImageConstPtr& imageMsg,
   408                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   409                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   411         sensor_msgs::LaserScan scan2dMsg; 
   412         sensor_msgs::PointCloud2 scan3dMsg; 
   416 void CommonDataSubscriber::rgbOdomDataScan2dInfoCallback(
   417                 const nav_msgs::OdometryConstPtr & odomMsg,
   418                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   419                 const sensor_msgs::ImageConstPtr& imageMsg,
   420                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   421                 const sensor_msgs::LaserScanConstPtr& scanMsg,
   422                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   424         sensor_msgs::PointCloud2 scan3dMsg; 
   428 void CommonDataSubscriber::rgbOdomDataScan3dInfoCallback(
   429                 const nav_msgs::OdometryConstPtr & odomMsg,
   430                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   431                 const sensor_msgs::ImageConstPtr& imageMsg,
   432                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   433                 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
   434                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
   436         sensor_msgs::LaserScan scan2dMsg; 
   440 void CommonDataSubscriber::rgbOdomDataScanDescInfoCallback(
   441                 const nav_msgs::OdometryConstPtr & odomMsg,
   442                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
   443                 const sensor_msgs::ImageConstPtr& imageMsg,
   444                 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
   445                 const rtabmap_ros::ScanDescriptorConstPtr& scanMsg,
   446                 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,
   470         ROS_INFO(
"Setup rgb-only callback");
   472         std::string rgbPrefix = 
"rgb";
   481 #ifdef RTABMAP_SYNC_USER_DATA   482         if(subscribeOdom && subscribeUserData)
   487                 if(subscribeScanDesc)
   491                         if(subscribeOdomInfo)
   502                 else if(subscribeScan2d)
   506                         if(subscribeOdomInfo)
   517                 else if(subscribeScan3d)
   521                         if(subscribeOdomInfo)
   532                 else if(subscribeOdomInfo)
   549                 if(subscribeScanDesc)
   553                         if(subscribeOdomInfo)
   564                 else if(subscribeScan2d)
   568                         if(subscribeOdomInfo)
   579                 else if(subscribeScan3d)
   583                         if(subscribeOdomInfo)
   594                 else if(subscribeOdomInfo)
   605 #ifdef RTABMAP_SYNC_USER_DATA   606         else if(subscribeUserData)
   610                 if(subscribeScanDesc)
   615                         if(subscribeOdomInfo)
   626                 else if(subscribeScan2d)
   631                         if(subscribeOdomInfo)
   642                 else if(subscribeScan3d)
   646                         if(subscribeOdomInfo)
   657                 else if(subscribeOdomInfo)
   671                 if(subscribeScanDesc)
   675                         if(subscribeOdomInfo)
   686                 else if(subscribeScan2d)
   690                         if(subscribeOdomInfo)
   701                 else if(subscribeScan3d)
   705                         if(subscribeOdomInfo)
   716                 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_
void setupRGBCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeScanDesc, bool subscribeOdomInfo, int queueSize, bool approxSync)
#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)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
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())