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 "std_msgs/Int32MultiArray.h"
43 #include <sensor_msgs/NavSatFix.h>
44 #include <nav_msgs/GetMap.h>
45 #include <nav_msgs/GetPlan.h>
46 #include <geometry_msgs/PoseWithCovarianceStamped.h>
47 #include <sensor_msgs/Imu.h>
48 
50 #include <rtabmap/core/Rtabmap.h>
52 
53 #include "rtabmap_ros/GetNodeData.h"
54 #include "rtabmap_ros/GetMap.h"
55 #include "rtabmap_ros/GetMap2.h"
56 #include "rtabmap_ros/ListLabels.h"
57 #include "rtabmap_ros/PublishMap.h"
58 #include "rtabmap_ros/SetGoal.h"
59 #include "rtabmap_ros/SetLabel.h"
60 #include "rtabmap_ros/RemoveLabel.h"
61 #include "rtabmap_ros/Goal.h"
62 #include "rtabmap_ros/GetPlan.h"
64 #include "rtabmap_ros/OdomInfo.h"
65 #include "rtabmap_ros/AddLink.h"
66 #include "rtabmap_ros/GetNodesInRadius.h"
67 #include "rtabmap_ros/LoadDatabase.h"
68 #include "rtabmap_ros/DetectMoreLoopClosures.h"
69 #include "rtabmap_ros/GlobalBundleAdjustment.h"
70 #include "rtabmap_ros/CleanupLocalGrids.h"
71 
72 #include "MapsManager.h"
73 
75 
76 #ifdef WITH_OCTOMAP_MSGS
77 #include <octomap_msgs/GetOctomap.h>
78 #endif
79 
80 #ifdef WITH_APRILTAG_ROS
81 #include <apriltag_ros/AprilTagDetectionArray.h>
82 #endif
83 
84 //#define WITH_FIDUCIAL_MSGS
85 #ifdef WITH_FIDUCIAL_MSGS
86 #include <fiducial_msgs/FiducialTransformArray.h>
87 #endif
88 
90 #include <move_base_msgs/MoveBaseAction.h>
91 #include <move_base_msgs/MoveBaseActionGoal.h>
92 #include <move_base_msgs/MoveBaseActionResult.h>
93 #include <move_base_msgs/MoveBaseActionFeedback.h>
94 #include <actionlib_msgs/GoalStatusArray.h>
96 
97 namespace rtabmap {
98 class StereoDense;
99 }
100 
101 namespace rtabmap_ros {
102 
104 {
105 public:
106  CoreWrapper();
107  virtual ~CoreWrapper();
108 
109 private:
110 
111  virtual void onInit();
112 
113  bool odomUpdate(const nav_msgs::OdometryConstPtr & odomMsg, ros::Time stamp);
114  bool odomTFUpdate(const ros::Time & stamp); // TF odom
115 
116  virtual void commonMultiCameraCallback(
117  const nav_msgs::OdometryConstPtr & odomMsg,
118  const rtabmap_ros::UserDataConstPtr & userDataMsg,
119  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
120  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
121  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
122  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
123  const sensor_msgs::LaserScan& scanMsg,
124  const sensor_msgs::PointCloud2& scan3dMsg,
125  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
126  const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
127  const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
128  const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
129  const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
130  void commonMultiCameraCallbackImpl(
131  const std::string & odomFrameId,
132  const rtabmap_ros::UserDataConstPtr & userDataMsg,
133  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
134  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
135  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
136  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
137  const sensor_msgs::LaserScan& scan2dMsg,
138  const sensor_msgs::PointCloud2& scan3dMsg,
139  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
140  const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs,
141  const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints,
142  const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d,
143  const std::vector<cv::Mat> & localDescriptors);
144  virtual void commonLaserScanCallback(
145  const nav_msgs::OdometryConstPtr & odomMsg,
146  const rtabmap_ros::UserDataConstPtr & userDataMsg,
147  const sensor_msgs::LaserScan& scanMsg,
148  const sensor_msgs::PointCloud2& scan3dMsg,
149  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
150  const rtabmap_ros::GlobalDescriptor & globalDescriptor = rtabmap_ros::GlobalDescriptor());
151  virtual void commonOdomCallback(
152  const nav_msgs::OdometryConstPtr & odomMsg,
153  const rtabmap_ros::UserDataConstPtr & userDataMsg,
154  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
155 
156  void defaultCallback(const sensor_msgs::ImageConstPtr & imageMsg); // no odom
157 
158  void userDataAsyncCallback(const rtabmap_ros::UserDataConstPtr & dataMsg);
159  void globalPoseAsyncCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & globalPoseMsg);
160  void gpsFixAsyncCallback(const sensor_msgs::NavSatFixConstPtr & gpsFixMsg);
161 #ifdef WITH_APRILTAG_ROS
162  void tagDetectionsAsyncCallback(const apriltag_ros::AprilTagDetectionArray & tagDetections);
163 #endif
164 #ifdef WITH_FIDUCIAL_MSGS
165  void fiducialDetectionsAsyncCallback(const fiducial_msgs::FiducialTransformArray & fiducialDetections);
166 #endif
167  void imuAsyncCallback(const sensor_msgs::ImuConstPtr & tagDetections);
168  void republishNodeDataCallback(const std_msgs::Int32MultiArray::ConstPtr& msg);
169  void interOdomCallback(const nav_msgs::OdometryConstPtr & msg);
170  void interOdomInfoCallback(const nav_msgs::OdometryConstPtr & msg1, const rtabmap_ros::OdomInfoConstPtr & msg2);
171 
172  void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & msg);
173 
174  void goalCommonCallback(int id,
175  const std::string & label,
176  const std::string & frameId,
177  const rtabmap::Transform & pose,
178  const ros::Time & stamp,
179  double * planningTime = 0);
180  void goalCallback(const geometry_msgs::PoseStampedConstPtr & msg);
181  void goalNodeCallback(const rtabmap_ros::GoalConstPtr & msg);
182  void updateGoal(const ros::Time & stamp);
183 
184  void process(
185  const ros::Time & stamp,
187  const rtabmap::Transform & odom = rtabmap::Transform(),
188  const std::vector<float> & odomVelocity = std::vector<float>(),
189  const std::string & odomFrameId = "",
190  const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
191  const rtabmap::OdometryInfo & odomInfo = rtabmap::OdometryInfo(),
192  double timeMsgConversion = 0.0);
193  std::map<int, rtabmap::Transform> filterNodesToAssemble(
194  const std::map<int, rtabmap::Transform> & nodes,
195  const rtabmap::Transform & currentPose);
196 
197  bool updateRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
198  bool resetRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
199  bool pauseRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
200  bool resumeRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
201  bool loadDatabaseCallback(rtabmap_ros::LoadDatabase::Request&, rtabmap_ros::LoadDatabase::Response&);
202  bool triggerNewMapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
203  bool backupDatabaseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
204  bool detectMoreLoopClosuresCallback(rtabmap_ros::DetectMoreLoopClosures::Request&, rtabmap_ros::DetectMoreLoopClosures::Response&);
205  bool globalBundleAdjustmentCallback(rtabmap_ros::GlobalBundleAdjustment::Request&, rtabmap_ros::GlobalBundleAdjustment::Response&);
206  bool cleanupLocalGridsCallback(rtabmap_ros::CleanupLocalGrids::Request&, rtabmap_ros::CleanupLocalGrids::Response&);
207  bool setModeLocalizationCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
208  bool setModeMappingCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
209  bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
210  bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
211  bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
212  bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
213  bool getNodeDataCallback(rtabmap_ros::GetNodeData::Request& req, rtabmap_ros::GetNodeData::Response& res);
214  bool getMapDataCallback(rtabmap_ros::GetMap::Request& req, rtabmap_ros::GetMap::Response& res);
215  bool getMapData2Callback(rtabmap_ros::GetMap2::Request& req, rtabmap_ros::GetMap2::Response& res);
216  bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
217  bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
218  bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
219  bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
220  bool publishMapCallback(rtabmap_ros::PublishMap::Request&, rtabmap_ros::PublishMap::Response&);
221  bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res);
222  bool getPlanNodesCallback(rtabmap_ros::GetPlan::Request &req, rtabmap_ros::GetPlan::Response &res);
223  bool setGoalCallback(rtabmap_ros::SetGoal::Request& req, rtabmap_ros::SetGoal::Response& res);
224  bool cancelGoalCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
225  bool setLabelCallback(rtabmap_ros::SetLabel::Request& req, rtabmap_ros::SetLabel::Response& res);
226  bool listLabelsCallback(rtabmap_ros::ListLabels::Request& req, rtabmap_ros::ListLabels::Response& res);
227  bool removeLabelCallback(rtabmap_ros::RemoveLabel::Request& req, rtabmap_ros::RemoveLabel::Response& res);
228  bool addLinkCallback(rtabmap_ros::AddLink::Request&, rtabmap_ros::AddLink::Response&);
229  bool getNodesInRadiusCallback(rtabmap_ros::GetNodesInRadius::Request&, rtabmap_ros::GetNodesInRadius::Response&);
230 #ifdef WITH_OCTOMAP_MSGS
231  bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
232  bool octomapFullCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
233 #endif
234 
235  void loadParameters(const std::string & configFile, rtabmap::ParametersMap & parameters);
236  void saveParameters(const std::string & configFile);
237 
238  void publishLoop(double tfDelay, double tfTolerance);
239 
240  void publishStats(const ros::Time & stamp);
241  void publishCurrentGoal(const ros::Time & stamp);
242  void goalDoneCb(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result);
243  void goalActiveCb();
244  void goalFeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
245  void publishLocalPath(const ros::Time & stamp);
246  void publishGlobalPath(const ros::Time & stamp);
247  void republishMaps();
248 
249 private:
251  bool paused_;
254  std::vector<float> lastPoseVelocity_;
256  cv::Mat covariance_;
261  std::map<std::string, float> rtabmapROSStats_;
262 
263  std::string frameId_;
264  std::string odomFrameId_;
265  std::string mapFrameId_;
266  std::string groundTruthFrameId_;
268  std::string configPath_;
269  std::string databasePath_;
278  bool genScan_;
281  bool genDepth_;
288 
290  boost::mutex mapToOdomMutex_;
291 
293 
306 
307  //Planning stuff
316  std::string goalFrameId_;
317 
320 
354 #ifdef WITH_OCTOMAP_MSGS
355  ros::ServiceServer octomapBinarySrv_;
356  ros::ServiceServer octomapFullSrv_;
357 #endif
358 
360 
361  boost::thread* transformThread_;
363 
364  // for loop closure detection only
366 
368  cv::Mat userData_;
370 
372  geometry_msgs::PoseWithCovarianceStamped globalPose_;
377  std::map<int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> > tags_; // id, <pose, size>
379  std::map<double, rtabmap::Transform> imus_;
380  std::string imuFrameId_;
382 
384  std::list<std::pair<nav_msgs::Odometry, rtabmap_ros::OdomInfo> > interOdoms_;
389 
392  float rate_;
399 
401 };
402 
403 }
404 
405 #endif /* COREWRAPPER_H_ */
406 
geometry_msgs::PoseWithCovarianceStamped globalPose_
Definition: CoreWrapper.h:372
ros::ServiceServer setLogErrorSrv_
Definition: CoreWrapper.h:336
ros::ServiceServer getMapDataSrv_
Definition: CoreWrapper.h:338
ros::Subscriber gpsFixAsyncSub_
Definition: CoreWrapper.h:373
ros::ServiceServer getNodesInRadiusSrv_
Definition: CoreWrapper.h:353
ros::ServiceServer getProjMapSrv_
Definition: CoreWrapper.h:340
ros::ServiceServer pauseSrv_
Definition: CoreWrapper.h:323
ros::Publisher localPathNodesPub_
Definition: CoreWrapper.h:315
ros::Subscriber republishNodeDataSub_
Definition: CoreWrapper.h:381
ros::ServiceServer setLogDebugSrv_
Definition: CoreWrapper.h:333
rtabmap::Transform lastPose_
Definition: CoreWrapper.h:252
ros::Publisher globalPathNodesPub_
Definition: CoreWrapper.h:314
ros::ServiceServer publishMapDataSrv_
Definition: CoreWrapper.h:344
ros::ServiceServer detectMoreLoopClosuresSrv_
Definition: CoreWrapper.h:328
ros::ServiceServer setLogWarnSrv_
Definition: CoreWrapper.h:335
image_transport::Subscriber defaultSub_
Definition: CoreWrapper.h:365
ros::ServiceServer resetSrv_
Definition: CoreWrapper.h:322
rtabmap::ParametersMap parameters_
Definition: CoreWrapper.h:260
ros::ServiceServer addLinkSrv_
Definition: CoreWrapper.h:352
ros::Subscriber tagDetectionsSub_
Definition: CoreWrapper.h:375
ros::Publisher localGridEmpty_
Definition: CoreWrapper.h:302
ros::ServiceServer getNodeDataSrv_
Definition: CoreWrapper.h:337
ros::ServiceServer getMapSrv_
Definition: CoreWrapper.h:341
ros::ServiceServer getGridMapSrv_
Definition: CoreWrapper.h:343
rtabmap::Rtabmap rtabmap_
Definition: CoreWrapper.h:250
data
ros::ServiceServer removeLabelSrv_
Definition: CoreWrapper.h:351
ros::Publisher localizationPosePub_
Definition: CoreWrapper.h:304
ros::Subscriber fiducialTransfromsSub_
Definition: CoreWrapper.h:376
rtabmap::Transform lastPublishedMetricGoal_
Definition: CoreWrapper.h:258
message_filters::Synchronizer< MyExactInterOdomSyncPolicy > * interOdomSync_
Definition: CoreWrapper.h:388
std::map< std::string, std::string > ParametersMap
ros::Publisher infoPub_
Definition: CoreWrapper.h:294
message_filters::sync_policies::ExactTime< nav_msgs::Odometry, rtabmap_ros::OdomInfo > MyExactInterOdomSyncPolicy
Definition: CoreWrapper.h:387
ros::ServiceServer getProbMapSrv_
Definition: CoreWrapper.h:342
ULogToRosout ulogToRosout_
Definition: CoreWrapper.h:400
ros::Publisher landmarksPub_
Definition: CoreWrapper.h:298
ros::Subscriber imuSub_
Definition: CoreWrapper.h:378
message_filters::Subscriber< rtabmap_ros::OdomInfo > interOdomInfoSyncSub_
Definition: CoreWrapper.h:386
ros::ServiceServer getMapData2Srv_
Definition: CoreWrapper.h:339
ros::ServiceServer cleanupLocalGridsSrv_
Definition: CoreWrapper.h:330
ros::Publisher nextMetricGoalPub_
Definition: CoreWrapper.h:310
ros::Subscriber initialPoseSub_
Definition: CoreWrapper.h:305
ros::Publisher mapDataPub_
Definition: CoreWrapper.h:295
ros::Subscriber globalPoseAsyncSub_
Definition: CoreWrapper.h:371
ros::Subscriber goalSub_
Definition: CoreWrapper.h:308
ros::ServiceServer globalBundleAdjustmentSrv_
Definition: CoreWrapper.h:329
ros::ServiceServer setModeMappingSrv_
Definition: CoreWrapper.h:332
ros::Subscriber userDataAsyncSub_
Definition: CoreWrapper.h:367
ros::ServiceServer updateSrv_
Definition: CoreWrapper.h:321
ros::ServiceServer backupDatabase_
Definition: CoreWrapper.h:327
ros::ServiceServer setLogInfoSrv_
Definition: CoreWrapper.h:334
std::map< std::string, float > rtabmapROSStats_
Definition: CoreWrapper.h:261
ros::Subscriber interOdomSub_
Definition: CoreWrapper.h:383
ros::ServiceServer setLabelSrv_
Definition: CoreWrapper.h:349
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: CoreWrapper.h:318
ros::Publisher localGridObstacle_
Definition: CoreWrapper.h:301
message_filters::Subscriber< nav_msgs::Odometry > interOdomSyncSub_
Definition: CoreWrapper.h:385
MoveBaseClient * mbClient_
Definition: CoreWrapper.h:359
boost::mutex mapToOdomMutex_
Definition: CoreWrapper.h:290
ros::ServiceServer cancelGoalSrv_
Definition: CoreWrapper.h:348
tf::TransformListener tfListener_
Definition: CoreWrapper.h:319
RecoveryProgressState state
rtabmap::Transform mapToOdom_
Definition: CoreWrapper.h:289
std::vector< float > lastPoseVelocity_
Definition: CoreWrapper.h:254
string frameId
Definition: patrol.py:11
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
Definition: CoreWrapper.h:95
ros::Publisher odomCachePub_
Definition: CoreWrapper.h:297
boost::thread * transformThread_
Definition: CoreWrapper.h:361
rtabmap::Transform currentMetricGoal_
Definition: CoreWrapper.h:257
ros::Subscriber goalNodeSub_
Definition: CoreWrapper.h:309
ros::ServiceServer listLabelsSrv_
Definition: CoreWrapper.h:350
ros::Publisher labelsPub_
Definition: CoreWrapper.h:299
ros::Publisher mapPathPub_
Definition: CoreWrapper.h:300
ros::ServiceServer getPlanNodesSrv_
Definition: CoreWrapper.h:346
ros::Publisher localPathPub_
Definition: CoreWrapper.h:313
std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > tags_
Definition: CoreWrapper.h:377
std::string groundTruthFrameId_
Definition: CoreWrapper.h:266
std::map< double, rtabmap::Transform > imus_
Definition: CoreWrapper.h:379
ros::ServiceServer loadDatabaseSrv_
Definition: CoreWrapper.h:325
ros::ServiceServer getPlanSrv_
Definition: CoreWrapper.h:345
std::list< std::pair< nav_msgs::Odometry, rtabmap_ros::OdomInfo > > interOdoms_
Definition: CoreWrapper.h:384
ros::ServiceServer setGoalSrv_
Definition: CoreWrapper.h:347
ros::Publisher globalPathPub_
Definition: CoreWrapper.h:312
res
std::string groundTruthBaseFrameId_
Definition: CoreWrapper.h:267
ros::ServiceServer setModeLocalizationSrv_
Definition: CoreWrapper.h:331
ros::Publisher goalReachedPub_
Definition: CoreWrapper.h:311
ros::ServiceServer triggerNewMapSrv_
Definition: CoreWrapper.h:326
ros::Publisher mapGraphPub_
Definition: CoreWrapper.h:296
ros::Publisher localGridGround_
Definition: CoreWrapper.h:303
ros::ServiceServer resumeSrv_
Definition: CoreWrapper.h:324


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