33                 const nav_msgs::OdometryConstPtr& odomMsg)
    36         rtabmap_ros::UserDataConstPtr userDataMsg; 
    37         sensor_msgs::PointCloud2ConstPtr scan3dMsg; 
    38         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    41 void CommonDataSubscriber::odomInfoCallback(
    42                 const nav_msgs::OdometryConstPtr& odomMsg,
    43                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    46         rtabmap_ros::UserDataConstPtr userDataMsg; 
    47         sensor_msgs::LaserScanConstPtr scan2dMsg; 
    50 #ifdef RTABMAP_SYNC_USER_DATA    51 void CommonDataSubscriber::odomDataCallback(
    52                 const nav_msgs::OdometryConstPtr& odomMsg,
    53                 const rtabmap_ros::UserDataConstPtr & userDataMsg)
    56         rtabmap_ros::OdomInfoConstPtr odomInfoMsg; 
    59 void CommonDataSubscriber::odomDataInfoCallback(
    60                 const nav_msgs::OdometryConstPtr& odomMsg,
    61                 const rtabmap_ros::UserDataConstPtr & userDataMsg,
    62                 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
    65         sensor_msgs::PointCloud2ConstPtr scan3dMsg; 
    73                 bool subscribeUserData,
    74                 bool subscribeOdomInfo,
    80         if(subscribeUserData || subscribeOdomInfo)
    84 #ifdef RTABMAP_SYNC_USER_DATA   101                 if(subscribeOdomInfo)
   112                                 uFormat(
"\n%s subscribed to:\n   %s",
 std::string uFormat(const char *fmt,...)
std::string getTopic() const
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_
void setupOdomCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeUserData, bool subscribeOdomInfo, int queueSize, bool approxSync)
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
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)
std::string subscribedTopicsMsg_
ros::Subscriber odomSubOnly_
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
void odomCallback(const nav_msgs::OdometryConstPtr &)