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_viz/GuiWrapper.h"
29 #include <QApplication>
30 #include <QDir>
31 
32 #include <std_srvs/Empty.h>
33 #include <std_msgs/Empty.h>
34 #include <std_msgs/Int32MultiArray.h>
35 
39 
40 #include <opencv2/highgui/highgui.hpp>
41 
42 #include <rtabmap/gui/MainWindow.h>
47 #include <rtabmap/core/util2d.h>
48 #include <rtabmap/core/util3d.h>
50 #include <rtabmap/utilite/UTimer.h>
51 
53 #include "rtabmap_msgs/GetMap.h"
54 #include "rtabmap_msgs/SetGoal.h"
55 #include "rtabmap_msgs/SetLabel.h"
56 #include "rtabmap_msgs/RemoveLabel.h"
58 
59 float max3( const float& a, const float& b, const float& c)
60 {
61  float m=a>b?a:b;
62  return m>c?m:c;
63 }
64 
65 namespace rtabmap_viz {
66 
67 GuiWrapper::GuiWrapper(int & argc, char** argv) :
68  rtabmap_sync::CommonDataSubscriber(true),
69  mainWindow_(0),
70  frameId_("base_link"),
71  odomFrameId_(""),
72  waitForTransform_(true),
73  waitForTransformDuration_(0.2), // 200 ms
74  odomSensorSync_(false),
75  maxOdomUpdateRate_(10),
76  cameraNodeName_(""),
77  lastOdomInfoUpdateTime_(0),
78  rtabmapNodeName_("rtabmap")
79 {
80  ros::NodeHandle nh;
81  ros::NodeHandle pnh("~");
82 
83  QString configFile = QDir::homePath()+"/.ros/rtabmapGUI.ini";
84  for(int i=1; i<argc; ++i)
85  {
86  if(strcmp(argv[i], "-d") == 0)
87  {
88  ++i;
89  if(i < argc)
90  {
91  configFile = argv[i];
92  }
93  break;
94  }
95  }
96 
97  configFile.replace('~', QDir::homePath());
98 
99  pnh.param("rtabmap", rtabmapNodeName_, rtabmapNodeName_);
100 
101  ROS_INFO("rtabmap_viz: Using configuration from \"%s\"", configFile.toStdString().c_str());
102  uSleep(500);
105  mainWindow_->setWindowTitle(mainWindow_->windowTitle()+" [ROS]");
106  mainWindow_->show();
107 
108  bool paused = false;
110  rnh.param("is_rtabmap_paused", paused, paused);
112 
113  // To receive odometry events
114  std::string initCachePath;
115  bool subscribeInfoOnly = false;
116  pnh.param("frame_id", frameId_, frameId_);
117  pnh.param("odom_frame_id", odomFrameId_, odomFrameId_); // set to use odom from TF
118  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
119  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
120  pnh.param("odom_sensor_sync", odomSensorSync_, odomSensorSync_);
121  pnh.param("max_odom_update_rate", maxOdomUpdateRate_, maxOdomUpdateRate_);
122  pnh.param("camera_node_name", cameraNodeName_, cameraNodeName_); // used to pause the rtabmap_conversions/camera when pausing the process
123  pnh.param("subscribe_info_only", subscribeInfoOnly, subscribeInfoOnly);
124  pnh.param("init_cache_path", initCachePath, initCachePath);
125  if(initCachePath.size())
126  {
127  initCachePath = uReplaceChar(initCachePath, '~', UDirectory::homeDir());
128  if(initCachePath.at(0) != '/')
129  {
130  initCachePath = UDirectory::currentDir(true) + initCachePath;
131  }
132  ROS_INFO("rtabmap_viz: Initializing cache with local database \"%s\"", initCachePath.c_str());
133  uSleep(2000); // make sure rtabmap node is created if launched at the same time
134  rtabmap_msgs::GetMap getMapSrv;
135  getMapSrv.request.global = false;
136  getMapSrv.request.optimized = true;
137  getMapSrv.request.graphOnly = true;
138  if(!ros::service::call("get_map", getMapSrv))
139  {
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.");
143  }
144  else
145  {
146  // this will update the poses and constraints of the MainWindow
147  processRequestedMap(getMapSrv.response.data);
148  }
149  QMetaObject::invokeMethod(mainWindow_, "updateCacheFromDatabase", Q_ARG(QString, QString(initCachePath.c_str())));
150  }
151 
152  if(pnh.hasParam("tf_prefix"))
153  {
154  ROS_ERROR("tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
155  }
156 
159 
160  republishNodeDataPub_ = nh.advertise<std_msgs::Int32MultiArray>("republish_node_data", 1);
161 
162  if(subscribeInfoOnly)
163  {
164  ROS_INFO("subscribe_info_only=true");
166  }
167  else
168  {
169  infoTopic_.subscribe(nh, "info", this->getTopicQueueSize());
170  mapDataTopic_.subscribe(nh, "mapData", this->getTopicQueueSize());
173  infoTopic_,
174  mapDataTopic_);
175  infoMapSync_->registerCallback(boost::bind(&GuiWrapper::infoMapCallback, this, boost::placeholders::_1, boost::placeholders::_2));
176  }
177 
178  goalTopic_.subscribe(nh, "goal_node", this->getTopicQueueSize());
179  pathTopic_.subscribe(nh, "global_path", this->getTopicQueueSize());
182  goalTopic_,
183  pathTopic_);
184  goalPathSync_->registerCallback(boost::bind(&GuiWrapper::goalPathCallback, this, boost::placeholders::_1, boost::placeholders::_2));
186 
187  setupCallbacks(nh, pnh, ros::this_node::getName()); // do it at the end
188 }
189 
191 {
192  UDEBUG("");
193 
194  delete infoMapSync_;
195  delete mainWindow_;
196 }
197 
199  const rtabmap_msgs::InfoConstPtr & infoMsg,
200  const rtabmap_msgs::MapDataConstPtr & mapMsg)
201 {
202  //ROS_INFO("rtabmap_viz: RTAB-Map info ex received!");
203 
204  // Map from ROS struct to rtabmap struct
205  rtabmap::Statistics stat;
206 
207  // Info
208  rtabmap_conversions::infoFromROS(*infoMsg, stat);
209 
210  // MapData
211  rtabmap::Transform mapToOdom;
212  std::map<int, rtabmap::Transform> poses;
213  std::map<int, Signature> signatures;
214  std::multimap<int, rtabmap::Link> links;
215 
216  rtabmap_conversions::mapDataFromROS(*mapMsg, poses, links, signatures, mapToOdom);
217 
218  stat.setMapCorrection(mapToOdom);
219  stat.setPoses(poses);
220  stat.setSignaturesData(signatures);
221  stat.setConstraints(links);
222 
223  this->post(new RtabmapEvent(stat));
224 
225  tick(infoMsg->header.stamp);
226 
227 }
228 
230  const rtabmap_msgs::InfoConstPtr & infoMsg)
231 {
232  rtabmap::Statistics stat;
233 
234  // Info from ROS
235  rtabmap_conversions::infoFromROS(*infoMsg, stat);
236 
237  // mapToOdom can be recovered from statistics
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())
244  {
245  rtabmap::Transform mapToOdom;
246  mapToOdom = rtabmap::Transform(
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);
253  stat.setMapCorrection(mapToOdom);
254  }
255 
256  this->post(new RtabmapEvent(stat));
257 
258  tick(infoMsg->header.stamp);
259 }
260 
262  const rtabmap_msgs::GoalConstPtr & goalMsg,
263  const nav_msgs::PathConstPtr & pathMsg)
264 {
265  // we don't have the node ids, just generate fake ones.
266  std::vector<std::pair<int, Transform> > poses(pathMsg->poses.size());
267  for(unsigned int i=0; i<pathMsg->poses.size(); ++i)
268  {
269  poses[i].first = -int(i)-1;
270  poses[i].second = rtabmap_conversions::transformFromPoseMsg(pathMsg->poses[i].pose);
271  }
272  this->post(new RtabmapGlobalPathEvent(goalMsg->node_id, goalMsg->node_label, poses, 0.0));
273 }
274 
276  const std_msgs::BoolConstPtr & value)
277 {
278  this->post(new RtabmapGoalStatusEvent(value->data?1:-1));
279 }
280 
281 void GuiWrapper::processRequestedMap(const rtabmap_msgs::MapData & map)
282 {
283  // Make sure parameters are loaded
284  if(((PreferencesDialogROS*)prefDialog_)->hasAllParameters())
285  {
286  QMetaObject::invokeMethod(((PreferencesDialogROS*)prefDialog_), "readRtabmapNodeParameters");
287  }
288 
289  std::map<int, Signature> signatures;
290  std::map<int, Transform> poses;
291  std::multimap<int, rtabmap::Link> constraints;
292  Transform mapToOdom;
293 
294  rtabmap_conversions::mapDataFromROS(map, poses, constraints, signatures, mapToOdom);
295 
296  RtabmapEvent3DMap e(signatures,
297  poses,
298  constraints);
299  QMetaObject::invokeMethod(mainWindow_, "processRtabmapEvent3DMap", Q_ARG(rtabmap::RtabmapEvent3DMap, e));
300 }
301 
303 {
304  if(anEvent->getClassName().compare("ParamEvent") == 0)
305  {
307  rtabmap::ParametersMap parameters = ((rtabmap::ParamEvent *)anEvent)->getParameters();
308  bool modified = false;
310  for(rtabmap::ParametersMap::iterator i=parameters.begin(); i!=parameters.end(); ++i)
311  {
312  //save only parameters with valid names
313  if(defaultParameters.find((*i).first) != defaultParameters.end())
314  {
315  rnh.setParam((*i).first, (*i).second);
316  modified = true;
317  }
318  else if((*i).first.find('/') != (*i).first.npos)
319  {
320  ROS_WARN("Parameter %s is not used by the rtabmap node.", (*i).first.c_str());
321  }
322  }
323  if(modified)
324  {
325  ROS_INFO("Parameters updated");
326  std_srvs::Empty srv;
327  if(!ros::service::call("update_parameters", srv))
328  {
329  ROS_ERROR("Can't call \"update_parameters\" service");
330  }
331  }
332  }
333  else if(anEvent->getClassName().compare("RtabmapEventCmd") == 0)
334  {
335  std_srvs::Empty emptySrv;
336  rtabmap::RtabmapEventCmd * cmdEvent = (rtabmap::RtabmapEventCmd *)anEvent;
339  {
340  if(!ros::service::call("reset", emptySrv))
341  {
342  ROS_ERROR("Can't call \"reset\" service");
343  }
344  }
346  {
347  // Pause the camera if the rtabmap/camera node is used
348  if(!cameraNodeName_.empty())
349  {
350  std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause true", cameraNodeName_.c_str());
351  if(system(str.c_str()) !=0)
352  {
353  ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
354  }
355  }
356 
357  // Pause visual_odometry
358  ros::service::call("pause_odom", emptySrv);
359 
360  // Pause rtabmap
361  if(!ros::service::call("pause", emptySrv))
362  {
363  ROS_ERROR("Can't call \"pause\" service");
364  }
365  }
367  {
368  // Resume rtabmap
369  if(!ros::service::call("resume", emptySrv))
370  {
371  ROS_ERROR("Can't call \"resume\" service");
372  }
373 
374  // Pause visual_odometry
375  ros::service::call("resume_odom", emptySrv);
376 
377  // Resume the camera if the rtabmap/camera node is used
378  if(!cameraNodeName_.empty())
379  {
380  std::string str = uFormat("rosrun dynamic_reconfigure dynparam set %s pause false", cameraNodeName_.c_str());
381  if(system(str.c_str()) !=0)
382  {
383  ROS_ERROR("Command \"%s\" returned non zero value.", str.c_str());
384  }
385  }
386  }
388  {
389  if(!ros::service::call("trigger_new_map", emptySrv))
390  {
391  ROS_ERROR("Can't call \"trigger_new_map\" service");
392  }
393  }
395  {
396  UASSERT(cmdEvent->value1().isBool());
397  UASSERT(cmdEvent->value2().isBool());
398  UASSERT(cmdEvent->value3().isBool());
399 
400  rtabmap_msgs::GetMap getMapSrv;
401  getMapSrv.request.global = cmdEvent->value1().toBool();
402  getMapSrv.request.optimized = cmdEvent->value2().toBool();
403  getMapSrv.request.graphOnly = cmdEvent->value3().toBool();
404  if(!ros::service::call("get_map_data", getMapSrv))
405  {
406  ROS_WARN("Can't call \"get_map_data\" service");
407  this->post(new RtabmapEvent3DMap(1)); // service error
408  }
409  else
410  {
411  processRequestedMap(getMapSrv.response.data);
412  }
413  }
415  {
416  UASSERT(cmdEvent->value1().isStr() || cmdEvent->value1().isInt() || cmdEvent->value1().isUInt());
417  rtabmap_msgs::SetGoal setGoalSrv;
418  setGoalSrv.request.node_id = !cmdEvent->value1().isStr()?cmdEvent->value1().toInt():0;
419  setGoalSrv.request.node_label = cmdEvent->value1().isStr()?cmdEvent->value1().toStr():"";
420  if(!ros::service::call("set_goal", setGoalSrv))
421  {
422  ROS_ERROR("Can't call \"set_goal\" service");
423  }
424  else
425  {
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)
429  {
430  poses[i].first = setGoalSrv.response.path_ids[i];
431  poses[i].second = rtabmap_conversions::transformFromPoseMsg(setGoalSrv.response.path_poses[i]);
432  }
433  this->post(new RtabmapGlobalPathEvent(setGoalSrv.request.node_id, setGoalSrv.request.node_label, poses, setGoalSrv.response.planning_time));
434  }
435  }
437  {
438  if(!ros::service::call("cancel_goal", emptySrv))
439  {
440  ROS_ERROR("Can't call \"cancel_goal\" service");
441  }
442  }
444  {
445  UASSERT(cmdEvent->value1().isStr());
446  UASSERT(cmdEvent->value2().isUndef() || cmdEvent->value2().isInt() || cmdEvent->value2().isUInt());
447  rtabmap_msgs::SetLabel setLabelSrv;
448  setLabelSrv.request.node_label = cmdEvent->value1().toStr();
449  setLabelSrv.request.node_id = cmdEvent->value2().isUndef()?0:cmdEvent->value2().toInt();
450  if(!ros::service::call("set_label", setLabelSrv))
451  {
452  ROS_ERROR("Can't call \"set_label\" service");
453  }
454  }
456  {
457  UASSERT(cmdEvent->value1().isStr());
458  rtabmap_msgs::RemoveLabel removeLabelSrv;
459  removeLabelSrv.request.label = cmdEvent->value1().toStr();
460  if(!ros::service::call("remove_label", removeLabelSrv))
461  {
462  ROS_ERROR("Can't call \"remove_label\" service");
463  }
464  }
466  {
467  UASSERT(cmdEvent->value1().isIntArray());
468  std_msgs::Int32MultiArray msg;
469  msg.data = cmdEvent->value1().toIntArray();
471  }
472  else
473  {
474  ROS_WARN("Not handled command (%d)...", cmd);
475  }
476  }
477  else if(anEvent->getClassName().compare("OdometryResetEvent") == 0)
478  {
479  std_srvs::Empty srv;
480  if(!ros::service::call("reset_odom", srv))
481  {
482  ROS_ERROR("Can't call \"reset_odom\" service, (will only work with rtabmap/visual_odometry node.)");
483  }
484  }
485  return false;
486 }
487 
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)
502 {
503  UASSERT(imageMsgs.size() == 0 || (imageMsgs.size() == cameraInfoMsgs.size()));
504 
505  std_msgs::Header odomHeader;
506  std::string frameId = frameId_;
507  if(odomMsg.get())
508  {
509  odomHeader = odomMsg->header;
510  if(!odomMsg->child_frame_id.empty())
511  {
512  frameId = odomMsg->child_frame_id;
513  }
514  else
515  {
516  ROS_WARN("Received odom topic with child_frame_id not set! Using \"%s\" as base frame.", frameId_.c_str());
517  }
518  }
519  else
520  {
521  if(!scan2dMsg.ranges.empty())
522  {
523  odomHeader = scan2dMsg.header;
524  }
525  else if(!scan3dMsg.data.empty())
526  {
527  odomHeader = scan3dMsg.header;
528  }
529  else if(cameraInfoMsgs.size())
530  {
531  odomHeader = cameraInfoMsgs[0].header;
532  }
533  else if(depthMsgs.size() && depthMsgs[0].get())
534  {
535  odomHeader = depthMsgs[0]->header;
536  }
537  else if(imageMsgs.size() && imageMsgs[0].get())
538  {
539  odomHeader = imageMsgs[0]->header;
540  }
541  odomHeader.frame_id = odomFrameId_;
542  }
543 
545  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
546  if(odomMsg.get())
547  {
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)
555  {
556  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
557  }
558  }
559  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
560  {
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)
567  {
568  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
569  }
570  }
571  if(odomHeader.frame_id.empty())
572  {
573  ROS_ERROR("Odometry frame not set!?");
574  return;
575  }
576 
577  cv::Mat rgb;
578  cv::Mat depth;
579  std::vector<rtabmap::CameraModel> cameraModels;
580  std::vector<rtabmap::StereoCameraModel> stereoCameraModels;
581  LaserScan scan;
583  bool ignoreData = false;
584 
585  // limit update rate
586  if(maxOdomUpdateRate_<=0.0 ||
590  {
592 
593  if(imageMsgs.size() && imageMsgs[0].get() && depthMsgs.size() && depthMsgs[0].get())
594  {
595  ParametersMap allParameters = prefDialog_->getAllParameters();
596  bool imagesAlreadyRectified = Parameters::defaultRtabmapImagesAlreadyRectified();
597  Parameters::parse(allParameters, Parameters::kRtabmapImagesAlreadyRectified(), imagesAlreadyRectified);
598 
600  imageMsgs,
601  depthMsgs,
602  cameraInfoMsgs,
603  depthCameraInfoMsgs,
604  frameId,
605  odomSensorSync_?odomHeader.frame_id:"",
606  odomHeader.stamp,
607  rgb,
608  depth,
609  cameraModels,
610  stereoCameraModels,
611  tfListener_,
613  imagesAlreadyRectified))
614  {
615  ROS_ERROR("Could not convert rgb/depth msgs! Aborting rtabmap_viz update...");
616  return;
617  }
618  }
619 
620  if(!scan2dMsg.ranges.empty())
621  {
623  scan2dMsg,
624  frameId,
625  odomSensorSync_?odomHeader.frame_id:"",
626  odomHeader.stamp,
627  scan,
628  tfListener_,
630  {
631  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmap_viz update...");
632  return;
633  }
634  }
635  else if(!scan3dMsg.data.empty())
636  {
638  scan3dMsg,
639  frameId,
640  odomSensorSync_?odomHeader.frame_id:"",
641  odomHeader.stamp,
642  scan,
643  tfListener_,
645  {
646  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmap_viz update...");
647  return;
648  }
649  }
650 
651  if(odomInfoMsg.get())
652  {
654  }
655  ignoreData = false;
656  }
657  else if(odomInfoMsg.get())
658  {
660  ignoreData = true;
661  }
662  else
663  {
664  // don't update GUI odom stuff if we don't use visual odometry
665  return;
666  }
667 
668  info.reg.covariance = covariance;
669  rtabmap::OdometryEvent odomEvent(
670  !stereoCameraModels.empty()?
672  scan,
673  rgb,
674  depth,
675  stereoCameraModels,
676  odomHeader.seq,
677  rtabmap_conversions::timestampFromROS(odomHeader.stamp)):
679  scan,
680  rgb,
681  depth,
682  cameraModels,
683  odomHeader.seq,
684  rtabmap_conversions::timestampFromROS(odomHeader.stamp)),
685  odomMsg.get()?rtabmap_conversions::transformFromPoseMsg(odomMsg->pose.pose):odomT,
686  info);
687 
688  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
689 }
690 
692  const nav_msgs::OdometryConstPtr & odomMsg,
693  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
694  const cv_bridge::CvImageConstPtr& leftImageMsg,
695  const cv_bridge::CvImageConstPtr& rightImageMsg,
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)
705 {
706  std_msgs::Header odomHeader;
707  std::string frameId = frameId_;
708  if(odomMsg.get())
709  {
710  odomHeader = odomMsg->header;
711  if(!odomMsg->child_frame_id.empty())
712  {
713  frameId = odomMsg->child_frame_id;
714  }
715  else
716  {
717  ROS_WARN("Received odom topic with child_frame_id not set! Using \"%s\" as base frame.", frameId_.c_str());
718  }
719  }
720  else
721  {
722  if(!scan2dMsg.ranges.empty())
723  {
724  odomHeader = scan2dMsg.header;
725  }
726  else if(!scan3dMsg.data.empty())
727  {
728  odomHeader = scan3dMsg.header;
729  }
730  else
731  {
732  odomHeader = leftCamInfoMsg.header;
733  }
734  odomHeader.frame_id = odomFrameId_;
735  }
736 
738  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
739  if(odomMsg.get())
740  {
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)
748  {
749  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
750  }
751  }
752  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
753  {
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)
760  {
761  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
762  }
763  }
764  if(odomHeader.frame_id.empty())
765  {
766  ROS_ERROR("Odometry frame not set!?");
767  return;
768  }
769 
770  cv::Mat left;
771  cv::Mat right;
772  LaserScan scan;
773  rtabmap::StereoCameraModel stereoModel;
775  bool ignoreData = false;
776 
777  // limit update rate
778  if(maxOdomUpdateRate_<=0.0 ||
782  {
784 
785  ParametersMap allParameters = prefDialog_->getAllParameters();
786  bool imagesAlreadyRectified = Parameters::defaultRtabmapImagesAlreadyRectified();
787  Parameters::parse(allParameters, Parameters::kRtabmapImagesAlreadyRectified(), imagesAlreadyRectified);
788 
790  leftImageMsg,
791  rightImageMsg,
792  leftCamInfoMsg,
793  rightCamInfoMsg,
794  frameId,
795  odomSensorSync_?odomHeader.frame_id:"",
796  odomHeader.stamp,
797  left,
798  right,
799  stereoModel,
800  tfListener_,
802  imagesAlreadyRectified))
803  {
804  ROS_ERROR("Could not convert stereo msgs! Aborting rtabmap_viz update...");
805  return;
806  }
807 
808  if(!scan2dMsg.ranges.empty())
809  {
811  scan2dMsg,
812  frameId,
813  odomSensorSync_?odomHeader.frame_id:"",
814  odomHeader.stamp,
815  scan,
816  tfListener_,
818  {
819  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmap_viz update...");
820  return;
821  }
822  }
823  else if(!scan3dMsg.data.empty())
824  {
826  scan3dMsg,
827  frameId,
828  odomSensorSync_?odomHeader.frame_id:"",
829  odomHeader.stamp,
830  scan,
831  tfListener_,
833  {
834  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmap_viz update...");
835  return;
836  }
837  }
838 
839  if(odomInfoMsg.get())
840  {
842  }
843  ignoreData = false;
844  }
845  else if(odomInfoMsg.get())
846  {
848  ignoreData = true;
849  }
850  else
851  {
852  // don't update GUI odom stuff if we don't use visual odometry
853  return;
854  }
855 
856  info.reg.covariance = covariance;
857  rtabmap::OdometryEvent odomEvent(
859  scan,
860  left,
861  right,
862  stereoModel,
863  odomHeader.seq,
864  rtabmap_conversions::timestampFromROS(odomHeader.stamp)),
865  odomMsg.get()?rtabmap_conversions::transformFromPoseMsg(odomMsg->pose.pose):odomT,
866  info);
867 
868  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
869 }
870 
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)
878 {
879  std_msgs::Header odomHeader;
880  std::string frameId = frameId_;
881  if(odomMsg.get())
882  {
883  odomHeader = odomMsg->header;
884  if(!odomMsg->child_frame_id.empty())
885  {
886  frameId = odomMsg->child_frame_id;
887  }
888  else
889  {
890  ROS_WARN("Received odom topic with child_frame_id not set! Using \"%s\" as base frame.", frameId_.c_str());
891  }
892  }
893  else
894  {
895  if(!scan2dMsg.ranges.empty())
896  {
897  odomHeader = scan2dMsg.header;
898  }
899  else if(!scan3dMsg.data.empty())
900  {
901  odomHeader = scan3dMsg.header;
902  }
903  else
904  {
905  return;
906  }
907  odomHeader.frame_id = odomFrameId_;
908  }
909 
911  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
912  if(odomMsg.get())
913  {
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)
921  {
922  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
923  }
924  }
925  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
926  {
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)
933  {
934  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
935  }
936  }
937  if(odomHeader.frame_id.empty())
938  {
939  ROS_ERROR("Odometry frame not set!?");
940  return;
941  }
942 
943  LaserScan scan;
945  bool ignoreData = false;
946 
947  // limit update rate
948  if(maxOdomUpdateRate_<=0.0 ||
952  {
954 
955  if(!scan2dMsg.ranges.empty())
956  {
958  scan2dMsg,
959  frameId,
960  odomSensorSync_?odomHeader.frame_id:"",
961  odomHeader.stamp,
962  scan,
963  tfListener_,
965  {
966  ROS_ERROR("Could not convert laser scan msg! Aborting rtabmap_viz update...");
967  return;
968  }
969  }
970  else if(!scan3dMsg.data.empty())
971  {
973  scan3dMsg,
974  frameId,
975  odomSensorSync_?odomHeader.frame_id:"",
976  odomHeader.stamp,
977  scan,
978  tfListener_,
980  {
981  ROS_ERROR("Could not convert 3d laser scan msg! Aborting rtabmap_viz update...");
982  return;
983  }
984  }
985 
986  if(odomInfoMsg.get())
987  {
989  }
990  ignoreData = false;
991  }
992  else if(odomInfoMsg.get())
993  {
995  ignoreData = true;
996  }
997  else
998  {
999  // don't update GUI odom stuff if we don't use visual odometry
1000  return;
1001  }
1002 
1003  info.reg.covariance = covariance;
1004  rtabmap::OdometryEvent odomEvent(
1006  scan,
1007  cv::Mat(),
1008  cv::Mat(),
1010  odomHeader.seq,
1011  rtabmap_conversions::timestampFromROS(odomHeader.stamp)),
1012  odomMsg.get()?rtabmap_conversions::transformFromPoseMsg(odomMsg->pose.pose):odomT,
1013  info);
1014 
1015  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
1016 }
1017 
1019  const nav_msgs::OdometryConstPtr & odomMsg,
1020  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
1021  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
1022 {
1023  UASSERT(odomMsg.get());
1024 
1025  std_msgs::Header odomHeader = odomMsg->header;
1026 
1027  Transform odomT = rtabmap_conversions::getTransform(odomHeader.frame_id, odomMsg->child_frame_id, odomHeader.stamp, tfListener_, waitForTransform_?waitForTransformDuration_:0);
1028  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
1029  if(odomMsg.get())
1030  {
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)
1038  {
1039  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
1040  }
1041  }
1042  if(odomHeader.frame_id.empty())
1043  {
1044  ROS_ERROR("Odometry frame not set!?");
1045  return;
1046  }
1047 
1049  bool ignoreData = false;
1050 
1051  // limit update rate
1052  if(maxOdomUpdateRate_<=0.0 ||
1056  {
1058 
1059  if(odomInfoMsg.get())
1060  {
1062  }
1063  ignoreData = false;
1064  }
1065  else if(odomInfoMsg.get())
1066  {
1068  ignoreData = true;
1069  }
1070  else
1071  {
1072  // don't update GUI odom stuff if we don't use visual odometry
1073  return;
1074  }
1075 
1076  info.reg.covariance = covariance;
1077  rtabmap::OdometryEvent odomEvent(
1079  cv::Mat(),
1080  cv::Mat(),
1082  odomHeader.seq,
1083  rtabmap_conversions::timestampFromROS(odomHeader.stamp)),
1084  odomMsg.get()?rtabmap_conversions::transformFromPoseMsg(odomMsg->pose.pose):odomT,
1085  info);
1086 
1087  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
1088 }
1089 
1091  const rtabmap_msgs::SensorDataConstPtr & sensorDataMsg,
1092  const nav_msgs::OdometryConstPtr & odomMsg,
1093  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
1094 {
1095  UASSERT(sensorDataMsg.get());
1096  std_msgs::Header odomHeader;
1097  std::string frameId = frameId_;
1098  if(odomMsg.get())
1099  {
1100  odomHeader = odomMsg->header;
1101  if(!odomMsg->child_frame_id.empty())
1102  {
1103  frameId = odomMsg->child_frame_id;
1104  }
1105  else
1106  {
1107  ROS_WARN("Received odom topic with child_frame_id not set! Using \"%s\" as base frame.", frameId_.c_str());
1108  }
1109  }
1110  else
1111  {
1112  odomHeader = sensorDataMsg->header;
1113  odomHeader.frame_id = odomFrameId_;
1114  }
1115 
1117  cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
1118  if(odomMsg.get())
1119  {
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)
1127  {
1128  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomMsg->twist.covariance.data()).clone();
1129  }
1130  }
1131  else if(odomInfoMsg.get() && odomInfoMsg->covariance.size() == 36)
1132  {
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)
1139  {
1140  covariance = cv::Mat(6,6,CV_64FC1,(void*)odomInfoMsg->covariance.data()).clone();
1141  }
1142  }
1143  if(odomHeader.frame_id.empty())
1144  {
1145  ROS_ERROR("Odometry frame not set!?");
1146  return;
1147  }
1148 
1151  bool ignoreData = false;
1152 
1153  // limit update rate
1154  if(maxOdomUpdateRate_<=0.0 ||
1158  {
1160 
1161  data = rtabmap_conversions::sensorDataFromROS(*sensorDataMsg);
1162  data.uncompressData();
1163 
1164  if(odomInfoMsg.get())
1165  {
1167  }
1168  ignoreData = false;
1169  }
1170  else if(odomInfoMsg.get())
1171  {
1172  data = rtabmap_conversions::sensorDataFromROS(*sensorDataMsg);
1173  data.clearRawData();
1174  data.clearCompressedData();
1176  ignoreData = true;
1177  }
1178  else
1179  {
1180  // don't update GUI odom stuff if we don't use visual odometry
1181  return;
1182  }
1183 
1184  info.reg.covariance = covariance;
1185  rtabmap::OdometryEvent odomEvent(
1186  data,
1187  odomMsg.get()?rtabmap_conversions::transformFromPoseMsg(odomMsg->pose.pose):odomT,
1188  info);
1189 
1190  QMetaObject::invokeMethod(mainWindow_, "processOdometry", Q_ARG(rtabmap::OdometryEvent, odomEvent), Q_ARG(bool, ignoreData));
1191 }
1192 
1193 }
rtabmap_viz::GuiWrapper::frameId_
std::string frameId_
Definition: GuiWrapper.h:130
rtabmap::SensorData
rtabmap::MainWindow
rtabmap_conversions::convertScanMsg
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)
int
int
rtabmap::OdometryEvent
rtabmap::MainWindow::setMonitoringState
void setMonitoringState(bool pauseChecked=false)
rtabmap::Statistics::setMapCorrection
void setMapCorrection(const Transform &mapCorrection)
rtabmap_viz::GuiWrapper::~GuiWrapper
virtual ~GuiWrapper()
Definition: GuiWrapper.cpp:190
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
rtabmap_viz::GuiWrapper::commonOdomCallback
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
Definition: GuiWrapper.cpp:1018
rtabmap::StereoCameraModel
rtabmap::Statistics
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
rtabmap::RtabmapEventCmd
msg
msg
UVariant::isInt
bool isInt() const
UTimer::now
static double now()
message_filters::Synchronizer
rtabmap::RtabmapEventCmd::getCmd
Cmd getCmd() const
boost::shared_ptr
rtabmap_conversions::getTransform
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
rtabmap_conversions::transformFromPoseMsg
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
rtabmap::ParamEvent
max3
float max3(const float &a, const float &b, const float &c)
Definition: GuiWrapper.cpp:59
b
Array< int, 3, 1 > b
ParamEvent.h
UVariant::toIntArray
std::vector< int > toIntArray(bool *ok=0) const
UEventsManager.h
rtabmap_viz::GuiWrapper::processRequestedMap
void processRequestedMap(const rtabmap_msgs::MapData &map)
Definition: GuiWrapper.cpp:281
rtabmap_sync
MainWindow.h
rtabmap::RtabmapEventCmd::kCmdPublish3DMap
kCmdPublish3DMap
rtabmap::PreferencesDialog::getAllParameters
rtabmap::ParametersMap getAllParameters() const
rtabmap_viz::GuiWrapper::GuiWrapper
GuiWrapper(int &argc, char **argv)
Definition: GuiWrapper.cpp:67
c
Scalar Scalar * c
rtabmap_viz::GuiWrapper::infoCallback
void infoCallback(const rtabmap_msgs::InfoConstPtr &infoMsg)
Definition: GuiWrapper.cpp:229
uFormat
std::string uFormat(const char *fmt,...)
rtabmap::RtabmapEventCmd::value3
const UVariant & value3() const
rtabmap::CameraModel
rtabmap_sync::CommonDataSubscriber::getTopicQueueSize
int getTopicQueueSize() const
rtabmap::RtabmapEventCmd::kCmdTriggerNewMap
kCmdTriggerNewMap
rtabmap_viz::GuiWrapper::pathTopic_
message_filters::Subscriber< nav_msgs::Path > pathTopic_
Definition: GuiWrapper.h:145
UVariant::isIntArray
bool isIntArray() const
RtabmapEvent.h
rtabmap::RtabmapEvent
rtabmap_sync::CommonDataSubscriber::setupCallbacks
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name, std::vector< diagnostic_updater::DiagnosticTask * > otherTasks=std::vector< diagnostic_updater::DiagnosticTask * >())
true
#define true
e
GLM_FUNC_DECL genType e()
rtabmap::LaserScan
UVariant::isUInt
bool isUInt() const
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
rtabmap_conversions::convertRGBDMsgs
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::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &rgb, cv::Mat &depth, std::vector< rtabmap::CameraModel > &cameraModels, std::vector< rtabmap::StereoCameraModel > &stereoCameraModels, tf::TransformListener &listener, double waitForTransform, bool alreadRectifiedImages, const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPointsMsgs=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3dMsgs=std::vector< std::vector< rtabmap_msgs::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)
rtabmap::RtabmapEventCmd::kCmdRepublishData
kCmdRepublishData
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rtabmap::RtabmapEventCmd::kCmdResetMemory
kCmdResetMemory
rtabmap_viz::GuiWrapper::tfListener_
tf::TransformListener tfListener_
Definition: GuiWrapper.h:136
rtabmap_viz::GuiWrapper::republishNodeDataPub_
ros::Publisher republishNodeDataPub_
Definition: GuiWrapper.h:138
rtabmap_viz::GuiWrapper::goalTopic_
message_filters::Subscriber< rtabmap_msgs::Goal > goalTopic_
Definition: GuiWrapper.h:144
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
GuiWrapper.h
rtabmap::RtabmapEventCmd::value2
const UVariant & value2() const
data
data
rtabmap::RtabmapEventCmd::value1
const UVariant & value1() const
UEvent
rtabmap_viz::GuiWrapper::commonMultiCameraCallback
virtual void commonMultiCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const sensor_msgs::LaserScan &scan2dMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_msgs::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())
Definition: GuiWrapper.cpp:488
UDirectory::homeDir
static std::string homeDir()
rtabmap_conversions::odomInfoFromROS
rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_msgs::OdomInfo &msg, bool ignoreData=false)
uReplaceChar
std::string uReplaceChar(const std::string &str, char before, char after)
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
rtabmap::Statistics::data
const std::map< std::string, float > & data() const
UDirectory::currentDir
static std::string currentDir(bool trailingSeparator=false)
rtabmap_viz::GuiWrapper::mapDataTopic_
message_filters::Subscriber< rtabmap_msgs::MapData > mapDataTopic_
Definition: GuiWrapper.h:141
rtabmap_viz::GuiWrapper::goalReachedCallback
void goalReachedCallback(const std_msgs::BoolConstPtr &value)
Definition: GuiWrapper.cpp:275
rtabmap_viz
Definition: GuiWrapper.h:55
rtabmap::RtabmapEventCmd::Cmd
Cmd
UEvent::getClassName
virtual std::string getClassName() const=0
rtabmap::RtabmapEvent3DMap
UVariant::isBool
bool isBool() const
rtabmap_viz::GuiWrapper::commonStereoCallback
virtual void commonStereoCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::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_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< rtabmap_msgs::KeyPoint > &localKeyPoints=std::vector< rtabmap_msgs::KeyPoint >(), const std::vector< rtabmap_msgs::Point3f > &localPoints3d=std::vector< rtabmap_msgs::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())
Definition: GuiWrapper.cpp:691
rtabmap_viz::GuiWrapper::lastOdomInfoUpdateTime_
double lastOdomInfoUpdateTime_
Definition: GuiWrapper.h:126
UEventsManager::addHandler
static void addHandler(UEventsHandler *handler)
rtabmap_viz::GuiWrapper::infoMapSync_
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
Definition: GuiWrapper.h:151
frameId
std::string const * frameId(const M &m)
rtabmap_viz::GuiWrapper::maxOdomUpdateRate_
double maxOdomUpdateRate_
Definition: GuiWrapper.h:135
rtabmap_conversions::infoFromROS
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
UVariant::isStr
bool isStr() const
info
else if n * info
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
rtabmap_viz::GuiWrapper::commonLaserScanCallback
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scan2dMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const rtabmap_msgs::GlobalDescriptor &globalDescriptor=rtabmap_msgs::GlobalDescriptor())
Definition: GuiWrapper.cpp:871
UASSERT
#define UASSERT(condition)
argv
argv
UDirectory.h
rtabmap::MainWindow::isProcessingOdometry
bool isProcessingOdometry() const
ROS_WARN
#define ROS_WARN(...)
rtabmap::RtabmapEventCmd::kCmdGoal
kCmdGoal
m
Matrix3f m
rtabmap_viz::GuiWrapper::waitForTransform_
bool waitForTransform_
Definition: GuiWrapper.h:132
rtabmap::OdometryInfo::copyWithoutData
OdometryInfo copyWithoutData() const
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
PreferencesDialogROS.h
rtabmap::RtabmapEventCmd::kCmdLabel
kCmdLabel
rtabmap_viz::GuiWrapper::goalPathCallback
void goalPathCallback(const rtabmap_msgs::GoalConstPtr &goalMsg, const nav_msgs::PathConstPtr &pathMsg)
Definition: GuiWrapper.cpp:261
rtabmap_viz::GuiWrapper::handleEvent
virtual bool handleEvent(UEvent *anEvent)
Definition: GuiWrapper.cpp:302
rtabmap_viz::GuiWrapper::MyGoalPathSyncPolicy
message_filters::sync_policies::ExactTime< rtabmap_msgs::Goal, nav_msgs::Path > MyGoalPathSyncPolicy
Definition: GuiWrapper.h:155
rtabmap::Statistics::setPoses
void setPoses(const std::map< int, Transform > &poses)
str
rtabmap_sync::CommonDataSubscriber::tick
void tick(const ros::Time &stamp, double targetFrequency=0)
rtabmap_viz::GuiWrapper::MyInfoMapSyncPolicy
message_filters::sync_policies::ExactTime< rtabmap_msgs::Info, rtabmap_msgs::MapData > MyInfoMapSyncPolicy
Definition: GuiWrapper.h:150
rtabmap_sync::CommonDataSubscriber::getSyncQueueSize
int getSyncQueueSize() const
message_filters::Subscriber::subscribe
void subscribe()
UVariant::toStr
std::string toStr(bool *ok=0) const
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
a
ArrayXXi a
rtabmap::Transform
rtabmap_viz::GuiWrapper::infoTopic_
message_filters::Subscriber< rtabmap_msgs::Info > infoTopic_
Definition: GuiWrapper.h:140
rtabmap::RtabmapGoalStatusEvent
rtabmap_conversions::timestampFromROS
double timestampFromROS(const ros::Time &stamp)
rtabmap::RtabmapEventCmd::kCmdCancelGoal
kCmdCancelGoal
rtabmap_viz::GuiWrapper::goalReachedTopic_
ros::Subscriber goalReachedTopic_
Definition: GuiWrapper.h:146
rtabmap_viz::GuiWrapper::commonSensorDataCallback
virtual void commonSensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &sensorDataMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
Definition: GuiWrapper.cpp:1090
rtabmap_viz::GuiWrapper::prefDialog_
rtabmap::PreferencesDialog * prefDialog_
Definition: GuiWrapper.h:123
rtabmap_viz::GuiWrapper::odomSensorSync_
bool odomSensorSync_
Definition: GuiWrapper.h:134
rtabmap_viz::GuiWrapper::cameraNodeName_
std::string cameraNodeName_
Definition: GuiWrapper.h:125
rtabmap::Statistics::setSignaturesData
void setSignaturesData(const std::map< int, Signature > &data)
rtabmap_viz::GuiWrapper::waitForTransformDuration_
double waitForTransformDuration_
Definition: GuiWrapper.h:133
ROS_ERROR
#define ROS_ERROR(...)
UDEBUG
#define UDEBUG(...)
PreferencesDialogROS
Definition: PreferencesDialogROS.h:36
rtabmap_viz::GuiWrapper::goalPathSync_
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
Definition: GuiWrapper.h:156
uSleep
void uSleep(unsigned int ms)
OdometryEvent.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap::OdometryInfo
UVariant::toBool
bool toBool() const
M_PI
#define M_PI
rtabmap_viz::GuiWrapper::infoMapCallback
void infoMapCallback(const rtabmap_msgs::InfoConstPtr &infoMsg, const rtabmap_msgs::MapDataConstPtr &mapMsg)
Definition: GuiWrapper.cpp:198
UVariant::isUndef
bool isUndef() const
Parameters.h
rtabmap::RtabmapEventCmd::kCmdResume
kCmdResume
rtabmap_conversions::convertScan3dMsg
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 is2D=false)
false
#define false
rtabmap_conversions::mapDataFromROS
void mapDataFromROS(const rtabmap_msgs::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
cmd
string cmd
UTimer.h
rtabmap::MainWindow::isProcessingStatistics
bool isProcessingStatistics() const
rtabmap_conversions::convertStereoMsg
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)
rtabmap::RtabmapEventCmd::kCmdRemoveLabel
kCmdRemoveLabel
ROS_INFO
#define ROS_INFO(...)
rtabmap::RtabmapEventCmd::kCmdPause
kCmdPause
UConversion.h
MsgConversion.h
rtabmap::RtabmapGlobalPathEvent
util3d_transforms.h
rtabmap_viz::GuiWrapper::odomFrameId_
std::string odomFrameId_
Definition: GuiWrapper.h:131
rtabmap_viz::GuiWrapper::mainWindow_
rtabmap::MainWindow * mainWindow_
Definition: GuiWrapper.h:124
rtabmap::Statistics::setConstraints
void setConstraints(const std::multimap< int, Link > &constraints)
value
value
i
int i
rtabmap_viz::GuiWrapper::infoOnlyTopic_
ros::Subscriber infoOnlyTopic_
Definition: GuiWrapper.h:142
UVariant::toInt
int toInt(bool *ok=0) const
util3d.h
rtabmap_conversions::sensorDataFromROS
rtabmap::SensorData sensorDataFromROS(const rtabmap_msgs::SensorData &msg)
ros::NodeHandle
rtabmap_viz::GuiWrapper::rtabmapNodeName_
std::string rtabmapNodeName_
Definition: GuiWrapper.h:127
util2d.h
UEventsSender::post
void post(UEvent *event, bool async=true) const


rtabmap_viz
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:31