33 void CommonDataSubscriber::stereoCallback(
34 const sensor_msgs::ImageConstPtr& leftImageMsg,
35 const sensor_msgs::ImageConstPtr& rightImageMsg,
36 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
37 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
39 nav_msgs::OdometryConstPtr odomMsg;
40 rtabmap_msgs::UserDataConstPtr userDataMsg;
41 sensor_msgs::LaserScan scanMsg;
42 sensor_msgs::PointCloud2 scan3dMsg;
43 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
46 void CommonDataSubscriber::stereoInfoCallback(
47 const sensor_msgs::ImageConstPtr& leftImageMsg,
48 const sensor_msgs::ImageConstPtr& rightImageMsg,
49 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
50 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
51 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
53 nav_msgs::OdometryConstPtr odomMsg;
54 rtabmap_msgs::UserDataConstPtr userDataMsg;
55 sensor_msgs::LaserScan scan2dMsg;
56 sensor_msgs::PointCloud2 scan3dMsg;
61 void CommonDataSubscriber::stereoOdomCallback(
62 const nav_msgs::OdometryConstPtr & odomMsg,
63 const sensor_msgs::ImageConstPtr& leftImageMsg,
64 const sensor_msgs::ImageConstPtr& rightImageMsg,
65 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
66 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
68 rtabmap_msgs::UserDataConstPtr userDataMsg;
69 sensor_msgs::LaserScan scanMsg;
70 sensor_msgs::PointCloud2 scan3dMsg;
71 rtabmap_msgs::OdomInfoConstPtr odomInfoMsg;
74 void CommonDataSubscriber::stereoOdomInfoCallback(
75 const nav_msgs::OdometryConstPtr & odomMsg,
76 const sensor_msgs::ImageConstPtr& leftImageMsg,
77 const sensor_msgs::ImageConstPtr& rightImageMsg,
78 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
79 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
80 const rtabmap_msgs::OdomInfoConstPtr & odomInfoMsg)
82 rtabmap_msgs::UserDataConstPtr userDataMsg;
83 sensor_msgs::LaserScan scan2dMsg;
84 sensor_msgs::PointCloud2 scan3dMsg;
92 bool subscribeOdomInfo)
114 if(subscribeOdomInfo)
127 if(subscribeOdomInfo)