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  cameraNodeName_(""),
74  lastOdomInfoUpdateTime_(0)
75 {
76  ros::NodeHandle nh;
77  ros::NodeHandle pnh("~");
78 
79  QString configFile = QDir::homePath()+"/.ros/rtabmapGUI.ini";
80  for(int i=1; i<argc; ++i)
81  {
82  if(strcmp(argv[i], "-d") == 0)
83  {
84  ++i;
85  if(i < argc)
86  {
87  configFile = argv[i];
88  }
89  break;
90  }
91  }
92 
93  configFile.replace('~', QDir::homePath());
94 
95  ROS_INFO("rtabmapviz: Using configuration from \"%s\"", configFile.toStdString().c_str());
96  uSleep(500);
97  mainWindow_ = new MainWindow(new PreferencesDialogROS(configFile));
98  mainWindow_->setWindowTitle(mainWindow_->windowTitle()+" [ROS]");
99  mainWindow_->show();
100  bool paused = false;
101  nh.param("is_rtabmap_paused", paused, paused);
103 
104  // To receive odometry events
105  std::string tfPrefix;
106  std::string initCachePath;
107  pnh.param("frame_id", frameId_, frameId_);
108  pnh.param("odom_frame_id", odomFrameId_, odomFrameId_); // set to use odom from TF
109  pnh.param("tf_prefix", tfPrefix, tfPrefix);
110  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
111  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
112  pnh.param("odom_sensor_sync", odomSensorSync_, odomSensorSync_);
113  pnh.param("camera_node_name", cameraNodeName_, cameraNodeName_); // used to pause the rtabmap_ros/camera when pausing the process
114  pnh.param("init_cache_path", initCachePath, initCachePath);
115  if(initCachePath.size())
116  {
117  initCachePath = uReplaceChar(initCachePath, '~', UDirectory::homeDir());
118  if(initCachePath.at(0) != '/')
119  {
120  initCachePath = UDirectory::currentDir(true) + initCachePath;
121  }
122  ROS_INFO("rtabmapviz: Initializing cache with local database \"%s\"", initCachePath.c_str());
123  uSleep(2000); // make sure rtabmap node is created if launched at the same time
124  rtabmap_ros::GetMap getMapSrv;
125  getMapSrv.request.global = false;
126  getMapSrv.request.optimized = true;
127  getMapSrv.request.graphOnly = true;
128  if(!ros::service::call("get_map", getMapSrv))
129  {
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.");
133  }
134  else
135  {
136  // this will update the poses and constraints of the MainWindow
137  processRequestedMap(getMapSrv.response.data);
138  }
139  QMetaObject::invokeMethod(mainWindow_, "updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
140  }
141 
142  if(!tfPrefix.empty())
143  {
144  if(!frameId_.empty())
145  {
146  frameId_ = tfPrefix + "/" + frameId_;
147  }
148  if(!odomFrameId_.empty())
149  {
150  odomFrameId_ = tfPrefix + "/" + odomFrameId_;
151  }
152  }
153 
156 
157  infoTopic_.subscribe(nh, "info", 1);
158  mapDataTopic_.subscribe(nh, "mapData", 1);
161  infoTopic_,
162  mapDataTopic_);
163  infoMapSync_->registerCallback(boost::bind(&GuiWrapper::infoMapCallback, this, _1, _2));
164 
165  goalTopic_.subscribe(nh, "goal_node", 1);
166  pathTopic_.subscribe(nh, "global_path", 1);
169  goalTopic_,
170  pathTopic_);
171  goalPathSync_->registerCallback(boost::bind(&GuiWrapper::goalPathCallback, this, _1, _2));
172  goalReachedTopic_ = nh.subscribe("goal_reached", 1, &GuiWrapper::goalReachedCallback, this);
173 
174  setupCallbacks(nh, pnh, ros::this_node::getName()); // do it at the end
175  if(!this->isDataSubscribed())
176  {
178 
179  ROS_INFO("\n%s subscribed to:\n %s",
180  ros::this_node::getName().c_str(),
181  defaultSub_.getTopic().c_str());
182  }
183 }
184 
186 {
187  UDEBUG("");
188 
189  delete infoMapSync_;
190  delete mainWindow_;
191 }
192 
194  const rtabmap_ros::InfoConstPtr & infoMsg,
195  const rtabmap_ros::MapDataConstPtr & mapMsg)
196 {
197  //ROS_INFO("rtabmapviz: RTAB-Map info ex received!");
198 
199  // Map from ROS struct to rtabmap struct
200  rtabmap::Statistics stat;
201 
202  // Info
203  rtabmap_ros::infoFromROS(*infoMsg, stat);
204 
205  // MapData
206  rtabmap::Transform mapToOdom;
207  std::map<int, rtabmap::Transform> poses;
208  std::map<int, Signature> signatures;
209  std::multimap<int, rtabmap::Link> links;
210 
211  rtabmap_ros::mapDataFromROS(*mapMsg, poses, links, signatures, mapToOdom);
212 
213  stat.setMapCorrection(mapToOdom);
214  stat.setPoses(poses);
215  stat.setSignatures(signatures);
216  stat.setConstraints(links);
217 
218  this->post(new RtabmapEvent(stat));
219 }
220 
222  const rtabmap_ros::GoalConstPtr & goalMsg,
223  const nav_msgs::PathConstPtr & pathMsg)
224 {
225  // we don't have the node ids, just generate fake ones.
226  std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
227  for(unsigned int i=0; i<pathMsg->poses.size(); ++i)
228  {
229  poses[i].first = -int(i)-1;
230  poses[i].second = rtabmap_ros::transformFromPoseMsg(pathMsg->poses[i].pose);
231  }
232  this->post(new RtabmapGlobalPathEvent(goalMsg->node_id, goalMsg->node_label, poses, 0.0));
233 }
234 
236  const std_msgs::BoolConstPtr & value)
237 {
238  this->post(new RtabmapGoalStatusEvent(value->data?1:-1));
239 }
240 
241 void GuiWrapper::processRequestedMap(const rtabmap_ros::MapData & map)
242 {
243  std::map<int, Signature> signatures;
244  std::map<int, Transform> poses;
245  std::multimap<int, rtabmap::Link> constraints;
246  Transform mapToOdom;
247 
248  rtabmap_ros::mapDataFromROS(map, poses, constraints, signatures, mapToOdom);
249 
250  RtabmapEvent3DMap e(signatures,
251  poses,
252  constraints);
253  QMetaObject::invokeMethod(mainWindow_, "processRtabmapEvent3DMap", Q_ARG(rtabmap::RtabmapEvent3DMap, e));
254 }
255 
257 {
258  if(anEvent->getClassName().compare("ParamEvent") == 0)
259  {
261  rtabmap::ParametersMap parameters = ((rtabmap::ParamEvent *)anEvent)->getParameters();
262  bool modified = false;
263  ros::NodeHandle nh;
264  for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
265  {
266  //save only parameters with valid names
267  if(defaultParameters.find((*i).first) != defaultParameters.end())
268  {
269  nh.setParam((*i).first, (*i).second);
270  modified = true;
271  }
272  else if((*i).first.find('/') != (*i).first.npos)
273  {
274  ROS_WARN("Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
275  }
276  }
277  if(modified)
278  {
279  ROS_INFO("Parameters updated");
280  std_srvs::Empty srv;
281  if(!ros::service::call("update_parameters", srv))
282  {
283  ROS_ERROR("Can't call \"update_parameters\" service");
284  }
285  }
286  }
287  else if(anEvent->getClassName().compare("RtabmapEventCmd") == 0)
288  {
289  std_srvs::Empty emptySrv;
290  rtabmap::RtabmapEventCmd * cmdEvent = (rtabmap::RtabmapEventCmd *)anEvent;
293  {
294  if(!ros::service::call("reset", emptySrv))
295  {
296  ROS_ERROR("Can't call \"reset\" service");
297  }
298  }
300  {
301  // Pause the camera if the rtabmap/camera node is used
302  if(!cameraNodeName_.empty())
303  {
304  std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause true", cameraNodeName_.c_str());
305  if(system(str.c_str()) !=0)
306  {
307  ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
308  }
309  }
310 
311  // Pause visual_odometry
312  ros::service::call("pause_odom", emptySrv);
313 
314  // Pause rtabmap
315  if(!ros::service::call("pause", emptySrv))
316  {
317  ROS_ERROR("Can't call \"pause\" service");
318  }
319  }
321  {
322  // Resume rtabmap
323  if(!ros::service::call("resume", emptySrv))
324  {
325  ROS_ERROR("Can't call \"resume\" service");
326  }
327 
328  // Pause visual_odometry
329  ros::service::call("resume_odom", emptySrv);
330 
331  // Resume the camera if the rtabmap/camera node is used
332  if(!cameraNodeName_.empty())
333  {
334  std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause false", cameraNodeName_.c_str());
335  if(system(str.c_str()) !=0)
336  {
337  ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
338  }
339  }
340  }
342  {
343  if(!ros::service::call("trigger_new_map", emptySrv))
344  {
345  ROS_ERROR("Can't call \"trigger_new_map\" service");
346  }
347  }
349  {
350  UASSERT(cmdEvent->value1().isBool());
351  UASSERT(cmdEvent->value2().isBool());
352  UASSERT(cmdEvent->value3().isBool());
353 
354  rtabmap_ros::GetMap getMapSrv;
355  getMapSrv.request.global = cmdEvent->value1().toBool();
356  getMapSrv.request.optimized = cmdEvent->value2().toBool();
357  getMapSrv.request.graphOnly = cmdEvent->value3().toBool();
358  if(!ros::service::call("get_map_data", getMapSrv))
359  {
360  ROS_WARN("Can't call \"get_map_data\" service");
361  this->post(new RtabmapEvent3DMap(1)); // service error
362  }
363  else
364  {
365  processRequestedMap(getMapSrv.response.data);
366  }
367  }
368  else if(cmd == rtabmap::RtabmapEventCmd::kCmdGoal)
369  {
370  UASSERT(cmdEvent->value1().isStr() || cmdEvent->value1().isInt() || cmdEvent->value1().isUInt());
371  rtabmap_ros::SetGoal setGoalSrv;
372  setGoalSrv.request.node_id = !cmdEvent->value1().isStr()?cmdEvent->value1().toInt():0;
373  setGoalSrv.request.node_label = cmdEvent->value1().isStr()?cmdEvent->value1().toStr():"";
374  if(!ros::service::call("set_goal", setGoalSrv))
375  {
376  ROS_ERROR("Can't call \"set_goal\" service");
377  }
378  else
379  {
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)
383  {
384  poses[i].first = setGoalSrv.response.path_ids[i];
385  poses[i].second = rtabmap_ros::transformFromPoseMsg(setGoalSrv.response.path_poses[i]);
386  }
387  this->post(new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
388  }
389  }
391  {
392  if(!ros::service::call("cancel_goal", emptySrv))
393  {
394  ROS_ERROR("Can't call \"cancel_goal\" service");
395  }
396  }
398  {
399  UASSERT(cmdEvent->value1().isStr());
400  UASSERT(cmdEvent->value2().isUndef() || cmdEvent->value2().isInt() || cmdEvent->value2().isUInt());
401  rtabmap_ros::SetLabel setLabelSrv;
402  setLabelSrv.request.node_label = cmdEvent->value1().toStr();
403  setLabelSrv.request.node_id = cmdEvent->value2().isUndef()?0:cmdEvent->value2().toInt();
404  if(!ros::service::call("set_label", setLabelSrv))
405  {
406  ROS_ERROR("Can't call \"set_label\" service");
407  }
408  }
409  else
410  {
411  ROS_WARN("Not handled command (%d)...", cmd);
412  }
413  }
414  else if(anEvent->getClassName().compare("OdometryResetEvent") == 0)
415  {
416  std_srvs::Empty srv;
417  if(!ros::service::call("reset_odom", srv))
418  {
419  ROS_ERROR("Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
420  }
421  }
422  return false;
423 }
424 
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)
434 {
435  UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == depthMsgs.size() && imageMsgs.size() == cameraInfoMsgs.size()));
436 
437  std_msgs::Header odomHeader;
438  if(odomMsg.get())
439  {
440  odomHeader = odomMsg->header;
441  }
442  else
443  {
444  if(scan2dMsg.get())
445  {
446  odomHeader = scan2dMsg->header;
447  }
448  else if(scan3dMsg.get())
449  {
450  odomHeader = scan3dMsg->header;
451  }
452  else if(cameraInfoMsgs.size())
453  {
454  odomHeader = cameraInfoMsgs[0].header;
455  }
456  else if(depthMsgs.size() && depthMsgs[0].get())
457  {
458  odomHeader = depthMsgs[0]->header;
459  }
460  else if(imageMsgs.size() && imageMsgs[0].get())
461  {
462  odomHeader = imageMsgs[0]->header;
463  }
464  odomHeader.frame_id = odomFrameId_;
465  }
466 
467  Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
468  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
469  if(odomMsg.get())
470  {
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)
478  {
479  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
480  }
481  }
482  if(odomHeader.frame_id.empty())
483  {
484  ROS_ERROR("Odometry frame not set!?");
485  return;
486  }
487 
488  cv::Mat rgb;
489  cv::Mat depth;
490  std::vector<CameraModel> cameraModels;
491  cv::Mat scan;
492  Transform scanLocalTransform = Transform::getIdentity();
494  bool ignoreData = false;
495 
496  if(UTimer::now() - lastOdomInfoUpdateTime_ > 0.1 &&
499  {
501 
502  if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs[0].get())
503  {
505  imageMsgs,
506  depthMsgs,
507  cameraInfoMsgs,
508  frameId_,
509  odomSensorSync_?odomHeader.frame_id:"",
510  odomHeader.stamp,
511  rgb,
512  depth,
513  cameraModels,
514  tfListener_,
515  waitForTransform_?waitForTransformDuration_:0.0))
516  {
517  ROS_ERROR("Could not convert rgb/depth msgs! Aborting rtabmapviz update...");
518  return;
519  }
520  }
521 
522  if(scan2dMsg.get() != 0)
523  {
525  scan2dMsg,
526  frameId_,
527  odomSensorSync_?odomHeader.frame_id:"",
528  odomHeader.stamp,
529  scan,
530  scanLocalTransform,
531  tfListener_,
532  waitForTransform_?waitForTransformDuration_:0))
533  {
534  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
535  return;
536  }
537  }
538  else if(scan3dMsg.get() != 0)
539  {
541  scan3dMsg,
542  frameId_,
543  odomSensorSync_?odomHeader.frame_id:"",
544  odomHeader.stamp,
545  scan,
546  scanLocalTransform,
547  tfListener_,
548  waitForTransform_?waitForTransformDuration_:0))
549  {
550  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
551  return;
552  }
553  }
554 
555  if(odomInfoMsg.get())
556  {
557  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
558  }
559  ignoreData = false;
560  }
561  else if(odomInfoMsg.get())
562  {
563  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
564  ignoreData = true;
565  }
566  else
567  {
568  // don't update GUI odom stuff if we don't use visual odometry
569  return;
570  }
571 
572  info.reg.covariance = covariance;
573  rtabmap::OdometryEvent odomEvent(
575  LaserScan::backwardCompatibility(scan,
576  scan2dMsg.get()?(int)scan2dMsg->ranges.size():0,
577  scan2dMsg.get()?(int)scan2dMsg->range_max:0,
578  scanLocalTransform),
579  rgb,
580  depth,
581  cameraModels,
582  odomHeader.seq,
583  rtabmap_ros::timestampFromROS(odomHeader.stamp)),
584  odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
585  info);
586 
587  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
588 }
589 
591  const nav_msgs::OdometryConstPtr & odomMsg,
592  const rtabmap_ros::UserDataConstPtr & userDataMsg,
593  const cv_bridge::CvImageConstPtr& leftImageMsg,
594  const cv_bridge::CvImageConstPtr& rightImageMsg,
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)
600 {
601  std_msgs::Header odomHeader;
602  if(odomMsg.get())
603  {
604  odomHeader = odomMsg->header;
605  }
606  else
607  {
608  if(scan2dMsg.get())
609  {
610  odomHeader = scan2dMsg->header;
611  }
612  else if(scan3dMsg.get())
613  {
614  odomHeader = scan3dMsg->header;
615  }
616  else
617  {
618  odomHeader = leftCamInfoMsg.header;
619  }
620  odomHeader.frame_id = odomFrameId_;
621  }
622 
623  Transform odomT = rtabmap_ros::getTransform(odomHeader.frame_id, frameId_, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
624  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
625  if(odomMsg.get())
626  {
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)
634  {
635  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
636  }
637  }
638  if(odomHeader.frame_id.empty())
639  {
640  ROS_ERROR("Odometry frame not set!?");
641  return;
642  }
643 
644  cv::Mat left;
645  cv::Mat right;
646  cv::Mat scan;
647  Transform scanLocalTransform = Transform::getIdentity();
648  rtabmap::StereoCameraModel stereoModel;
650  bool ignoreData = false;
651 
652  // limit 10 Hz max
653  if(UTimer::now() - lastOdomInfoUpdateTime_ > 0.1 &&
656  {
658 
660  leftImageMsg,
661  rightImageMsg,
662  leftCamInfoMsg,
663  rightCamInfoMsg,
664  frameId_,
665  odomSensorSync_?odomHeader.frame_id:"",
666  odomHeader.stamp,
667  left,
668  right,
669  stereoModel,
670  tfListener_,
671  waitForTransform_?waitForTransformDuration_:0.0))
672  {
673  ROS_ERROR("Could not convert stereo msgs! Aborting rtabmapviz update...");
674  return;
675  }
676 
677  if(scan2dMsg.get() != 0)
678  {
680  scan2dMsg,
681  frameId_,
682  odomSensorSync_?odomHeader.frame_id:"",
683  odomHeader.stamp,
684  scan,
685  scanLocalTransform,
686  tfListener_,
687  waitForTransform_?waitForTransformDuration_:0))
688  {
689  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmapviz update...");
690  return;
691  }
692  }
693  else if(scan3dMsg.get() != 0)
694  {
696  scan3dMsg,
697  frameId_,
698  odomSensorSync_?odomHeader.frame_id:"",
699  odomHeader.stamp,
700  scan,
701  scanLocalTransform,
702  tfListener_,
703  waitForTransform_?waitForTransformDuration_:0))
704  {
705  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmapviz update...");
706  return;
707  }
708  }
709 
710  if(odomInfoMsg.get())
711  {
712  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg);
713  }
714  ignoreData = false;
715  }
716  else if(odomInfoMsg.get())
717  {
718  info = rtabmap_ros::odomInfoFromROS(*odomInfoMsg).copyWithoutData();
719  ignoreData = true;
720  }
721  else
722  {
723  // don't update GUI odom stuff if we don't use visual odometry
724  return;
725  }
726 
727  info.reg.covariance = covariance;
728  rtabmap::OdometryEvent odomEvent(
730  LaserScan::backwardCompatibility(scan,
731  scan2dMsg.get()?(int)scan2dMsg->ranges.size():0,
732  scan2dMsg.get()?(int)scan2dMsg->range_max:0,
733  scanLocalTransform),
734  left,
735  right,
736  stereoModel,
737  odomHeader.seq,
738  rtabmap_ros::timestampFromROS(odomHeader.stamp)),
739  odomMsg.get()?rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose):odomT,
740  info);
741 
742  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
743 }
744 
745 // With odom msg
746 void GuiWrapper::defaultCallback(const nav_msgs::OdometryConstPtr & odomMsg)
747 {
749  odomMsg,
750  rtabmap_ros::UserDataConstPtr(),
753  sensor_msgs::CameraInfo(),
754  sensor_msgs::CameraInfo(),
755  sensor_msgs::LaserScanConstPtr(),
756  sensor_msgs::PointCloud2ConstPtr(),
757  rtabmap_ros::OdomInfoConstPtr());
758 }
759 
760 }
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)
bool isBool() const
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
Definition: GuiWrapper.h:124
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
Definition: GuiWrapper.h:107
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
Definition: GuiWrapper.h:110
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)
Definition: GuiWrapper.cpp:425
std::string uReplaceChar(const std::string &str, char before, char after)
virtual bool handleEvent(UEvent *anEvent)
Definition: GuiWrapper.cpp:256
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)
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()
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)
Definition: GuiWrapper.cpp:590
std::map< std::string, std::string > ParametersMap
void infoMapCallback(const rtabmap_ros::InfoConstPtr &infoMsg, const rtabmap_ros::MapDataConstPtr &mapMsg)
Definition: GuiWrapper.cpp:193
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:241
#define ROS_WARN(...)
rtabmap::MainWindow * mainWindow_
Definition: GuiWrapper.h:95
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:235
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
Definition: GuiWrapper.h:108
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)
double lastOdomInfoUpdateTime_
Definition: GuiWrapper.h:97
double waitForTransformDuration_
Definition: GuiWrapper.h:103
void setPoses(const std::map< int, Transform > &poses)
ros::Subscriber defaultSub_
Definition: GuiWrapper.h:114
ros::Subscriber goalReachedTopic_
Definition: GuiWrapper.h:112
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
Definition: GuiWrapper.h:119
virtual std::string getClassName() const =0
bool isInt() const
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
bool isStr() const
void defaultCallback(const nav_msgs::OdometryConstPtr &odomMsg)
Definition: GuiWrapper.cpp:746
#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
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)
Definition: GuiWrapper.cpp:221
void setMonitoringState(bool pauseChecked=false)
float max3(const float &a, const float &b, const float &c)
Definition: GuiWrapper.cpp:57
void setMapCorrection(const Transform &mapCorrection)
bool isUInt() const
#define false
void uSleep(unsigned int ms)
void setSignatures(const std::map< int, Signature > &signatures)
static const ParametersMap & getDefaultParameters()
tf::TransformListener tfListener_
Definition: GuiWrapper.h:105
#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:123
std::string cameraNodeName_
Definition: GuiWrapper.h:96
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:111
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:118
std::string odomFrameId_
Definition: GuiWrapper.h:101
#define ROS_ERROR(...)
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)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:03