38 const rtabmap_msgs::SensorDataConstPtr& imagesMsg)
40 nav_msgs::OdometryConstPtr odomMsg;
41 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
44 void CommonDataSubscriber::sensorDataInfoCallback(
45 const rtabmap_msgs::SensorDataConstPtr& imagesMsg,
46 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
48 nav_msgs::OdometryConstPtr odomMsg;
52 void CommonDataSubscriber::sensorDataOdomCallback(
53 const nav_msgs::OdometryConstPtr & odomMsg,
54 const rtabmap_msgs::SensorDataConstPtr& imagesMsg)
56 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
59 void CommonDataSubscriber::sensorDataOdomInfoCallback(
60 const nav_msgs::OdometryConstPtr & odomMsg,
61 const rtabmap_msgs::SensorDataConstPtr& imagesMsg,
62 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
71 bool subscribeOdomInfo)
73 ROS_INFO(
"Setup SensorData callback");
104 uFormat(
"\n%s subscribed to:\n %s",