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_msgs/GetNodeData.h"
54 #include "rtabmap_msgs/GetMap.h"
55 #include "rtabmap_msgs/GetMap2.h"
56 #include "rtabmap_msgs/ListLabels.h"
57 #include "rtabmap_msgs/PublishMap.h"
58 #include "rtabmap_msgs/SetGoal.h"
59 #include "rtabmap_msgs/SetLabel.h"
60 #include "rtabmap_msgs/RemoveLabel.h"
61 #include "rtabmap_msgs/Goal.h"
62 #include "rtabmap_msgs/GetPlan.h"
64 #include "rtabmap_msgs/OdomInfo.h"
65 #include "rtabmap_msgs/AddLink.h"
66 #include "rtabmap_msgs/GetNodesInRadius.h"
67 #include "rtabmap_msgs/LoadDatabase.h"
68 #include "rtabmap_msgs/DetectMoreLoopClosures.h"
69 #include "rtabmap_msgs/GlobalBundleAdjustment.h"
70 #include "rtabmap_msgs/CleanupLocalGrids.h"
71 
74 
75 #ifdef WITH_OCTOMAP_MSGS
76 #include <octomap_msgs/GetOctomap.h>
77 #endif
78 
79 #ifdef WITH_APRILTAG_ROS
80 #include <apriltag_ros/AprilTagDetectionArray.h>
81 #endif
82 
83 //#define WITH_FIDUCIAL_MSGS
84 #ifdef WITH_FIDUCIAL_MSGS
85 #include <fiducial_msgs/FiducialTransformArray.h>
86 #endif
87 
89 #include <move_base_msgs/MoveBaseAction.h>
90 #include <move_base_msgs/MoveBaseActionGoal.h>
91 #include <move_base_msgs/MoveBaseActionResult.h>
92 #include <move_base_msgs/MoveBaseActionFeedback.h>
93 #include <actionlib_msgs/GoalStatusArray.h>
95 
96 namespace rtabmap {
97 class StereoDense;
98 }
99 
100 namespace rtabmap_slam {
101 
103 {
104 public:
105  CoreWrapper();
106  virtual ~CoreWrapper();
107 
108 private:
109 
110  virtual void onInit();
111 
112  bool odomUpdate(const nav_msgs::OdometryConstPtr & odomMsg, ros::Time stamp);
113  bool odomTFUpdate(const ros::Time & stamp); // TF odom
114 
115  virtual void commonMultiCameraCallback(
116  const nav_msgs::OdometryConstPtr & odomMsg,
117  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
118  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
119  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
120  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
121  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
122  const sensor_msgs::LaserScan& scanMsg,
123  const sensor_msgs::PointCloud2& scan3dMsg,
124  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
125  const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_msgs::GlobalDescriptor>(),
126  const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_msgs::KeyPoint> >(),
127  const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_msgs::Point3f> >(),
128  const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
130  const std::string & odomFrameId,
131  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
132  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
133  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
134  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
135  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
136  const sensor_msgs::LaserScan& scan2dMsg,
137  const sensor_msgs::PointCloud2& scan3dMsg,
138  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
139  const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs,
140  const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPoints,
141  const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3d,
142  const std::vector<cv::Mat> & localDescriptors);
143  virtual void commonLaserScanCallback(
144  const nav_msgs::OdometryConstPtr & odomMsg,
145  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
146  const sensor_msgs::LaserScan& scanMsg,
147  const sensor_msgs::PointCloud2& scan3dMsg,
148  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
149  const rtabmap_msgs::GlobalDescriptor & globalDescriptor = rtabmap_msgs::GlobalDescriptor());
150  virtual void commonOdomCallback(
151  const nav_msgs::OdometryConstPtr & odomMsg,
152  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
153  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg);
154  virtual void commonSensorDataCallback(
155  const rtabmap_msgs::SensorDataConstPtr & sensorDataMsg,
156  const nav_msgs::OdometryConstPtr & odomMsg,
157  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg);
158 
159  void defaultCallback(const sensor_msgs::ImageConstPtr & imageMsg); // no odom
160 
161  void userDataAsyncCallback(const rtabmap_msgs::UserDataConstPtr & dataMsg);
162  void globalPoseAsyncCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & globalPoseMsg);
163  void gpsFixAsyncCallback(const sensor_msgs::NavSatFixConstPtr & gpsFixMsg);
164 #ifdef WITH_APRILTAG_ROS
165  void tagDetectionsAsyncCallback(const apriltag_ros::AprilTagDetectionArray & tagDetections);
166 #endif
167 #ifdef WITH_FIDUCIAL_MSGS
168  void fiducialDetectionsAsyncCallback(const fiducial_msgs::FiducialTransformArray & fiducialDetections);
169 #endif
170  void imuAsyncCallback(const sensor_msgs::ImuConstPtr & tagDetections);
171  void republishNodeDataCallback(const std_msgs::Int32MultiArray::ConstPtr& msg);
172  void interOdomCallback(const nav_msgs::OdometryConstPtr & msg);
173  void interOdomInfoCallback(const nav_msgs::OdometryConstPtr & msg1, const rtabmap_msgs::OdomInfoConstPtr & msg2);
174 
175  void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & msg);
176 
177  void goalCommonCallback(int id,
178  const std::string & label,
179  const std::string & frameId,
180  const rtabmap::Transform & pose,
181  const ros::Time & stamp,
182  double * planningTime = 0);
183  void goalCallback(const geometry_msgs::PoseStampedConstPtr & msg);
184  void goalNodeCallback(const rtabmap_msgs::GoalConstPtr & msg);
185  void updateGoal(const ros::Time & stamp);
186 
187  void process(
188  const ros::Time & stamp,
190  const rtabmap::Transform & odom = rtabmap::Transform(),
191  const std::vector<float> & odomVelocity = std::vector<float>(),
192  const std::string & odomFrameId = "",
193  const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
194  const rtabmap::OdometryInfo & odomInfo = rtabmap::OdometryInfo(),
195  double timeMsgConversion = 0.0);
196  std::map<int, rtabmap::Transform> filterNodesToAssemble(
197  const std::map<int, rtabmap::Transform> & nodes,
198  const rtabmap::Transform & currentPose);
199 
200  bool updateRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
201  bool resetRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
202  bool pauseRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
203  bool resumeRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
204  bool loadDatabaseCallback(rtabmap_msgs::LoadDatabase::Request&, rtabmap_msgs::LoadDatabase::Response&);
205  bool triggerNewMapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
206  bool backupDatabaseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
207  bool detectMoreLoopClosuresCallback(rtabmap_msgs::DetectMoreLoopClosures::Request&, rtabmap_msgs::DetectMoreLoopClosures::Response&);
208  bool globalBundleAdjustmentCallback(rtabmap_msgs::GlobalBundleAdjustment::Request&, rtabmap_msgs::GlobalBundleAdjustment::Response&);
209  bool cleanupLocalGridsCallback(rtabmap_msgs::CleanupLocalGrids::Request&, rtabmap_msgs::CleanupLocalGrids::Response&);
210  bool setModeLocalizationCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
211  bool setModeMappingCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
212  bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
213  bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
214  bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
215  bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
216  bool getNodeDataCallback(rtabmap_msgs::GetNodeData::Request& req, rtabmap_msgs::GetNodeData::Response& res);
217  bool getMapDataCallback(rtabmap_msgs::GetMap::Request& req, rtabmap_msgs::GetMap::Response& res);
218  bool getMapData2Callback(rtabmap_msgs::GetMap2::Request& req, rtabmap_msgs::GetMap2::Response& res);
219  bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
220  bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
221  bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
222  bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
223  bool publishMapCallback(rtabmap_msgs::PublishMap::Request&, rtabmap_msgs::PublishMap::Response&);
224  bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res);
225  bool getPlanNodesCallback(rtabmap_msgs::GetPlan::Request &req, rtabmap_msgs::GetPlan::Response &res);
226  bool setGoalCallback(rtabmap_msgs::SetGoal::Request& req, rtabmap_msgs::SetGoal::Response& res);
227  bool cancelGoalCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
228  bool setLabelCallback(rtabmap_msgs::SetLabel::Request& req, rtabmap_msgs::SetLabel::Response& res);
229  bool listLabelsCallback(rtabmap_msgs::ListLabels::Request& req, rtabmap_msgs::ListLabels::Response& res);
230  bool removeLabelCallback(rtabmap_msgs::RemoveLabel::Request& req, rtabmap_msgs::RemoveLabel::Response& res);
231  bool addLinkCallback(rtabmap_msgs::AddLink::Request&, rtabmap_msgs::AddLink::Response&);
232  bool getNodesInRadiusCallback(rtabmap_msgs::GetNodesInRadius::Request&, rtabmap_msgs::GetNodesInRadius::Response&);
233 #ifdef WITH_OCTOMAP_MSGS
234  bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
235  bool octomapFullCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
236 #endif
237 
238  void loadParameters(const std::string & configFile, rtabmap::ParametersMap & parameters);
239  void saveParameters(const std::string & configFile);
240 
241  void publishLoop(double tfDelay, double tfTolerance);
242 
243  void publishStats(const ros::Time & stamp);
244  void publishCurrentGoal(const ros::Time & stamp);
245  void goalDoneCb(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result);
246  void goalActiveCb();
247  void goalFeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
248  void publishLocalPath(const ros::Time & stamp);
249  void publishGlobalPath(const ros::Time & stamp);
250  void republishMaps();
251 
252 private:
254  bool paused_;
257  std::vector<float> lastPoseVelocity_;
259  cv::Mat covariance_;
266  std::map<std::string, float> rtabmapROSStats_;
267 
268  std::string frameId_;
269  std::string odomFrameId_;
270  std::string mapFrameId_;
271  std::string groundTruthFrameId_;
273  std::string configPath_;
274  std::string databasePath_;
283  bool genScan_;
286  bool genDepth_;
293 
295  boost::mutex mapToOdomMutex_;
296 
298 
311 
312  //Planning stuff
321  std::string goalFrameId_;
322 
325 
359 #ifdef WITH_OCTOMAP_MSGS
360  ros::ServiceServer octomapBinarySrv_;
361  ros::ServiceServer octomapFullSrv_;
362 #endif
363 
365 
366  boost::thread* transformThread_;
368 
369  // for loop closure detection only
371 
373  cv::Mat userData_;
375 
377  geometry_msgs::PoseWithCovarianceStamped globalPose_;
382  std::map<int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> > tags_; // id, <pose, size>
384  std::map<double, rtabmap::Transform> imus_;
385  std::string imuFrameId_;
387 
389  std::list<std::pair<nav_msgs::Odometry, rtabmap_msgs::OdomInfo> > interOdoms_;
394 
397  float rate_;
404 
406 
408  {
409  public:
411  void setLocalizationThreshold(double value);
412  void updateStatus(const cv::Mat & covariance, bool twoDMapping);
414  private:
417  };
419 };
420 
421 }
422 
423 #endif /* COREWRAPPER_H_ */
424 
rtabmap_slam::CoreWrapper::loadParameters
void loadParameters(const std::string &configFile, rtabmap::ParametersMap &parameters)
Definition: CoreWrapper.cpp:899
rtabmap::SensorData
rtabmap_slam::CoreWrapper::publishLocalPath
void publishLocalPath(const ros::Time &stamp)
Definition: CoreWrapper.cpp:4463
rtabmap_slam::CoreWrapper::LocalizationStatusTask::updateStatus
void updateStatus(const cv::Mat &covariance, bool twoDMapping)
Definition: CoreWrapper.cpp:4571
rtabmap_slam::CoreWrapper::waitForTransformDuration_
double waitForTransformDuration_
Definition: CoreWrapper.h:280
rtabmap_slam::CoreWrapper::commonLaserScanCallback
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const rtabmap_msgs::GlobalDescriptor &globalDescriptor=rtabmap_msgs::GlobalDescriptor())
Definition: CoreWrapper.cpp:1562
rtabmap_slam::CoreWrapper::setLogError
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3313
rtabmap_slam::CoreWrapper::mapPathPub_
ros::Publisher mapPathPub_
Definition: CoreWrapper.h:305
rtabmap_slam::CoreWrapper::latestNodeWasReached_
bool latestNodeWasReached_
Definition: CoreWrapper.h:262
rtabmap_slam::CoreWrapper::goalNodeSub_
ros::Subscriber goalNodeSub_
Definition: CoreWrapper.h:314
rtabmap_slam::CoreWrapper::addLinkCallback
bool addLinkCallback(rtabmap_msgs::AddLink::Request &, rtabmap_msgs::AddLink::Response &)
Definition: CoreWrapper.cpp:4039
rtabmap_slam::CoreWrapper::gpsFixAsyncCallback
void gpsFixAsyncCallback(const sensor_msgs::NavSatFixConstPtr &gpsFixMsg)
Definition: CoreWrapper.cpp:2376
rtabmap_slam::CoreWrapper::LocalizationStatusTask::localizationThreshold_
double localizationThreshold_
Definition: CoreWrapper.h:415
msg
msg
ros::Publisher
rtabmap_slam::CoreWrapper::~CoreWrapper
virtual ~CoreWrapper()
Definition: CoreWrapper.cpp:868
rtabmap_slam::CoreWrapper::commonSensorDataCallback
virtual void commonSensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &sensorDataMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
Definition: CoreWrapper.cpp:1759
rtabmap_slam::CoreWrapper::globalPose_
geometry_msgs::PoseWithCovarianceStamped globalPose_
Definition: CoreWrapper.h:377
rtabmap_slam::CoreWrapper::setGoalSrv_
ros::ServiceServer setGoalSrv_
Definition: CoreWrapper.h:352
rtabmap_slam::CoreWrapper::landmarksPub_
ros::Publisher landmarksPub_
Definition: CoreWrapper.h:303
rtabmap_slam::CoreWrapper::genDepthFillHolesSize_
int genDepthFillHolesSize_
Definition: CoreWrapper.h:288
rtabmap_slam::CoreWrapper::process
void process(const ros::Time &stamp, rtabmap::SensorData &data, const rtabmap::Transform &odom=rtabmap::Transform(), const std::vector< float > &odomVelocity=std::vector< float >(), const std::string &odomFrameId="", const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const rtabmap::OdometryInfo &odomInfo=rtabmap::OdometryInfo(), double timeMsgConversion=0.0)
Definition: CoreWrapper.cpp:1801
rtabmap_slam::CoreWrapper::nextMetricGoalPub_
ros::Publisher nextMetricGoalPub_
Definition: CoreWrapper.h:315
message_filters::Synchronizer
rtabmap_slam::CoreWrapper::labelsPub_
ros::Publisher labelsPub_
Definition: CoreWrapper.h:304
rtabmap_slam::CoreWrapper::globalPathNodesPub_
ros::Publisher globalPathNodesPub_
Definition: CoreWrapper.h:319
rtabmap_slam::CoreWrapper::mappingMaxNodes_
int mappingMaxNodes_
Definition: CoreWrapper.h:399
rtabmap_slam::CoreWrapper::interOdomInfoSyncSub_
message_filters::Subscriber< rtabmap_msgs::OdomInfo > interOdomInfoSyncSub_
Definition: CoreWrapper.h:391
rtabmap_slam::CoreWrapper::parameters_
rtabmap::ParametersMap parameters_
Definition: CoreWrapper.h:265
rtabmap_slam::CoreWrapper::MyExactInterOdomSyncPolicy
message_filters::sync_policies::ExactTime< nav_msgs::Odometry, rtabmap_msgs::OdomInfo > MyExactInterOdomSyncPolicy
Definition: CoreWrapper.h:392
rtabmap_slam::CoreWrapper::frameId_
std::string frameId_
Definition: CoreWrapper.h:268
CommonDataSubscriber.h
rtabmap_slam::CoreWrapper::localPathNodesPub_
ros::Publisher localPathNodesPub_
Definition: CoreWrapper.h:320
rtabmap_slam::CoreWrapper::getProbMapCallback
bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: CoreWrapper.cpp:3487
rtabmap_slam::CoreWrapper::resumeSrv_
ros::ServiceServer resumeSrv_
Definition: CoreWrapper.h:329
rtabmap_slam::CoreWrapper::goalNodeCallback
void goalNodeCallback(const rtabmap_msgs::GoalConstPtr &msg)
Definition: CoreWrapper.cpp:2740
rtabmap_slam::CoreWrapper::removeLabelSrv_
ros::ServiceServer removeLabelSrv_
Definition: CoreWrapper.h:356
rtabmap_slam::CoreWrapper::setLabelSrv_
ros::ServiceServer setLabelSrv_
Definition: CoreWrapper.h:354
rtabmap_slam::CoreWrapper::genScanMaxDepth_
double genScanMaxDepth_
Definition: CoreWrapper.h:284
rtabmap_slam::CoreWrapper::interOdoms_
std::list< std::pair< nav_msgs::Odometry, rtabmap_msgs::OdomInfo > > interOdoms_
Definition: CoreWrapper.h:389
rtabmap_slam::CoreWrapper::genDepth_
bool genDepth_
Definition: CoreWrapper.h:286
rtabmap_slam::CoreWrapper::filterNodesToAssemble
std::map< int, rtabmap::Transform > filterNodesToAssemble(const std::map< int, rtabmap::Transform > &nodes, const rtabmap::Transform &currentPose)
Definition: CoreWrapper.cpp:2319
rtabmap_slam::CoreWrapper::scanCloudIs2d_
bool scanCloudIs2d_
Definition: CoreWrapper.h:292
ros.h
rtabmap_slam::CoreWrapper::userDataMutex_
UMutex userDataMutex_
Definition: CoreWrapper.h:374
rtabmap_slam::CoreWrapper::LocalizationStatusTask::run
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: CoreWrapper.cpp:4586
rtabmap_slam::CoreWrapper::publishCurrentGoal
void publishCurrentGoal(const ros::Time &stamp)
Definition: CoreWrapper.cpp:4354
rtabmap_slam::CoreWrapper::commonMultiCameraCallback
virtual void commonMultiCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_msgs::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())
Definition: CoreWrapper.cpp:1190
rtabmap_slam::CoreWrapper::lastPoseVelocity_
std::vector< float > lastPoseVelocity_
Definition: CoreWrapper.h:257
rtabmap_slam::CoreWrapper::localPathPub_
ros::Publisher localPathPub_
Definition: CoreWrapper.h:318
rtabmap_slam::CoreWrapper::globalBundleAdjustmentCallback
bool globalBundleAdjustmentCallback(rtabmap_msgs::GlobalBundleAdjustment::Request &, rtabmap_msgs::GlobalBundleAdjustment::Response &)
Definition: CoreWrapper.cpp:3225
actionlib::SimpleClientGoalState
rtabmap_slam::CoreWrapper::commonMultiCameraCallbackImpl
void commonMultiCameraCallbackImpl(const std::string &odomFrameId, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const sensor_msgs::LaserScan &scan2dMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs, const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPoints, const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3d, const std::vector< cv::Mat > &localDescriptors)
Definition: CoreWrapper.cpp:1262
rtabmap_slam::CoreWrapper::genDepthFillHolesError_
double genDepthFillHolesError_
Definition: CoreWrapper.h:290
rtabmap_slam::CoreWrapper::republishNodeDataCallback
void republishNodeDataCallback(const std_msgs::Int32MultiArray::ConstPtr &msg)
Definition: CoreWrapper.cpp:2505
rtabmap_slam::CoreWrapper::mbClient_
MoveBaseClient * mbClient_
Definition: CoreWrapper.h:364
rtabmap_slam::CoreWrapper::setLogWarnSrv_
ros::ServiceServer setLogWarnSrv_
Definition: CoreWrapper.h:340
rtabmap_slam::CoreWrapper::imuFrameId_
std::string imuFrameId_
Definition: CoreWrapper.h:385
rtabmap_slam::CoreWrapper::getNodesInRadiusSrv_
ros::ServiceServer getNodesInRadiusSrv_
Definition: CoreWrapper.h:358
rtabmap::GPS
rtabmap_slam::CoreWrapper::republishNodeDataSub_
ros::Subscriber republishNodeDataSub_
Definition: CoreWrapper.h:386
frameId
string frameId
rtabmap_slam::CoreWrapper::LocalizationStatusTask::LocalizationStatusTask
LocalizationStatusTask()
Definition: CoreWrapper.cpp:4560
rtabmap_slam::CoreWrapper::globalPoseAsyncSub_
ros::Subscriber globalPoseAsyncSub_
Definition: CoreWrapper.h:376
rtabmap_slam::CoreWrapper::configPath_
std::string configPath_
Definition: CoreWrapper.h:273
rtabmap_slam::CoreWrapper::globalBundleAdjustmentSrv_
ros::ServiceServer globalBundleAdjustmentSrv_
Definition: CoreWrapper.h:334
Rtabmap.h
rtabmap_util::MapsManager
rtabmap_slam::CoreWrapper::getProjMapSrv_
ros::ServiceServer getProjMapSrv_
Definition: CoreWrapper.h:345
rtabmap_slam::CoreWrapper::createIntermediateNodes_
bool createIntermediateNodes_
Definition: CoreWrapper.h:398
rtabmap_slam::CoreWrapper::cleanupLocalGridsCallback
bool cleanupLocalGridsCallback(rtabmap_msgs::CleanupLocalGrids::Request &, rtabmap_msgs::CleanupLocalGrids::Response &)
Definition: CoreWrapper.cpp:3175
rtabmap_slam::CoreWrapper::setModeMappingCallback
bool setModeMappingCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3283
rtabmap_slam::CoreWrapper::mapToOdom_
rtabmap::Transform mapToOdom_
Definition: CoreWrapper.h:294
res
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
rtabmap_slam::CoreWrapper::groundTruthFrameId_
std::string groundTruthFrameId_
Definition: CoreWrapper.h:271
rtabmap_slam::CoreWrapper::lastPublishedMetricGoal_
rtabmap::Transform lastPublishedMetricGoal_
Definition: CoreWrapper.h:261
rtabmap_slam::CoreWrapper::setLogErrorSrv_
ros::ServiceServer setLogErrorSrv_
Definition: CoreWrapper.h:341
rtabmap_slam::CoreWrapper::imus_
std::map< double, rtabmap::Transform > imus_
Definition: CoreWrapper.h:384
rtabmap_slam::CoreWrapper::setModeLocalizationCallback
bool setModeLocalizationCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3271
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
rtabmap_slam::CoreWrapper::initialPoseCallback
void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
Definition: CoreWrapper.cpp:2527
rtabmap_slam::CoreWrapper::listLabelsSrv_
ros::ServiceServer listLabelsSrv_
Definition: CoreWrapper.h:355
rtabmap_slam::CoreWrapper::resumeRtabmapCallback
bool resumeRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:2871
rtabmap_slam::CoreWrapper::setLogWarn
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3307
rtabmap_slam
Definition: CoreWrapper.h:100
rtabmap_slam::CoreWrapper::triggerNewMapSrv_
ros::ServiceServer triggerNewMapSrv_
Definition: CoreWrapper.h:331
rtabmap_slam::CoreWrapper::LocalizationStatusTask::setLocalizationThreshold
void setLocalizationThreshold(double value)
Definition: CoreWrapper.cpp:4566
rtabmap_slam::CoreWrapper::currentMetricGoal_
rtabmap::Transform currentMetricGoal_
Definition: CoreWrapper.h:260
rtabmap_slam::CoreWrapper::interOdomSync_
message_filters::Synchronizer< MyExactInterOdomSyncPolicy > * interOdomSync_
Definition: CoreWrapper.h:393
rtabmap_slam::CoreWrapper::previousStamp_
ros::Time previousStamp_
Definition: CoreWrapper.h:403
data
data
transform_broadcaster.h
rtabmap_slam::CoreWrapper::goalReachedPub_
ros::Publisher goalReachedPub_
Definition: CoreWrapper.h:316
message_filters::Subscriber< nav_msgs::Odometry >
ros::ServiceServer
rtabmap_slam::CoreWrapper::getNodeDataSrv_
ros::ServiceServer getNodeDataSrv_
Definition: CoreWrapper.h:342
rtabmap_slam::CoreWrapper::paused_
bool paused_
Definition: CoreWrapper.h:254
image_transport::Subscriber
rtabmap_slam::CoreWrapper::goalCommonCallback
void goalCommonCallback(int id, const std::string &label, const std::string &frameId, const rtabmap::Transform &pose, const ros::Time &stamp, double *planningTime=0)
Definition: CoreWrapper.cpp:2566
rtabmap_slam::CoreWrapper::detectMoreLoopClosuresCallback
bool detectMoreLoopClosuresCallback(rtabmap_msgs::DetectMoreLoopClosures::Request &, rtabmap_msgs::DetectMoreLoopClosures::Response &)
Definition: CoreWrapper.cpp:3107
MapsManager.h
rtabmap_slam::CoreWrapper::mapFrameId_
std::string mapFrameId_
Definition: CoreWrapper.h:270
rtabmap_slam::CoreWrapper::stereoToDepth_
bool stereoToDepth_
Definition: CoreWrapper.h:395
rtabmap_slam::CoreWrapper::odomUpdate
bool odomUpdate(const nav_msgs::OdometryConstPtr &odomMsg, ros::Time stamp)
Definition: CoreWrapper.cpp:1022
diagnostic_updater::DiagnosticTask
rtabmap_slam::CoreWrapper::twoDMapping_
bool twoDMapping_
Definition: CoreWrapper.h:402
actionlib::SimpleActionClient
rtabmap_slam::CoreWrapper::publishGlobalPath
void publishGlobalPath(const ros::Time &stamp)
Definition: CoreWrapper.cpp:4501
rtabmap_slam::CoreWrapper::initialPoseSub_
ros::Subscriber initialPoseSub_
Definition: CoreWrapper.h:310
rtabmap_slam::CoreWrapper::goalFeedbackCb
void goalFeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
Definition: CoreWrapper.cpp:4457
rtabmap_slam::CoreWrapper::scanCloudMaxPoints_
int scanCloudMaxPoints_
Definition: CoreWrapper.h:291
rtabmap_slam::CoreWrapper::goalDoneCb
void goalDoneCb(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
Definition: CoreWrapper.cpp:4405
rtabmap_slam::CoreWrapper::getMapSrv_
ros::ServiceServer getMapSrv_
Definition: CoreWrapper.h:346
rtabmap_slam::CoreWrapper::updateSrv_
ros::ServiceServer updateSrv_
Definition: CoreWrapper.h:326
rtabmap_slam::CoreWrapper::odomTFUpdate
bool odomTFUpdate(const ros::Time &stamp)
Definition: CoreWrapper.cpp:1133
rtabmap_slam::CoreWrapper::loadDatabaseSrv_
ros::ServiceServer loadDatabaseSrv_
Definition: CoreWrapper.h:330
rtabmap_slam::CoreWrapper::getPlanNodesCallback
bool getPlanNodesCallback(rtabmap_msgs::GetPlan::Request &req, rtabmap_msgs::GetPlan::Response &res)
Definition: CoreWrapper.cpp:3849
rtabmap_slam::CoreWrapper::updateRtabmapCallback
bool updateRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:2756
rtabmap_slam::CoreWrapper::rate_
float rate_
Definition: CoreWrapper.h:397
rtabmap_slam::CoreWrapper::mappingAltitudeDelta_
double mappingAltitudeDelta_
Definition: CoreWrapper.h:400
rtabmap_slam::CoreWrapper::getMapData2Srv_
ros::ServiceServer getMapData2Srv_
Definition: CoreWrapper.h:344
UMutex
rtabmap_slam::CoreWrapper::cancelGoalSrv_
ros::ServiceServer cancelGoalSrv_
Definition: CoreWrapper.h:353
simple_action_client.h
rtabmap_slam::CoreWrapper::mapToOdomMutex_
boost::mutex mapToOdomMutex_
Definition: CoreWrapper.h:295
rtabmap_slam::CoreWrapper::globalPoseAsyncCallback
void globalPoseAsyncCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &globalPoseMsg)
Definition: CoreWrapper.cpp:2368
rtabmap_slam::CoreWrapper::fiducialTransfromsSub_
ros::Subscriber fiducialTransfromsSub_
Definition: CoreWrapper.h:381
rtabmap_slam::CoreWrapper::publishMapDataSrv_
ros::ServiceServer publishMapDataSrv_
Definition: CoreWrapper.h:349
rtabmap_slam::CoreWrapper::graphLatched_
bool graphLatched_
Definition: CoreWrapper.h:264
rtabmap_slam::CoreWrapper::landmarkDefaultLinVariance_
double landmarkDefaultLinVariance_
Definition: CoreWrapper.h:278
rtabmap_slam::CoreWrapper::gpsFixAsyncSub_
ros::Subscriber gpsFixAsyncSub_
Definition: CoreWrapper.h:378
rtabmap_slam::CoreWrapper::getPlanSrv_
ros::ServiceServer getPlanSrv_
Definition: CoreWrapper.h:350
rtabmap_slam::CoreWrapper::odomDefaultLinVariance_
double odomDefaultLinVariance_
Definition: CoreWrapper.h:276
rtabmap_slam::CoreWrapper::resetSrv_
ros::ServiceServer resetSrv_
Definition: CoreWrapper.h:327
rtabmap_slam::CoreWrapper::getMapCallback
bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: CoreWrapper.cpp:3446
rtabmap_slam::CoreWrapper::transformThread_
boost::thread * transformThread_
Definition: CoreWrapper.h:366
rtabmap_slam::CoreWrapper::tfBroadcaster_
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: CoreWrapper.h:323
rtabmap_slam::CoreWrapper::genScan_
bool genScan_
Definition: CoreWrapper.h:283
rtabmap_slam::CoreWrapper::userDataAsyncSub_
ros::Subscriber userDataAsyncSub_
Definition: CoreWrapper.h:372
rtabmap_slam::CoreWrapper::loadDatabaseCallback
bool loadDatabaseCallback(rtabmap_msgs::LoadDatabase::Request &, rtabmap_msgs::LoadDatabase::Response &)
Definition: CoreWrapper.cpp:2886
rtabmap_slam::CoreWrapper::odomDefaultAngVariance_
double odomDefaultAngVariance_
Definition: CoreWrapper.h:275
rtabmap_slam::CoreWrapper::publishMapCallback
bool publishMapCallback(rtabmap_msgs::PublishMap::Request &, rtabmap_msgs::PublishMap::Response &)
Definition: CoreWrapper.cpp:3528
rtabmap_slam::CoreWrapper::setModeLocalizationSrv_
ros::ServiceServer setModeLocalizationSrv_
Definition: CoreWrapper.h:336
rtabmap_slam::CoreWrapper::setLogInfo
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3301
rtabmap_slam::CoreWrapper::defaultCallback
void defaultCallback(const sensor_msgs::ImageConstPtr &imageMsg)
Definition: CoreWrapper.cpp:953
rtabmap_slam::CoreWrapper::mapGraphPub_
ros::Publisher mapGraphPub_
Definition: CoreWrapper.h:301
rtabmap_slam::CoreWrapper::localGridObstacle_
ros::Publisher localGridObstacle_
Definition: CoreWrapper.h:306
rtabmap_slam::CoreWrapper::republishMaps
void republishMaps()
Definition: CoreWrapper.cpp:3070
rtabmap_slam::CoreWrapper::groundTruthBaseFrameId_
std::string groundTruthBaseFrameId_
Definition: CoreWrapper.h:272
rtabmap_slam::CoreWrapper::interOdomInfoCallback
void interOdomInfoCallback(const nav_msgs::OdometryConstPtr &msg1, const rtabmap_msgs::OdomInfoConstPtr &msg2)
Definition: CoreWrapper.cpp:2518
rtabmap_slam::CoreWrapper::updateGoal
void updateGoal(const ros::Time &stamp)
rtabmap_slam::CoreWrapper::goalActiveCb
void goalActiveCb()
Definition: CoreWrapper.cpp:4451
rtabmap_slam::CoreWrapper::setLogDebugSrv_
ros::ServiceServer setLogDebugSrv_
Definition: CoreWrapper.h:338
rtabmap_slam::CoreWrapper::interOdomCallback
void interOdomCallback(const nav_msgs::OdometryConstPtr &msg)
Definition: CoreWrapper.cpp:2510
rtabmap_slam::CoreWrapper::localGridGround_
ros::Publisher localGridGround_
Definition: CoreWrapper.h:308
rtabmap_slam::CoreWrapper::mapDataPub_
ros::Publisher mapDataPub_
Definition: CoreWrapper.h:300
rtabmap_slam::CoreWrapper::detectMoreLoopClosuresSrv_
ros::ServiceServer detectMoreLoopClosuresSrv_
Definition: CoreWrapper.h:333
rtabmap_slam::CoreWrapper::alreadyRectifiedImages_
bool alreadyRectifiedImages_
Definition: CoreWrapper.h:401
rtabmap_slam::CoreWrapper::lastPose_
rtabmap::Transform lastPose_
Definition: CoreWrapper.h:255
rtabmap_slam::CoreWrapper::publishStats
void publishStats(const ros::Time &stamp)
Definition: CoreWrapper.cpp:4083
rtabmap_slam::CoreWrapper::useSavedMap_
bool useSavedMap_
Definition: CoreWrapper.h:282
rtabmap_slam::CoreWrapper::pubLocPoseOnlyWhenLocalizing_
bool pubLocPoseOnlyWhenLocalizing_
Definition: CoreWrapper.h:263
rtabmap_slam::CoreWrapper::pauseRtabmapCallback
bool pauseRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:2856
nodes
KeyVector nodes
rtabmap_slam::CoreWrapper::CoreWrapper
CoreWrapper()
Definition: CoreWrapper.cpp:87
rtabmap_slam::CoreWrapper::LocalizationStatusTask
Definition: CoreWrapper.h:407
rtabmap_slam::CoreWrapper::listLabelsCallback
bool listLabelsCallback(rtabmap_msgs::ListLabels::Request &req, rtabmap_msgs::ListLabels::Response &res)
Definition: CoreWrapper.cpp:4006
rtabmap_slam::CoreWrapper::getGridMapCallback
bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: CoreWrapper.cpp:3440
rtabmap_slam::CoreWrapper::userData_
cv::Mat userData_
Definition: CoreWrapper.h:373
transform_listener.h
rtabmap_slam::CoreWrapper::imuAsyncCallback
void imuAsyncCallback(const sensor_msgs::ImuConstPtr &tagDetections)
Definition: CoreWrapper.cpp:2470
rtabmap_slam::CoreWrapper::interOdomSub_
ros::Subscriber interOdomSub_
Definition: CoreWrapper.h:388
rtabmap::Transform
rtabmap_slam::CoreWrapper::publishLoop
void publishLoop(double tfDelay, double tfTolerance)
Definition: CoreWrapper.cpp:930
rtabmap_slam::CoreWrapper::infoPub_
ros::Publisher infoPub_
Definition: CoreWrapper.h:299
rtabmap_slam::CoreWrapper::getNodesInRadiusCallback
bool getNodesInRadiusCallback(rtabmap_msgs::GetNodesInRadius::Request &, rtabmap_msgs::GetNodesInRadius::Response &)
Definition: CoreWrapper.cpp:4050
rtabmap_slam::CoreWrapper::localizationDiagnostic_
LocalizationStatusTask localizationDiagnostic_
Definition: CoreWrapper.h:418
rtabmap_slam::CoreWrapper::LocalizationStatusTask::localizationError_
double localizationError_
Definition: CoreWrapper.h:416
rtabmap_slam::CoreWrapper::lastPoseIntermediate_
bool lastPoseIntermediate_
Definition: CoreWrapper.h:258
OdometryInfo.h
rtabmap_slam::CoreWrapper::genDepthDecimation_
int genDepthDecimation_
Definition: CoreWrapper.h:287
rtabmap_slam::CoreWrapper::tags_
std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > tags_
Definition: CoreWrapper.h:382
nodelet::Nodelet
rtabmap_slam::CoreWrapper::getGridMapSrv_
ros::ServiceServer getGridMapSrv_
Definition: CoreWrapper.h:348
rtabmap_slam::CoreWrapper::tfListener_
tf::TransformListener tfListener_
Definition: CoreWrapper.h:324
ros::Time
rtabmap_slam::CoreWrapper::odomFrameId_
std::string odomFrameId_
Definition: CoreWrapper.h:269
rtabmap_slam::CoreWrapper::triggerNewMapCallback
bool triggerNewMapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3020
rtabmap_slam::CoreWrapper::getPlanCallback
bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res)
Definition: CoreWrapper.cpp:3775
rtabmap_slam::CoreWrapper::removeLabelCallback
bool removeLabelCallback(rtabmap_msgs::RemoveLabel::Request &req, rtabmap_msgs::RemoveLabel::Response &res)
Definition: CoreWrapper.cpp:4018
rtabmap_slam::CoreWrapper::setGoalCallback
bool setGoalCallback(rtabmap_msgs::SetGoal::Request &req, rtabmap_msgs::SetGoal::Response &res)
Definition: CoreWrapper.cpp:3938
nodelet.h
rtabmap_slam::CoreWrapper::defaultSub_
image_transport::Subscriber defaultSub_
Definition: CoreWrapper.h:370
rtabmap_slam::CoreWrapper::mapsManager_
rtabmap_util::MapsManager mapsManager_
Definition: CoreWrapper.h:297
rtabmap_slam::CoreWrapper::odomCachePub_
ros::Publisher odomCachePub_
Definition: CoreWrapper.h:302
rtabmap_slam::CoreWrapper::tfThreadRunning_
bool tfThreadRunning_
Definition: CoreWrapper.h:367
rtabmap_slam::CoreWrapper::goalFrameId_
std::string goalFrameId_
Definition: CoreWrapper.h:321
rtabmap_slam::CoreWrapper::setLogDebug
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3295
rtabmap_slam::CoreWrapper::commonOdomCallback
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
Definition: CoreWrapper.cpp:1700
rtabmap_slam::CoreWrapper::pauseSrv_
ros::ServiceServer pauseSrv_
Definition: CoreWrapper.h:328
rtabmap_slam::CoreWrapper::genDepthFillIterations_
int genDepthFillIterations_
Definition: CoreWrapper.h:289
rtabmap_slam::CoreWrapper::rtabmapROSStats_
std::map< std::string, float > rtabmapROSStats_
Definition: CoreWrapper.h:266
rtabmap_slam::CoreWrapper::goalSub_
ros::Subscriber goalSub_
Definition: CoreWrapper.h:313
rtabmap_slam::CoreWrapper::interOdomSyncSub_
message_filters::Subscriber< nav_msgs::Odometry > interOdomSyncSub_
Definition: CoreWrapper.h:390
rtabmap_slam::CoreWrapper::saveParameters
void saveParameters(const std::string &configFile)
Definition: CoreWrapper.cpp:912
rtabmap_slam::CoreWrapper::getProjMapCallback
bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: CoreWrapper.cpp:3422
tf2_ros::TransformBroadcaster
rtabmap_slam::CoreWrapper::setModeMappingSrv_
ros::ServiceServer setModeMappingSrv_
Definition: CoreWrapper.h:337
tf::TransformListener
rtabmap_slam::CoreWrapper::genScanMinDepth_
double genScanMinDepth_
Definition: CoreWrapper.h:285
rtabmap::OdometryInfo
diagnostic_updater::DiagnosticStatusWrapper
rtabmap_slam::CoreWrapper::localizationPosePub_
ros::Publisher localizationPosePub_
Definition: CoreWrapper.h:309
rtabmap_slam::CoreWrapper::cancelGoalCallback
bool cancelGoalCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: CoreWrapper.cpp:3954
rtabmap_slam::CoreWrapper::getNodeDataCallback
bool getNodeDataCallback(rtabmap_msgs::GetNodeData::Request &req, rtabmap_msgs::GetNodeData::Response &res)
Definition: CoreWrapper.cpp:3320
rtabmap_slam::CoreWrapper::getMapDataCallback
bool getMapDataCallback(rtabmap_msgs::GetMap::Request &req, rtabmap_msgs::GetMap::Response &res)
Definition: CoreWrapper.cpp:3349
rtabmap_slam::CoreWrapper::globalPathPub_
ros::Publisher globalPathPub_
Definition: CoreWrapper.h:317
rtabmap_slam::CoreWrapper
Definition: CoreWrapper.h:102
rtabmap_slam::CoreWrapper::tagDetectionsSub_
ros::Subscriber tagDetectionsSub_
Definition: CoreWrapper.h:380
Parameters.h
rtabmap::Rtabmap
rtabmap_slam::CoreWrapper::onInit
virtual void onInit()
Definition: CoreWrapper.cpp:140
rtabmap_slam::CoreWrapper::ulogToRosout_
rtabmap_util::ULogToRosout ulogToRosout_
Definition: CoreWrapper.h:405
rtabmap_slam::CoreWrapper::gps_
rtabmap::GPS gps_
Definition: CoreWrapper.h:379
MoveBaseClient
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
Definition: CoreWrapper.h:94
rtabmap_slam::CoreWrapper::getMapData2Callback
bool getMapData2Callback(rtabmap_msgs::GetMap2::Request &req, rtabmap_msgs::GetMap2::Response &res)
Definition: CoreWrapper.cpp:3383
rtabmap_util::ULogToRosout
rtabmap_slam::CoreWrapper::databasePath_
std::string databasePath_
Definition: CoreWrapper.h:274
rtabmap_slam::CoreWrapper::goalCallback
void goalCallback(const geometry_msgs::PoseStampedConstPtr &msg)
Definition: CoreWrapper.cpp:2713
rtabmap_slam::CoreWrapper::setLogInfoSrv_
ros::ServiceServer setLogInfoSrv_
Definition: CoreWrapper.h:339
rtabmap_slam::CoreWrapper::getPlanNodesSrv_
ros::ServiceServer getPlanNodesSrv_
Definition: CoreWrapper.h:351
message_filters::sync_policies::ExactTime
rtabmap_slam::CoreWrapper::setLabelCallback
bool setLabelCallback(rtabmap_msgs::SetLabel::Request &req, rtabmap_msgs::SetLabel::Response &res)
Definition: CoreWrapper.cpp:3979
rtabmap
rtabmap_slam::CoreWrapper::getMapDataSrv_
ros::ServiceServer getMapDataSrv_
Definition: CoreWrapper.h:343
rtabmap_slam::CoreWrapper::landmarkDefaultAngVariance_
double landmarkDefaultAngVariance_
Definition: CoreWrapper.h:277
rtabmap_slam::CoreWrapper::getProbMapSrv_
ros::ServiceServer getProbMapSrv_
Definition: CoreWrapper.h:347
value
value
rtabmap_slam::CoreWrapper::userDataAsyncCallback
void userDataAsyncCallback(const rtabmap_msgs::UserDataConstPtr &dataMsg)
Definition: CoreWrapper.cpp:2349
rtabmap_slam::CoreWrapper::useActionForGoal_
bool useActionForGoal_
Definition: CoreWrapper.h:281
rtabmap_slam::CoreWrapper::odomSensorSync_
bool odomSensorSync_
Definition: CoreWrapper.h:396
rtabmap_slam::CoreWrapper::resetRtabmapCallback
bool resetRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:2825
result
RESULT & result
rtabmap_slam::CoreWrapper::addLinkSrv_
ros::ServiceServer addLinkSrv_
Definition: CoreWrapper.h:357
rtabmap_slam::CoreWrapper::waitForTransform_
bool waitForTransform_
Definition: CoreWrapper.h:279
ULogToRosout.h
rtabmap_slam::CoreWrapper::covariance_
cv::Mat covariance_
Definition: CoreWrapper.h:259
rtabmap_sync::CommonDataSubscriber
rtabmap_slam::CoreWrapper::cleanupLocalGridsSrv_
ros::ServiceServer cleanupLocalGridsSrv_
Definition: CoreWrapper.h:335
ros::Subscriber
rtabmap_slam::CoreWrapper::rtabmap_
rtabmap::Rtabmap rtabmap_
Definition: CoreWrapper.h:253
rtabmap_slam::CoreWrapper::lastPoseStamp_
ros::Time lastPoseStamp_
Definition: CoreWrapper.h:256
rtabmap_slam::CoreWrapper::localGridEmpty_
ros::Publisher localGridEmpty_
Definition: CoreWrapper.h:307
state
state
rtabmap_slam::CoreWrapper::backupDatabase_
ros::ServiceServer backupDatabase_
Definition: CoreWrapper.h:332
rtabmap_slam::CoreWrapper::imuSub_
ros::Subscriber imuSub_
Definition: CoreWrapper.h:383
rtabmap_slam::CoreWrapper::backupDatabaseCallback
bool backupDatabaseCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: CoreWrapper.cpp:3027


rtabmap_slam
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:43:58