29 #include <QApplication>
32 #include <std_srvs/Empty.h>
33 #include <std_msgs/Empty.h>
34 #include <std_msgs/Int32MultiArray.h>
40 #include <opencv2/highgui/highgui.hpp>
53 #include "rtabmap_msgs/GetMap.h"
54 #include "rtabmap_msgs/SetGoal.h"
55 #include "rtabmap_msgs/SetLabel.h"
56 #include "rtabmap_msgs/RemoveLabel.h"
59 float max3(
const float& a,
const float& b,
const float& c)
70 frameId_(
"base_link"),
72 waitForTransform_(
true),
73 waitForTransformDuration_(0.2),
74 odomSensorSync_(
false),
75 maxOdomUpdateRate_(10),
77 lastOdomInfoUpdateTime_(0),
78 rtabmapNodeName_(
"rtabmap")
83 QString configFile = QDir::homePath()+
"/.ros/rtabmapGUI.ini";
84 for(
int i=1;
i<argc; ++
i)
86 if(strcmp(
argv[
i],
"-d") == 0)
97 configFile.replace(
'~', QDir::homePath());
101 ROS_INFO(
"rtabmap_viz: Using configuration from \"%s\"", configFile.toStdString().c_str());
110 rnh.
param(
"is_rtabmap_paused", paused, paused);
114 std::string initCachePath;
115 bool subscribeInfoOnly =
false;
123 pnh.
param(
"subscribe_info_only", subscribeInfoOnly, subscribeInfoOnly);
124 pnh.
param(
"init_cache_path", initCachePath, initCachePath);
125 if(initCachePath.size())
128 if(initCachePath.at(0) !=
'/')
132 ROS_INFO(
"rtabmap_viz: Initializing cache with local database \"%s\"", initCachePath.c_str());
134 rtabmap_msgs::GetMap getMapSrv;
135 getMapSrv.request.global =
false;
136 getMapSrv.request.optimized =
true;
137 getMapSrv.request.graphOnly =
true;
140 ROS_WARN(
"Can't call \"get_map\" service. The cache will still be loaded "
141 "but the clouds won't be created until next time rtabmap_viz "
142 "receives the optimized graph.");
149 QMetaObject::invokeMethod(
mainWindow_,
"updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
154 ROS_ERROR(
"tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
162 if(subscribeInfoOnly)
164 ROS_INFO(
"subscribe_info_only=true");
199 const rtabmap_msgs::InfoConstPtr & infoMsg,
200 const rtabmap_msgs::MapDataConstPtr & mapMsg)
212 std::map<int, rtabmap::Transform> poses;
213 std::map<int, Signature> signatures;
214 std::multimap<int, rtabmap::Link> links;
225 tick(infoMsg->header.stamp);
230 const rtabmap_msgs::InfoConstPtr & infoMsg)
238 if(stat.
data().find(Statistics::kLoopMapToOdom_x()) != stat.
data().end() &&
239 stat.
data().find(Statistics::kLoopMapToOdom_y()) != stat.
data().end() &&
240 stat.
data().find(Statistics::kLoopMapToOdom_z()) != stat.
data().end() &&
241 stat.
data().find(Statistics::kLoopMapToOdom_roll()) != stat.
data().end() &&
242 stat.
data().find(Statistics::kLoopMapToOdom_pitch()) != stat.
data().end() &&
243 stat.
data().find(Statistics::kLoopMapToOdom_yaw()) != stat.
data().end())
247 stat.
data().at(Statistics::kLoopMapToOdom_x()),
248 stat.
data().at(Statistics::kLoopMapToOdom_y()),
249 stat.
data().at(Statistics::kLoopMapToOdom_z()),
250 stat.
data().at(Statistics::kLoopMapToOdom_roll())*
M_PI/180.f,
251 stat.
data().at(Statistics::kLoopMapToOdom_pitch())*
M_PI/180.f,
252 stat.
data().at(Statistics::kLoopMapToOdom_yaw())*
M_PI/180.f);
258 tick(infoMsg->header.stamp);
262 const rtabmap_msgs::GoalConstPtr & goalMsg,
263 const nav_msgs::PathConstPtr & pathMsg)
266 std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
267 for(
unsigned int i=0;
i<pathMsg->poses.size(); ++
i)
269 poses[
i].first = -
int(
i)-1;
276 const std_msgs::BoolConstPtr & value)
289 std::map<int, Signature> signatures;
290 std::map<int, Transform> poses;
291 std::multimap<int, rtabmap::Link> constraints;
308 bool modified =
false;
310 for(rtabmap::ParametersMap::iterator
i=parameters.begin();
i!=parameters.end(); ++
i)
313 if(defaultParameters.find((*i).first) != defaultParameters.end())
315 rnh.
setParam((*i).first, (*i).second);
318 else if((*i).first.find(
'/') != (*i).first.npos)
320 ROS_WARN(
"Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
329 ROS_ERROR(
"Can't call \"update_parameters\" service");
333 else if(anEvent->
getClassName().compare(
"RtabmapEventCmd") == 0)
335 std_srvs::Empty emptySrv;
342 ROS_ERROR(
"Can't call \"reset\" service");
351 if(system(
str.c_str()) !=0)
353 ROS_ERROR(
"Command \"%s\" returned non zero value.",
str.c_str());
363 ROS_ERROR(
"Can't call \"pause\" service");
371 ROS_ERROR(
"Can't call \"resume\" service");
381 if(system(
str.c_str()) !=0)
383 ROS_ERROR(
"Command \"%s\" returned non zero value.",
str.c_str());
391 ROS_ERROR(
"Can't call \"trigger_new_map\" service");
400 rtabmap_msgs::GetMap getMapSrv;
402 getMapSrv.request.optimized = cmdEvent->
value2().
toBool();
403 getMapSrv.request.graphOnly = cmdEvent->
value3().
toBool();
406 ROS_WARN(
"Can't call \"get_map_data\" service");
417 rtabmap_msgs::SetGoal setGoalSrv;
422 ROS_ERROR(
"Can't call \"set_goal\" service");
426 UASSERT(setGoalSrv.response.path_ids.size() == setGoalSrv.response.path_poses.size());
427 std::vector<std::pair<int, Transform> > poses(setGoalSrv.response.path_poses.size());
428 for(
unsigned int i=0;
i<setGoalSrv.response.path_poses.size(); ++
i)
430 poses[
i].first = setGoalSrv.response.path_ids[
i];
433 this->
post(
new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
440 ROS_ERROR(
"Can't call \"cancel_goal\" service");
447 rtabmap_msgs::SetLabel setLabelSrv;
448 setLabelSrv.request.node_label = cmdEvent->
value1().
toStr();
452 ROS_ERROR(
"Can't call \"set_label\" service");
458 rtabmap_msgs::RemoveLabel removeLabelSrv;
459 removeLabelSrv.request.label = cmdEvent->
value1().
toStr();
462 ROS_ERROR(
"Can't call \"remove_label\" service");
468 std_msgs::Int32MultiArray
msg;
477 else if(anEvent->
getClassName().compare(
"OdometryResetEvent") == 0)
482 ROS_ERROR(
"Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
489 const nav_msgs::OdometryConstPtr & odomMsg,
490 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
491 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
492 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
493 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
494 const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
495 const sensor_msgs::LaserScan& scan2dMsg,
496 const sensor_msgs::PointCloud2& scan3dMsg,
497 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
498 const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs,
499 const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPoints,
500 const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3d,
501 const std::vector<cv::Mat> & localDescriptors)
503 UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == cameraInfoMsgs.size()));
505 std_msgs::Header odomHeader;
509 odomHeader = odomMsg->header;
510 if(!odomMsg->child_frame_id.empty())
512 frameId = odomMsg->child_frame_id;
516 ROS_WARN(
"Received odom topic with child_frame_id not set! Using \"%s\" as base frame.",
frameId_.c_str());
521 if(!scan2dMsg.ranges.empty())
523 odomHeader = scan2dMsg.header;
525 else if(!scan3dMsg.data.empty())
527 odomHeader = scan3dMsg.header;
529 else if(cameraInfoMsgs.size())
531 odomHeader = cameraInfoMsgs[0].header;
533 else if(depthMsgs.size() && depthMsgs[0].get())
535 odomHeader = depthMsgs[0]->header;
537 else if(imageMsgs.size() && imageMsgs[0].get())
539 odomHeader = imageMsgs[0]->header;
545 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
548 UASSERT(odomMsg->twist.covariance.size() == 36);
549 if(odomMsg->twist.covariance[0] != 0 &&
550 odomMsg->twist.covariance[7] != 0 &&
551 odomMsg->twist.covariance[14] != 0 &&
552 odomMsg->twist.covariance[21] != 0 &&
553 odomMsg->twist.covariance[28] != 0 &&
554 odomMsg->twist.covariance[35] != 0)
556 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
559 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
561 if(odomInfoMsg->covariance[0] != 0 &&
562 odomInfoMsg->covariance[7] != 0 &&
563 odomInfoMsg->covariance[14] != 0 &&
564 odomInfoMsg->covariance[21] != 0 &&
565 odomInfoMsg->covariance[28] != 0 &&
566 odomInfoMsg->covariance[35] != 0)
568 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
571 if(odomHeader.frame_id.empty())
579 std::vector<rtabmap::CameraModel> cameraModels;
580 std::vector<rtabmap::StereoCameraModel> stereoCameraModels;
583 bool ignoreData =
false;
593 if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs.size() && depthMsgs[0].get())
596 bool imagesAlreadyRectified = Parameters::defaultRtabmapImagesAlreadyRectified();
597 Parameters::parse(allParameters, Parameters::kRtabmapImagesAlreadyRectified(), imagesAlreadyRectified);
613 imagesAlreadyRectified))
615 ROS_ERROR(
"Could not convert rgb/depth msgs! Aborting rtabmap_viz update...");
620 if(!scan2dMsg.ranges.empty())
631 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmap_viz update...");
635 else if(!scan3dMsg.data.empty())
646 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmap_viz update...");
651 if(odomInfoMsg.get())
657 else if(odomInfoMsg.get())
668 info.reg.covariance = covariance;
670 !stereoCameraModels.empty()?
692 const nav_msgs::OdometryConstPtr & odomMsg,
693 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
696 const sensor_msgs::CameraInfo& leftCamInfoMsg,
697 const sensor_msgs::CameraInfo& rightCamInfoMsg,
698 const sensor_msgs::LaserScan& scan2dMsg,
699 const sensor_msgs::PointCloud2& scan3dMsg,
700 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
701 const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs,
702 const std::vector<rtabmap_msgs::KeyPoint> & localKeyPoints,
703 const std::vector<rtabmap_msgs::Point3f> & localPoints3d,
704 const cv::Mat & localDescriptors)
706 std_msgs::Header odomHeader;
710 odomHeader = odomMsg->header;
711 if(!odomMsg->child_frame_id.empty())
713 frameId = odomMsg->child_frame_id;
717 ROS_WARN(
"Received odom topic with child_frame_id not set! Using \"%s\" as base frame.",
frameId_.c_str());
722 if(!scan2dMsg.ranges.empty())
724 odomHeader = scan2dMsg.header;
726 else if(!scan3dMsg.data.empty())
728 odomHeader = scan3dMsg.header;
732 odomHeader = leftCamInfoMsg.header;
738 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
741 UASSERT(odomMsg->twist.covariance.size() == 36);
742 if(odomMsg->twist.covariance[0] != 0 &&
743 odomMsg->twist.covariance[7] != 0 &&
744 odomMsg->twist.covariance[14] != 0 &&
745 odomMsg->twist.covariance[21] != 0 &&
746 odomMsg->twist.covariance[28] != 0 &&
747 odomMsg->twist.covariance[35] != 0)
749 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
752 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
754 if(odomInfoMsg->covariance[0] != 0 &&
755 odomInfoMsg->covariance[7] != 0 &&
756 odomInfoMsg->covariance[14] != 0 &&
757 odomInfoMsg->covariance[21] != 0 &&
758 odomInfoMsg->covariance[28] != 0 &&
759 odomInfoMsg->covariance[35] != 0)
761 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
764 if(odomHeader.frame_id.empty())
775 bool ignoreData =
false;
786 bool imagesAlreadyRectified = Parameters::defaultRtabmapImagesAlreadyRectified();
787 Parameters::parse(allParameters, Parameters::kRtabmapImagesAlreadyRectified(), imagesAlreadyRectified);
802 imagesAlreadyRectified))
804 ROS_ERROR(
"Could not convert stereo msgs! Aborting rtabmap_viz update...");
808 if(!scan2dMsg.ranges.empty())
819 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmap_viz update...");
823 else if(!scan3dMsg.data.empty())
834 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmap_viz update...");
839 if(odomInfoMsg.get())
845 else if(odomInfoMsg.get())
856 info.reg.covariance = covariance;
872 const nav_msgs::OdometryConstPtr & odomMsg,
873 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
874 const sensor_msgs::LaserScan& scan2dMsg,
875 const sensor_msgs::PointCloud2& scan3dMsg,
876 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
877 const rtabmap_msgs::GlobalDescriptor & globalDescriptor)
879 std_msgs::Header odomHeader;
883 odomHeader = odomMsg->header;
884 if(!odomMsg->child_frame_id.empty())
886 frameId = odomMsg->child_frame_id;
890 ROS_WARN(
"Received odom topic with child_frame_id not set! Using \"%s\" as base frame.",
frameId_.c_str());
895 if(!scan2dMsg.ranges.empty())
897 odomHeader = scan2dMsg.header;
899 else if(!scan3dMsg.data.empty())
901 odomHeader = scan3dMsg.header;
911 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
914 UASSERT(odomMsg->twist.covariance.size() == 36);
915 if(odomMsg->twist.covariance[0] != 0 &&
916 odomMsg->twist.covariance[7] != 0 &&
917 odomMsg->twist.covariance[14] != 0 &&
918 odomMsg->twist.covariance[21] != 0 &&
919 odomMsg->twist.covariance[28] != 0 &&
920 odomMsg->twist.covariance[35] != 0)
922 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
925 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
927 if(odomInfoMsg->covariance[0] != 0 &&
928 odomInfoMsg->covariance[7] != 0 &&
929 odomInfoMsg->covariance[14] != 0 &&
930 odomInfoMsg->covariance[21] != 0 &&
931 odomInfoMsg->covariance[28] != 0 &&
932 odomInfoMsg->covariance[35] != 0)
934 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
937 if(odomHeader.frame_id.empty())
945 bool ignoreData =
false;
955 if(!scan2dMsg.ranges.empty())
966 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmap_viz update...");
970 else if(!scan3dMsg.data.empty())
981 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmap_viz update...");
986 if(odomInfoMsg.get())
992 else if(odomInfoMsg.get())
1003 info.reg.covariance = covariance;
1019 const nav_msgs::OdometryConstPtr & odomMsg,
1020 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
1021 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
1025 std_msgs::Header odomHeader = odomMsg->header;
1028 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
1031 UASSERT(odomMsg->twist.covariance.size() == 36);
1032 if(odomMsg->twist.covariance[0] != 0 &&
1033 odomMsg->twist.covariance[7] != 0 &&
1034 odomMsg->twist.covariance[14] != 0 &&
1035 odomMsg->twist.covariance[21] != 0 &&
1036 odomMsg->twist.covariance[28] != 0 &&
1037 odomMsg->twist.covariance[35] != 0)
1039 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
1042 if(odomHeader.frame_id.empty())
1049 bool ignoreData =
false;
1059 if(odomInfoMsg.get())
1065 else if(odomInfoMsg.get())
1076 info.reg.covariance = covariance;
1091 const rtabmap_msgs::SensorDataConstPtr & sensorDataMsg,
1092 const nav_msgs::OdometryConstPtr & odomMsg,
1093 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
1096 std_msgs::Header odomHeader;
1100 odomHeader = odomMsg->header;
1101 if(!odomMsg->child_frame_id.empty())
1103 frameId = odomMsg->child_frame_id;
1107 ROS_WARN(
"Received odom topic with child_frame_id not set! Using \"%s\" as base frame.",
frameId_.c_str());
1112 odomHeader = sensorDataMsg->header;
1117 cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
1120 UASSERT(odomMsg->twist.covariance.size() == 36);
1121 if(odomMsg->twist.covariance[0] != 0 &&
1122 odomMsg->twist.covariance[7] != 0 &&
1123 odomMsg->twist.covariance[14] != 0 &&
1124 odomMsg->twist.covariance[21] != 0 &&
1125 odomMsg->twist.covariance[28] != 0 &&
1126 odomMsg->twist.covariance[35] != 0)
1128 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
1131 else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
1133 if(odomInfoMsg->covariance[0] != 0 &&
1134 odomInfoMsg->covariance[7] != 0 &&
1135 odomInfoMsg->covariance[14] != 0 &&
1136 odomInfoMsg->covariance[21] != 0 &&
1137 odomInfoMsg->covariance[28] != 0 &&
1138 odomInfoMsg->covariance[35] != 0)
1140 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomInfoMsg->covariance.data()).clone();
1143 if(odomHeader.frame_id.empty())
1151 bool ignoreData =
false;
1162 data.uncompressData();
1164 if(odomInfoMsg.get())
1170 else if(odomInfoMsg.get())
1173 data.clearRawData();
1174 data.clearCompressedData();
1184 info.reg.covariance = covariance;