GuiWrapper.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "rtabmap_ros/GuiWrapper.h"
29 #include <QApplication>
30 #include <QDir>
31 
32 #include <std_srvs/Empty.h>
33 #include <std_msgs/Empty.h>
34 
38 
39 #include <opencv2/highgui/highgui.hpp>
40 
41 #include <rtabmap/gui/MainWindow.h>
46 #include <rtabmap/core/util2d.h>
47 #include <rtabmap/core/util3d.h>
49 #include <rtabmap/utilite/UTimer.h>
50 
52 #include "rtabmap_ros/GetMap.h"
53 #include "rtabmap_ros/SetGoal.h"
54 #include "rtabmap_ros/SetLabel.h"
56 
57 float max3( const float& a, const float& b, const float& c)
58 {
59  float m=a>b?a:b;
60  return m>c?m:c;
61 }
62 
63 namespace rtabmap_ros {
64 
65 GuiWrapper::GuiWrapper(int & argc, char** argv) :
67  mainWindow_(0),
68  frameId_("base_link"),
69  odomFrameId_(""),
70  waitForTransform_(true),
71  waitForTransformDuration_(0.2), // 200 ms
72  odomSensorSync_(false),
73  maxOdomUpdateRate_(10),
74  cameraNodeName_(""),
75  lastOdomInfoUpdateTime_(0)
76 {
77  ros::NodeHandle nh;
78  ros::NodeHandle pnh("~");
79 
80  QString configFile = QDir::homePath()+"/.ros/rtabmapGUI.ini";
81  for(int i=1; i<argc; ++i)
82  {
83  if(strcmp(argv[i], "-d") == 0)
84  {
85  ++i;
86  if(i < argc)
87  {
88  configFile = argv[i];
89  }
90  break;
91  }
92  }
93 
94  configFile.replace('~', QDir::homePath());
95 
96  ROS_INFO("rtabmapviz: Using configuration from \"%s\"", configFile.toStdString().c_str());
97  uSleep(500);
98  mainWindow_ = new MainWindow(new PreferencesDialogROS(configFile));
99  mainWindow_->setWindowTitle(mainWindow_->windowTitle()+" [ROS]");
100  mainWindow_->show();
101  bool paused = false;
102  nh.param("is_rtabmap_paused", paused, paused);
104 
105  // To receive odometry events
106  std::string tfPrefix;
107  std::string initCachePath;
108  pnh.param("frame_id", frameId_, frameId_);
109  pnh.param("odom_frame_id", odomFrameId_, odomFrameId_); // set to use odom from TF
110  pnh.param("tf_prefix", tfPrefix, tfPrefix);
111  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
112  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
113  pnh.param("odom_sensor_sync", odomSensorSync_, odomSensorSync_);
114  pnh.param("max_odom_update_rate", maxOdomUpdateRate_, maxOdomUpdateRate_);
115  pnh.param("camera_node_name", cameraNodeName_, cameraNodeName_); // used to pause the rtabmap_ros/camera when pausing the process
116  pnh.param("init_cache_path", initCachePath, initCachePath);
117  if(initCachePath.size())
118  {
119  initCachePath = uReplaceChar(initCachePath, '~', UDirectory::homeDir());
120  if(initCachePath.at(0) != '/')
121  {
122  initCachePath = UDirectory::currentDir(true) + initCachePath;
123  }
124  ROS_INFO("rtabmapviz: Initializing cache with local database \"%s\"", initCachePath.c_str());
125  uSleep(2000); // make sure rtabmap node is created if launched at the same time
126  rtabmap_ros::GetMap getMapSrv;
127  getMapSrv.request.global = false;
128  getMapSrv.request.optimized = true;
129  getMapSrv.request.graphOnly = true;
130  if(!ros::service::call("get_map", getMapSrv))
131  {
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.");
135  }
136  else
137  {
138  // this will update the poses and constraints of the MainWindow
139  processRequestedMap(getMapSrv.response.data);
140  }
141  QMetaObject::invokeMethod(mainWindow_, "updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
142  }
143 
144  if(!tfPrefix.empty())
145  {
146  if(!frameId_.empty())
147  {
148  frameId_ = tfPrefix + "/" + frameId_;
149  }
150  if(!odomFrameId_.empty())
151  {
152  odomFrameId_ = tfPrefix + "/" + odomFrameId_;
153  }
154  }
155 
158 
159  infoTopic_.subscribe(nh, "info", 1);
160  mapDataTopic_.subscribe(nh, "mapData", 1);
163  infoTopic_,
164  mapDataTopic_);
165  infoMapSync_->registerCallback(boost::bind(&GuiWrapper::infoMapCallback, this, _1, _2));
166 
167  goalTopic_.subscribe(nh, "goal_node", 1);
168  pathTopic_.subscribe(nh, "global_path", 1);
171  goalTopic_,
172  pathTopic_);
173  goalPathSync_->registerCallback(boost::bind(&GuiWrapper::goalPathCallback, this, _1, _2));
174  goalReachedTopic_ = nh.subscribe("goal_reached", 1, &GuiWrapper::goalReachedCallback, this);
175 
176  setupCallbacks(nh, pnh, ros::this_node::getName()); // do it at the end
177 }
178 
180 {
181  UDEBUG("");
182 
183  delete infoMapSync_;
184  delete mainWindow_;
185 }
186 
188  const rtabmap_ros::InfoConstPtr & infoMsg,
189  const rtabmap_ros::MapDataConstPtr & mapMsg)
190 {
191  //ROS_INFO("rtabmapviz: RTAB-Map info ex received!");
192 
193  // Map from ROS struct to rtabmap struct
194  rtabmap::Statistics stat;
195 
196  // Info
197  rtabmap_ros::infoFromROS(*infoMsg, stat);
198 
199  // MapData
200  rtabmap::Transform mapToOdom;
201  std::map<int, rtabmap::Transform> poses;
202  std::map<int, Signature> signatures;
203  std::multimap<int, rtabmap::Link> links;
204 
205  rtabmap_ros::mapDataFromROS(*mapMsg, poses, links, signatures, mapToOdom);
206 
207  stat.setMapCorrection(mapToOdom);
208  stat.setPoses(poses);
209  if(signatures.size())
210  {
211  stat.setLastSignatureData(signatures.rbegin()->second);
212  }
213  stat.setConstraints(links);
214 
215  this->post(new RtabmapEvent(stat));
216 }
217 
219  const rtabmap_ros::GoalConstPtr & goalMsg,
220  const nav_msgs::PathConstPtr & pathMsg)
221 {
222  // we don't have the node ids, just generate fake ones.
223  std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
224  for(unsigned int i=0; i<pathMsg->poses.size(); ++i)
225  {
226  poses[i].first = -int(i)-1;
227  poses[i].second = rtabmap_ros::transformFromPoseMsg(pathMsg->poses[i].pose);
228  }
229  this->post(new RtabmapGlobalPathEvent(goalMsg->node_id, goalMsg->node_label, poses, 0.0));
230 }
231 
233  const std_msgs::BoolConstPtr & value)
234 {
235  this->post(new RtabmapGoalStatusEvent(value->data?1:-1));
236 }
237 
238 void GuiWrapper::processRequestedMap(const rtabmap_ros::MapData & map)
239 {
240  std::map<int, Signature> signatures;
241  std::map<int, Transform> poses;
242  std::multimap<int, rtabmap::Link> constraints;
243  Transform mapToOdom;
244 
245  rtabmap_ros::mapDataFromROS(map, poses, constraints, signatures, mapToOdom);
246 
247  RtabmapEvent3DMap e(signatures,
248  poses,
249  constraints);
250  QMetaObject::invokeMethod(mainWindow_, "processRtabmapEvent3DMap", Q_ARG(rtabmap::RtabmapEvent3DMap, e));
251 }
252 
254 {
255  if(anEvent->getClassName().compare("ParamEvent") == 0)
256  {
258  rtabmap::ParametersMap parameters = ((rtabmap::ParamEvent *)anEvent)->getParameters();
259  bool modified = false;
260  ros::NodeHandle nh;
261  for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
262  {
263  //save only parameters with valid names
264  if(defaultParameters.find((*i).first) != defaultParameters.end())
265  {
266  nh.setParam((*i).first, (*i).second);
267  modified = true;
268  }
269  else if((*i).first.find('/') != (*i).first.npos)
270  {
271  ROS_WARN("Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
272  }
273  }
274  if(modified)
275  {
276  ROS_INFO("Parameters updated");
277  std_srvs::Empty srv;
278  if(!ros::service::call("update_parameters", srv))
279  {
280  ROS_ERROR("Can't call \"update_parameters\" service");
281  }
282  }
283  }
284  else if(anEvent->getClassName().compare("RtabmapEventCmd") == 0)
285  {
286  std_srvs::Empty emptySrv;
287  rtabmap::RtabmapEventCmd * cmdEvent = (rtabmap::RtabmapEventCmd *)anEvent;
290  {
291  if(!ros::service::call("reset", emptySrv))
292  {
293  ROS_ERROR("Can't call \"reset\" service");
294  }
295  }
297  {
298  // Pause the camera if the rtabmap/camera node is used
299  if(!cameraNodeName_.empty())
300  {
301  std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause true", cameraNodeName_.c_str());
302  if(system(str.c_str()) !=0)
303  {
304  ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
305  }
306  }
307 
308  // Pause visual_odometry
309  ros::service::call("pause_odom", emptySrv);
310 
311  // Pause rtabmap
312  if(!ros::service::call("pause", emptySrv))
313  {
314  ROS_ERROR("Can't call \"pause\" service");
315  }
316  }
318  {
319  // Resume rtabmap
320  if(!ros::service::call("resume", emptySrv))
321  {
322  ROS_ERROR("Can't call \"resume\" service");
323  }
324 
325  // Pause visual_odometry
326  ros::service::call("resume_odom", emptySrv);
327 
328  // Resume the camera if the rtabmap/camera node is used
329  if(!cameraNodeName_.empty())
330  {
331  std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause false", cameraNodeName_.c_str());
332  if(system(str.c_str()) !=0)
333  {
334  ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
335  }
336  }
337  }
339  {
340  if(!ros::service::call("trigger_new_map", emptySrv))
341  {
342  ROS_ERROR("Can't call \"trigger_new_map\" service");
343  }
344  }
346  {
347  UASSERT(cmdEvent->value1().isBool());
348  UASSERT(cmdEvent->value2().isBool());
349  UASSERT(cmdEvent->value3().isBool());
350 
351  rtabmap_ros::GetMap getMapSrv;
352  getMapSrv.request.global = cmdEvent->value1().toBool();
353  getMapSrv.request.optimized = cmdEvent->value2().toBool();
354  getMapSrv.request.graphOnly = cmdEvent->value3().toBool();
355  if(!ros::service::call("get_map_data", getMapSrv))
356  {
357  ROS_WARN("Can't call \"get_map_data\" service");
358  this->post(new RtabmapEvent3DMap(1)); // service error
359  }
360  else
361  {
362  processRequestedMap(getMapSrv.response.data);
363  }
364  }
365  else if(cmd == rtabmap::RtabmapEventCmd::kCmdGoal)
366  {
367  UASSERT(cmdEvent->value1().isStr() || cmdEvent->value1().isInt() || cmdEvent->value1().isUInt());
368  rtabmap_ros::SetGoal setGoalSrv;
369  setGoalSrv.request.node_id = !cmdEvent->value1().isStr()?cmdEvent->value1().toInt():0;
370  setGoalSrv.request.node_label = cmdEvent->value1().isStr()?cmdEvent->value1().toStr():"";
371  if(!ros::service::call("set_goal", setGoalSrv))
372  {
373  ROS_ERROR("Can't call \"set_goal\" service");
374  }
375  else
376  {
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)
380  {
381  poses[i].first = setGoalSrv.response.path_ids[i];
382  poses[i].second = rtabmap_ros::transformFromPoseMsg(setGoalSrv.response.path_poses[i]);
383  }
384  this->post(new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
385  }
386  }
388  {
389  if(!ros::service::call("cancel_goal", emptySrv))
390  {
391  ROS_ERROR("Can't call \"cancel_goal\" service");
392  }
393  }
395  {
396  UASSERT(cmdEvent->value1().isStr());
397  UASSERT(cmdEvent->value2().isUndef() || cmdEvent->value2().isInt() || cmdEvent->value2().isUInt());
398  rtabmap_ros::SetLabel setLabelSrv;
399  setLabelSrv.request.node_label = cmdEvent->value1().toStr();
400  setLabelSrv.request.node_id = cmdEvent->value2().isUndef()?0:cmdEvent->value2().toInt();
401  if(!ros::service::call("set_label", setLabelSrv))
402  {
403  ROS_ERROR("Can't call \"set_label\" service");
404  }
405  }
406  else
407  {
408  ROS_WARN("Not handled command (%d)...", cmd);
409  }
410  }
411  else if(anEvent->getClassName().compare("OdometryResetEvent") == 0)
412  {
413  std_srvs::Empty srv;
414  if(!ros::service::call("reset_odom", srv))
415  {
416  ROS_ERROR("Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
417  }
418  }
419  return false;
420 }
421 
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)
435 {
436  UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == cameraInfoMsgs.size()));
437 
438  std_msgs::Header odomHeader;
439  if(odomMsg.get())
440  {
441  odomHeader = odomMsg->header;
442  }
443  else
444  {
445  if(!scan2dMsg.ranges.empty())
446  {
447  odomHeader = scan2dMsg.header;
448  }
449  else if(!scan3dMsg.data.empty())
450  {
451  odomHeader = scan3dMsg.header;
452  }
453  else if(cameraInfoMsgs.size())
454  {
455  odomHeader = cameraInfoMsgs[0].header;
456  }
457  else if(depthMsgs.size() && depthMsgs[0].get())
458  {
459  odomHeader = depthMsgs[0]->header;
460  }
461  else if(imageMsgs.size() && imageMsgs[0].get())
462  {
463  odomHeader = imageMsgs[0]->header;
464  }
465  odomHeader.frame_id = odomFrameId_;
466  }
467 
468  Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
469  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
470  if(odomMsg.get())
471  {
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)
479  {
480  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
481  }
482  }
483  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
484  {
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)
491  {
492  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
493  }
494  }
495  if(odomHeader.frame_id.empty())
496  {
497  ROS_ERROR("Odometry frame not set!?");
498  return;
499  }
500 
501  cv::Mat rgb;
502  cv::Mat depth;
503  std::vector<CameraModel> cameraModels;
504  LaserScan scan;
506  bool ignoreData = false;
507 
508  // limit update rate
509  if(maxOdomUpdateRate_<=0.0 ||
513  {
515 
516  if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs.size() && depthMsgs[0].get())
517  {
519  imageMsgs,
520  depthMsgs,
521  cameraInfoMsgs,
522  frameId_,
523  odomSensorSync_?odomHeader.frame_id:"",
524  odomHeader.stamp,
525  rgb,
526  depth,
527  cameraModels,
528  tfListener_,
529  waitForTransform_?waitForTransformDuration_:0.0))
530  {
531  ROS_ERROR("Could not convert rgb/depth msgs! Aborting rtabmapviz update...");
532  return;
533  }
534  }
535 
536  if(!scan2dMsg.ranges.empty())
537  {
539  scan2dMsg,
540  frameId_,
541  odomSensorSync_?odomHeader.frame_id:"",
542  odomHeader.stamp,
543  scan,
544  tfListener_,
545  waitForTransform_?waitForTransformDuration_:0))
546  {
547  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
548  return;
549  }
550  }
551  else if(!scan3dMsg.data.empty())
552  {
554  scan3dMsg,
555  frameId_,
556  odomSensorSync_?odomHeader.frame_id:"",
557  odomHeader.stamp,
558  scan,
559  tfListener_,
560  waitForTransform_?waitForTransformDuration_:0))
561  {
562  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
563  return;
564  }
565  }
566 
567  if(odomInfoMsg.get())
568  {
569  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
570  }
571  ignoreData = false;
572  }
573  else if(odomInfoMsg.get())
574  {
575  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
576  ignoreData = true;
577  }
578  else
579  {
580  // don't update GUI odom stuff if we don't use visual odometry
581  return;
582  }
583 
584  info.reg.covariance = covariance;
585  rtabmap::OdometryEvent odomEvent(
587  scan,
588  rgb,
589  depth,
590  cameraModels,
591  odomHeader.seq,
592  rtabmap_ros::timestampFromROS(odomHeader.stamp)),
593  odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
594  info);
595 
596  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
597 }
598 
600  const nav_msgs::OdometryConstPtr & odomMsg,
601  const rtabmap_ros::UserDataConstPtr & userDataMsg,
602  const cv_bridge::CvImageConstPtr& leftImageMsg,
603  const cv_bridge::CvImageConstPtr& rightImageMsg,
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)
613 {
614  std_msgs::Header odomHeader;
615  if(odomMsg.get())
616  {
617  odomHeader = odomMsg->header;
618  }
619  else
620  {
621  if(!scan2dMsg.ranges.empty())
622  {
623  odomHeader = scan2dMsg.header;
624  }
625  else if(!scan3dMsg.data.empty())
626  {
627  odomHeader = scan3dMsg.header;
628  }
629  else
630  {
631  odomHeader = leftCamInfoMsg.header;
632  }
633  odomHeader.frame_id = odomFrameId_;
634  }
635 
636  Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
637  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
638  if(odomMsg.get())
639  {
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)
647  {
648  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
649  }
650  }
651  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
652  {
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)
659  {
660  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
661  }
662  }
663  if(odomHeader.frame_id.empty())
664  {
665  ROS_ERROR("Odometry frame not set!?");
666  return;
667  }
668 
669  cv::Mat left;
670  cv::Mat right;
671  LaserScan scan;
672  rtabmap::StereoCameraModel stereoModel;
674  bool ignoreData = false;
675 
676  // limit update rate
677  if(maxOdomUpdateRate_<=0.0 ||
681  {
683 
685  leftImageMsg,
686  rightImageMsg,
687  leftCamInfoMsg,
688  rightCamInfoMsg,
689  frameId_,
690  odomSensorSync_?odomHeader.frame_id:"",
691  odomHeader.stamp,
692  left,
693  right,
694  stereoModel,
695  tfListener_,
696  waitForTransform_?waitForTransformDuration_:0.0,
697  true))
698  {
699  ROS_ERROR("Could not convert stereo msgs! Aborting rtabmapviz update...");
700  return;
701  }
702 
703  if(!scan2dMsg.ranges.empty())
704  {
706  scan2dMsg,
707  frameId_,
708  odomSensorSync_?odomHeader.frame_id:"",
709  odomHeader.stamp,
710  scan,
711  tfListener_,
712  waitForTransform_?waitForTransformDuration_:0))
713  {
714  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
715  return;
716  }
717  }
718  else if(!scan3dMsg.data.empty())
719  {
721  scan3dMsg,
722  frameId_,
723  odomSensorSync_?odomHeader.frame_id:"",
724  odomHeader.stamp,
725  scan,
726  tfListener_,
727  waitForTransform_?waitForTransformDuration_:0))
728  {
729  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
730  return;
731  }
732  }
733 
734  if(odomInfoMsg.get())
735  {
736  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
737  }
738  ignoreData = false;
739  }
740  else if(odomInfoMsg.get())
741  {
742  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
743  ignoreData = true;
744  }
745  else
746  {
747  // don't update GUI odom stuff if we don't use visual odometry
748  return;
749  }
750 
751  info.reg.covariance = covariance;
752  rtabmap::OdometryEvent odomEvent(
754  scan,
755  left,
756  right,
757  stereoModel,
758  odomHeader.seq,
759  rtabmap_ros::timestampFromROS(odomHeader.stamp)),
760  odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
761  info);
762 
763  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
764 }
765 
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)
773 {
774  std_msgs::Header odomHeader;
775  if(odomMsg.get())
776  {
777  odomHeader = odomMsg->header;
778  }
779  else
780  {
781  if(!scan2dMsg.ranges.empty())
782  {
783  odomHeader = scan2dMsg.header;
784  }
785  else if(!scan3dMsg.data.empty())
786  {
787  odomHeader = scan3dMsg.header;
788  }
789  else
790  {
791  return;
792  }
793  odomHeader.frame_id = odomFrameId_;
794  }
795 
796  Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
797  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
798  if(odomMsg.get())
799  {
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)
807  {
808  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
809  }
810  }
811  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
812  {
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)
819  {
820  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
821  }
822  }
823  if(odomHeader.frame_id.empty())
824  {
825  ROS_ERROR("Odometry frame not set!?");
826  return;
827  }
828 
829  LaserScan scan;
831  bool ignoreData = false;
832  Transform fakeCameraLocalTransform;
833 
834  // limit update rate
835  if(maxOdomUpdateRate_<=0.0 ||
839  {
841 
842  if(!scan2dMsg.ranges.empty())
843  {
845  scan2dMsg,
846  frameId_,
847  odomSensorSync_?odomHeader.frame_id:"",
848  odomHeader.stamp,
849  scan,
850  tfListener_,
851  waitForTransform_?waitForTransformDuration_:0))
852  {
853  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
854  return;
855  }
856  }
857  else if(!scan3dMsg.data.empty())
858  {
860  scan3dMsg,
861  frameId_,
862  odomSensorSync_?odomHeader.frame_id:"",
863  odomHeader.stamp,
864  scan,
865  tfListener_,
866  waitForTransform_?waitForTransformDuration_:0))
867  {
868  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
869  return;
870  }
871  }
872 
873  if(odomInfoMsg.get())
874  {
875  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
876  }
877  ignoreData = false;
878  }
879  else if(odomInfoMsg.get())
880  {
881  //just get scan local transform to adjust camera frame
882  if(!scan2dMsg.ranges.empty())
883  {
884  fakeCameraLocalTransform = getTransform(frameId_, scan2dMsg.header.frame_id, scan2dMsg.header.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
885  }
886  else if(!scan3dMsg.data.empty())
887  {
888  fakeCameraLocalTransform = getTransform(frameId_, scan3dMsg.header.frame_id, scan3dMsg.header.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
889  }
890 
891  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
892  ignoreData = true;
893  }
894  else
895  {
896  // don't update GUI odom stuff if we don't use visual odometry
897  return;
898  }
899 
900  cv::Mat rgb;
901  cv::Mat depth;
902  CameraModel model(
903  2,
904  2,
905  2,
906  1.5,
907  (fakeCameraLocalTransform.isNull()?scan.localTransform():fakeCameraLocalTransform)*Transform(0,0,1,0, -1,0,0,0, 0,-1,0,0),
908  0,
909  cv::Size(4,3));
910 
911  info.reg.covariance = covariance;
912  rtabmap::OdometryEvent odomEvent(
914  scan,
915  rgb,
916  depth,
917  model,
918  odomHeader.seq,
919  rtabmap_ros::timestampFromROS(odomHeader.stamp)),
920  odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
921  info);
922 
923  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
924 }
925 
927  const nav_msgs::OdometryConstPtr & odomMsg,
928  const rtabmap_ros::UserDataConstPtr & userDataMsg,
929  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
930 {
931  UASSERT(odomMsg.get());
932 
933  std_msgs::Header odomHeader = odomMsg->header;
934 
935  Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
936  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
937  if(odomMsg.get())
938  {
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)
946  {
947  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
948  }
949  }
950  if(odomHeader.frame_id.empty())
951  {
952  ROS_ERROR("Odometry frame not set!?");
953  return;
954  }
955 
957  bool ignoreData = false;
958 
959  // limit update rate
960  if(maxOdomUpdateRate_<=0.0 ||
964  {
966 
967  if(odomInfoMsg.get())
968  {
969  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
970  }
971  ignoreData = false;
972  }
973  else if(odomInfoMsg.get())
974  {
975  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
976  ignoreData = true;
977  }
978  else
979  {
980  // don't update GUI odom stuff if we don't use visual odometry
981  return;
982  }
983 
984  cv::Mat rgb;
985  cv::Mat depth;
986  CameraModel model(
987  2,
988  2,
989  2,
990  1.5,
991  Transform(0,0,1,0, -1,0,0,0, 0,-1,0,0),
992  0,
993  cv::Size(4,3));
994 
995  info.reg.covariance = covariance;
996  rtabmap::OdometryEvent odomEvent(
998  rgb,
999  depth,
1000  model,
1001  odomHeader.seq,
1002  rtabmap_ros::timestampFromROS(odomHeader.stamp)),
1003  odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
1004  info);
1005 
1006  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
1007 }
1008 
1009 }
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)
Definition: GuiWrapper.cpp:926
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)
bool isBool() const
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
Definition: GuiWrapper.h:143
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 >())
Definition: GuiWrapper.cpp:422
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
Definition: GuiWrapper.h:128
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
Definition: GuiWrapper.h:131
std::string uReplaceChar(const std::string &str, char before, char after)
virtual bool handleEvent(UEvent *anEvent)
Definition: GuiWrapper.cpp:253
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())
Definition: GuiWrapper.cpp:599
string cmd
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)
Definition: GuiWrapper.cpp:187
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)
Definition: GuiWrapper.cpp:238
#define ROS_WARN(...)
rtabmap::MainWindow * mainWindow_
Definition: GuiWrapper.h:115
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)
Definition: GuiWrapper.cpp:232
void setLastSignatureData(const Signature &data)
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
Definition: GuiWrapper.h:129
static std::string currentDir(bool trailingSeparator=false)
int toInt(bool *ok=0) const
#define true
bool paused
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)
bool isNull() const
double waitForTransformDuration_
Definition: GuiWrapper.h:123
void setPoses(const std::map< int, Transform > &poses)
ros::Subscriber goalReachedTopic_
Definition: GuiWrapper.h:133
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
Definition: GuiWrapper.h:138
virtual std::string getClassName() const =0
bool isInt() const
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
bool isStr() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void infoFromROS(const rtabmap_ros::Info &info, rtabmap::Statistics &stat)
bool toBool() const
Transform localTransform() const
void goalPathCallback(const rtabmap_ros::GoalConstPtr &goalMsg, const nav_msgs::PathConstPtr &pathMsg)
Definition: GuiWrapper.cpp:218
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)
Definition: GuiWrapper.cpp:57
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)
bool isUInt() const
#define false
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())
Definition: GuiWrapper.cpp:766
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_
Definition: GuiWrapper.h:126
#define UDEBUG(...)
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
Definition: GuiWrapper.h:142
std::string cameraNodeName_
Definition: GuiWrapper.h:116
static double now()
double timestampFromROS(const ros::Time &stamp)
std::string toStr(bool *ok=0) const
RegistrationInfo reg
message_filters::Subscriber< nav_msgs::Path > pathTopic_
Definition: GuiWrapper.h:132
GuiWrapper(int &argc, char **argv)
Definition: GuiWrapper.cpp:65
bool isUndef() const
message_filters::sync_policies::ExactTime< rtabmap_ros::Info, rtabmap_ros::MapData > MyInfoMapSyncPolicy
Definition: GuiWrapper.h:137
std::string odomFrameId_
Definition: GuiWrapper.h:121
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


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