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<sensor_msgs::CameraInfo> depthCameraInfoMsgs; \ 54 depthCameraInfoMsgs.push_back(image1Msg->depth_camera_info); \ 55 depthCameraInfoMsgs.push_back(image2Msg->depth_camera_info); \ 56 depthCameraInfoMsgs.push_back(image3Msg->depth_camera_info); \ 57 depthCameraInfoMsgs.push_back(image4Msg->depth_camera_info); \ 58 depthCameraInfoMsgs.push_back(image5Msg->depth_camera_info); \ 59 std::vector<rtabmap_ros::GlobalDescriptor> globalDescriptorMsgs; \ 60 std::vector<std::vector<rtabmap_ros::KeyPoint> > localKeyPoints; \ 61 std::vector<std::vector<rtabmap_ros::Point3f> > localPoints3d; \ 62 std::vector<cv::Mat> localDescriptors; \ 63 if(!image1Msg->global_descriptor.data.empty()) \ 64 globalDescriptorMsgs.push_back(image1Msg->global_descriptor); \ 65 if(!image2Msg->global_descriptor.data.empty()) \ 66 globalDescriptorMsgs.push_back(image2Msg->global_descriptor); \ 67 if(!image3Msg->global_descriptor.data.empty()) \ 68 globalDescriptorMsgs.push_back(image3Msg->global_descriptor); \ 69 if(!image4Msg->global_descriptor.data.empty()) \ 70 globalDescriptorMsgs.push_back(image4Msg->global_descriptor); \ 71 if(!image5Msg->global_descriptor.data.empty()) \ 72 globalDescriptorMsgs.push_back(image5Msg->global_descriptor); \ 73 localKeyPoints.push_back(image1Msg->key_points); \ 74 localKeyPoints.push_back(image2Msg->key_points); \ 75 localKeyPoints.push_back(image3Msg->key_points); \ 76 localKeyPoints.push_back(image4Msg->key_points); \ 77 localKeyPoints.push_back(image5Msg->key_points); \ 78 localPoints3d.push_back(image1Msg->points); \ 79 localPoints3d.push_back(image2Msg->points); \ 80 localPoints3d.push_back(image3Msg->points); \ 81 localPoints3d.push_back(image4Msg->points); \ 82 localPoints3d.push_back(image5Msg->points); \ 83 localDescriptors.push_back(rtabmap::uncompressData(image1Msg->descriptors)); \ 84 localDescriptors.push_back(rtabmap::uncompressData(image2Msg->descriptors)); \ 85 localDescriptors.push_back(rtabmap::uncompressData(image3Msg->descriptors)); \ 86 localDescriptors.push_back(rtabmap::uncompressData(image4Msg->descriptors)); \ 87 localDescriptors.push_back(rtabmap::uncompressData(image5Msg->descriptors)); 90 void CommonDataSubscriber::rgbd5Callback(
91 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
92 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
93 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
94 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
95 const rtabmap_ros::RGBDImageConstPtr& image5Msg)
99 nav_msgs::OdometryConstPtr odomMsg;
100 rtabmap_ros::UserDataConstPtr userDataMsg;
101 sensor_msgs::LaserScan scanMsg;
102 sensor_msgs::PointCloud2 scan3dMsg;
103 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
104 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
106 void CommonDataSubscriber::rgbd5Scan2dCallback(
107 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
108 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
109 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
110 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
111 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
112 const sensor_msgs::LaserScanConstPtr& scanMsg)
116 nav_msgs::OdometryConstPtr odomMsg;
117 rtabmap_ros::UserDataConstPtr userDataMsg;
118 sensor_msgs::PointCloud2 scan3dMsg;
119 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
120 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
122 void CommonDataSubscriber::rgbd5Scan3dCallback(
123 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
124 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
125 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
126 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
127 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
128 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
132 nav_msgs::OdometryConstPtr odomMsg;
133 rtabmap_ros::UserDataConstPtr userDataMsg;
134 sensor_msgs::LaserScan scanMsg;
135 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
136 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
138 void CommonDataSubscriber::rgbd5ScanDescCallback(
139 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
140 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
141 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
142 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
143 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
144 const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
148 nav_msgs::OdometryConstPtr odomMsg;
149 rtabmap_ros::UserDataConstPtr userDataMsg;
150 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
151 if(!scanDescMsg->global_descriptor.data.empty())
153 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
155 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
157 void CommonDataSubscriber::rgbd5InfoCallback(
158 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
159 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
160 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
161 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
162 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
163 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
167 nav_msgs::OdometryConstPtr odomMsg;
168 rtabmap_ros::UserDataConstPtr userDataMsg;
169 sensor_msgs::LaserScan scanMsg;
170 sensor_msgs::PointCloud2 scan3dMsg;
171 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
175 void CommonDataSubscriber::rgbd5OdomCallback(
176 const nav_msgs::OdometryConstPtr & odomMsg,
177 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
178 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
179 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
180 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
181 const rtabmap_ros::RGBDImageConstPtr& image5Msg)
185 rtabmap_ros::UserDataConstPtr userDataMsg;
186 sensor_msgs::LaserScan scanMsg;
187 sensor_msgs::PointCloud2 scan3dMsg;
188 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
189 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
191 void CommonDataSubscriber::rgbd5OdomScan2dCallback(
192 const nav_msgs::OdometryConstPtr & odomMsg,
193 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
194 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
195 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
196 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
197 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
198 const sensor_msgs::LaserScanConstPtr& scanMsg)
202 rtabmap_ros::UserDataConstPtr userDataMsg;
203 sensor_msgs::PointCloud2 scan3dMsg;
204 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
205 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, *scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
207 void CommonDataSubscriber::rgbd5OdomScan3dCallback(
208 const nav_msgs::OdometryConstPtr & odomMsg,
209 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
210 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
211 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
212 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
213 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
214 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg)
218 rtabmap_ros::UserDataConstPtr userDataMsg;
219 sensor_msgs::LaserScan scanMsg;
220 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
221 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, *scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
223 void CommonDataSubscriber::rgbd5OdomScanDescCallback(
224 const nav_msgs::OdometryConstPtr & odomMsg,
225 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
226 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
227 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
228 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
229 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
230 const rtabmap_ros::ScanDescriptorConstPtr& scanDescMsg)
234 rtabmap_ros::UserDataConstPtr userDataMsg;
235 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
236 if(!scanDescMsg->global_descriptor.data.empty())
238 globalDescriptorMsgs.push_back(scanDescMsg->global_descriptor);
240 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanDescMsg->scan, scanDescMsg->scan_cloud, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
242 void CommonDataSubscriber::rgbd5OdomInfoCallback(
243 const nav_msgs::OdometryConstPtr & odomMsg,
244 const rtabmap_ros::RGBDImageConstPtr& image1Msg,
245 const rtabmap_ros::RGBDImageConstPtr& image2Msg,
246 const rtabmap_ros::RGBDImageConstPtr& image3Msg,
247 const rtabmap_ros::RGBDImageConstPtr& image4Msg,
248 const rtabmap_ros::RGBDImageConstPtr& image5Msg,
249 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
253 rtabmap_ros::UserDataConstPtr userDataMsg;
254 sensor_msgs::LaserScan scanMsg;
255 sensor_msgs::PointCloud2 scan3dMsg;
256 commonMultiCameraCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, depthCameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg, globalDescriptorMsgs, localKeyPoints, localPoints3d, localDescriptors);
259 void CommonDataSubscriber::setupRGBD5Callbacks(
263 bool subscribeUserData,
264 bool subscribeScan2d,
265 bool subscribeScan3d,
266 bool subscribeScanDesc,
267 bool subscribeOdomInfo,
274 for(
int i=0; i<5; ++i)
282 if(subscribeScanDesc)
286 if(subscribeOdomInfo)
289 ROS_WARN(
"subscribe_odom_info ignored...");
291 SYNC_DECL7(
CommonDataSubscriber, rgbd5OdomScanDesc, approxSync, queueSize,
odomSub_, (*
rgbdSubs_[0]), (*
rgbdSubs_[1]), (*
rgbdSubs_[2]), (*
rgbdSubs_[3]), (*
rgbdSubs_[4]),
scanDescSub_);
293 else if(subscribeScan2d)
297 if(subscribeOdomInfo)
300 ROS_WARN(
"subscribe_odom_info ignored...");
302 SYNC_DECL7(
CommonDataSubscriber, rgbd5OdomScan2d, approxSync, queueSize,
odomSub_, (*
rgbdSubs_[0]), (*
rgbdSubs_[1]), (*
rgbdSubs_[2]), (*
rgbdSubs_[3]), (*
rgbdSubs_[4]),
scanSub_);
304 else if(subscribeScan3d)
308 if(subscribeOdomInfo)
311 ROS_WARN(
"subscribe_odom_info ignored...");
313 SYNC_DECL7(
CommonDataSubscriber, rgbd5OdomScan3d, approxSync, queueSize,
odomSub_, (*
rgbdSubs_[0]), (*
rgbdSubs_[1]), (*
rgbdSubs_[2]), (*
rgbdSubs_[3]), (*
rgbdSubs_[4]),
scan3dSub_);
315 else if(subscribeOdomInfo)
319 SYNC_DECL7(
CommonDataSubscriber, rgbd5OdomInfo, approxSync, queueSize,
odomSub_, (*
rgbdSubs_[0]), (*
rgbdSubs_[1]), (*
rgbdSubs_[2]), (*
rgbdSubs_[3]), (*
rgbdSubs_[4]),
odomInfoSub_);
328 if(subscribeScanDesc)
332 if(subscribeOdomInfo)
335 ROS_WARN(
"subscribe_odom_info ignored...");
339 else if(subscribeScan2d)
343 if(subscribeOdomInfo)
346 ROS_WARN(
"subscribe_odom_info ignored...");
350 else if(subscribeScan3d)
354 if(subscribeOdomInfo)
357 ROS_WARN(
"subscribe_odom_info ignored...");
361 else if(subscribeOdomInfo)
CommonDataSubscriber(bool gui)
std::string uFormat(const char *fmt,...)
bool subscribedToOdomInfo_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
#define IMAGE_CONVERSION()
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
bool subscribedToScanDescriptor_
message_filters::Subscriber< sensor_msgs::LaserScan > scanSub_
message_filters::Subscriber< rtabmap_ros::ScanDescriptor > scanDescSub_
virtual void commonMultiCameraCallback(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 std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, 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
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
#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)
#define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_