CoreWrapper.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 COREWRAPPER_H_
29 #define COREWRAPPER_H_
30 
31 
32 #include <ros/ros.h>
33 #include <nodelet/nodelet.h>
34 
35 #include <std_srvs/Empty.h>
36 
37 #include <tf/transform_listener.h>
39 
40 #include <std_msgs/Empty.h>
41 #include <std_msgs/Int32.h>
42 #include <nav_msgs/GetMap.h>
43 #include <nav_msgs/GetPlan.h>
44 #include <geometry_msgs/PoseWithCovarianceStamped.h>
45 
47 #include <rtabmap/core/Rtabmap.h>
49 
50 #include "rtabmap_ros/GetMap.h"
51 #include "rtabmap_ros/ListLabels.h"
52 #include "rtabmap_ros/PublishMap.h"
53 #include "rtabmap_ros/SetGoal.h"
54 #include "rtabmap_ros/SetLabel.h"
55 #include "rtabmap_ros/Goal.h"
57 
58 #include "MapsManager.h"
59 
60 #ifdef WITH_OCTOMAP_MSGS
61 #include <octomap_msgs/GetOctomap.h>
62 #endif
63 
65 #include <move_base_msgs/MoveBaseAction.h>
66 #include <move_base_msgs/MoveBaseActionGoal.h>
67 #include <move_base_msgs/MoveBaseActionResult.h>
68 #include <move_base_msgs/MoveBaseActionFeedback.h>
69 #include <actionlib_msgs/GoalStatusArray.h>
71 
72 namespace rtabmap {
73 class StereoDense;
74 }
75 
76 namespace rtabmap_ros {
77 
79 {
80 public:
81  CoreWrapper();
82  virtual ~CoreWrapper();
83 
84 private:
85 
86  virtual void onInit();
87 
88  bool odomUpdate(const nav_msgs::OdometryConstPtr & odomMsg, ros::Time stamp);
89  bool odomTFUpdate(const ros::Time & stamp); // TF odom
90 
91  virtual void commonDepthCallback(
92  const nav_msgs::OdometryConstPtr & odomMsg,
93  const rtabmap_ros::UserDataConstPtr & userDataMsg,
94  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
95  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
96  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
97  const sensor_msgs::LaserScanConstPtr& scanMsg,
98  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
99  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
100  void commonDepthCallbackImpl(
101  const std::string & odomFrameId,
102  const rtabmap_ros::UserDataConstPtr & userDataMsg,
103  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
104  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
105  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
106  const sensor_msgs::LaserScanConstPtr& scan2dMsg,
107  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
108  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
109  virtual void commonStereoCallback(
110  const nav_msgs::OdometryConstPtr & odomMsg,
111  const rtabmap_ros::UserDataConstPtr & userDataMsg,
112  const cv_bridge::CvImageConstPtr& leftImageMsg,
113  const cv_bridge::CvImageConstPtr& rightImageMsg,
114  const sensor_msgs::CameraInfo& leftCamInfoMsg,
115  const sensor_msgs::CameraInfo& rightCamInfoMsg,
116  const sensor_msgs::LaserScanConstPtr& scanMsg,
117  const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
118  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
119 
120  void defaultCallback(const sensor_msgs::ImageConstPtr & imageMsg); // no odom
121 
122  void userDataAsyncCallback(const rtabmap_ros::UserDataConstPtr & dataMsg);
123  void globalPoseAsyncCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & globalPoseMsg);
124 
125  void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & msg);
126 
127  void goalCommonCallback(int id, const std::string & label, const rtabmap::Transform & pose, const ros::Time & stamp, double * planningTime = 0);
128  void goalCallback(const geometry_msgs::PoseStampedConstPtr & msg);
129  void goalNodeCallback(const rtabmap_ros::GoalConstPtr & msg);
130  void updateGoal(const ros::Time & stamp);
131 
132  void process(
133  const ros::Time & stamp,
134  const rtabmap::SensorData & data,
135  const rtabmap::Transform & odom = rtabmap::Transform(),
136  const std::string & odomFrameId = "",
137  const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
138  const rtabmap::OdometryInfo & odomInfo = rtabmap::OdometryInfo());
139 
140  bool updateRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
141  bool resetRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
142  bool pauseRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
143  bool resumeRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
144  bool triggerNewMapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
145  bool backupDatabaseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
146  bool setModeLocalizationCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
147  bool setModeMappingCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
148  bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
149  bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
150  bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
151  bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
152  bool getMapDataCallback(rtabmap_ros::GetMap::Request& req, rtabmap_ros::GetMap::Response& res);
153  bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
154  bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
155  bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
156  bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
157  bool publishMapCallback(rtabmap_ros::PublishMap::Request&, rtabmap_ros::PublishMap::Response&);
158  bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res);
159  bool setGoalCallback(rtabmap_ros::SetGoal::Request& req, rtabmap_ros::SetGoal::Response& res);
160  bool cancelGoalCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
161  bool setLabelCallback(rtabmap_ros::SetLabel::Request& req, rtabmap_ros::SetLabel::Response& res);
162  bool listLabelsCallback(rtabmap_ros::ListLabels::Request& req, rtabmap_ros::ListLabels::Response& res);
163 #ifdef WITH_OCTOMAP_MSGS
164  bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
165  bool octomapFullCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
166 #endif
167 
168  void loadParameters(const std::string & configFile, rtabmap::ParametersMap & parameters);
169  void saveParameters(const std::string & configFile);
170 
171  void publishLoop(double tfDelay, double tfTolerance);
172 
173  void publishStats(const ros::Time & stamp);
174  void publishCurrentGoal(const ros::Time & stamp);
175  void goalDoneCb(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result);
176  void goalActiveCb();
177  void goalFeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
178  void publishLocalPath(const ros::Time & stamp);
179  void publishGlobalPath(const ros::Time & stamp);
180 
181 private:
183  bool paused_;
187  cv::Mat covariance_;
192  std::map<std::string, float> rtabmapROSStats_;
193 
194  std::string frameId_;
195  std::string odomFrameId_;
196  std::string mapFrameId_;
197  std::string groundTruthFrameId_;
199  std::string configPath_;
200  std::string databasePath_;
207  bool genScan_;
211 
213  boost::mutex mapToOdomMutex_;
214 
216 
224 
225  //Planning stuff
232 
235 
259 #ifdef WITH_OCTOMAP_MSGS
260  ros::ServiceServer octomapBinarySrv_;
261  ros::ServiceServer octomapFullSrv_;
262 #endif
263 
265 
266  boost::thread* transformThread_;
268 
269  // for loop closure detection only
271 
272  // for rgb/localization
276  DATA_SYNCS2(rgb, sensor_msgs::Image, sensor_msgs::CameraInfo);
277  DATA_SYNCS3(rgbOdom, sensor_msgs::Image, sensor_msgs::CameraInfo, nav_msgs::Odometry);
278 
280  cv::Mat userData_;
282 
284  geometry_msgs::PoseWithCovarianceStamped globalPose_;
285 
288  float rate_;
293 };
294 
295 }
296 
297 #endif /* COREWRAPPER_H_ */
298 
geometry_msgs::PoseWithCovarianceStamped globalPose_
Definition: CoreWrapper.h:284
ros::ServiceServer setLogErrorSrv_
Definition: CoreWrapper.h:247
ros::ServiceServer getMapDataSrv_
Definition: CoreWrapper.h:248
ros::ServiceServer getProjMapSrv_
Definition: CoreWrapper.h:249
ros::ServiceServer pauseSrv_
Definition: CoreWrapper.h:238
#define DATA_SYNCS3(PREFIX, MSG0, MSG1, MSG2)
ros::ServiceServer setLogDebugSrv_
Definition: CoreWrapper.h:244
rtabmap::Transform lastPose_
Definition: CoreWrapper.h:184
ros::ServiceServer publishMapDataSrv_
Definition: CoreWrapper.h:253
ros::ServiceServer setLogWarnSrv_
Definition: CoreWrapper.h:246
image_transport::Subscriber defaultSub_
Definition: CoreWrapper.h:270
#define DATA_SYNCS2(PREFIX, MSG0, MSG1)
ros::ServiceServer resetSrv_
Definition: CoreWrapper.h:237
rtabmap::ParametersMap parameters_
Definition: CoreWrapper.h:191
ros::ServiceServer getMapSrv_
Definition: CoreWrapper.h:250
ros::ServiceServer getGridMapSrv_
Definition: CoreWrapper.h:252
rtabmap::Rtabmap rtabmap_
Definition: CoreWrapper.h:182
ros::Publisher localizationPosePub_
Definition: CoreWrapper.h:222
rtabmap::Transform lastPublishedMetricGoal_
Definition: CoreWrapper.h:189
std::map< std::string, std::string > ParametersMap
ros::Publisher infoPub_
Definition: CoreWrapper.h:217
ros::ServiceServer getProbMapSrv_
Definition: CoreWrapper.h:251
ros::Publisher nextMetricGoalPub_
Definition: CoreWrapper.h:228
ros::Subscriber initialPoseSub_
Definition: CoreWrapper.h:223
ros::Publisher mapDataPub_
Definition: CoreWrapper.h:218
ros::Subscriber globalPoseAsyncSub_
Definition: CoreWrapper.h:283
ros::Subscriber goalSub_
Definition: CoreWrapper.h:226
ros::ServiceServer setModeMappingSrv_
Definition: CoreWrapper.h:243
ros::Subscriber userDataAsyncSub_
Definition: CoreWrapper.h:279
ros::ServiceServer updateSrv_
Definition: CoreWrapper.h:236
ros::ServiceServer backupDatabase_
Definition: CoreWrapper.h:241
ros::ServiceServer setLogInfoSrv_
Definition: CoreWrapper.h:245
std::map< std::string, float > rtabmapROSStats_
Definition: CoreWrapper.h:192
ros::ServiceServer setLabelSrv_
Definition: CoreWrapper.h:257
MoveBaseClient mbClient_
Definition: CoreWrapper.h:264
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: CoreWrapper.h:233
message_filters::Subscriber< nav_msgs::Odometry > rgbOdomSub_
Definition: CoreWrapper.h:274
boost::mutex mapToOdomMutex_
Definition: CoreWrapper.h:213
ros::ServiceServer cancelGoalSrv_
Definition: CoreWrapper.h:256
tf::TransformListener tfListener_
Definition: CoreWrapper.h:234
RecoveryProgressState state
rtabmap::Transform mapToOdom_
Definition: CoreWrapper.h:212
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
Definition: CoreWrapper.h:70
boost::thread * transformThread_
Definition: CoreWrapper.h:266
rtabmap::Transform currentMetricGoal_
Definition: CoreWrapper.h:188
message_filters::Subscriber< sensor_msgs::CameraInfo > rgbCameraInfoSub_
Definition: CoreWrapper.h:275
image_transport::SubscriberFilter rgbSub_
Definition: CoreWrapper.h:273
ros::Subscriber goalNodeSub_
Definition: CoreWrapper.h:227
ros::ServiceServer listLabelsSrv_
Definition: CoreWrapper.h:258
ros::Publisher labelsPub_
Definition: CoreWrapper.h:220
ros::Publisher mapPathPub_
Definition: CoreWrapper.h:221
ros::Publisher localPathPub_
Definition: CoreWrapper.h:231
std::string groundTruthFrameId_
Definition: CoreWrapper.h:197
ros::ServiceServer getPlanSrv_
Definition: CoreWrapper.h:254
ros::ServiceServer setGoalSrv_
Definition: CoreWrapper.h:255
ros::Publisher globalPathPub_
Definition: CoreWrapper.h:230
std::string groundTruthBaseFrameId_
Definition: CoreWrapper.h:198
ros::ServiceServer setModeLocalizationSrv_
Definition: CoreWrapper.h:242
ros::Publisher goalReachedPub_
Definition: CoreWrapper.h:229
ros::ServiceServer triggerNewMapSrv_
Definition: CoreWrapper.h:240
ros::Publisher mapGraphPub_
Definition: CoreWrapper.h:219
ros::ServiceServer resumeSrv_
Definition: CoreWrapper.h:239


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