Public Member Functions | Private Member Functions | Private Attributes
rtabmap_ros::CoreWrapper Class Reference

#include <CoreWrapper.h>

Inheritance diagram for rtabmap_ros::CoreWrapper:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 CoreWrapper ()
virtual ~CoreWrapper ()

Private Member Functions

bool backupDatabaseCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool cancelGoalCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual void commonDepthCallback (const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
void commonDepthCallbackImpl (const std::string &odomFrameId, const rtabmap_ros::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const sensor_msgs::LaserScanConstPtr &scan2dMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
virtual void commonStereoCallback (const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
 DATA_SYNCS2 (rgb, sensor_msgs::Image, sensor_msgs::CameraInfo)
 DATA_SYNCS3 (rgbOdom, sensor_msgs::Image, sensor_msgs::CameraInfo, nav_msgs::Odometry)
void defaultCallback (const sensor_msgs::ImageConstPtr &imageMsg)
bool getGridMapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
bool getMapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
bool getMapDataCallback (rtabmap_ros::GetMap::Request &req, rtabmap_ros::GetMap::Response &res)
bool getPlanCallback (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res)
bool getProbMapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
bool getProjMapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void globalPoseAsyncCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &globalPoseMsg)
void goalActiveCb ()
void goalCallback (const geometry_msgs::PoseStampedConstPtr &msg)
void goalCommonCallback (int id, const std::string &label, const rtabmap::Transform &pose, const ros::Time &stamp, double *planningTime=0)
void goalDoneCb (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
void goalFeedbackCb (const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
void goalNodeCallback (const rtabmap_ros::GoalConstPtr &msg)
void initialPoseCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
bool listLabelsCallback (rtabmap_ros::ListLabels::Request &req, rtabmap_ros::ListLabels::Response &res)
void loadParameters (const std::string &configFile, rtabmap::ParametersMap &parameters)
bool odomTFUpdate (const ros::Time &stamp)
bool odomUpdate (const nav_msgs::OdometryConstPtr &odomMsg, ros::Time stamp)
virtual void onInit ()
bool pauseRtabmapCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void process (const ros::Time &stamp, const rtabmap::SensorData &data, const rtabmap::Transform &odom=rtabmap::Transform(), const std::string &odomFrameId="", const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const rtabmap::OdometryInfo &odomInfo=rtabmap::OdometryInfo())
void publishCurrentGoal (const ros::Time &stamp)
void publishGlobalPath (const ros::Time &stamp)
void publishLocalPath (const ros::Time &stamp)
void publishLoop (double tfDelay, double tfTolerance)
bool publishMapCallback (rtabmap_ros::PublishMap::Request &, rtabmap_ros::PublishMap::Response &)
void publishStats (const ros::Time &stamp)
bool resetRtabmapCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool resumeRtabmapCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void saveParameters (const std::string &configFile)
bool setGoalCallback (rtabmap_ros::SetGoal::Request &req, rtabmap_ros::SetGoal::Response &res)
bool setLabelCallback (rtabmap_ros::SetLabel::Request &req, rtabmap_ros::SetLabel::Response &res)
bool setLogDebug (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setLogError (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setLogInfo (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setLogWarn (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setModeLocalizationCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setModeMappingCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool triggerNewMapCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void updateGoal (const ros::Time &stamp)
bool updateRtabmapCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void userDataAsyncCallback (const rtabmap_ros::UserDataConstPtr &dataMsg)

Private Attributes

ros::ServiceServer backupDatabase_
ros::ServiceServer cancelGoalSrv_
std::string configPath_
cv::Mat covariance_
bool createIntermediateNodes_
rtabmap::Transform currentMetricGoal_
std::string databasePath_
image_transport::Subscriber defaultSub_
std::string frameId_
bool genScan_
double genScanMaxDepth_
double genScanMinDepth_
ros::ServiceServer getGridMapSrv_
ros::ServiceServer getMapDataSrv_
ros::ServiceServer getMapSrv_
ros::ServiceServer getPlanSrv_
ros::ServiceServer getProbMapSrv_
ros::ServiceServer getProjMapSrv_
ros::Publisher globalPathPub_
geometry_msgs::PoseWithCovarianceStamped globalPose_
ros::Subscriber globalPoseAsyncSub_
ros::Subscriber goalNodeSub_
ros::Publisher goalReachedPub_
ros::Subscriber goalSub_
std::string groundTruthBaseFrameId_
std::string groundTruthFrameId_
ros::Publisher infoPub_
ros::Subscriber initialPoseSub_
ros::Publisher labelsPub_
rtabmap::Transform lastPose_
bool lastPoseIntermediate_
ros::Time lastPoseStamp_
rtabmap::Transform lastPublishedMetricGoal_
bool latestNodeWasReached_
ros::ServiceServer listLabelsSrv_
ros::Publisher localizationPosePub_
ros::Publisher localPathPub_
ros::Publisher mapDataPub_
std::string mapFrameId_
ros::Publisher mapGraphPub_
ros::Publisher mapPathPub_
MapsManager mapsManager_
rtabmap::Transform mapToOdom_
boost::mutex mapToOdomMutex_
int maxMappingNodes_
MoveBaseClient mbClient_
ros::Publisher nextMetricGoalPub_
double odomDefaultAngVariance_
double odomDefaultLinVariance_
std::string odomFrameId_
bool odomSensorSync_
rtabmap::ParametersMap parameters_
bool paused_
ros::ServiceServer pauseSrv_
ros::Time previousStamp_
ros::ServiceServer publishMapDataSrv_
float rate_
ros::ServiceServer resetSrv_
ros::ServiceServer resumeSrv_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
rgbCameraInfoSub_
message_filters::Subscriber
< nav_msgs::Odometry > 
rgbOdomSub_
image_transport::SubscriberFilter rgbSub_
rtabmap::Rtabmap rtabmap_
std::map< std::string, float > rtabmapROSStats_
int scanCloudMaxPoints_
ros::ServiceServer setGoalSrv_
ros::ServiceServer setLabelSrv_
ros::ServiceServer setLogDebugSrv_
ros::ServiceServer setLogErrorSrv_
ros::ServiceServer setLogInfoSrv_
ros::ServiceServer setLogWarnSrv_
ros::ServiceServer setModeLocalizationSrv_
ros::ServiceServer setModeMappingSrv_
bool stereoToDepth_
tf2_ros::TransformBroadcaster tfBroadcaster_
tf::TransformListener tfListener_
bool tfThreadRunning_
ros::Time time_
boost::thread * transformThread_
ros::ServiceServer triggerNewMapSrv_
ros::ServiceServer updateSrv_
bool useActionForGoal_
cv::Mat userData_
ros::Subscriber userDataAsyncSub_
UMutex userDataMutex_
bool useSavedMap_
bool waitForTransform_
double waitForTransformDuration_

Detailed Description

Definition at line 78 of file CoreWrapper.h.


Constructor & Destructor Documentation

Definition at line 84 of file CoreWrapper.cpp.

Definition at line 648 of file CoreWrapper.cpp.


Member Function Documentation

bool rtabmap_ros::CoreWrapper::backupDatabaseCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2023 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::cancelGoalCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [private]

Definition at line 2517 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::commonDepthCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_ros::UserDataConstPtr &  userDataMsg,
const std::vector< cv_bridge::CvImageConstPtr > &  imageMsgs,
const std::vector< cv_bridge::CvImageConstPtr > &  depthMsgs,
const std::vector< sensor_msgs::CameraInfo > &  cameraInfoMsgs,
const sensor_msgs::LaserScanConstPtr &  scanMsg,
const sensor_msgs::PointCloud2ConstPtr &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg 
) [private, virtual]

Implements rtabmap_ros::CommonDataSubscriber.

Definition at line 980 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::commonDepthCallbackImpl ( const std::string &  odomFrameId,
const rtabmap_ros::UserDataConstPtr &  userDataMsg,
const std::vector< cv_bridge::CvImageConstPtr > &  imageMsgs,
const std::vector< cv_bridge::CvImageConstPtr > &  depthMsgs,
const std::vector< sensor_msgs::CameraInfo > &  cameraInfoMsgs,
const sensor_msgs::LaserScanConstPtr &  scan2dMsg,
const sensor_msgs::PointCloud2ConstPtr &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg 
) [private]

Definition at line 1042 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::commonStereoCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_ros::UserDataConstPtr &  userDataMsg,
const cv_bridge::CvImageConstPtr leftImageMsg,
const cv_bridge::CvImageConstPtr rightImageMsg,
const sensor_msgs::CameraInfo &  leftCamInfoMsg,
const sensor_msgs::CameraInfo &  rightCamInfoMsg,
const sensor_msgs::LaserScanConstPtr &  scanMsg,
const sensor_msgs::PointCloud2ConstPtr &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg 
) [private, virtual]

Implements rtabmap_ros::CommonDataSubscriber.

Definition at line 1237 of file CoreWrapper.cpp.

rtabmap_ros::CoreWrapper::DATA_SYNCS2 ( rgb  ,
sensor_msgs::Image  ,
sensor_msgs::CameraInfo   
) [private]
rtabmap_ros::CoreWrapper::DATA_SYNCS3 ( rgbOdom  ,
sensor_msgs::Image  ,
sensor_msgs::CameraInfo  ,
nav_msgs::Odometry   
) [private]
void rtabmap_ros::CoreWrapper::defaultCallback ( const sensor_msgs::ImageConstPtr &  imageMsg) [private]

Definition at line 740 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getGridMapCallback ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
) [private]

Definition at line 2157 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getMapCallback ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
) [private]

Definition at line 2163 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getMapDataCallback ( rtabmap_ros::GetMap::Request &  req,
rtabmap_ros::GetMap::Response &  res 
) [private]

Definition at line 2097 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getPlanCallback ( nav_msgs::GetPlan::Request &  req,
nav_msgs::GetPlan::Response &  res 
) [private]

Definition at line 2433 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getProbMapCallback ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
) [private]

Definition at line 2196 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getProjMapCallback ( nav_msgs::GetMap::Request &  req,
nav_msgs::GetMap::Response &  res 
) [private]

Definition at line 2139 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::globalPoseAsyncCallback ( const geometry_msgs::PoseWithCovarianceStampedConstPtr &  globalPoseMsg) [private]

Definition at line 1742 of file CoreWrapper.cpp.

Definition at line 2822 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::goalCallback ( const geometry_msgs::PoseStampedConstPtr &  msg) [private]

Definition at line 1889 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::goalCommonCallback ( int  id,
const std::string &  label,
const rtabmap::Transform pose,
const ros::Time stamp,
double *  planningTime = 0 
) [private]

Definition at line 1762 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::goalDoneCb ( const actionlib::SimpleClientGoalState state,
const move_base_msgs::MoveBaseResultConstPtr &  result 
) [private]

Definition at line 2777 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::goalFeedbackCb ( const move_base_msgs::MoveBaseFeedbackConstPtr &  feedback) [private]

Definition at line 2828 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::goalNodeCallback ( const rtabmap_ros::GoalConstPtr &  msg) [private]

Definition at line 1914 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::initialPoseCallback ( const geometry_msgs::PoseWithCovarianceStampedConstPtr &  msg) [private]

Definition at line 1750 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::listLabelsCallback ( rtabmap_ros::ListLabels::Request &  req,
rtabmap_ros::ListLabels::Response &  res 
) [private]

Definition at line 2568 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::loadParameters ( const std::string &  configFile,
rtabmap::ParametersMap parameters 
) [private]

Definition at line 686 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::odomTFUpdate ( const ros::Time stamp) [private]

Definition at line 927 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::odomUpdate ( const nav_msgs::OdometryConstPtr &  odomMsg,
ros::Time  stamp 
) [private]

Definition at line 829 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::onInit ( ) [private, virtual]

Implements nodelet::Nodelet.

Definition at line 124 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::pauseRtabmapCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 1984 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::process ( const ros::Time stamp,
const rtabmap::SensorData data,
const rtabmap::Transform odom = rtabmap::Transform(),
const std::string &  odomFrameId = "",
const cv::Mat &  odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
const rtabmap::OdometryInfo odomInfo = rtabmap::OdometryInfo() 
) [private]

Definition at line 1458 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::publishCurrentGoal ( const ros::Time stamp) [private]

Definition at line 2730 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::publishGlobalPath ( const ros::Time stamp) [private]

Definition at line 2860 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::publishLocalPath ( const ros::Time stamp) [private]

Definition at line 2834 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::publishLoop ( double  tfDelay,
double  tfTolerance 
) [private]

Definition at line 717 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::publishMapCallback ( rtabmap_ros::PublishMap::Request &  req,
rtabmap_ros::PublishMap::Response &  res 
) [private]

Definition at line 2229 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::publishStats ( const ros::Time stamp) [private]

Definition at line 2579 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::resetRtabmapCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 1965 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::resumeRtabmapCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2000 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::saveParameters ( const std::string &  configFile) [private]

Definition at line 699 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setGoalCallback ( rtabmap_ros::SetGoal::Request &  req,
rtabmap_ros::SetGoal::Response &  res 
) [private]

Definition at line 2501 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setLabelCallback ( rtabmap_ros::SetLabel::Request &  req,
rtabmap_ros::SetLabel::Response &  res 
) [private]

Definition at line 2541 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setLogDebug ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2072 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setLogError ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2090 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setLogInfo ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2078 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setLogWarn ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2084 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setModeLocalizationCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2050 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::setModeMappingCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2061 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::triggerNewMapCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 2016 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::updateGoal ( const ros::Time stamp) [private]
bool rtabmap_ros::CoreWrapper::updateRtabmapCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
) [private]

Definition at line 1924 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::userDataAsyncCallback ( const rtabmap_ros::UserDataConstPtr &  dataMsg) [private]

Definition at line 1726 of file CoreWrapper.cpp.


Member Data Documentation

Definition at line 241 of file CoreWrapper.h.

Definition at line 256 of file CoreWrapper.h.

Definition at line 199 of file CoreWrapper.h.

Definition at line 187 of file CoreWrapper.h.

Definition at line 289 of file CoreWrapper.h.

Definition at line 188 of file CoreWrapper.h.

Definition at line 200 of file CoreWrapper.h.

Definition at line 270 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::frameId_ [private]

Definition at line 194 of file CoreWrapper.h.

Definition at line 207 of file CoreWrapper.h.

Definition at line 208 of file CoreWrapper.h.

Definition at line 209 of file CoreWrapper.h.

Definition at line 252 of file CoreWrapper.h.

Definition at line 248 of file CoreWrapper.h.

Definition at line 250 of file CoreWrapper.h.

Definition at line 254 of file CoreWrapper.h.

Definition at line 251 of file CoreWrapper.h.

Definition at line 249 of file CoreWrapper.h.

Definition at line 230 of file CoreWrapper.h.

geometry_msgs::PoseWithCovarianceStamped rtabmap_ros::CoreWrapper::globalPose_ [private]

Definition at line 284 of file CoreWrapper.h.

Definition at line 283 of file CoreWrapper.h.

Definition at line 227 of file CoreWrapper.h.

Definition at line 229 of file CoreWrapper.h.

Definition at line 226 of file CoreWrapper.h.

Definition at line 198 of file CoreWrapper.h.

Definition at line 197 of file CoreWrapper.h.

Definition at line 217 of file CoreWrapper.h.

Definition at line 223 of file CoreWrapper.h.

Definition at line 220 of file CoreWrapper.h.

Definition at line 184 of file CoreWrapper.h.

Definition at line 186 of file CoreWrapper.h.

Definition at line 185 of file CoreWrapper.h.

Definition at line 189 of file CoreWrapper.h.

Definition at line 190 of file CoreWrapper.h.

Definition at line 258 of file CoreWrapper.h.

Definition at line 222 of file CoreWrapper.h.

Definition at line 231 of file CoreWrapper.h.

Definition at line 218 of file CoreWrapper.h.

Definition at line 196 of file CoreWrapper.h.

Definition at line 219 of file CoreWrapper.h.

Definition at line 221 of file CoreWrapper.h.

Definition at line 215 of file CoreWrapper.h.

Definition at line 212 of file CoreWrapper.h.

Definition at line 213 of file CoreWrapper.h.

Definition at line 290 of file CoreWrapper.h.

Definition at line 264 of file CoreWrapper.h.

Definition at line 228 of file CoreWrapper.h.

Definition at line 201 of file CoreWrapper.h.

Definition at line 202 of file CoreWrapper.h.

Definition at line 195 of file CoreWrapper.h.

Definition at line 287 of file CoreWrapper.h.

Definition at line 191 of file CoreWrapper.h.

Definition at line 183 of file CoreWrapper.h.

Definition at line 238 of file CoreWrapper.h.

Definition at line 292 of file CoreWrapper.h.

Definition at line 253 of file CoreWrapper.h.

Definition at line 288 of file CoreWrapper.h.

Definition at line 237 of file CoreWrapper.h.

Definition at line 239 of file CoreWrapper.h.

Definition at line 275 of file CoreWrapper.h.

Definition at line 274 of file CoreWrapper.h.

Definition at line 273 of file CoreWrapper.h.

Definition at line 182 of file CoreWrapper.h.

std::map<std::string, float> rtabmap_ros::CoreWrapper::rtabmapROSStats_ [private]

Definition at line 192 of file CoreWrapper.h.

Definition at line 210 of file CoreWrapper.h.

Definition at line 255 of file CoreWrapper.h.

Definition at line 257 of file CoreWrapper.h.

Definition at line 244 of file CoreWrapper.h.

Definition at line 247 of file CoreWrapper.h.

Definition at line 245 of file CoreWrapper.h.

Definition at line 246 of file CoreWrapper.h.

Definition at line 242 of file CoreWrapper.h.

Definition at line 243 of file CoreWrapper.h.

Definition at line 286 of file CoreWrapper.h.

Definition at line 233 of file CoreWrapper.h.

Definition at line 234 of file CoreWrapper.h.

Definition at line 267 of file CoreWrapper.h.

Definition at line 291 of file CoreWrapper.h.

Definition at line 266 of file CoreWrapper.h.

Definition at line 240 of file CoreWrapper.h.

Definition at line 236 of file CoreWrapper.h.

Definition at line 205 of file CoreWrapper.h.

Definition at line 280 of file CoreWrapper.h.

Definition at line 279 of file CoreWrapper.h.

Definition at line 281 of file CoreWrapper.h.

Definition at line 206 of file CoreWrapper.h.

Definition at line 203 of file CoreWrapper.h.

Definition at line 204 of file CoreWrapper.h.


The documentation for this class was generated from the following files:


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:50