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),
74 lastOdomInfoUpdateTime_(0)
79 QString configFile = QDir::homePath()+
"/.ros/rtabmapGUI.ini";
80 for(
int i=1; i<argc; ++i)
82 if(strcmp(argv[i],
"-d") == 0)
93 configFile.replace(
'~', QDir::homePath());
95 ROS_INFO(
"rtabmapviz: Using configuration from \"%s\"", configFile.toStdString().c_str());
101 nh.
param(
"is_rtabmap_paused", paused, paused);
105 std::string tfPrefix;
106 std::string initCachePath;
109 pnh.
param(
"tf_prefix", tfPrefix, tfPrefix);
114 pnh.
param(
"init_cache_path", initCachePath, initCachePath);
115 if(initCachePath.size())
118 if(initCachePath.at(0) !=
'/')
122 ROS_INFO(
"rtabmapviz: Initializing cache with local database \"%s\"", initCachePath.c_str());
124 rtabmap_ros::GetMap getMapSrv;
125 getMapSrv.request.global =
false;
126 getMapSrv.request.optimized =
true;
127 getMapSrv.request.graphOnly =
true;
130 ROS_WARN(
"Can't call \"get_map\" service. The cache will still be loaded " 131 "but the clouds won't be created until next time rtabmapviz " 132 "receives the optimized graph.");
139 QMetaObject::invokeMethod(
mainWindow_,
"updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
142 if(!tfPrefix.empty())
179 ROS_INFO(
"\n%s subscribed to:\n %s",
194 const rtabmap_ros::InfoConstPtr & infoMsg,
195 const rtabmap_ros::MapDataConstPtr & mapMsg)
207 std::map<int, rtabmap::Transform> poses;
208 std::map<int, Signature> signatures;
209 std::multimap<int, rtabmap::Link> links;
222 const rtabmap_ros::GoalConstPtr & goalMsg,
223 const nav_msgs::PathConstPtr & pathMsg)
226 std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
227 for(
unsigned int i=0; i<pathMsg->poses.size(); ++i)
229 poses[i].first = -int(i)-1;
236 const std_msgs::BoolConstPtr & value)
243 std::map<int, Signature> signatures;
244 std::map<int, Transform> poses;
245 std::multimap<int, rtabmap::Link> constraints;
262 bool modified =
false;
264 for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
267 if(defaultParameters.find((*i).first) != defaultParameters.end())
269 nh.
setParam((*i).first, (*i).second);
272 else if((*i).first.find(
'/') != (*i).first.npos)
274 ROS_WARN(
"Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
283 ROS_ERROR(
"Can't call \"update_parameters\" service");
287 else if(anEvent->
getClassName().compare(
"RtabmapEventCmd") == 0)
289 std_srvs::Empty emptySrv;
296 ROS_ERROR(
"Can't call \"reset\" service");
304 std::string str =
uFormat(
"rosrun dynamic_reconfigure dynparam set %s pause true",
cameraNodeName_.c_str());
305 if(system(str.c_str()) !=0)
307 ROS_ERROR(
"Command \"%s\" returned non zero value.", str.c_str());
315 if(!ros::service::call(
"pause", emptySrv))
317 ROS_ERROR(
"Can't call \"pause\" service");
325 ROS_ERROR(
"Can't call \"resume\" service");
334 std::string str =
uFormat(
"rosrun dynamic_reconfigure dynparam set %s pause false",
cameraNodeName_.c_str());
335 if(system(str.c_str()) !=0)
337 ROS_ERROR(
"Command \"%s\" returned non zero value.", str.c_str());
345 ROS_ERROR(
"Can't call \"trigger_new_map\" service");
354 rtabmap_ros::GetMap getMapSrv;
356 getMapSrv.request.optimized = cmdEvent->
value2().
toBool();
357 getMapSrv.request.graphOnly = cmdEvent->
value3().
toBool();
360 ROS_WARN(
"Can't call \"get_map_data\" service");
371 rtabmap_ros::SetGoal setGoalSrv;
376 ROS_ERROR(
"Can't call \"set_goal\" service");
380 UASSERT(setGoalSrv.response.path_ids.size() == setGoalSrv.response.path_poses.size());
381 std::vector<std::pair<int, Transform> > poses(setGoalSrv.response.path_poses.size());
382 for(
unsigned int i=0; i<setGoalSrv.response.path_poses.size(); ++i)
384 poses[i].first = setGoalSrv.response.path_ids[i];
387 this->
post(
new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
394 ROS_ERROR(
"Can't call \"cancel_goal\" service");
401 rtabmap_ros::SetLabel setLabelSrv;
402 setLabelSrv.request.node_label = cmdEvent->
value1().
toStr();
406 ROS_ERROR(
"Can't call \"set_label\" service");
411 ROS_WARN(
"Not handled command (%d)...", cmd);
414 else if(anEvent->
getClassName().compare(
"OdometryResetEvent") == 0)
419 ROS_ERROR(
"Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
426 const nav_msgs::OdometryConstPtr & odomMsg,
427 const rtabmap_ros::UserDataConstPtr & userDataMsg,
428 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
429 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
430 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
431 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
432 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
433 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
435 UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == depthMsgs.size() && imageMsgs.size() == cameraInfoMsgs.size()));
437 std_msgs::Header odomHeader;
440 odomHeader = odomMsg->header;
446 odomHeader = scan2dMsg->header;
448 else if(scan3dMsg.get())
450 odomHeader = scan3dMsg->header;
452 else if(cameraInfoMsgs.size())
454 odomHeader = cameraInfoMsgs[0].header;
456 else if(depthMsgs.size() && depthMsgs[0].get())
458 odomHeader = depthMsgs[0]->header;
460 else if(imageMsgs.size() && imageMsgs[0].get())
462 odomHeader = imageMsgs[0]->header;
468 cv::Mat
covariance = cv::Mat::eye(6,6,CV_64FC1);
471 UASSERT(odomMsg->twist.covariance.size() == 36);
472 if(odomMsg->twist.covariance[0] != 0 &&
473 odomMsg->twist.covariance[7] != 0 &&
474 odomMsg->twist.covariance[14] != 0 &&
475 odomMsg->twist.covariance[21] != 0 &&
476 odomMsg->twist.covariance[28] != 0 &&
477 odomMsg->twist.covariance[35] != 0)
479 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
482 if(odomHeader.frame_id.empty())
490 std::vector<CameraModel> cameraModels;
492 Transform scanLocalTransform = Transform::getIdentity();
494 bool ignoreData =
false;
502 if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs[0].get())
517 ROS_ERROR(
"Could not convert rgb/depth msgs! Aborting rtabmapviz update...");
522 if(scan2dMsg.get() != 0)
534 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmapviz update...");
538 else if(scan3dMsg.get() != 0)
550 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
555 if(odomInfoMsg.get())
561 else if(odomInfoMsg.get())
575 LaserScan::backwardCompatibility(scan,
576 scan2dMsg.get()?(int)scan2dMsg->ranges.size():0,
577 scan2dMsg.get()?(int)scan2dMsg->range_max:0,
591 const nav_msgs::OdometryConstPtr & odomMsg,
592 const rtabmap_ros::UserDataConstPtr & userDataMsg,
595 const sensor_msgs::CameraInfo& leftCamInfoMsg,
596 const sensor_msgs::CameraInfo& rightCamInfoMsg,
597 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
598 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
599 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
601 std_msgs::Header odomHeader;
604 odomHeader = odomMsg->header;
610 odomHeader = scan2dMsg->header;
612 else if(scan3dMsg.get())
614 odomHeader = scan3dMsg->header;
618 odomHeader = leftCamInfoMsg.header;
624 cv::Mat
covariance = cv::Mat::eye(6,6,CV_64FC1);
627 UASSERT(odomMsg->twist.covariance.size() == 36);
628 if(odomMsg->twist.covariance[0] != 0 &&
629 odomMsg->twist.covariance[7] != 0 &&
630 odomMsg->twist.covariance[14] != 0 &&
631 odomMsg->twist.covariance[21] != 0 &&
632 odomMsg->twist.covariance[28] != 0 &&
633 odomMsg->twist.covariance[35] != 0)
635 covariance = cv::Mat(6,6,CV_64FC1,(
void*)odomMsg->twist.covariance.data()).clone();
638 if(odomHeader.frame_id.empty())
647 Transform scanLocalTransform = Transform::getIdentity();
650 bool ignoreData =
false;
673 ROS_ERROR(
"Could not convert stereo msgs! Aborting rtabmapviz update...");
677 if(scan2dMsg.get() != 0)
689 ROS_ERROR(
"Could not convert laser scan msg! Aborting rtabmapviz update...");
693 else if(scan3dMsg.get() != 0)
705 ROS_ERROR(
"Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
710 if(odomInfoMsg.get())
716 else if(odomInfoMsg.get())
730 LaserScan::backwardCompatibility(scan,
731 scan2dMsg.get()?(int)scan2dMsg->ranges.size():0,
732 scan2dMsg.get()?(int)scan2dMsg->range_max:0,
750 rtabmap_ros::UserDataConstPtr(),
753 sensor_msgs::CameraInfo(),
754 sensor_msgs::CameraInfo(),
755 sensor_msgs::LaserScanConstPtr(),
756 sensor_msgs::PointCloud2ConstPtr(),
757 rtabmap_ros::OdomInfoConstPtr());
bool convertScanMsg(const sensor_msgs::LaserScanConstPtr &scan2dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &scan, rtabmap::Transform &scanLocalTransform, tf::TransformListener &listener, double waitForTransform)
static std::string homeDir()
const UVariant & value2() const
bool isProcessingOdometry() const
std::string uFormat(const char *fmt,...)
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::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
bool convertScan3dMsg(const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &scan, rtabmap::Transform &scanLocalTransform, tf::TransformListener &listener, double waitForTransform)
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 &scan2dMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
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)
const UVariant & value3() const
bool call(const std::string &service_name, MReq &req, MRes &res)
OdometryInfo copyWithoutData() const
GLM_FUNC_DECL genType e()
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 &scan2dMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
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)
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 defaultSub_
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)
void defaultCallback(const nav_msgs::OdometryConstPtr &odomMsg)
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)
bool isDataSubscribed() const
std::string getTopic() const
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)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg)
void goalPathCallback(const rtabmap_ros::GoalConstPtr &goalMsg, const nav_msgs::PathConstPtr &pathMsg)
void setMonitoringState(bool pauseChecked=false)
float max3(const float &a, const float &b, const float &c)
void setMapCorrection(const Transform &mapCorrection)
void uSleep(unsigned int ms)
void setSignatures(const std::map< int, Signature > &signatures)
static const ParametersMap & getDefaultParameters()
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
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)