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  class PreferencesDialog;
51 }
52 
53 class QApplication;
54 
55 namespace rtabmap_ros {
56 
58 {
59 public:
60  GuiWrapper(int & argc, char** argv);
61  virtual ~GuiWrapper();
62 
63 protected:
64  virtual bool handleEvent(UEvent * anEvent);
65 
66 private:
67  void infoMapCallback(const rtabmap_ros::InfoConstPtr & infoMsg, const rtabmap_ros::MapDataConstPtr & mapMsg);
68  void goalPathCallback(const rtabmap_ros::GoalConstPtr & goalMsg, const nav_msgs::PathConstPtr & pathMsg);
69  void goalReachedCallback(const std_msgs::BoolConstPtr & value);
70 
71  virtual void commonMultiCameraCallback(
72  const nav_msgs::OdometryConstPtr & odomMsg,
73  const rtabmap_ros::UserDataConstPtr & userDataMsg,
74  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
75  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
76  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
77  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
78  const sensor_msgs::LaserScan& scan2dMsg,
79  const sensor_msgs::PointCloud2& scan3dMsg,
80  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
81  const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
82  const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
83  const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
84  const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
85  virtual void commonStereoCallback(
86  const nav_msgs::OdometryConstPtr & odomMsg,
87  const rtabmap_ros::UserDataConstPtr & userDataMsg,
88  const cv_bridge::CvImageConstPtr& leftImageMsg,
89  const cv_bridge::CvImageConstPtr& rightImageMsg,
90  const sensor_msgs::CameraInfo& leftCamInfoMsg,
91  const sensor_msgs::CameraInfo& rightCamInfoMsg,
92  const sensor_msgs::LaserScan& scan2dMsg,
93  const sensor_msgs::PointCloud2& scan3dMsg,
94  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
95  const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
96  const std::vector<rtabmap_ros::KeyPoint> & localKeyPoints = std::vector<rtabmap_ros::KeyPoint>(),
97  const std::vector<rtabmap_ros::Point3f> & localPoints3d = std::vector<rtabmap_ros::Point3f>(),
98  const cv::Mat & localDescriptors = cv::Mat());
99  virtual void commonLaserScanCallback(
100  const nav_msgs::OdometryConstPtr & odomMsg,
101  const rtabmap_ros::UserDataConstPtr & userDataMsg,
102  const sensor_msgs::LaserScan& scan2dMsg,
103  const sensor_msgs::PointCloud2& scan3dMsg,
104  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
105  const rtabmap_ros::GlobalDescriptor & globalDescriptor = rtabmap_ros::GlobalDescriptor());
106 
107  virtual void commonOdomCallback(
108  const nav_msgs::OdometryConstPtr & odomMsg,
109  const rtabmap_ros::UserDataConstPtr & userDataMsg,
110  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
111 
112  void defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg);
113 
114  void processRequestedMap(const rtabmap_ros::MapData & map);
115 
116 private:
119  std::string cameraNodeName_;
121  std::string rtabmapNodeName_;
122 
123  // odometry subscription stuffs
124  std::string frameId_;
125  std::string odomFrameId_;
131 
133 
136 
140 
142  rtabmap_ros::Info,
143  rtabmap_ros::MapData> MyInfoMapSyncPolicy;
145 
147  rtabmap_ros::Goal,
150 };
151 
152 }
153 
154 #endif /* GUIWRAPPER_H_ */
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
Definition: GuiWrapper.h:149
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
Definition: GuiWrapper.h:134
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
Definition: GuiWrapper.h:137
rtabmap::MainWindow * mainWindow_
Definition: GuiWrapper.h:118
rtabmap::PreferencesDialog * prefDialog_
Definition: GuiWrapper.h:117
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
Definition: GuiWrapper.h:135
std::string rtabmapNodeName_
Definition: GuiWrapper.h:121
double waitForTransformDuration_
Definition: GuiWrapper.h:127
ros::Subscriber goalReachedTopic_
Definition: GuiWrapper.h:139
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
Definition: GuiWrapper.h:144
tf::TransformListener tfListener_
Definition: GuiWrapper.h:130
message_filters::sync_policies::ExactTime< rtabmap_ros::Goal, nav_msgs::Path > MyGoalPathSyncPolicy
Definition: GuiWrapper.h:148
argv
std::string cameraNodeName_
Definition: GuiWrapper.h:119
message_filters::Subscriber< nav_msgs::Path > pathTopic_
Definition: GuiWrapper.h:138
ros::Publisher republishNodeDataPub_
Definition: GuiWrapper.h:132
message_filters::sync_policies::ExactTime< rtabmap_ros::Info, rtabmap_ros::MapData > MyInfoMapSyncPolicy
Definition: GuiWrapper.h:143
std::string odomFrameId_
Definition: GuiWrapper.h:125


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40