GuiWrapper.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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/utilite/UEventsHandler.h"
00036 
00037 #include <tf/transform_listener.h>
00038 
00039 #include <geometry_msgs/TwistStamped.h>
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <sensor_msgs/Image.h>
00042 #include <sensor_msgs/CameraInfo.h>
00043 #include <sensor_msgs/LaserScan.h>
00044 #include <nav_msgs/Odometry.h>
00045 
00046 #include <message_filters/subscriber.h>
00047 #include <message_filters/synchronizer.h>
00048 #include <message_filters/sync_policies/approximate_time.h>
00049 #include <message_filters/sync_policies/exact_time.h>
00050 
00051 #include <image_transport/image_transport.h>
00052 #include <image_transport/subscriber_filter.h>
00053 
00054 namespace rtabmap
00055 {
00056         class MainWindow;
00057 }
00058 
00059 class QApplication;
00060 
00061 class GuiWrapper : public UEventsHandler
00062 {
00063 public:
00064         GuiWrapper(int & argc, char** argv);
00065         virtual ~GuiWrapper();
00066 
00067         int exec();
00068 
00069 protected:
00070         virtual void handleEvent(UEvent * anEvent);
00071 
00072 private:
00073         void infoMapCallback(const rtabmap_ros::InfoConstPtr & infoMsg, const rtabmap_ros::MapDataConstPtr & mapMsg);
00074 
00075         void setupCallbacks(bool subscribeDepth, bool subscribeLaserScan, bool subscribeOdomInfo, bool subscribeStereo, int queueSize);
00076         void defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg); // odom
00077         void depthCallback(const sensor_msgs::ImageConstPtr& imageMsg,
00078                                            const nav_msgs::OdometryConstPtr & odomMsg,
00079                                            const sensor_msgs::ImageConstPtr& imageDepthMsg,
00080                                            const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00081         void depthOdomInfoCallback(
00082                         const sensor_msgs::ImageConstPtr& imageMsg,
00083                         const nav_msgs::OdometryConstPtr & odomMsg,
00084                         const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00085                         const sensor_msgs::ImageConstPtr& depthMsg,
00086                         const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg);
00087         void depthScanCallback(const sensor_msgs::ImageConstPtr& imageMsg,
00088                                                    const nav_msgs::OdometryConstPtr & odomMsg,
00089                                                    const sensor_msgs::ImageConstPtr& imageDepthMsg,
00090                                                    const sensor_msgs::CameraInfoConstPtr& camInfoMsg,
00091                                                    const sensor_msgs::LaserScanConstPtr& scanMsg);
00092 
00093         void stereoScanCallback(
00094                         const nav_msgs::OdometryConstPtr & odomMsg,
00095                         const sensor_msgs::LaserScanConstPtr& scanMsg,
00096                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00097                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00098                         const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00099                         const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00100         void stereoOdomInfoCallback(
00101                         const nav_msgs::OdometryConstPtr & odomMsg,
00102                         const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg,
00103                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00104                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00105                         const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00106                         const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00107         void stereoCallback(
00108                         const nav_msgs::OdometryConstPtr & odomMsg,
00109                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00110                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00111                         const sensor_msgs::CameraInfoConstPtr& leftCameraInfoMsg,
00112                         const sensor_msgs::CameraInfoConstPtr& rightCameraInfoMsg);
00113 
00114         void processRequestedMap(const rtabmap_ros::MapData & map);
00115 
00116 private:
00117         QApplication * app_;
00118         rtabmap::MainWindow * mainWindow_;
00119         std::string cameraNodeName_;
00120         double lastOdomInfoUpdateTime_;
00121 
00122         // odometry subscription stuffs
00123         std::string frameId_;
00124         bool waitForTransform_;
00125         tf::TransformListener tfListener_;
00126 
00127         message_filters::Subscriber<rtabmap_ros::Info> infoTopic_;
00128         message_filters::Subscriber<rtabmap_ros::MapData> mapDataTopic_;
00129 
00130         ros::Subscriber defaultSub_; // odometry only
00131         image_transport::SubscriberFilter imageSub_;
00132         image_transport::SubscriberFilter imageDepthSub_;
00133         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoSub_;
00134         message_filters::Subscriber<nav_msgs::Odometry> odomSub_;
00135         message_filters::Subscriber<rtabmap_ros::OdomInfo> odomInfoSub_;
00136         message_filters::Subscriber<sensor_msgs::LaserScan> scanSub_;
00137 
00138         image_transport::SubscriberFilter imageRectLeft_;
00139         image_transport::SubscriberFilter imageRectRight_;
00140         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoLeft_;
00141         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoRight_;
00142 
00143         typedef message_filters::sync_policies::ExactTime<
00144                         rtabmap_ros::Info,
00145                         rtabmap_ros::MapData> MyInfoMapSyncPolicy;
00146         message_filters::Synchronizer<MyInfoMapSyncPolicy> * infoMapSync_;
00147 
00148         typedef message_filters::sync_policies::ApproximateTime<
00149                         sensor_msgs::Image,
00150                         nav_msgs::Odometry,
00151                         sensor_msgs::Image,
00152                         sensor_msgs::CameraInfo,
00153                         sensor_msgs::LaserScan> MyDepthScanSyncPolicy;
00154         message_filters::Synchronizer<MyDepthScanSyncPolicy> * depthScanSync_;
00155 
00156         typedef message_filters::sync_policies::ApproximateTime<
00157                         sensor_msgs::Image,
00158                         nav_msgs::Odometry,
00159                         sensor_msgs::Image,
00160                         sensor_msgs::CameraInfo> MyDepthSyncPolicy;
00161         message_filters::Synchronizer<MyDepthSyncPolicy> * depthSync_;
00162 
00163         typedef message_filters::sync_policies::ApproximateTime<
00164                         sensor_msgs::Image,
00165                         nav_msgs::Odometry,
00166                         rtabmap_ros::OdomInfo,
00167                         sensor_msgs::Image,
00168                         sensor_msgs::CameraInfo> MyDepthOdomInfoSyncPolicy;
00169         message_filters::Synchronizer<MyDepthOdomInfoSyncPolicy> * depthOdomInfoSync_;
00170 
00171         typedef message_filters::sync_policies::ApproximateTime<
00172                         nav_msgs::Odometry,
00173                         sensor_msgs::Image,
00174                         sensor_msgs::Image,
00175                         sensor_msgs::CameraInfo,
00176                         sensor_msgs::CameraInfo> MyStereoSyncPolicy;
00177         message_filters::Synchronizer<MyStereoSyncPolicy> * stereoSync_;
00178 
00179         typedef message_filters::sync_policies::ApproximateTime<
00180                         nav_msgs::Odometry,
00181                         sensor_msgs::LaserScan,
00182                         sensor_msgs::Image,
00183                         sensor_msgs::Image,
00184                         sensor_msgs::CameraInfo,
00185                         sensor_msgs::CameraInfo> MyStereoScanSyncPolicy;
00186         message_filters::Synchronizer<MyStereoScanSyncPolicy> * stereoScanSync_;
00187 
00188         typedef message_filters::sync_policies::ApproximateTime<
00189                         nav_msgs::Odometry,
00190                         rtabmap_ros::OdomInfo,
00191                         sensor_msgs::Image,
00192                         sensor_msgs::Image,
00193                         sensor_msgs::CameraInfo,
00194                         sensor_msgs::CameraInfo> MyStereoOdomInfoSyncPolicy;
00195         message_filters::Synchronizer<MyStereoOdomInfoSyncPolicy> * stereoOdomInfoSync_;
00196 };
00197 
00198 #endif /* GUIWRAPPER_H_ */


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24