00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef GUIWRAPPER_H_
00029 #define GUIWRAPPER_H_
00030
00031 #include <ros/ros.h>
00032 #include "rtabmap_ros/Info.h"
00033 #include "rtabmap_ros/MapData.h"
00034 #include "rtabmap_ros/OdomInfo.h"
00035 #include "rtabmap_ros/Goal.h"
00036 #include "rtabmap/utilite/UEventsHandler.h"
00037 #include "rtabmap/core/Transform.h"
00038
00039 #include <tf/transform_listener.h>
00040
00041 #include <geometry_msgs/TwistStamped.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <sensor_msgs/Image.h>
00044 #include <sensor_msgs/CameraInfo.h>
00045 #include <sensor_msgs/LaserScan.h>
00046 #include <nav_msgs/Odometry.h>
00047 #include <nav_msgs/Path.h>
00048 #include <std_msgs/Bool.h>
00049
00050 #include <message_filters/subscriber.h>
00051 #include <message_filters/synchronizer.h>
00052 #include <message_filters/sync_policies/approximate_time.h>
00053 #include <message_filters/sync_policies/exact_time.h>
00054
00055 #include <image_transport/image_transport.h>
00056 #include <image_transport/subscriber_filter.h>
00057
00058 namespace rtabmap
00059 {
00060 class MainWindow;
00061 }
00062
00063 class QApplication;
00064
00065 class GuiWrapper : public UEventsHandler
00066 {
00067 public:
00068 GuiWrapper(int & argc, char** argv);
00069 virtual ~GuiWrapper();
00070
00071 protected:
00072 virtual void handleEvent(UEvent * anEvent);
00073
00074 private:
00075 void infoMapCallback(const rtabmap_ros::InfoConstPtr & infoMsg, const rtabmap_ros::MapDataConstPtr & mapMsg);
00076 void goalPathCallback(const rtabmap_ros::GoalConstPtr & goalMsg, const nav_msgs::PathConstPtr & pathMsg);
00077 void goalReachedCallback(const std_msgs::BoolConstPtr & value);
00078
00079 void setupCallbacks(
00080 bool subscribeDepth,
00081 bool subscribeLaserScan2d,
00082 bool subscribeLaserScan3d,
00083 bool subscribeOdomInfo,
00084 bool subscribeStereo,
00085 int queueSize,
00086 int depthCameras);
00087
00088 void commonDepthCallback(
00089 const nav_msgs::OdometryConstPtr & odomMsg,
00090 const sensor_msgs::ImageConstPtr& imageMsg,
00091 const sensor_msgs::ImageConstPtr& depthMsg,
00092 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg,
00093 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00094 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00095 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
00096 void commonDepthCallback(
00097 const nav_msgs::OdometryConstPtr & odomMsg,
00098 const std::vector<sensor_msgs::ImageConstPtr> & imageMsgs,
00099 const std::vector<sensor_msgs::ImageConstPtr> & depthMsgs,
00100 const std::vector<sensor_msgs::CameraInfoConstPtr> & cameraInfoMsgs,
00101 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00102 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00103 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
00104 void commonStereoCallback(
00105 const nav_msgs::OdometryConstPtr & odomMsg,
00106 const sensor_msgs::ImageConstPtr& leftImageMsg,
00107 const sensor_msgs::ImageConstPtr& rightImageMsg,
00108 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00109 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00110 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00111 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00112 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
00113
00114 void defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg);
00115
00116
00117 void depthCallback(
00118 const nav_msgs::OdometryConstPtr & odomMsg,
00119 const sensor_msgs::ImageConstPtr& imageMsg,
00120 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00121 const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00122 void depth2Callback(
00123 const nav_msgs::OdometryConstPtr & odomMsg,
00124 const sensor_msgs::ImageConstPtr& image1Msg,
00125 const sensor_msgs::ImageConstPtr& depth1Msg,
00126 const sensor_msgs::CameraInfoConstPtr& cameraInfo1Msg,
00127 const sensor_msgs::ImageConstPtr& image2Msg,
00128 const sensor_msgs::ImageConstPtr& depth2Msg,
00129 const sensor_msgs::CameraInfoConstPtr& cameraInfo2Msg);
00130 void depthOdomInfoCallback(
00131 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00132 const nav_msgs::OdometryConstPtr & odomMsg,
00133 const sensor_msgs::ImageConstPtr& imageMsg,
00134 const sensor_msgs::ImageConstPtr& depthMsg,
00135 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg);
00136 void depthOdomInfo2Callback(
00137 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00138 const nav_msgs::OdometryConstPtr & odomMsg,
00139 const sensor_msgs::ImageConstPtr& image1Msg,
00140 const sensor_msgs::ImageConstPtr& depth1Msg,
00141 const sensor_msgs::CameraInfoConstPtr& cameraInfo1Msg,
00142 const sensor_msgs::ImageConstPtr& image2Msg,
00143 const sensor_msgs::ImageConstPtr& depth2Msg,
00144 const sensor_msgs::CameraInfoConstPtr& cameraInfo2Msg);
00145 void depthScanCallback(
00146 const sensor_msgs::LaserScanConstPtr& scanMsg,
00147 const nav_msgs::OdometryConstPtr & odomMsg,
00148 const sensor_msgs::ImageConstPtr& imageMsg,
00149 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00150 const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00151 void depthScanOdomInfoCallback(
00152 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00153 const sensor_msgs::LaserScanConstPtr& scanMsg,
00154 const nav_msgs::OdometryConstPtr & odomMsg,
00155 const sensor_msgs::ImageConstPtr& imageMsg,
00156 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00157 const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00158 void depthScan3dCallback(
00159 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
00160 const nav_msgs::OdometryConstPtr & odomMsg,
00161 const sensor_msgs::ImageConstPtr& imageMsg,
00162 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00163 const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00164 void depthScan3dOdomInfoCallback(
00165 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00166 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
00167 const nav_msgs::OdometryConstPtr & odomMsg,
00168 const sensor_msgs::ImageConstPtr& imageMsg,
00169 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00170 const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00171
00172 void stereoScanCallback(
00173 const sensor_msgs::LaserScanConstPtr& scanMsg,
00174 const nav_msgs::OdometryConstPtr & odomMsg,
00175 const sensor_msgs::ImageConstPtr& leftImageMsg,
00176 const sensor_msgs::ImageConstPtr& rightImageMsg,
00177 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00178 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00179 void stereoScanOdomInfoCallback(
00180 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00181 const sensor_msgs::LaserScanConstPtr& scanMsg,
00182 const nav_msgs::OdometryConstPtr & odomMsg,
00183 const sensor_msgs::ImageConstPtr& leftImageMsg,
00184 const sensor_msgs::ImageConstPtr& rightImageMsg,
00185 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00186 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00187 void stereoScan3dCallback(
00188 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
00189 const nav_msgs::OdometryConstPtr & odomMsg,
00190 const sensor_msgs::ImageConstPtr& leftImageMsg,
00191 const sensor_msgs::ImageConstPtr& rightImageMsg,
00192 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00193 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00194 void stereoScan3dOdomInfoCallback(
00195 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00196 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
00197 const nav_msgs::OdometryConstPtr & odomMsg,
00198 const sensor_msgs::ImageConstPtr& leftImageMsg,
00199 const sensor_msgs::ImageConstPtr& rightImageMsg,
00200 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00201 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00202 void stereoOdomInfoCallback(
00203 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00204 const nav_msgs::OdometryConstPtr & odomMsg,
00205 const sensor_msgs::ImageConstPtr& leftImageMsg,
00206 const sensor_msgs::ImageConstPtr& rightImageMsg,
00207 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00208 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00209 void stereoCallback(
00210 const nav_msgs::OdometryConstPtr & odomMsg,
00211 const sensor_msgs::ImageConstPtr& leftImageMsg,
00212 const sensor_msgs::ImageConstPtr& rightImageMsg,
00213 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00214 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00215
00216
00217 void depthTFCallback(const sensor_msgs::ImageConstPtr& imageMsg,
00218 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00219 const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00220 void depthOdomInfoTFCallback(
00221 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00222 const sensor_msgs::ImageConstPtr& imageMsg,
00223 const sensor_msgs::ImageConstPtr& depthMsg,
00224 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg);
00225 void depthScanTFCallback(
00226 const sensor_msgs::LaserScanConstPtr& scanMsg,
00227 const sensor_msgs::ImageConstPtr& imageMsg,
00228 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00229 const sensor_msgs:: CameraInfoConstPtr& camInfoMsg);
00230 void depthScan3dTFCallback(
00231 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
00232 const sensor_msgs::ImageConstPtr& imageMsg,
00233 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00234 const sensor_msgs:: CameraInfoConstPtr& camInfoMsg);
00235
00236 void stereoScanTFCallback(
00237 const sensor_msgs::LaserScanConstPtr& scanMsg,
00238 const sensor_msgs::ImageConstPtr& leftImageMsg,
00239 const sensor_msgs::ImageConstPtr& rightImageMsg,
00240 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00241 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00242 void stereoScan3dTFCallback(
00243 const sensor_msgs::PointCloud2ConstPtr& scanMsg,
00244 const sensor_msgs::ImageConstPtr& leftImageMsg,
00245 const sensor_msgs::ImageConstPtr& rightImageMsg,
00246 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00247 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00248 void stereoOdomInfoTFCallback(
00249 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00250 const sensor_msgs::ImageConstPtr& leftImageMsg,
00251 const sensor_msgs::ImageConstPtr& rightImageMsg,
00252 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00253 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00254 void stereoTFCallback(
00255 const sensor_msgs::ImageConstPtr& leftImageMsg,
00256 const sensor_msgs::ImageConstPtr& rightImageMsg,
00257 const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00258 const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00259
00260 void processRequestedMap(const rtabmap_ros::MapData & map);
00261 rtabmap::Transform getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const;
00262
00263 private:
00264 rtabmap::MainWindow * mainWindow_;
00265 std::string cameraNodeName_;
00266 double lastOdomInfoUpdateTime_;
00267
00268
00269 std::string frameId_;
00270 std::string odomFrameId_;
00271 bool waitForTransform_;
00272 double waitForTransformDuration_;
00273 tf::TransformListener tfListener_;
00274
00275 message_filters::Subscriber<rtabmap_ros::Info> infoTopic_;
00276 message_filters::Subscriber<rtabmap_ros::MapData> mapDataTopic_;
00277
00278 message_filters::Subscriber<rtabmap_ros::Goal> goalTopic_;
00279 message_filters::Subscriber<nav_msgs::Path> pathTopic_;
00280 ros::Subscriber goalReachedTopic_;
00281
00282 ros::Subscriber defaultSub_;
00283 std::vector<image_transport::SubscriberFilter*> imageSubs_;
00284 std::vector<image_transport::SubscriberFilter*> imageDepthSubs_;
00285 std::vector<message_filters::Subscriber<sensor_msgs::CameraInfo>* > cameraInfoSubs_;
00286 message_filters::Subscriber<nav_msgs::Odometry> odomSub_;
00287 message_filters::Subscriber<rtabmap_ros::OdomInfo> odomInfoSub_;
00288 message_filters::Subscriber<sensor_msgs::LaserScan> scanSub_;
00289 message_filters::Subscriber<sensor_msgs::PointCloud2> scan3dSub_;
00290
00291 image_transport::SubscriberFilter imageRectLeft_;
00292 image_transport::SubscriberFilter imageRectRight_;
00293 message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoLeft_;
00294 message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoRight_;
00295
00296 typedef message_filters::sync_policies::ExactTime<
00297 rtabmap_ros::Info,
00298 rtabmap_ros::MapData> MyInfoMapSyncPolicy;
00299 message_filters::Synchronizer<MyInfoMapSyncPolicy> * infoMapSync_;
00300
00301 typedef message_filters::sync_policies::ExactTime<
00302 rtabmap_ros::Goal,
00303 nav_msgs::Path> MyGoalPathSyncPolicy;
00304 message_filters::Synchronizer<MyGoalPathSyncPolicy> * goalPathSync_;
00305
00306
00307 typedef message_filters::sync_policies::ApproximateTime<
00308 sensor_msgs::LaserScan,
00309 nav_msgs::Odometry,
00310 sensor_msgs::Image,
00311 sensor_msgs::Image,
00312 sensor_msgs::CameraInfo> MyDepthScanSyncPolicy;
00313 message_filters::Synchronizer<MyDepthScanSyncPolicy> * depthScanSync_;
00314
00315 typedef message_filters::sync_policies::ApproximateTime<
00316 rtabmap_ros::OdomInfo,
00317 sensor_msgs::LaserScan,
00318 nav_msgs::Odometry,
00319 sensor_msgs::Image,
00320 sensor_msgs::Image,
00321 sensor_msgs::CameraInfo> MyDepthScanOdomInfoSyncPolicy;
00322 message_filters::Synchronizer<MyDepthScanOdomInfoSyncPolicy> * depthScanOdomInfoSync_;
00323
00324 typedef message_filters::sync_policies::ApproximateTime<
00325 sensor_msgs::PointCloud2,
00326 nav_msgs::Odometry,
00327 sensor_msgs::Image,
00328 sensor_msgs::Image,
00329 sensor_msgs::CameraInfo> MyDepthScan3dSyncPolicy;
00330 message_filters::Synchronizer<MyDepthScan3dSyncPolicy> * depthScan3dSync_;
00331
00332 typedef message_filters::sync_policies::ApproximateTime<
00333 rtabmap_ros::OdomInfo,
00334 sensor_msgs::PointCloud2,
00335 nav_msgs::Odometry,
00336 sensor_msgs::Image,
00337 sensor_msgs::Image,
00338 sensor_msgs::CameraInfo> MyDepthScan3dOdomInfoSyncPolicy;
00339 message_filters::Synchronizer<MyDepthScan3dOdomInfoSyncPolicy> * depthScan3dOdomInfoSync_;
00340
00341 typedef message_filters::sync_policies::ApproximateTime<
00342 nav_msgs::Odometry,
00343 sensor_msgs::Image,
00344 sensor_msgs::Image,
00345 sensor_msgs::CameraInfo> MyDepthSyncPolicy;
00346 message_filters::Synchronizer<MyDepthSyncPolicy> * depthSync_;
00347
00348 typedef message_filters::sync_policies::ApproximateTime<
00349 rtabmap_ros::OdomInfo,
00350 nav_msgs::Odometry,
00351 sensor_msgs::Image,
00352 sensor_msgs::Image,
00353 sensor_msgs::CameraInfo> MyDepthOdomInfoSyncPolicy;
00354 message_filters::Synchronizer<MyDepthOdomInfoSyncPolicy> * depthOdomInfoSync_;
00355
00356 typedef message_filters::sync_policies::ApproximateTime<
00357 nav_msgs::Odometry,
00358 sensor_msgs::Image,
00359 sensor_msgs::Image,
00360 sensor_msgs::CameraInfo,
00361 sensor_msgs::CameraInfo> MyStereoSyncPolicy;
00362 message_filters::Synchronizer<MyStereoSyncPolicy> * stereoSync_;
00363
00364 typedef message_filters::sync_policies::ApproximateTime<
00365 sensor_msgs::LaserScan,
00366 nav_msgs::Odometry,
00367 sensor_msgs::Image,
00368 sensor_msgs::Image,
00369 sensor_msgs::CameraInfo,
00370 sensor_msgs::CameraInfo> MyStereoScanSyncPolicy;
00371 message_filters::Synchronizer<MyStereoScanSyncPolicy> * stereoScanSync_;
00372
00373 typedef message_filters::sync_policies::ApproximateTime<
00374 rtabmap_ros::OdomInfo,
00375 sensor_msgs::LaserScan,
00376 nav_msgs::Odometry,
00377 sensor_msgs::Image,
00378 sensor_msgs::Image,
00379 sensor_msgs::CameraInfo,
00380 sensor_msgs::CameraInfo> MyStereoScanOdomInfoSyncPolicy;
00381 message_filters::Synchronizer<MyStereoScanOdomInfoSyncPolicy> * stereoScanOdomInfoSync_;
00382
00383 typedef message_filters::sync_policies::ApproximateTime<
00384 sensor_msgs::PointCloud2,
00385 nav_msgs::Odometry,
00386 sensor_msgs::Image,
00387 sensor_msgs::Image,
00388 sensor_msgs::CameraInfo,
00389 sensor_msgs::CameraInfo> MyStereoScan3dSyncPolicy;
00390 message_filters::Synchronizer<MyStereoScan3dSyncPolicy> * stereoScan3dSync_;
00391
00392 typedef message_filters::sync_policies::ApproximateTime<
00393 rtabmap_ros::OdomInfo,
00394 sensor_msgs::PointCloud2,
00395 nav_msgs::Odometry,
00396 sensor_msgs::Image,
00397 sensor_msgs::Image,
00398 sensor_msgs::CameraInfo,
00399 sensor_msgs::CameraInfo> MyStereoScan3dOdomInfoSyncPolicy;
00400 message_filters::Synchronizer<MyStereoScan3dOdomInfoSyncPolicy> * stereoScan3dOdomInfoSync_;
00401
00402 typedef message_filters::sync_policies::ApproximateTime<
00403 rtabmap_ros::OdomInfo,
00404 nav_msgs::Odometry,
00405 sensor_msgs::Image,
00406 sensor_msgs::Image,
00407 sensor_msgs::CameraInfo,
00408 sensor_msgs::CameraInfo> MyStereoOdomInfoSyncPolicy;
00409 message_filters::Synchronizer<MyStereoOdomInfoSyncPolicy> * stereoOdomInfoSync_;
00410
00411 typedef message_filters::sync_policies::ApproximateTime<
00412 nav_msgs::Odometry,
00413 sensor_msgs::Image,
00414 sensor_msgs::Image,
00415 sensor_msgs::CameraInfo,
00416 sensor_msgs::Image,
00417 sensor_msgs::Image,
00418 sensor_msgs::CameraInfo> MyDepth2SyncPolicy;
00419 message_filters::Synchronizer<MyDepth2SyncPolicy> * depth2Sync_;
00420
00421 typedef message_filters::sync_policies::ApproximateTime<
00422 rtabmap_ros::OdomInfo,
00423 nav_msgs::Odometry,
00424 sensor_msgs::Image,
00425 sensor_msgs::Image,
00426 sensor_msgs::CameraInfo,
00427 sensor_msgs::Image,
00428 sensor_msgs::Image,
00429 sensor_msgs::CameraInfo> MyDepthOdomInfo2SyncPolicy;
00430 message_filters::Synchronizer<MyDepthOdomInfo2SyncPolicy> * depthOdomInfo2Sync_;
00431
00432
00433 typedef message_filters::sync_policies::ApproximateTime<
00434 sensor_msgs::LaserScan,
00435 sensor_msgs::Image,
00436 sensor_msgs::Image,
00437 sensor_msgs::CameraInfo> MyDepthScanTFSyncPolicy;
00438 message_filters::Synchronizer<MyDepthScanTFSyncPolicy> * depthScanTFSync_;
00439
00440 typedef message_filters::sync_policies::ApproximateTime<
00441 sensor_msgs::PointCloud2,
00442 sensor_msgs::Image,
00443 sensor_msgs::Image,
00444 sensor_msgs::CameraInfo> MyDepthScan3dTFSyncPolicy;
00445 message_filters::Synchronizer<MyDepthScan3dTFSyncPolicy> * depthScan3dTFSync_;
00446
00447 typedef message_filters::sync_policies::ApproximateTime<
00448 sensor_msgs::Image,
00449 sensor_msgs::Image,
00450 sensor_msgs::CameraInfo> MyDepthTFSyncPolicy;
00451 message_filters::Synchronizer<MyDepthTFSyncPolicy> * depthTFSync_;
00452
00453 typedef message_filters::sync_policies::ApproximateTime<
00454 rtabmap_ros::OdomInfo,
00455 sensor_msgs::Image,
00456 sensor_msgs::Image,
00457 sensor_msgs::CameraInfo> MyDepthOdomInfoTFSyncPolicy;
00458 message_filters::Synchronizer<MyDepthOdomInfoTFSyncPolicy> * depthOdomInfoTFSync_;
00459
00460 typedef message_filters::sync_policies::ApproximateTime<
00461 sensor_msgs::Image,
00462 sensor_msgs::Image,
00463 sensor_msgs::CameraInfo,
00464 sensor_msgs::CameraInfo> MyStereoTFSyncPolicy;
00465 message_filters::Synchronizer<MyStereoTFSyncPolicy> * stereoTFSync_;
00466
00467 typedef message_filters::sync_policies::ApproximateTime<
00468 sensor_msgs::LaserScan,
00469 sensor_msgs::Image,
00470 sensor_msgs::Image,
00471 sensor_msgs::CameraInfo,
00472 sensor_msgs::CameraInfo> MyStereoScanTFSyncPolicy;
00473 message_filters::Synchronizer<MyStereoScanTFSyncPolicy> * stereoScanTFSync_;
00474
00475 typedef message_filters::sync_policies::ApproximateTime<
00476 sensor_msgs::PointCloud2,
00477 sensor_msgs::Image,
00478 sensor_msgs::Image,
00479 sensor_msgs::CameraInfo,
00480 sensor_msgs::CameraInfo> MyStereoScan3dTFSyncPolicy;
00481 message_filters::Synchronizer<MyStereoScan3dTFSyncPolicy> * stereoScan3dTFSync_;
00482
00483 typedef message_filters::sync_policies::ApproximateTime<
00484 rtabmap_ros::OdomInfo,
00485 sensor_msgs::Image,
00486 sensor_msgs::Image,
00487 sensor_msgs::CameraInfo,
00488 sensor_msgs::CameraInfo> MyStereoOdomInfoTFSyncPolicy;
00489 message_filters::Synchronizer<MyStereoOdomInfoTFSyncPolicy> * stereoOdomInfoTFSync_;
00490 };
00491
00492 #endif