Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::CoreWrapper Class Reference

#include <CoreWrapper.h>

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

Public Member Functions

 CoreWrapper ()
 
virtual ~CoreWrapper ()
 
- Public Member Functions inherited from rtabmap_ros::CommonDataSubscriber
 CommonDataSubscriber (bool gui)
 
int getQueueSize () const
 
bool isApproxSync () const
 
bool isDataSubscribed () const
 
bool isSubscribedToDepth () const
 
bool isSubscribedToOdom () const
 
bool isSubscribedToOdomInfo () const
 
bool isSubscribedToRGB () const
 
bool isSubscribedToRGBD () const
 
bool isSubscribedToScan2d () const
 
bool isSubscribedToScan3d () const
 
bool isSubscribedToStereo () const
 
const std::string & name () const
 
int rgbdCameras () const
 
virtual ~CommonDataSubscriber ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Types

typedef message_filters::sync_policies::ExactTime< nav_msgs::Odometry, rtabmap_ros::OdomInfo > MyExactInterOdomSyncPolicy
 

Private Member Functions

bool addLinkCallback (rtabmap_ros::AddLink::Request &, rtabmap_ros::AddLink::Response &)
 
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::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_ros::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_ros::KeyPoint > >(), const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_ros::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())
 
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::LaserScan &scan2dMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs, const std::vector< std::vector< rtabmap_ros::KeyPoint > > &localKeyPoints, const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3d, const std::vector< cv::Mat > &localDescriptors)
 
virtual void commonLaserScanCallback (const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const rtabmap_ros::GlobalDescriptor &globalDescriptor=rtabmap_ros::GlobalDescriptor())
 
virtual void commonOdomCallback (const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, 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::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
 
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 getMapData2Callback (rtabmap_ros::GetMap2::Request &req, rtabmap_ros::GetMap2::Response &res)
 
bool getMapDataCallback (rtabmap_ros::GetMap::Request &req, rtabmap_ros::GetMap::Response &res)
 
bool getNodeDataCallback (rtabmap_ros::GetNodeData::Request &req, rtabmap_ros::GetNodeData::Response &res)
 
bool getNodesInRadiusCallback (rtabmap_ros::GetNodesInRadius::Request &, rtabmap_ros::GetNodesInRadius::Response &)
 
bool getPlanCallback (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res)
 
bool getPlanNodesCallback (rtabmap_ros::GetPlan::Request &req, rtabmap_ros::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 std::string &frameId, 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 gpsFixAsyncCallback (const sensor_msgs::NavSatFixConstPtr &gpsFixMsg)
 
void imuAsyncCallback (const sensor_msgs::ImuConstPtr &tagDetections)
 
void initialPoseCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
 
void interOdomCallback (const nav_msgs::OdometryConstPtr &msg)
 
void interOdomInfoCallback (const nav_msgs::OdometryConstPtr &msg1, const rtabmap_ros::OdomInfoConstPtr &msg2)
 
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, 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 addLinkSrv_
 
bool alreadyRectifiedImages_
 
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 genDepth_
 
int genDepthDecimation_
 
double genDepthFillHolesError_
 
int genDepthFillHolesSize_
 
int genDepthFillIterations_
 
bool genScan_
 
double genScanMaxDepth_
 
double genScanMinDepth_
 
ros::ServiceServer getGridMapSrv_
 
ros::ServiceServer getMapData2Srv_
 
ros::ServiceServer getMapDataSrv_
 
ros::ServiceServer getMapSrv_
 
ros::ServiceServer getNodeDataSrv_
 
ros::ServiceServer getNodesInRadiusSrv_
 
ros::ServiceServer getPlanNodesSrv_
 
ros::ServiceServer getPlanSrv_
 
ros::ServiceServer getProbMapSrv_
 
ros::ServiceServer getProjMapSrv_
 
ros::Publisher globalPathNodesPub_
 
ros::Publisher globalPathPub_
 
geometry_msgs::PoseWithCovarianceStamped globalPose_
 
ros::Subscriber globalPoseAsyncSub_
 
std::string goalFrameId_
 
ros::Subscriber goalNodeSub_
 
ros::Publisher goalReachedPub_
 
ros::Subscriber goalSub_
 
rtabmap::GPS gps_
 
ros::Subscriber gpsFixAsyncSub_
 
std::string groundTruthBaseFrameId_
 
std::string groundTruthFrameId_
 
std::string imuFrameId_
 
std::map< double, rtabmap::Transformimus_
 
ros::Subscriber imuSub_
 
ros::Publisher infoPub_
 
ros::Subscriber initialPoseSub_
 
message_filters::Subscriber< rtabmap_ros::OdomInfo > interOdomInfoSyncSub_
 
std::list< std::pair< nav_msgs::Odometry, rtabmap_ros::OdomInfo > > interOdoms_
 
ros::Subscriber interOdomSub_
 
message_filters::Synchronizer< MyExactInterOdomSyncPolicy > * interOdomSync_
 
message_filters::Subscriber< nav_msgs::Odometry > interOdomSyncSub_
 
ros::Publisher labelsPub_
 
double landmarkDefaultAngVariance_
 
double landmarkDefaultLinVariance_
 
ros::Publisher landmarksPub_
 
rtabmap::Transform lastPose_
 
bool lastPoseIntermediate_
 
ros::Time lastPoseStamp_
 
rtabmap::Transform lastPublishedMetricGoal_
 
bool latestNodeWasReached_
 
ros::ServiceServer listLabelsSrv_
 
ros::Publisher localGridEmpty_
 
ros::Publisher localGridGround_
 
ros::Publisher localGridObstacle_
 
ros::Publisher localizationPosePub_
 
ros::Publisher localPathNodesPub_
 
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_
 
MoveBaseClientmbClient_
 
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_
 
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_
 
ros::Subscriber tagDetectionsSub_
 
std::map< int, geometry_msgs::PoseWithCovarianceStamped > tags_
 
tf2_ros::TransformBroadcaster tfBroadcaster_
 
tf::TransformListener tfListener_
 
bool tfThreadRunning_
 
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_
 

Additional Inherited Members

- Protected Member Functions inherited from rtabmap_ros::CommonDataSubscriber
void commonSingleDepthCallback (const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &imageMsg, const cv_bridge::CvImageConstPtr &depthMsg, const sensor_msgs::CameraInfo &rgbCameraInfoMsg, const sensor_msgs::CameraInfo &depthCameraInfoMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
 
void setupCallbacks (ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Attributes inherited from rtabmap_ros::CommonDataSubscriber
int queueSize_
 
std::string subscribedTopicsMsg_
 

Detailed Description

Definition at line 90 of file CoreWrapper.h.

Member Typedef Documentation

typedef message_filters::sync_policies::ExactTime<nav_msgs::Odometry, rtabmap_ros::OdomInfo> rtabmap_ros::CoreWrapper::MyExactInterOdomSyncPolicy
private

Definition at line 361 of file CoreWrapper.h.

Constructor & Destructor Documentation

rtabmap_ros::CoreWrapper::CoreWrapper ( )

Definition at line 85 of file CoreWrapper.cpp.

rtabmap_ros::CoreWrapper::~CoreWrapper ( )
virtual

Definition at line 750 of file CoreWrapper.cpp.

Member Function Documentation

bool rtabmap_ros::CoreWrapper::addLinkCallback ( rtabmap_ros::AddLink::Request &  req,
rtabmap_ros::AddLink::Response &   
)
private

Definition at line 3513 of file CoreWrapper.cpp.

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

Definition at line 2716 of file CoreWrapper.cpp.

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

Definition at line 3449 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::LaserScan &  scanMsg,
const sensor_msgs::PointCloud2 &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg,
const std::vector< rtabmap_ros::GlobalDescriptor > &  globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
const std::vector< std::vector< rtabmap_ros::KeyPoint > > &  localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
const std::vector< std::vector< rtabmap_ros::Point3f > > &  localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
const std::vector< cv::Mat > &  localDescriptors = std::vector<cv::Mat>() 
)
privatevirtual

Implements rtabmap_ros::CommonDataSubscriber.

Definition at line 1068 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::LaserScan &  scan2dMsg,
const sensor_msgs::PointCloud2 &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg,
const std::vector< rtabmap_ros::GlobalDescriptor > &  globalDescriptorMsgs,
const std::vector< std::vector< rtabmap_ros::KeyPoint > > &  localKeyPoints,
const std::vector< std::vector< rtabmap_ros::Point3f > > &  localPoints3d,
const std::vector< cv::Mat > &  localDescriptors 
)
private

Definition at line 1138 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::commonLaserScanCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_ros::UserDataConstPtr &  userDataMsg,
const sensor_msgs::LaserScan &  scanMsg,
const sensor_msgs::PointCloud2 &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg,
const rtabmap_ros::GlobalDescriptor &  globalDescriptor = rtabmap_ros::GlobalDescriptor() 
)
privatevirtual

Implements rtabmap_ros::CommonDataSubscriber.

Definition at line 1585 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::commonOdomCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_ros::UserDataConstPtr &  userDataMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg 
)
privatevirtual

Implements rtabmap_ros::CommonDataSubscriber.

Definition at line 1729 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::LaserScan &  scanMsg,
const sensor_msgs::PointCloud2 &  scan3dMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg,
const std::vector< rtabmap_ros::GlobalDescriptor > &  globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
const std::vector< rtabmap_ros::KeyPoint > &  localKeyPoints = std::vector<rtabmap_ros::KeyPoint>(),
const std::vector< rtabmap_ros::Point3f > &  localPoints3d = std::vector<rtabmap_ros::Point3f>(),
const cv::Mat &  localDescriptors = cv::Mat() 
)
privatevirtual

Implements rtabmap_ros::CommonDataSubscriber.

Definition at line 1338 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::defaultCallback ( const sensor_msgs::ImageConstPtr &  imageMsg)
private

Definition at line 842 of file CoreWrapper.cpp.

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

Definition at line 2926 of file CoreWrapper.cpp.

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

Definition at line 2932 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getMapData2Callback ( rtabmap_ros::GetMap2::Request &  req,
rtabmap_ros::GetMap2::Response &  res 
)
private

Definition at line 2869 of file CoreWrapper.cpp.

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

Definition at line 2835 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getNodeDataCallback ( rtabmap_ros::GetNodeData::Request &  req,
rtabmap_ros::GetNodeData::Response &  res 
)
private

Definition at line 2806 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getNodesInRadiusCallback ( rtabmap_ros::GetNodesInRadius::Request &  req,
rtabmap_ros::GetNodesInRadius::Response &  res 
)
private

Definition at line 3524 of file CoreWrapper.cpp.

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

Definition at line 3270 of file CoreWrapper.cpp.

bool rtabmap_ros::CoreWrapper::getPlanNodesCallback ( rtabmap_ros::GetPlan::Request &  req,
rtabmap_ros::GetPlan::Response &  res 
)
private

Definition at line 3344 of file CoreWrapper.cpp.

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

Definition at line 2973 of file CoreWrapper.cpp.

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

Definition at line 2908 of file CoreWrapper.cpp.

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

Definition at line 2278 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::goalActiveCb ( )
private

Definition at line 3878 of file CoreWrapper.cpp.

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

Definition at line 2568 of file CoreWrapper.cpp.

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

Definition at line 2421 of file CoreWrapper.cpp.

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

Definition at line 3832 of file CoreWrapper.cpp.

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

Definition at line 3884 of file CoreWrapper.cpp.

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

Definition at line 2595 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::gpsFixAsyncCallback ( const sensor_msgs::NavSatFixConstPtr &  gpsFixMsg)
private

Definition at line 2286 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::imuAsyncCallback ( const sensor_msgs::ImuConstPtr &  tagDetections)
private

Definition at line 2357 of file CoreWrapper.cpp.

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

Definition at line 2409 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::interOdomCallback ( const nav_msgs::OdometryConstPtr &  msg)
private

Definition at line 2392 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::interOdomInfoCallback ( const nav_msgs::OdometryConstPtr &  msg1,
const rtabmap_ros::OdomInfoConstPtr &  msg2 
)
private

Definition at line 2400 of file CoreWrapper.cpp.

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

Definition at line 3501 of file CoreWrapper.cpp.

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

Definition at line 788 of file CoreWrapper.cpp.

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

Definition at line 1012 of file CoreWrapper.cpp.

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

Definition at line 911 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::onInit ( )
privatevirtual

Implements nodelet::Nodelet.

Definition at line 133 of file CoreWrapper.cpp.

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

Definition at line 2677 of file CoreWrapper.cpp.

void rtabmap_ros::CoreWrapper::process ( const ros::Time stamp,
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 1796 of file CoreWrapper.cpp.

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

Definition at line 3781 of file CoreWrapper.cpp.

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

Definition at line 3928 of file CoreWrapper.cpp.

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

Definition at line 3890 of file CoreWrapper.cpp.

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

Definition at line 819 of file CoreWrapper.cpp.

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

Definition at line 3014 of file CoreWrapper.cpp.

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

Definition at line 3553 of file CoreWrapper.cpp.

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

Definition at line 2652 of file CoreWrapper.cpp.

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

Definition at line 2693 of file CoreWrapper.cpp.

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

Definition at line 801 of file CoreWrapper.cpp.

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

Definition at line 3433 of file CoreWrapper.cpp.

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

Definition at line 3474 of file CoreWrapper.cpp.

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

Definition at line 2781 of file CoreWrapper.cpp.

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

Definition at line 2799 of file CoreWrapper.cpp.

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

Definition at line 2787 of file CoreWrapper.cpp.

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

Definition at line 2793 of file CoreWrapper.cpp.

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

Definition at line 2757 of file CoreWrapper.cpp.

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

Definition at line 2769 of file CoreWrapper.cpp.

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

Definition at line 2709 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 2611 of file CoreWrapper.cpp.

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

Definition at line 2259 of file CoreWrapper.cpp.

Member Data Documentation

ros::ServiceServer rtabmap_ros::CoreWrapper::addLinkSrv_
private

Definition at line 328 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::alreadyRectifiedImages_
private

Definition at line 369 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::backupDatabase_
private

Definition at line 307 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::cancelGoalSrv_
private

Definition at line 325 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::configPath_
private

Definition at line 251 of file CoreWrapper.h.

cv::Mat rtabmap_ros::CoreWrapper::covariance_
private

Definition at line 239 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::createIntermediateNodes_
private

Definition at line 367 of file CoreWrapper.h.

rtabmap::Transform rtabmap_ros::CoreWrapper::currentMetricGoal_
private

Definition at line 240 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::databasePath_
private

Definition at line 252 of file CoreWrapper.h.

image_transport::Subscriber rtabmap_ros::CoreWrapper::defaultSub_
private

Definition at line 341 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::frameId_
private

Definition at line 246 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::genDepth_
private

Definition at line 264 of file CoreWrapper.h.

int rtabmap_ros::CoreWrapper::genDepthDecimation_
private

Definition at line 265 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::genDepthFillHolesError_
private

Definition at line 268 of file CoreWrapper.h.

int rtabmap_ros::CoreWrapper::genDepthFillHolesSize_
private

Definition at line 266 of file CoreWrapper.h.

int rtabmap_ros::CoreWrapper::genDepthFillIterations_
private

Definition at line 267 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::genScan_
private

Definition at line 261 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::genScanMaxDepth_
private

Definition at line 262 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::genScanMinDepth_
private

Definition at line 263 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getGridMapSrv_
private

Definition at line 320 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getMapData2Srv_
private

Definition at line 316 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getMapDataSrv_
private

Definition at line 315 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getMapSrv_
private

Definition at line 318 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getNodeDataSrv_
private

Definition at line 314 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getNodesInRadiusSrv_
private

Definition at line 329 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getPlanNodesSrv_
private

Definition at line 323 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getPlanSrv_
private

Definition at line 322 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getProbMapSrv_
private

Definition at line 319 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::getProjMapSrv_
private

Definition at line 317 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::globalPathNodesPub_
private

Definition at line 295 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::globalPathPub_
private

Definition at line 293 of file CoreWrapper.h.

geometry_msgs::PoseWithCovarianceStamped rtabmap_ros::CoreWrapper::globalPose_
private

Definition at line 348 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::globalPoseAsyncSub_
private

Definition at line 347 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::goalFrameId_
private

Definition at line 297 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::goalNodeSub_
private

Definition at line 290 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::goalReachedPub_
private

Definition at line 292 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::goalSub_
private

Definition at line 289 of file CoreWrapper.h.

rtabmap::GPS rtabmap_ros::CoreWrapper::gps_
private

Definition at line 350 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::gpsFixAsyncSub_
private

Definition at line 349 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::groundTruthBaseFrameId_
private

Definition at line 250 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::groundTruthFrameId_
private

Definition at line 249 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::imuFrameId_
private

Definition at line 355 of file CoreWrapper.h.

std::map<double, rtabmap::Transform> rtabmap_ros::CoreWrapper::imus_
private

Definition at line 354 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::imuSub_
private

Definition at line 353 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::infoPub_
private

Definition at line 276 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::initialPoseSub_
private

Definition at line 286 of file CoreWrapper.h.

message_filters::Subscriber<rtabmap_ros::OdomInfo> rtabmap_ros::CoreWrapper::interOdomInfoSyncSub_
private

Definition at line 360 of file CoreWrapper.h.

std::list<std::pair<nav_msgs::Odometry, rtabmap_ros::OdomInfo> > rtabmap_ros::CoreWrapper::interOdoms_
private

Definition at line 358 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::interOdomSub_
private

Definition at line 357 of file CoreWrapper.h.

message_filters::Synchronizer<MyExactInterOdomSyncPolicy>* rtabmap_ros::CoreWrapper::interOdomSync_
private

Definition at line 362 of file CoreWrapper.h.

message_filters::Subscriber<nav_msgs::Odometry> rtabmap_ros::CoreWrapper::interOdomSyncSub_
private

Definition at line 359 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::labelsPub_
private

Definition at line 280 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::landmarkDefaultAngVariance_
private

Definition at line 255 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::landmarkDefaultLinVariance_
private

Definition at line 256 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::landmarksPub_
private

Definition at line 279 of file CoreWrapper.h.

rtabmap::Transform rtabmap_ros::CoreWrapper::lastPose_
private

Definition at line 236 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::lastPoseIntermediate_
private

Definition at line 238 of file CoreWrapper.h.

ros::Time rtabmap_ros::CoreWrapper::lastPoseStamp_
private

Definition at line 237 of file CoreWrapper.h.

rtabmap::Transform rtabmap_ros::CoreWrapper::lastPublishedMetricGoal_
private

Definition at line 241 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::latestNodeWasReached_
private

Definition at line 242 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::listLabelsSrv_
private

Definition at line 327 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::localGridEmpty_
private

Definition at line 283 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::localGridGround_
private

Definition at line 284 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::localGridObstacle_
private

Definition at line 282 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::localizationPosePub_
private

Definition at line 285 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::localPathNodesPub_
private

Definition at line 296 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::localPathPub_
private

Definition at line 294 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::mapDataPub_
private

Definition at line 277 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::mapFrameId_
private

Definition at line 248 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::mapGraphPub_
private

Definition at line 278 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::mapPathPub_
private

Definition at line 281 of file CoreWrapper.h.

MapsManager rtabmap_ros::CoreWrapper::mapsManager_
private

Definition at line 274 of file CoreWrapper.h.

rtabmap::Transform rtabmap_ros::CoreWrapper::mapToOdom_
private

Definition at line 271 of file CoreWrapper.h.

boost::mutex rtabmap_ros::CoreWrapper::mapToOdomMutex_
private

Definition at line 272 of file CoreWrapper.h.

int rtabmap_ros::CoreWrapper::maxMappingNodes_
private

Definition at line 368 of file CoreWrapper.h.

MoveBaseClient* rtabmap_ros::CoreWrapper::mbClient_
private

Definition at line 335 of file CoreWrapper.h.

ros::Publisher rtabmap_ros::CoreWrapper::nextMetricGoalPub_
private

Definition at line 291 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::odomDefaultAngVariance_
private

Definition at line 253 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::odomDefaultLinVariance_
private

Definition at line 254 of file CoreWrapper.h.

std::string rtabmap_ros::CoreWrapper::odomFrameId_
private

Definition at line 247 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::odomSensorSync_
private

Definition at line 365 of file CoreWrapper.h.

rtabmap::ParametersMap rtabmap_ros::CoreWrapper::parameters_
private

Definition at line 243 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::paused_
private

Definition at line 235 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::pauseSrv_
private

Definition at line 304 of file CoreWrapper.h.

ros::Time rtabmap_ros::CoreWrapper::previousStamp_
private

Definition at line 370 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::publishMapDataSrv_
private

Definition at line 321 of file CoreWrapper.h.

float rtabmap_ros::CoreWrapper::rate_
private

Definition at line 366 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::resetSrv_
private

Definition at line 303 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::resumeSrv_
private

Definition at line 305 of file CoreWrapper.h.

rtabmap::Rtabmap rtabmap_ros::CoreWrapper::rtabmap_
private

Definition at line 234 of file CoreWrapper.h.

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

Definition at line 244 of file CoreWrapper.h.

int rtabmap_ros::CoreWrapper::scanCloudMaxPoints_
private

Definition at line 269 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setGoalSrv_
private

Definition at line 324 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setLabelSrv_
private

Definition at line 326 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setLogDebugSrv_
private

Definition at line 310 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setLogErrorSrv_
private

Definition at line 313 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setLogInfoSrv_
private

Definition at line 311 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setLogWarnSrv_
private

Definition at line 312 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setModeLocalizationSrv_
private

Definition at line 308 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::setModeMappingSrv_
private

Definition at line 309 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::stereoToDepth_
private

Definition at line 364 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::tagDetectionsSub_
private

Definition at line 351 of file CoreWrapper.h.

std::map<int, geometry_msgs::PoseWithCovarianceStamped> rtabmap_ros::CoreWrapper::tags_
private

Definition at line 352 of file CoreWrapper.h.

tf2_ros::TransformBroadcaster rtabmap_ros::CoreWrapper::tfBroadcaster_
private

Definition at line 299 of file CoreWrapper.h.

tf::TransformListener rtabmap_ros::CoreWrapper::tfListener_
private

Definition at line 300 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::tfThreadRunning_
private

Definition at line 338 of file CoreWrapper.h.

boost::thread* rtabmap_ros::CoreWrapper::transformThread_
private

Definition at line 337 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::triggerNewMapSrv_
private

Definition at line 306 of file CoreWrapper.h.

ros::ServiceServer rtabmap_ros::CoreWrapper::updateSrv_
private

Definition at line 302 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::useActionForGoal_
private

Definition at line 259 of file CoreWrapper.h.

cv::Mat rtabmap_ros::CoreWrapper::userData_
private

Definition at line 344 of file CoreWrapper.h.

ros::Subscriber rtabmap_ros::CoreWrapper::userDataAsyncSub_
private

Definition at line 343 of file CoreWrapper.h.

UMutex rtabmap_ros::CoreWrapper::userDataMutex_
private

Definition at line 345 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::useSavedMap_
private

Definition at line 260 of file CoreWrapper.h.

bool rtabmap_ros::CoreWrapper::waitForTransform_
private

Definition at line 257 of file CoreWrapper.h.

double rtabmap_ros::CoreWrapper::waitForTransformDuration_
private

Definition at line 258 of file CoreWrapper.h.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19