Go to the documentation of this file.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 <nav_msgs/Path.h>
00043 #include <std_msgs/Bool.h>
00044
00045 #include <rtabmap_ros/CommonDataSubscriber.h>
00046
00047 namespace rtabmap
00048 {
00049 class MainWindow;
00050 }
00051
00052 class QApplication;
00053
00054 namespace rtabmap_ros {
00055
00056 class GuiWrapper : public UEventsHandler, public CommonDataSubscriber
00057 {
00058 public:
00059 GuiWrapper(int & argc, char** argv);
00060 virtual ~GuiWrapper();
00061
00062 protected:
00063 virtual bool handleEvent(UEvent * anEvent);
00064
00065 private:
00066 void infoMapCallback(const rtabmap_ros::InfoConstPtr & infoMsg, const rtabmap_ros::MapDataConstPtr & mapMsg);
00067 void goalPathCallback(const rtabmap_ros::GoalConstPtr & goalMsg, const nav_msgs::PathConstPtr & pathMsg);
00068 void goalReachedCallback(const std_msgs::BoolConstPtr & value);
00069
00070 virtual void commonDepthCallback(
00071 const nav_msgs::OdometryConstPtr & odomMsg,
00072 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00073 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
00074 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
00075 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
00076 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00077 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00078 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
00079 virtual void commonStereoCallback(
00080 const nav_msgs::OdometryConstPtr & odomMsg,
00081 const rtabmap_ros::UserDataConstPtr & userDataMsg,
00082 const cv_bridge::CvImageConstPtr& leftImageMsg,
00083 const cv_bridge::CvImageConstPtr& rightImageMsg,
00084 const sensor_msgs::CameraInfo& leftCamInfoMsg,
00085 const sensor_msgs::CameraInfo& rightCamInfoMsg,
00086 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00087 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
00088 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
00089
00090 void defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg);
00091
00092 void processRequestedMap(const rtabmap_ros::MapData & map);
00093
00094 private:
00095 rtabmap::MainWindow * mainWindow_;
00096 std::string cameraNodeName_;
00097 double lastOdomInfoUpdateTime_;
00098
00099
00100 std::string frameId_;
00101 std::string odomFrameId_;
00102 bool waitForTransform_;
00103 double waitForTransformDuration_;
00104 bool odomSensorSync_;
00105 tf::TransformListener tfListener_;
00106
00107 message_filters::Subscriber<rtabmap_ros::Info> infoTopic_;
00108 message_filters::Subscriber<rtabmap_ros::MapData> mapDataTopic_;
00109
00110 message_filters::Subscriber<rtabmap_ros::Goal> goalTopic_;
00111 message_filters::Subscriber<nav_msgs::Path> pathTopic_;
00112 ros::Subscriber goalReachedTopic_;
00113
00114 ros::Subscriber defaultSub_;
00115
00116 typedef message_filters::sync_policies::ExactTime<
00117 rtabmap_ros::Info,
00118 rtabmap_ros::MapData> MyInfoMapSyncPolicy;
00119 message_filters::Synchronizer<MyInfoMapSyncPolicy> * infoMapSync_;
00120
00121 typedef message_filters::sync_policies::ExactTime<
00122 rtabmap_ros::Goal,
00123 nav_msgs::Path> MyGoalPathSyncPolicy;
00124 message_filters::Synchronizer<MyGoalPathSyncPolicy> * goalPathSync_;
00125 };
00126
00127 }
00128
00129 #endif