29 #include <QApplication> 32 #include <std_srvs/Empty.h> 33 #include <std_msgs/Empty.h> 39 #include <opencv2/highgui/highgui.hpp> 52 #include "rtabmap_ros/GetMap.h" 53 #include "rtabmap_ros/SetGoal.h" 54 #include "rtabmap_ros/SetLabel.h" 57 float max3(
const float& a,
const float& b,
const float& c)
68 frameId_(
"base_link"),
70 waitForTransform_(
true),
71 waitForTransformDuration_(0.2),
72 odomSensorSync_(
false),
73 maxOdomUpdateRate_(10),
75 lastOdomInfoUpdateTime_(0)
80 QString configFile = QDir::homePath()+
"/.ros/rtabmapGUI.ini";
81 for(
int i=1; i<argc; ++i)
83 if(strcmp(argv[i],
"-d") == 0)
94 configFile.replace(
'~', QDir::homePath());
96 ROS_INFO(
"rtabmapviz: Using configuration from \"%s\"", configFile.toStdString().c_str());
102 nh.
param(
"is_rtabmap_paused", paused, paused);
106 std::string tfPrefix;
107 std::string initCachePath;
110 pnh.
param(
"tf_prefix", tfPrefix, tfPrefix);
116 pnh.
param(
"init_cache_path", initCachePath, initCachePath);
117 if(initCachePath.size())
120 if(initCachePath.at(0) !=
'/')
124 ROS_INFO(
"rtabmapviz: Initializing cache with local database \"%s\"", initCachePath.c_str());
127 getMapSrv.request.global =
false;
128 getMapSrv.request.optimized =
true;
129 getMapSrv.request.graphOnly =
true;
132 ROS_WARN(
"Can't call \"get_map\" service. The cache will still be loaded " 133 "but the clouds won't be created until next time rtabmapviz " 134 "receives the optimized graph.");
141 QMetaObject::invokeMethod(
mainWindow_,
"updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
144 if(!tfPrefix.empty())
188 const rtabmap_ros::InfoConstPtr & infoMsg,
189 const rtabmap_ros::MapDataConstPtr & mapMsg)
201 std::map<int, rtabmap::Transform> poses;
202 std::map<int, Signature> signatures;
203 std::multimap<int, rtabmap::Link> links;
209 if(signatures.size())
219 const rtabmap_ros::GoalConstPtr & goalMsg,
220 const nav_msgs::PathConstPtr & pathMsg)
223 std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
224 for(
unsigned int i=0; i<pathMsg->poses.size(); ++i)
226 poses[i].first = -int(i)-1;
233 const std_msgs::BoolConstPtr & value)
240 std::map<int, Signature> signatures;
241 std::map<int, Transform> poses;
242 std::multimap<int, rtabmap::Link> constraints;
259 bool modified =
false;
261 for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
264 if(defaultParameters.find((*i).first) != defaultParameters.end())
266 nh.
setParam((*i).first, (*i).second);
269 else if((*i).first.find(
'/') != (*i).first.npos)
271 ROS_WARN(
"Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
280 ROS_ERROR(
"Can't call \"update_parameters\" service");
284 else if(anEvent->
getClassName().compare(
"RtabmapEventCmd") == 0)
286 std_srvs::Empty emptySrv;
293 ROS_ERROR(
"Can't call \"reset\" service");
301 std::string str =
uFormat(
"rosrun dynamic_reconfigure dynparam set %s pause true",
cameraNodeName_.c_str());
302 if(system(str.c_str()) !=0)
304 ROS_ERROR(
"Command \"%s\" returned non zero value.", str.c_str());
312 if(!ros::service::call(
"pause", emptySrv))
314 ROS_ERROR(
"Can't call \"pause\" service");
322 ROS_ERROR(
"Can't call \"resume\" service");
331 std::string str =
uFormat(
"rosrun dynamic_reconfigure dynparam set %s pause false",
cameraNodeName_.c_str());
332 if(system(str.c_str()) !=0)
334 ROS_ERROR(
"Command \"%s\" returned non zero value.", str.c_str());
342 ROS_ERROR(
"Can't call \"trigger_new_map\" service");
353 getMapSrv.request.optimized = cmdEvent->
value2().
toBool();
354 getMapSrv.request.graphOnly = cmdEvent->
value3().
toBool();
357 ROS_WARN(
"Can't call \"get_map_data\" service");
368 rtabmap_ros::SetGoal setGoalSrv;
373 ROS_ERROR(
"Can't call \"set_goal\" service");
377 UASSERT(setGoalSrv.response.path_ids.size() == setGoalSrv.response.path_poses.size());
378 std::vector<std::pair<int, Transform> > poses(setGoalSrv.response.path_poses.size());
379 for(
unsigned int i=0; i<setGoalSrv.response.path_poses.size(); ++i)
381 poses[i].first = setGoalSrv.response.path_ids[i];
384 this->
post(
new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
391 ROS_ERROR(
"Can't call \"cancel_goal\" service");
398 rtabmap_ros::SetLabel setLabelSrv;
399 setLabelSrv.request.node_label = cmdEvent->
value1().
toStr();
403 ROS_ERROR(
"Can't call \"set_label\" service");
408 ROS_WARN(
"Not handled command (%d)...", cmd);
411 else if(anEvent->
getClassName().compare(
"OdometryResetEvent") == 0)
416 ROS_ERROR(
"Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
423 const nav_msgs::OdometryConstPtr & odomMsg,
424 const rtabmap_ros::UserDataConstPtr & userDataMsg,
425 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
426 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
427 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
428 const sensor_msgs::LaserScan& scan2dMsg,
429 const sensor_msgs::PointCloud2& scan3dMsg,
430 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
431 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs,
432 const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints,
433 const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d,
434 const std::vector<cv::Mat> & localDescriptors)
436 UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == cameraInfoMsgs.size()));
438 std_msgs::Header odomHeader;
441 odomHeader = odomMsg->header;
445 if(!scan2dMsg.ranges.empty())
447 odomHeader = scan2dMsg.header;
449 else if(!scan3dMsg.data.empty())
451 odomHeader = scan3dMsg.header;
453 else if(cameraInfoMsgs.size())
455 odomHeader = cameraInfoMsgs[0].header;
457 else if(depthMsgs.size() && depthMsgs[0].get())
459 odomHeader = depthMsgs[0]->header;
461 else if(imageMsgs.size() && imageMsgs[0].get())
463 odomHeader = imageMsgs[0]->header;
469 cv::Mat
covariance = cv::Mat::eye(6,6,CV_64FC1);
472 UASSERT(odomMsg->twist.covariance.size() == 36);
473 if(odomMsg->twist.covariance[0] != 0 &&
474 odomMsg->twist.covariance[7] != 0 &&
475 odomMsg->twist.covariance[14] != 0 &&
476 odomMsg->twist.covariance[21] != 0 &&
477 odomMsg->twist.covariance[28] != 0 &&
478 odomMsg->twist.covariance[35] != 0)
480 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
483 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
485 if(odomInfoMsg->covariance[0] != 0 &&
486 odomInfoMsg->covariance[7] != 0 &&
487 odomInfoMsg->covariance[14] != 0 &&
488 odomInfoMsg->covariance[21] != 0 &&
489 odomInfoMsg->covariance[28] != 0 &&
490 odomInfoMsg->covariance[35] != 0)
492 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
495 if(odomHeader.frame_id.empty())
503 std::vector<CameraModel> cameraModels;
506 bool ignoreData =
false;
516 if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs.size() && depthMsgs[0].get())
531 ROS_ERROR(
"Could not convert rgb/depth msgs! Aborting rtabmapviz update...");
536 if(!scan2dMsg.ranges.empty())
547 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmapviz update...");
551 else if(!scan3dMsg.data.empty())
562 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
567 if(odomInfoMsg.get())
573 else if(odomInfoMsg.get())
600 const nav_msgs::OdometryConstPtr & odomMsg,
601 const rtabmap_ros::UserDataConstPtr & userDataMsg,
604 const sensor_msgs::CameraInfo& leftCamInfoMsg,
605 const sensor_msgs::CameraInfo& rightCamInfoMsg,
606 const sensor_msgs::LaserScan& scan2dMsg,
607 const sensor_msgs::PointCloud2& scan3dMsg,
608 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
609 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs,
610 const std::vector<rtabmap_ros::KeyPoint> & localKeyPoints,
611 const std::vector<rtabmap_ros::Point3f> & localPoints3d,
612 const cv::Mat & localDescriptors)
614 std_msgs::Header odomHeader;
617 odomHeader = odomMsg->header;
621 if(!scan2dMsg.ranges.empty())
623 odomHeader = scan2dMsg.header;
625 else if(!scan3dMsg.data.empty())
627 odomHeader = scan3dMsg.header;
631 odomHeader = leftCamInfoMsg.header;
637 cv::Mat
covariance = cv::Mat::eye(6,6,CV_64FC1);
640 UASSERT(odomMsg->twist.covariance.size() == 36);
641 if(odomMsg->twist.covariance[0] != 0 &&
642 odomMsg->twist.covariance[7] != 0 &&
643 odomMsg->twist.covariance[14] != 0 &&
644 odomMsg->twist.covariance[21] != 0 &&
645 odomMsg->twist.covariance[28] != 0 &&
646 odomMsg->twist.covariance[35] != 0)
648 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
651 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
653 if(odomInfoMsg->covariance[0] != 0 &&
654 odomInfoMsg->covariance[7] != 0 &&
655 odomInfoMsg->covariance[14] != 0 &&
656 odomInfoMsg->covariance[21] != 0 &&
657 odomInfoMsg->covariance[28] != 0 &&
658 odomInfoMsg->covariance[35] != 0)
660 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
663 if(odomHeader.frame_id.empty())
674 bool ignoreData =
false;
699 ROS_ERROR(
"Could not convert stereo msgs! Aborting rtabmapviz update...");
703 if(!scan2dMsg.ranges.empty())
714 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmapviz update...");
718 else if(!scan3dMsg.data.empty())
729 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
734 if(odomInfoMsg.get())
740 else if(odomInfoMsg.get())
767 const nav_msgs::OdometryConstPtr & odomMsg,
768 const rtabmap_ros::UserDataConstPtr & userDataMsg,
769 const sensor_msgs::LaserScan& scan2dMsg,
770 const sensor_msgs::PointCloud2& scan3dMsg,
771 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
772 const rtabmap_ros::GlobalDescriptor & globalDescriptor)
774 std_msgs::Header odomHeader;
777 odomHeader = odomMsg->header;
781 if(!scan2dMsg.ranges.empty())
783 odomHeader = scan2dMsg.header;
785 else if(!scan3dMsg.data.empty())
787 odomHeader = scan3dMsg.header;
797 cv::Mat
covariance = cv::Mat::eye(6,6,CV_64FC1);
800 UASSERT(odomMsg->twist.covariance.size() == 36);
801 if(odomMsg->twist.covariance[0] != 0 &&
802 odomMsg->twist.covariance[7] != 0 &&
803 odomMsg->twist.covariance[14] != 0 &&
804 odomMsg->twist.covariance[21] != 0 &&
805 odomMsg->twist.covariance[28] != 0 &&
806 odomMsg->twist.covariance[35] != 0)
808 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
811 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
813 if(odomInfoMsg->covariance[0] != 0 &&
814 odomInfoMsg->covariance[7] != 0 &&
815 odomInfoMsg->covariance[14] != 0 &&
816 odomInfoMsg->covariance[21] != 0 &&
817 odomInfoMsg->covariance[28] != 0 &&
818 odomInfoMsg->covariance[35] != 0)
820 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
823 if(odomHeader.frame_id.empty())
831 bool ignoreData =
false;
842 if(!scan2dMsg.ranges.empty())
853 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmapviz update...");
857 else if(!scan3dMsg.data.empty())
868 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
873 if(odomInfoMsg.get())
879 else if(odomInfoMsg.get())
882 if(!scan2dMsg.ranges.empty())
886 else if(!scan3dMsg.data.empty())
907 (fakeCameraLocalTransform.
isNull()?scan.
localTransform():fakeCameraLocalTransform)*
Transform(0,0,1,0, -1,0,0,0, 0,-1,0,0),
927 const nav_msgs::OdometryConstPtr & odomMsg,
928 const rtabmap_ros::UserDataConstPtr & userDataMsg,
929 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
933 std_msgs::Header odomHeader = odomMsg->header;
936 cv::Mat
covariance = cv::Mat::eye(6,6,CV_64FC1);
939 UASSERT(odomMsg->twist.covariance.size() == 36);
940 if(odomMsg->twist.covariance[0] != 0 &&
941 odomMsg->twist.covariance[7] != 0 &&
942 odomMsg->twist.covariance[14] != 0 &&
943 odomMsg->twist.covariance[21] != 0 &&
944 odomMsg->twist.covariance[28] != 0 &&
945 odomMsg->twist.covariance[35] != 0)
947 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
950 if(odomHeader.frame_id.empty())
957 bool ignoreData =
false;
967 if(odomInfoMsg.get())
973 else if(odomInfoMsg.get())
991 Transform(0,0,1,0, -1,0,0,0, 0,-1,0,0),
ros::ServiceClient getMapSrv
static std::string homeDir()
const UVariant & value2() const
bool isProcessingOdometry() const
std::string uFormat(const char *fmt,...)
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
bool convertScan3dMsg(const sensor_msgs::PointCloud2 &scan3dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, rtabmap::LaserScan &scan, tf::TransformListener &listener, double waitForTransform, int maxPoints=0, float maxRange=0.0f)
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
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 &scan2dMsg, 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 >())
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
std::string uReplaceChar(const std::string &str, char before, char after)
virtual bool handleEvent(UEvent *anEvent)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo &msg)
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 &scan2dMsg, 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())
const UVariant & value3() const
bool call(const std::string &service_name, MReq &req, MRes &res)
OdometryInfo copyWithoutData() const
GLM_FUNC_DECL genType e()
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
std::map< std::string, std::string > ParametersMap
void infoMapCallback(const rtabmap_ros::InfoConstPtr &infoMsg, const rtabmap_ros::MapDataConstPtr &mapMsg)
const UVariant & value1() const
ROSCPP_DECL const std::string & getName()
void setConstraints(const std::multimap< int, Link > &constraints)
void processRequestedMap(const rtabmap_ros::MapData &map)
rtabmap::MainWindow * mainWindow_
bool isProcessingStatistics() const
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
void post(UEvent *event, bool async=true) const
#define UASSERT(condition)
void goalReachedCallback(const std_msgs::BoolConstPtr &value)
void setLastSignatureData(const Signature &data)
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
static std::string currentDir(bool trailingSeparator=false)
int toInt(bool *ok=0) const
void mapDataFromROS(const rtabmap_ros::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
double lastOdomInfoUpdateTime_
double waitForTransformDuration_
void setPoses(const std::map< int, Transform > &poses)
ros::Subscriber goalReachedTopic_
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
virtual std::string getClassName() const =0
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void infoFromROS(const rtabmap_ros::Info &info, rtabmap::Statistics &stat)
Transform localTransform() const
void goalPathCallback(const rtabmap_ros::GoalConstPtr &goalMsg, const nav_msgs::PathConstPtr &pathMsg)
bool convertRGBDMsgs(const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &rgb, cv::Mat &depth, std::vector< rtabmap::CameraModel > &cameraModels, tf::TransformListener &listener, double waitForTransform, const std::vector< std::vector< rtabmap_ros::KeyPoint > > &localKeyPointsMsgs=std::vector< std::vector< rtabmap_ros::KeyPoint > >(), const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3dMsgs=std::vector< std::vector< rtabmap_ros::Point3f > >(), const std::vector< cv::Mat > &localDescriptorsMsgs=std::vector< cv::Mat >(), std::vector< cv::KeyPoint > *localKeyPoints=0, std::vector< cv::Point3f > *localPoints3d=0, cv::Mat *localDescriptors=0)
void setMonitoringState(bool pauseChecked=false)
float max3(const float &a, const float &b, const float &c)
bool convertStereoMsg(const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &left, cv::Mat &right, rtabmap::StereoCameraModel &stereoModel, tf::TransformListener &listener, double waitForTransform, bool alreadyRectified)
void setMapCorrection(const Transform &mapCorrection)
double maxOdomUpdateRate_
void uSleep(unsigned int ms)
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scan2dMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const rtabmap_ros::GlobalDescriptor &globalDescriptor=rtabmap_ros::GlobalDescriptor())
static const ParametersMap & getDefaultParameters()
bool convertScanMsg(const sensor_msgs::LaserScan &scan2dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, rtabmap::LaserScan &scan, tf::TransformListener &listener, double waitForTransform, bool outputInFrameId=false)
tf::TransformListener tfListener_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
static void addHandler(UEventsHandler *handler)
message_filters::sync_policies::ExactTime< rtabmap_ros::Goal, nav_msgs::Path > MyGoalPathSyncPolicy
std::string cameraNodeName_
double timestampFromROS(const ros::Time &stamp)
std::string toStr(bool *ok=0) const
message_filters::Subscriber< nav_msgs::Path > pathTopic_
GuiWrapper(int &argc, char **argv)
message_filters::sync_policies::ExactTime< rtabmap_ros::Info, rtabmap_ros::MapData > MyInfoMapSyncPolicy
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const