36 #define IMAGE_CONVERSION() \ 38 std::vector<cv_bridge::CvImageConstPtr> imageMsgs(5); \ 39 std::vector<cv_bridge::CvImageConstPtr> depthMsgs(5); \ 40 rtabmap_ros::toCvShare(image1Msg, imageMsgs[0], depthMsgs[0]); \ 41 rtabmap_ros::toCvShare(image2Msg, imageMsgs[1], depthMsgs[1]); \ 42 rtabmap_ros::toCvShare(image3Msg, imageMsgs[2], depthMsgs[2]); \ 43 rtabmap_ros::toCvShare(image4Msg, imageMsgs[3], depthMsgs[3]); \ 44 rtabmap_ros::toCvShare(image5Msg, imageMsgs[4], depthMsgs[4]); \ 45 if(!depthMsgs[0].get()) \ 47 std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \ 48 cameraInfoMsgs.push_back(image1Msg->rgb_camera_info); \ 49 cameraInfoMsgs.push_back(image2Msg->rgb_camera_info); \ 50 cameraInfoMsgs.push_back(image3Msg->rgb_camera_info); \ 51 cameraInfoMsgs.push_back(image4Msg->rgb_camera_info); \ 52 cameraInfoMsgs.push_back(image5Msg->rgb_camera_info); \ 53 std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptorMsgs; \ 54 std::vector<std::vector<rtabmap_ros::KeyPoint> > localKeyPoints; \ 55 std::vector<std::vector<rtabmap_ros::Point3f> > localPoints3d; \ 56 std::vector<cv::Mat> localDescriptors; \ 57 if(!image1Msg->global_descriptor.data.empty()) \ 58 globalDescriptorMsgs.push_back(image1Msg->global_descriptor); \ 59 if(!image2Msg->global_descriptor.data.empty()) \ 60 globalDescriptorMsgs.push_back(image2Msg->global_descriptor); \ 61 if(!image3Msg->global_descriptor.data.empty()) \ 62 globalDescriptorMsgs.push_back(image3Msg->global_descriptor); \ 63 if(!image4Msg->global_descriptor.data.empty()) \ 64 globalDescriptorMsgs.push_back(image4Msg->global_descriptor); \ 65 if(!image5Msg->global_descriptor.data.empty()) \ 66 globalDescriptorMsgs.push_back(image5Msg->global_descriptor); \ 67 localKeyPoints.push_back(image1Msg->key_points); \ 68 localKeyPoints.push_back(image2Msg->key_points); \ 69 localKeyPoints.push_back(image3Msg->key_points); \ 70 localKeyPoints.push_back(image4Msg->key_points); \ 71 localKeyPoints.push_back(image5Msg->key_points); \ 72 localPoints3d.push_back(image1Msg->points); \ 73 localPoints3d.push_back(image2Msg->points); \ 74 localPoints3d.push_back(image3Msg->points); \ 75 localPoints3d.push_back(image4Msg->points); \ 76 localPoints3d.push_back(image5Msg->points); \ 77 localDescriptors.push_back(rtabmap::uncompressData(image1Msg->descriptors)); \ 78 localDescriptors.push_back(rtabmap::uncompressData(image2Msg->descriptors)); \ 79 localDescriptors.push_back(rtabmap::uncompressData(image3Msg->descriptors)); \ 80 localDescriptors.push_back(rtabmap::uncompressData(image4Msg->descriptors)); \ 81 localDescriptors.push_back(rtabmap::uncompressData(image5Msg->descriptors)); 84 void CommonDataSubscriber::rgbd5Callback(
85 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
86 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
87 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
88 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
89 const rtabmap_ros::RGBDImageConstPtr& image5Msg)
93 nav_msgs::OdometryConstPtr odomMsg;
94 rtabmap_ros::UserDataConstPtr userDataMsg;
95 sensor_msgs::LaserScan scanMsg;
96 sensor_msgs::PointCloud2 scan3dMsg;
97 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
98 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
100 void CommonDataSubscriber::rgbd5Scan2dCallback(
101 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
102 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
103 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
104 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
105 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
106 const sensor_msgs::LaserScanConstPtr& scanMsg)
110 nav_msgs::OdometryConstPtr odomMsg;
111 rtabmap_ros::UserDataConstPtr userDataMsg;
112 sensor_msgs::PointCloud2 scan3dMsg;
113 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
114 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
116 void CommonDataSubscriber::rgbd5Scan3dCallback(
117 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
118 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
119 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
120 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
121 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
122 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
126 nav_msgs::OdometryConstPtr odomMsg;
127 rtabmap_ros::UserDataConstPtr userDataMsg;
128 sensor_msgs::LaserScan scanMsg;
129 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
130 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
132 void CommonDataSubscriber::rgbd5ScanDescCallback(
133 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
134 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
135 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
136 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
137 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
138 const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
142 nav_msgs::OdometryConstPtr odomMsg;
143 rtabmap_ros::UserDataConstPtr userDataMsg;
144 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
145 if(!scanDescMsg->global_descriptor.data.empty())
147 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
149 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
151 void CommonDataSubscriber::rgbd5InfoCallback(
152 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
153 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
154 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
155 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
156 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
157 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
161 nav_msgs::OdometryConstPtr odomMsg;
162 rtabmap_ros::UserDataConstPtr userDataMsg;
163 sensor_msgs::LaserScan scanMsg;
164 sensor_msgs::PointCloud2 scan3dMsg;
165 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
169 void CommonDataSubscriber::rgbd5OdomCallback(
170 const nav_msgs::OdometryConstPtr & odomMsg,
171 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
172 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
173 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
174 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
175 const rtabmap_ros::RGBDImageConstPtr& image5Msg)
179 rtabmap_ros::UserDataConstPtr userDataMsg;
180 sensor_msgs::LaserScan scanMsg;
181 sensor_msgs::PointCloud2 scan3dMsg;
182 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
183 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
185 void CommonDataSubscriber::rgbd5OdomScan2dCallback(
186 const nav_msgs::OdometryConstPtr & odomMsg,
187 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
188 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
189 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
190 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
191 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
192 const sensor_msgs::LaserScanConstPtr& scanMsg)
196 rtabmap_ros::UserDataConstPtr userDataMsg;
197 sensor_msgs::PointCloud2 scan3dMsg;
198 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
199 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
201 void CommonDataSubscriber::rgbd5OdomScan3dCallback(
202 const nav_msgs::OdometryConstPtr & odomMsg,
203 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
204 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
205 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
206 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
207 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
208 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
212 rtabmap_ros::UserDataConstPtr userDataMsg;
213 sensor_msgs::LaserScan scanMsg;
214 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
215 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
217 void CommonDataSubscriber::rgbd5OdomScanDescCallback(
218 const nav_msgs::OdometryConstPtr & odomMsg,
219 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
220 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
221 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
222 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
223 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
224 const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
228 rtabmap_ros::UserDataConstPtr userDataMsg;
229 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
230 if(!scanDescMsg->global_descriptor.data.empty())
232 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
234 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
236 void CommonDataSubscriber::rgbd5OdomInfoCallback(
237 const nav_msgs::OdometryConstPtr & odomMsg,
238 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
239 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
240 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
241 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
242 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
243 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
247 rtabmap_ros::UserDataConstPtr userDataMsg;
248 sensor_msgs::LaserScan scanMsg;
249 sensor_msgs::PointCloud2 scan3dMsg;
250 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
253 void CommonDataSubscriber::setupRGBD5Callbacks(
257 bool subscribeUserData,
258 bool subscribeScan2d,
259 bool subscribeScan3d,
260 bool subscribeScanDesc,
261 bool subscribeOdomInfo,
268 for(
int i=0; i<5; ++i)
276 if(subscribeScanDesc)
280 if(subscribeOdomInfo)
283 ROS_WARN(
"subscribe_odom_info ignored...");
287 else if(subscribeScan2d)
291 if(subscribeOdomInfo)
294 ROS_WARN(
"subscribe_odom_info ignored...");
298 else if(subscribeScan3d)
302 if(subscribeOdomInfo)
305 ROS_WARN(
"subscribe_odom_info ignored...");
309 else if(subscribeOdomInfo)
322 if(subscribeScanDesc)
326 if(subscribeOdomInfo)
329 ROS_WARN(
"subscribe_odom_info ignored...");
333 else if(subscribeScan2d)
337 if(subscribeOdomInfo)
340 ROS_WARN(
"subscribe_odom_info ignored...");
344 else if(subscribeScan3d)
348 if(subscribeOdomInfo)
351 ROS_WARN(
"subscribe_odom_info ignored...");
355 else if(subscribeOdomInfo)
std::string uFormat(const char *fmt,...)
#define SYNC_DECL7(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
#define SYNC_DECL5(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
virtual void commonDepthCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, 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< std::vector< rtabmap_ros::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_ros::KeyPoint > >(), const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_ros::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())=0
bool subscribedToOdomInfo_
#define SYNC_DECL6(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
#define IMAGE_CONVERSION()
bool subscribedToScanDescriptor_
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
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)
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_