GuiWrapper.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef GUIWRAPPER_H_
29 #define GUIWRAPPER_H_
30 
31 #include <ros/ros.h>
32 #include "rtabmap_ros/Info.h"
33 #include "rtabmap_ros/MapData.h"
34 #include "rtabmap_ros/OdomInfo.h"
35 #include "rtabmap_ros/Goal.h"
37 #include "rtabmap/core/Transform.h"
38 
39 #include <tf/transform_listener.h>
40 
41 #include <geometry_msgs/TwistStamped.h>
42 #include <nav_msgs/Path.h>
43 #include <std_msgs/Bool.h>
44 
46 
47 namespace rtabmap
48 {
49  class MainWindow;
50 }
51 
52 class QApplication;
53 
54 namespace rtabmap_ros {
55 
57 {
58 public:
59  GuiWrapper(int & argc, char** argv);
60  virtual ~GuiWrapper();
61 
62 protected:
63  virtual bool handleEvent(UEvent * anEvent);
64 
65 private:
66  void infoMapCallback(const rtabmap_ros::InfoConstPtr & infoMsg, const rtabmap_ros::MapDataConstPtr & mapMsg);
67  void goalPathCallback(const rtabmap_ros::GoalConstPtr & goalMsg, const nav_msgs::PathConstPtr & pathMsg);
68  void goalReachedCallback(const std_msgs::BoolConstPtr & value);
69 
70  virtual void commonDepthCallback(
71  const nav_msgs::OdometryConstPtr & odomMsg,
72  const rtabmap_ros::UserDataConstPtr & userDataMsg,
73  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
74  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
75  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
76  const sensor_msgs::LaserScanConstPtr& scan2dMsg,
77  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
78  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
79  virtual void commonStereoCallback(
80  const nav_msgs::OdometryConstPtr & odomMsg,
81  const rtabmap_ros::UserDataConstPtr & userDataMsg,
82  const cv_bridge::CvImageConstPtr& leftImageMsg,
83  const cv_bridge::CvImageConstPtr& rightImageMsg,
84  const sensor_msgs::CameraInfo& leftCamInfoMsg,
85  const sensor_msgs::CameraInfo& rightCamInfoMsg,
86  const sensor_msgs::LaserScanConstPtr& scan2dMsg,
87  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
88  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
89 
90  void defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg);
91 
92  void processRequestedMap(const rtabmap_ros::MapData & map);
93 
94 private:
96  std::string cameraNodeName_;
98 
99  // odometry subscription stuffs
100  std::string frameId_;
101  std::string odomFrameId_;
106 
109 
113 
114  ros::Subscriber defaultSub_; // odometry only
115 
117  rtabmap_ros::Info,
118  rtabmap_ros::MapData> MyInfoMapSyncPolicy;
120 
122  rtabmap_ros::Goal,
123  nav_msgs::Path> MyGoalPathSyncPolicy;
125 };
126 
127 }
128 
129 #endif /* GUIWRAPPER_H_ */
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
Definition: GuiWrapper.h:124
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
Definition: GuiWrapper.h:107
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
Definition: GuiWrapper.h:110
rtabmap::MainWindow * mainWindow_
Definition: GuiWrapper.h:95
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
Definition: GuiWrapper.h:108
double lastOdomInfoUpdateTime_
Definition: GuiWrapper.h:97
double waitForTransformDuration_
Definition: GuiWrapper.h:103
ros::Subscriber defaultSub_
Definition: GuiWrapper.h:114
ros::Subscriber goalReachedTopic_
Definition: GuiWrapper.h:112
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
Definition: GuiWrapper.h:119
tf::TransformListener tfListener_
Definition: GuiWrapper.h:105
message_filters::sync_policies::ExactTime< rtabmap_ros::Goal, nav_msgs::Path > MyGoalPathSyncPolicy
Definition: GuiWrapper.h:123
std::string cameraNodeName_
Definition: GuiWrapper.h:96
message_filters::Subscriber< nav_msgs::Path > pathTopic_
Definition: GuiWrapper.h:111
message_filters::sync_policies::ExactTime< rtabmap_ros::Info, rtabmap_ros::MapData > MyInfoMapSyncPolicy
Definition: GuiWrapper.h:118
std::string odomFrameId_
Definition: GuiWrapper.h:101


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:03