MapCloudDisplay.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 
29 
30 #include <QApplication>
31 #include <QMessageBox>
32 #include <QTimer>
33 
34 #include <OgreSceneNode.h>
35 #include <OgreSceneManager.h>
36 
37 #include <ros/time.h>
38 
39 #include <tf/transform_listener.h>
40 
41 #include <rviz/display_context.h>
42 #include <rviz/frame_manager.h>
44 #include <rviz/validate_floats.h>
50 
52 
53 #include <rtabmap/core/Transform.h>
56 #include <rtabmap/core/util3d.h>
58 #include <rtabmap/core/Graph.h>
60 #include <rtabmap_msgs/GetMap.h>
61 #include <std_msgs/Int32MultiArray.h>
62 
63 
64 namespace rtabmap_rviz_plugins
65 {
66 
67 
69  manager_(0),
70  pose_(rtabmap::Transform::getIdentity()),
71  id_(0),
72  scene_node_(0)
73 {}
74 
76 {
77  clear();
78 }
79 
81 {
82  if ( scene_node_ )
83  {
84  manager_->destroySceneNode( scene_node_ );
85  scene_node_=0;
86  }
87 }
88 
90  : spinner_(1, &cbqueue_),
91  lastCloudAdded_(-1),
97 {
98  //QIcon icon;
99  //this->setIcon(icon);
100 
101  style_property_ = new rviz::EnumProperty( "Style", "Flat Squares",
102  "Rendering mode to use, in order of computational complexity.",
103  this, SLOT( updateStyle() ), this );
109 
110  point_world_size_property_ = new rviz::FloatProperty( "Size (m)", 0.01,
111  "Point size in meters.",
112  this, SLOT( updateBillboardSize() ), this );
114 
115  point_pixel_size_property_ = new rviz::FloatProperty( "Size (Pixels)", 3,
116  "Point size in pixels.",
117  this, SLOT( updateBillboardSize() ), this );
119 
120  alpha_property_ = new rviz::FloatProperty( "Alpha", 1.0,
121  "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
122  this, SLOT( updateAlpha() ), this );
123  alpha_property_->setMin( 0 );
124  alpha_property_->setMax( 1 );
125 
126  xyz_transformer_property_ = new rviz::EnumProperty( "Position Transformer", "",
127  "Set the transformer to use to set the position of the points.",
128  this, SLOT( updateXyzTransformer() ), this );
129  connect( xyz_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
130  this, SLOT( setXyzTransformerOptions( EnumProperty* )));
131 
132  color_transformer_property_ = new rviz::EnumProperty( "Color Transformer", "",
133  "Set the transformer to use to set the color of the points.",
134  this, SLOT( updateColorTransformer() ), this );
135  connect( color_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
136  this, SLOT( setColorTransformerOptions( EnumProperty* )));
137 
138  cloud_from_scan_ = new rviz::BoolProperty( "Cloud from scan", false,
139  "Create the cloud from laser scans instead of the RGB-D/Stereo images.",
140  this, SLOT( updateCloudParameters() ), this );
142 
143  cloud_decimation_ = new rviz::IntProperty( "Cloud decimation", 4,
144  "Decimation of the input RGB and depth images before creating the cloud.",
145  this, SLOT( updateCloudParameters() ), this );
147  cloud_decimation_->setMax( 16 );
148 
149  cloud_max_depth_ = new rviz::FloatProperty( "Cloud max depth (m)", 4.0f,
150  "Maximum depth of the generated clouds.",
151  this, SLOT( updateCloudParameters() ), this );
152  cloud_max_depth_->setMin( 0.0f );
153  cloud_max_depth_->setMax( 999.0f );
154 
155  cloud_min_depth_ = new rviz::FloatProperty( "Cloud min depth (m)", 0.0f,
156  "Minimum depth of the generated clouds.",
157  this, SLOT( updateCloudParameters() ), this );
158  cloud_min_depth_->setMin( 0.0f );
159  cloud_min_depth_->setMax( 999.0f );
160 
161  cloud_voxel_size_ = new rviz::FloatProperty( "Cloud voxel size (m)", 0.01f,
162  "Voxel size of the generated clouds.",
163  this, SLOT( updateCloudParameters() ), this );
164  cloud_voxel_size_->setMin( 0.0f );
165  cloud_voxel_size_->setMax( 1.0f );
166 
167  cloud_filter_floor_height_ = new rviz::FloatProperty( "Filter floor (m)", 0.0f,
168  "Filter the floor up to maximum height set here "
169  "(only appropriate for 2D mapping).",
170  this, SLOT( updateCloudParameters() ), this );
173 
174  cloud_filter_ceiling_height_ = new rviz::FloatProperty( "Filter ceiling (m)", 0.0f,
175  "Filter the ceiling at the specified height set here "
176  "(only appropriate for 2D mapping).",
177  this, SLOT( updateCloudParameters() ), this );
180 
181  node_filtering_radius_ = new rviz::FloatProperty( "Node filtering radius (m)", 0.0f,
182  "(Disabled=0) Only keep one node in the specified radius.",
183  this, SLOT( updateCloudParameters() ), this );
186 
187  node_filtering_angle_ = new rviz::FloatProperty( "Node filtering angle (degrees)", 30.0f,
188  "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
189  this, SLOT( updateCloudParameters() ), this );
191  node_filtering_angle_->setMax( 359.0f );
192 
193  download_namespace = new rviz::StringProperty("Download namespace", "rtabmap", "Namespace used to call Download services below", this, SLOT( downloadNamespaceChanged() ), this);
194 
195  download_map_ = new rviz::BoolProperty( "Download map", false,
196  "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
197  this, SLOT( downloadMap() ), this );
198 
199  download_graph_ = new rviz::BoolProperty( "Download graph", false,
200  "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
201  this, SLOT( downloadGraph() ), this );
202 
204 
205  // PointCloudCommon sets up a callback queue with a thread for each
206  // instance. Use that for processing incoming messages.
208 }
209 
211 {
213  {
215  }
216 
217  spinner_.stop();
218 }
219 
221 {
222  std::vector<std::string> classes = transformer_class_loader_->getDeclaredClasses();
223  std::vector<std::string>::iterator ci;
224 
225  for( ci = classes.begin(); ci != classes.end(); ci++ )
226  {
227  const std::string& lookup_name = *ci;
228  std::string name = transformer_class_loader_->getName( lookup_name );
229 
230  if( transformers_.count( name ) > 0 )
231  {
232  ROS_ERROR( "Transformer type [%s] is already loaded.", name.c_str() );
233  continue;
234  }
235 
237  trans->init();
238  connect( trans.get(), SIGNAL( needRetransform() ), this, SLOT( causeRetransform() ));
239 
241  info.transformer = trans;
242  info.readable_name = name;
243  info.lookup_name = lookup_name;
244 
245  info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_XYZ, info.xyz_props );
246  setPropertiesHidden( info.xyz_props, true );
247 
248  info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_Color, info.color_props );
249  setPropertiesHidden( info.color_props, true );
250 
251  transformers_[ name ] = info;
252  }
253 }
254 
256 {
258 
259  transformer_class_loader_ = new pluginlib::ClassLoader<rviz::PointCloudTransformer>( "rviz", "rviz::PointCloudTransformer" );
261 
262  updateStyle();
264  updateAlpha();
265 
266  spinner_.start();
267 }
268 
269 void MapCloudDisplay::processMessage( const rtabmap_msgs::MapDataConstPtr& msg )
270 {
272 
273  this->emitTimeSignal(msg->header.stamp);
274 }
275 
276 void MapCloudDisplay::processMapData(const rtabmap_msgs::MapData& map)
277 {
278  std::map<int, rtabmap::Transform> poses;
279  for(unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
280  {
281  poses.insert(std::make_pair(map.graph.posesId[i], rtabmap_conversions::transformFromPoseMsg(map.graph.poses[i])));
282  }
283 
284  // Add new clouds...
285  bool fromDepth = !cloud_from_scan_->getBool();
286  std::set<int> nodeDataReceived;
287  for(unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
288  {
289  int id = map.nodes[i].id;
290 
291  // Always refresh the cloud if there are data
293  if((fromDepth &&
294  !s.sensorData().imageCompressed().empty() &&
295  !s.sensorData().depthOrRightCompressed().empty() &&
296  (s.sensorData().cameraModels().size() || s.sensorData().stereoCameraModels().size())) ||
297  (!fromDepth && !s.sensorData().laserScanCompressed().isEmpty()))
298  {
299  cv::Mat image, depth;
300  rtabmap::LaserScan scan;
301 
302  s.sensorData().uncompressData(fromDepth?&image:0, fromDepth?&depth:0, !fromDepth?&scan:0);
303 
304  sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
305  if(fromDepth && !s.sensorData().imageRaw().empty() && !s.sensorData().depthOrRightRaw().empty())
306  {
307  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
308  pcl::IndicesPtr validIndices(new std::vector<int>);
309 
311  s.sensorData(),
315  validIndices.get());
316 
317  if(!cloud->empty())
318  {
320  {
321  cloud = rtabmap::util3d::voxelize(cloud, validIndices, cloud_voxel_size_->getFloat());
322  }
323 
325  {
326  // convert in /odom frame
327  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose());
328  cloud = rtabmap::util3d::passThrough(cloud, "z",
331  // convert back in /base_link frame
332  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose().inverse());
333  }
334 
335  if(!cloud->empty())
336  {
337  pcl::toROSMsg(*cloud, *cloudMsg);
338  }
339  }
340  }
341  else if(!fromDepth && !scan.isEmpty())
342  {
344  scan,
345  1,
349  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud;
350  cloud = rtabmap::util3d::laserScanToPointCloudI(scan, scan.localTransform());
352  {
353  // convert in /odom frame
354  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose());
355  cloud = rtabmap::util3d::passThrough(cloud, "z",
358  // convert back in /base_link frame
359  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose().inverse());
360  }
361 
362  if(!cloud->empty())
363  {
364  pcl::toROSMsg(*cloud, *cloudMsg);
365  }
366  }
367 
368  if(!cloudMsg->data.empty())
369  {
370  cloudMsg->header = map.header;
372  info->message_ = cloudMsg;
374  info->id_ = id;
375 
376  if (transformCloud(info, true))
377  {
378  boost::mutex::scoped_lock lock(new_clouds_mutex_);
379  new_cloud_infos_.erase(id);
380  new_cloud_infos_.insert(std::make_pair(id, info));
381  }
382  }
383  }
384  nodeDataReceived.insert(id);
385  }
386 
387  // Update graph
389  {
392  node_filtering_angle_->getFloat()*CV_PI/180.0);
393  }
394 
395  {
396  boost::mutex::scoped_lock lock(current_map_mutex_);
397  current_map_ = poses;
398  current_map_updated_ = true;
399  nodeDataReceived_.insert(nodeDataReceived.begin(), nodeDataReceived.end());
400  }
401 }
402 
403 void MapCloudDisplay::setPropertiesHidden( const QList<Property*>& props, bool hide )
404 {
405  for( int i = 0; i < props.size(); i++ )
406  {
407  props[ i ]->setHidden( hide );
408  }
409 }
410 
411 void MapCloudDisplay::updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud )
412 {
413  std::string xyz_name = xyz_transformer_property_->getStdString();
414  std::string color_name = color_transformer_property_->getStdString();
415 
418 
419  // Get the channels that we could potentially render
420  typedef std::set<std::pair<uint8_t, std::string> > S_string;
421  S_string valid_xyz, valid_color;
422  bool cur_xyz_valid = false;
423  bool cur_color_valid = false;
424  bool has_rgb_transformer = false;
425  bool has_intensity_transformer = false;
426  M_TransformerInfo::iterator trans_it = transformers_.begin();
427  M_TransformerInfo::iterator trans_end = transformers_.end();
428  for(;trans_it != trans_end; ++trans_it)
429  {
430  const std::string& name = trans_it->first;
431  const rviz::PointCloudTransformerPtr& trans = trans_it->second.transformer;
432  uint32_t mask = trans->supports(cloud);
434  {
435  valid_xyz.insert(std::make_pair(trans->score(cloud), name));
436  if (name == xyz_name)
437  {
438  cur_xyz_valid = true;
439  }
441  }
442 
444  {
445  valid_color.insert(std::make_pair(trans->score(cloud), name));
446  if (name == color_name)
447  {
448  cur_color_valid = true;
449  }
450  if (name == "RGB8")
451  {
452  has_rgb_transformer = true;
453  }
454  else if (name == "Intensity")
455  {
456  has_intensity_transformer = true;
457  }
459  }
460  }
461 
462  if( !cur_xyz_valid )
463  {
464  if( !valid_xyz.empty() )
465  {
466  xyz_transformer_property_->setStringStd( valid_xyz.rbegin()->second );
467  }
468  }
469 
470  if( !cur_color_valid )
471  {
472  if( !valid_color.empty() )
473  {
474  if (has_rgb_transformer)
475  {
477  }
478  else if (has_intensity_transformer)
479  {
481  }
482  else
483  {
484  color_transformer_property_->setStringStd( valid_color.rbegin()->second );
485  }
486  }
487  }
488 }
489 
491 {
492  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
493  {
494  it->second->cloud_->setAlpha( alpha_property_->getFloat() );
495  }
496 }
497 
499 {
502  {
505  }
506  else
507  {
510  }
511  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
512  {
513  it->second->cloud_->setRenderMode( mode );
514  }
516 }
517 
519 {
521  float size;
523  {
525  }
526  else
527  {
529  }
530  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
531  {
532  it->second->cloud_->setDimensions( size, size, size );
533  }
535 }
536 
538 {
539  // do nothing for most parameters... only take effect on next generated clouds
540 
541  // if we change the kind of map, clear
543  {
544  reset();
545  }
547 }
548 
549 void MapCloudDisplay::downloadMap(bool graphOnly)
550 {
551  rtabmap_msgs::GetMap getMapSrv;
552  getMapSrv.request.global = false;
553  getMapSrv.request.optimized = true;
554  getMapSrv.request.graphOnly = graphOnly;
555  std::string rtabmapNs = download_namespace->getStdString();
556  std::string srvName = update_nh_.resolveName(uFormat("%s/get_map_data", rtabmapNs.c_str()));
557  QMessageBox * messageBox = new QMessageBox(
558  QMessageBox::NoIcon,
559  tr("Calling \"%1\" service...").arg(srvName.c_str()),
560  tr("Downloading the map... please wait (rviz could become gray!)"),
561  QMessageBox::NoButton);
562  messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
563  messageBox->show();
564  QApplication::processEvents();
565  uSleep(100); // hack make sure the text in the QMessageBox is shown...
566  QApplication::processEvents();
567  if(!ros::service::call(srvName, getMapSrv))
568  {
569  ROS_ERROR("MapCloudDisplay: Cannot call \"%s\" service. "
570  "Tip: if rtabmap node is not in \"%s\" namespace, you can "
571  "change the \"Download namespace\" option.",
572  srvName.c_str(),
573  rtabmapNs.c_str());
574  messageBox->setText(tr("MapCloudDisplay: Cannot call \"%1\" service. "
575  "Tip: if rtabmap node is not in \"%2\" namespace, you can "
576  "change the \"Download namespace\" option.").
577  arg(srvName.c_str()).arg(rtabmapNs.c_str()));
578  }
579  else if(graphOnly)
580  {
581  messageBox->setText(tr("Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
582  QApplication::processEvents();
583  processMapData(getMapSrv.response.data);
584  messageBox->setText(tr("Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
585 
586  QTimer::singleShot(1000, messageBox, SLOT(close()));
587  }
588  else
589  {
590  messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)...")
591  .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
592  QApplication::processEvents();
593  this->reset();
594  processMapData(getMapSrv.response.data);
595  messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
596  .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
597 
598  QTimer::singleShot(1000, messageBox, SLOT(close()));
599  }
600 }
601 
603 {
604  std::string rtabmapNs = download_namespace->getStdString();
605  std::string topicName = update_nh_.resolveName(uFormat("%s/republish_node_data", rtabmapNs.c_str()));
606  republishNodeDataPub_ = update_nh_.advertise<std_msgs::Int32MultiArray>(topicName, 1);
607 }
608 
610 {
611  if(download_map_->getBool())
612  {
613  downloadMap(false);
614  download_map_->blockSignals(true);
615  download_map_->setBool(false);
616  download_map_->blockSignals(false);
617  }
618  else
619  {
620  // just stay true if double-clicked on DownloadMap property, let the
621  // first process above finishes
622  download_map_->blockSignals(true);
623  download_map_->setBool(true);
624  download_map_->blockSignals(false);
625  }
626 }
627 
629 {
630  if(download_graph_->getBool())
631  {
632  downloadMap(true);
633  download_graph_->blockSignals(true);
634  download_graph_->setBool(false);
635  download_graph_->blockSignals(false);
636  }
637  else
638  {
639  // just stay true if double-clicked on DownloadGraph property, let the
640  // first process above finishes
641  download_graph_->blockSignals(true);
642  download_graph_->setBool(true);
643  download_graph_->blockSignals(false);
644  }
645 }
646 
648 {
649  needs_retransform_ = true;
650 }
651 
652 void MapCloudDisplay::update( float wall_dt, float ros_dt )
653 {
655 
656  int lastCloudAdded = -1;
657 
658  if (needs_retransform_)
659  {
660  retransform();
661  needs_retransform_ = false;
662  }
663 
664  {
665  boost::mutex::scoped_lock lock(new_clouds_mutex_);
666  if( !new_cloud_infos_.empty() )
667  {
668  float size;
671  } else {
673  }
674 
675  std::map<int, CloudInfoPtr>::iterator it = new_cloud_infos_.begin();
676  std::map<int, CloudInfoPtr>::iterator end = new_cloud_infos_.end();
677  for (; it != end; ++it)
678  {
679  CloudInfoPtr cloud_info = it->second;
680 
681  cloud_info->cloud_.reset( new rviz::PointCloud() );
682  cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
683  cloud_info->cloud_->setRenderMode( mode );
684  cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
685  cloud_info->cloud_->setDimensions( size, size, size );
686  cloud_info->cloud_->setAutoSize(false);
687 
688  cloud_info->manager_ = context_->getSceneManager();
689 
690  cloud_info->scene_node_ = scene_node_->createChildSceneNode();
691 
692  cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
693  cloud_info->scene_node_->setVisible(false);
694 
695  cloud_infos_.erase(it->first);
696  cloud_infos_.insert(*it);
697  lastCloudAdded = it->first;
698  }
699 
700  new_cloud_infos_.clear();
701  }
702  }
703 
704  {
705  boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ );
706 
707  if( lock.owns_lock() )
708  {
710  {
711  M_TransformerInfo::iterator it = transformers_.begin();
712  M_TransformerInfo::iterator end = transformers_.end();
713  for (; it != end; ++it)
714  {
715  const std::string& name = it->first;
716  TransformerInfo& info = it->second;
717 
720  }
721  }
722  }
723 
724  new_xyz_transformer_ = false;
725  new_color_transformer_ = false;
726  }
727 
728  int totalPoints = 0;
729  int totalNodesShown = 0;
730  {
731  // update poses
732  boost::mutex::scoped_lock lock(current_map_mutex_);
733  if(!current_map_.empty())
734  {
735  std::vector<int> missingNodes;
736  for (std::map<int, rtabmap::Transform>::iterator it=current_map_.begin(); it != current_map_.end(); ++it)
737  {
738  std::map<int, CloudInfoPtr>::iterator cloudInfoIt = cloud_infos_.find(it->first);
739  if(cloudInfoIt != cloud_infos_.end())
740  {
741  totalPoints += cloudInfoIt->second->transformed_points_.size();
742  cloudInfoIt->second->pose_ = it->second;
743  Ogre::Vector3 framePosition;
744  Ogre::Quaternion frameOrientation;
745  std::string error;
746  if (context_->getFrameManager()->getTransform(cloudInfoIt->second->message_->header, framePosition, frameOrientation))
747  {
748  // Multiply frame with pose
749  Ogre::Matrix4 frameTransform;
750  frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
751  const rtabmap::Transform & p = cloudInfoIt->second->pose_;
752  Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
753  p[4], p[5], p[6], p[7],
754  p[8], p[9], p[10], p[11],
755  0, 0, 0, 1);
756  frameTransform = frameTransform * pose;
757  Ogre::Vector3 posePosition = frameTransform.getTrans();
758  Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
759  poseOrientation.normalise();
760 
761  cloudInfoIt->second->scene_node_->setPosition(posePosition);
762  cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
763  cloudInfoIt->second->scene_node_->setVisible(true);
764  ++totalNodesShown;
765  }
766  else if(context_->getFrameManager()->frameHasProblems(cloudInfoIt->second->message_->header.frame_id, cloudInfoIt->second->message_->header.stamp, error))
767  {
768  ROS_ERROR("MapCloudDisplay: Could not update pose of node %d (cannot transform pose in target frame id \"%s\" (reason=%s), set fixed frame in global options to \"%s\")",
769  it->first,
770  cloudInfoIt->second->message_->header.frame_id.c_str(),
771  error.c_str(),
772  cloudInfoIt->second->message_->header.frame_id.c_str());
773  }
774  }
775  else if(it->first>0 && current_map_updated_&& nodeDataReceived_.find(it->first) == nodeDataReceived_.end())
776  {
777  missingNodes.push_back(it->first);
778  }
779  }
780  //hide not used clouds
781  for(std::map<int, CloudInfoPtr>::iterator iter = cloud_infos_.begin(); iter!=cloud_infos_.end();)
782  {
783  if(current_map_.find(iter->first) == current_map_.end())
784  {
785  if(iter->first == lastCloudAdded_)
786  {
787  // remove from cache, the node has been discarded
788  cloud_infos_.erase(iter++);
789  lastCloudAdded_ = -1;
790  }
791  else
792  {
793  iter->second->scene_node_->setVisible(false);
794  ++iter;
795  }
796  }
797  else
798  {
799  ++iter;
800  }
801  }
802 
803  if(!missingNodes.empty())
804  {
805  std_msgs::Int32MultiArray msg;
806  msg.data = missingNodes;
808  }
809  }
810  current_map_updated_ = false;
811  }
812  if(lastCloudAdded>0)
813  {
814  lastCloudAdded_ = lastCloudAdded;
815  }
816 
817  this->setStatusStd(rviz::StatusProperty::Ok, "Points", tr("%1").arg(totalPoints).toStdString());
818  this->setStatusStd(rviz::StatusProperty::Ok, "Nodes", tr("%1 shown of %2").arg(totalNodesShown).arg(cloud_infos_.size()).toStdString());
819 }
820 
822 {
823  lastCloudAdded_ = -1;
824  {
825  boost::mutex::scoped_lock lock(new_clouds_mutex_);
826  cloud_infos_.clear();
827  new_cloud_infos_.clear();
828  }
829  {
830  boost::mutex::scoped_lock lock(current_map_mutex_);
831  current_map_.clear();
832  current_map_updated_ = false;
833  nodeDataReceived_.clear();
834  }
835  MFDClass::reset();
836 }
837 
839 {
840  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
842  {
843  return;
844  }
845  new_xyz_transformer_ = true;
847 }
848 
850 {
851  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
853  {
854  return;
855  }
856  new_color_transformer_ = true;
858 }
859 
861 {
863 }
864 
866 {
868 }
869 
871 {
872  prop->clearOptions();
873 
874  if (cloud_infos_.empty())
875  {
876  return;
877  }
878 
879  boost::recursive_mutex::scoped_lock tlock(transformers_mutex_);
880 
881  const sensor_msgs::PointCloud2ConstPtr& msg = cloud_infos_.begin()->second->message_;
882 
883  M_TransformerInfo::iterator it = transformers_.begin();
884  M_TransformerInfo::iterator end = transformers_.end();
885  for (; it != end; ++it)
886  {
887  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
888  if ((trans->supports(msg) & mask) == mask)
889  {
890  prop->addOption( QString::fromStdString( it->first ));
891  }
892  }
893 }
894 
895 rviz::PointCloudTransformerPtr MapCloudDisplay::getXYZTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
896 {
897  boost::recursive_mutex::scoped_lock lock( transformers_mutex_);
898  M_TransformerInfo::iterator it = transformers_.find( xyz_transformer_property_->getStdString() );
899  if( it != transformers_.end() )
900  {
901  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
902  if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_XYZ )
903  {
904  return trans;
905  }
906  }
907 
909 }
910 
911 rviz::PointCloudTransformerPtr MapCloudDisplay::getColorTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
912 {
913  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
914  M_TransformerInfo::iterator it = transformers_.find( color_transformer_property_->getStdString() );
915  if( it != transformers_.end() )
916  {
917  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
918  if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_Color )
919  {
920  return trans;
921  }
922  }
923 
925 }
926 
927 
929 {
930  boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
931 
932  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
933  {
934  const CloudInfoPtr& cloud_info = it->second;
935  transformCloud(cloud_info, false);
936  cloud_info->cloud_->clear();
937  cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
938  }
939 }
940 
941 bool MapCloudDisplay::transformCloud(const CloudInfoPtr& cloud_info, bool update_transformers)
942 {
943  rviz::V_PointCloudPoint& cloud_points = cloud_info->transformed_points_;
944  cloud_points.clear();
945 
946  size_t size = cloud_info->message_->width * cloud_info->message_->height;
947  rviz::PointCloud::Point default_pt;
948  default_pt.color = Ogre::ColourValue(1, 1, 1);
949  default_pt.position = Ogre::Vector3::ZERO;
950  cloud_points.resize(size, default_pt);
951 
952  {
953  boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
954  if( update_transformers )
955  {
956  updateTransformers( cloud_info->message_ );
957  }
958  rviz::PointCloudTransformerPtr xyz_trans = getXYZTransformer(cloud_info->message_);
959  rviz::PointCloudTransformerPtr color_trans = getColorTransformer(cloud_info->message_);
960 
961  if (!xyz_trans)
962  {
963  std::stringstream ss;
964  ss << "No position transformer available for cloud";
965  this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
966  return false;
967  }
968 
969  if (!color_trans)
970  {
971  std::stringstream ss;
972  ss << "No color transformer available for cloud";
973  this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
974  return false;
975  }
976 
977  xyz_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_XYZ, Ogre::Matrix4::IDENTITY, cloud_points);
978  color_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_Color, Ogre::Matrix4::IDENTITY, cloud_points);
979  }
980 
981  for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
982  {
983  if (!rviz::validateFloats(cloud_point->position))
984  {
985  cloud_point->position.x = 999999.0f;
986  cloud_point->position.y = 999999.0f;
987  cloud_point->position.z = 999999.0f;
988  }
989  }
990 
991  return true;
992 }
993 
994 } // namespace rtabmap_rviz_plugins
995 
rtabmap_rviz_plugins::MapCloudDisplay::current_map_mutex_
boost::mutex current_map_mutex_
Definition: MapCloudDisplay.h:182
rviz::BoolProperty::getBool
virtual bool getBool() const
rtabmap_conversions::nodeFromROS
rtabmap::Signature nodeFromROS(const rtabmap_msgs::Node &msg)
rviz::EnumProperty::getOptionInt
virtual int getOptionInt()
rtabmap::util3d::passThrough
pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
rviz::EnumProperty::clearOptions
virtual void clearOptions()
rviz::IntProperty::setMin
void setMin(int min)
rtabmap_rviz_plugins::MapCloudDisplay::updateStyle
void updateStyle()
Definition: MapCloudDisplay.cpp:498
name
rviz::MessageFilterDisplay::reset
void reset() override
mask
GLM_FUNC_DECL genIType mask(genIType const &count)
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
rviz::DisplayContext::queueRender
virtual void queueRender()=0
rviz::Display::emitTimeSignal
void emitTimeSignal(ros::Time time)
arg::arg
constexpr arg(const char *name=nullptr)
rtabmap_rviz_plugins::MapCloudDisplay::TransformerInfo
Definition: MapCloudDisplay.h:187
rtabmap_rviz_plugins::MapCloudDisplay::cloud_filter_ceiling_height_
rviz::FloatProperty * cloud_filter_ceiling_height_
Definition: MapCloudDisplay.h:119
boost::shared_ptr< PointCloudTransformer >
rtabmap_conversions::transformFromPoseMsg
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
s
RealScalar s
rtabmap_rviz_plugins::MapCloudDisplay::fromScan_
bool fromScan_
Definition: MapCloudDisplay.h:179
rviz::StatusProperty::Error
Error
rtabmap_rviz_plugins::MapCloudDisplay::loadTransformers
void loadTransformers()
Definition: MapCloudDisplay.cpp:220
ros::AsyncSpinner::start
void start()
rtabmap_rviz_plugins::MapCloudDisplay::setPropertiesHidden
void setPropertiesHidden(const QList< Property * > &props, bool hide)
Definition: MapCloudDisplay.cpp:403
rviz::Property::show
void show()
rviz::BoolProperty::setBool
bool setBool(bool value)
uFormat
std::string uFormat(const char *fmt,...)
uint32_t
::uint32_t uint32_t
rtabmap::Transform::getIdentity
static Transform getIdentity()
size
Index size
Compression.h
rtabmap::util3d::commonFiltering
RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin, float rangeMax, float voxelSize, int normalK, float normalRadius, bool forceGroundNormalsUp)
time.h
rtabmap_rviz_plugins
Definition: InfoDisplay.h:37
rviz::BoolProperty
rviz::FloatProperty::setMax
void setMax(float max)
rtabmap_rviz_plugins::MapCloudDisplay::new_xyz_transformer_
bool new_xyz_transformer_
Definition: MapCloudDisplay.h:200
rtabmap_rviz_plugins::MapCloudDisplay::updateTransformers
void updateTransformers(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: MapCloudDisplay.cpp:411
int_property.h
frame_manager.h
rtabmap_rviz_plugins::MapCloudDisplay::cloud_max_depth_
rviz::FloatProperty * cloud_max_depth_
Definition: MapCloudDisplay.h:115
rtabmap_rviz_plugins::MapCloudDisplay::downloadGraph
void downloadGraph()
Definition: MapCloudDisplay.cpp:628
end
end
rviz::V_PointCloudPoint
std::vector< PointCloud::Point > V_PointCloudPoint
rtabmap_rviz_plugins::MapCloudDisplay::cloud_min_depth_
rviz::FloatProperty * cloud_min_depth_
Definition: MapCloudDisplay.h:116
rtabmap_rviz_plugins::MapCloudDisplay::MapCloudDisplay
MapCloudDisplay()
Definition: MapCloudDisplay.cpp:89
validate_floats.h
enum_property.h
rtabmap_rviz_plugins::MapCloudDisplay::cloud_decimation_
rviz::IntProperty * cloud_decimation_
Definition: MapCloudDisplay.h:114
rtabmap_rviz_plugins::MapCloudDisplay::transformer_class_loader_
pluginlib::ClassLoader< rviz::PointCloudTransformer > * transformer_class_loader_
Definition: MapCloudDisplay.h:204
rtabmap_rviz_plugins::MapCloudDisplay::cloud_voxel_size_
rviz::FloatProperty * cloud_voxel_size_
Definition: MapCloudDisplay.h:117
rtabmap::LaserScan
rtabmap_rviz_plugins::MapCloudDisplay::node_filtering_radius_
rviz::FloatProperty * node_filtering_radius_
Definition: MapCloudDisplay.h:120
f
Vector3 f(-6, 1, 0.5)
rtabmap_rviz_plugins::MapCloudDisplay::cloud_filter_floor_height_
rviz::FloatProperty * cloud_filter_floor_height_
Definition: MapCloudDisplay.h:118
rviz::validateFloats
bool validateFloats(const boost::array< T, N > &arr)
rviz::PointCloud::RM_POINTS
RM_POINTS
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rviz::PointCloud::RM_SPHERES
RM_SPHERES
rviz::FloatProperty::setMin
void setMin(float min)
rtabmap_rviz_plugins::MapCloudDisplay::fillTransformerOptions
void fillTransformerOptions(rviz::EnumProperty *prop, uint32_t mask)
Definition: MapCloudDisplay.cpp:870
rviz::DisplayContext::getSceneManager
virtual Ogre::SceneManager * getSceneManager() const=0
point_cloud.h
float_property.h
rviz::Display
rviz::EnumProperty
rviz::PointCloud
rtabmap_rviz_plugins::MapCloudDisplay::download_graph_
rviz::BoolProperty * download_graph_
Definition: MapCloudDisplay.h:124
rtabmap_rviz_plugins::MapCloudDisplay::downloadMap
void downloadMap()
Definition: MapCloudDisplay.cpp:609
rviz::FloatProperty
rviz::Property::hide
void hide()
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
mode
const DiscreteKey mode
rtabmap::util3d::cloudRGBFromSensorData
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
rtabmap_rviz_plugins::MapCloudDisplay::alpha_property_
rviz::FloatProperty * alpha_property_
Definition: MapCloudDisplay.h:109
rviz::PointCloud::RM_SQUARES
RM_SQUARES
rtabmap_rviz_plugins::MapCloudDisplay::cbqueue_
ros::CallbackQueue cbqueue_
Definition: MapCloudDisplay.h:170
bool_property.h
rtabmap_rviz_plugins::MapCloudDisplay::transformCloud
bool transformCloud(const CloudInfoPtr &cloud, bool fully_update_transformers)
Transforms the cloud into the correct frame, and sets up our renderable cloud.
Definition: MapCloudDisplay.cpp:941
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rtabmap_rviz_plugins::MapCloudDisplay::current_map_updated_
bool current_map_updated_
Definition: MapCloudDisplay.h:183
rviz::FloatProperty::getFloat
virtual float getFloat() const
rviz::EnumProperty::addOption
virtual void addOption(const QString &option, int value=0)
rviz::PointCloud::Point::color
Ogre::ColourValue color
rtabmap::util3d::voxelize
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT voxelize(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
rtabmap_rviz_plugins::MapCloudDisplay::setColorTransformerOptions
void setColorTransformerOptions(EnumProperty *prop)
Definition: MapCloudDisplay.cpp:865
rtabmap_rviz_plugins::MapCloudDisplay::color_transformer_property_
rviz::EnumProperty * color_transformer_property_
Definition: MapCloudDisplay.h:111
rtabmap_rviz_plugins::MapCloudDisplay::getXYZTransformer
rviz::PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: MapCloudDisplay.cpp:895
rtabmap_rviz_plugins::MapCloudDisplay::setXyzTransformerOptions
void setXyzTransformerOptions(EnumProperty *prop)
Definition: MapCloudDisplay.cpp:860
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
rtabmap_rviz_plugins::MapCloudDisplay::download_map_
rviz::BoolProperty * download_map_
Definition: MapCloudDisplay.h:123
rviz::Property::connect
std::enable_if<!QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type connect(const QObject *context, Func &&slot, Qt::ConnectionType type=Qt::AutoConnection)
rtabmap_rviz_plugins::MapCloudDisplay::updateBillboardSize
void updateBillboardSize()
Definition: MapCloudDisplay.cpp:518
arg
rviz::StringProperty
rviz::StringProperty::getStdString
std::string getStdString()
rtabmap_rviz_plugins::MapCloudDisplay::getColorTransformer
rviz::PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: MapCloudDisplay.cpp:911
rviz::StatusProperty::Ok
Ok
rviz::IntProperty::setMax
void setMax(int max)
rtabmap_rviz_plugins::MapCloudDisplay::transformers_mutex_
boost::recursive_mutex transformers_mutex_
Definition: MapCloudDisplay.h:198
rtabmap_rviz_plugins::MapCloudDisplay::CloudInfo
Definition: MapCloudDisplay.h:80
rtabmap_rviz_plugins::MapCloudDisplay::update
virtual void update(float wall_dt, float ros_dt)
Definition: MapCloudDisplay.cpp:652
rtabmap_rviz_plugins::MapCloudDisplay::nodeDataReceived_
std::set< int > nodeDataReceived_
Definition: MapCloudDisplay.h:178
MapCloudDisplay.h
info
else if n * info
rviz::PointCloudTransformer::Support_XYZ
Support_XYZ
rtabmap_rviz_plugins::MapCloudDisplay::new_clouds_mutex_
boost::mutex new_clouds_mutex_
Definition: MapCloudDisplay.h:176
rtabmap_rviz_plugins::MapCloudDisplay::needs_retransform_
bool needs_retransform_
Definition: MapCloudDisplay.h:202
rviz::PointCloudTransformerPtr
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
error
void error(const char *str)
p
Point3_ p(2)
rviz::FrameManager::frameHasProblems
bool frameHasProblems(const std::string &frame, ros::Time time, std::string &error)
rtabmap_rviz_plugins::MapCloudDisplay::~MapCloudDisplay
virtual ~MapCloudDisplay()
Definition: MapCloudDisplay.cpp:210
pluginlib::ClassLoader< rviz::PointCloudTransformer >
rtabmap::util3d::laserScanToPointCloudI
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const=0
rtabmap_rviz_plugins::MapCloudDisplay::updateCloudParameters
void updateCloudParameters()
Definition: MapCloudDisplay.cpp:537
rtabmap_rviz_plugins::MapCloudDisplay::processMessage
virtual void processMessage(const rtabmap_msgs::MapDataConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
Definition: MapCloudDisplay.cpp:269
rtabmap::util3d::transformPointCloud
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT transformPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform)
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
rviz::EnumProperty::addOptionStd
void addOptionStd(const std::string &option, int value=0)
util3d_filtering.h
rtabmap_rviz_plugins::MapCloudDisplay::updateXyzTransformer
void updateXyzTransformer()
Definition: MapCloudDisplay.cpp:838
rtabmap_rviz_plugins::MapCloudDisplay::point_world_size_property_
rviz::FloatProperty * point_world_size_property_
Definition: MapCloudDisplay.h:107
ros::AsyncSpinner::stop
void stop()
transform_listener.h
rviz::MessageFilterDisplay::onInitialize
void onInitialize() override
rtabmap_rviz_plugins::MapCloudDisplay::point_pixel_size_property_
rviz::FloatProperty * point_pixel_size_property_
Definition: MapCloudDisplay.h:108
rtabmap::Transform
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
rviz::PointCloudTransformer::Support_Color
Support_Color
rviz::PointCloud::Point::position
Ogre::Vector3 position
rviz::Display::setStatusStd
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
rviz::Display::context_
DisplayContext * context_
rtabmap_rviz_plugins::MapCloudDisplay::download_namespace
rviz::StringProperty * download_namespace
Definition: MapCloudDisplay.h:122
rtabmap_rviz_plugins::MapCloudDisplay::lastCloudAdded_
int lastCloudAdded_
Definition: MapCloudDisplay.h:185
rtabmap_rviz_plugins::MapCloudDisplay::node_filtering_angle_
rviz::FloatProperty * node_filtering_angle_
Definition: MapCloudDisplay.h:121
trans
Matrix trans(const Matrix &A)
rtabmap_rviz_plugins::MapCloudDisplay::style_property_
rviz::EnumProperty * style_property_
Definition: MapCloudDisplay.h:112
iter
iterator iter(handle obj)
S_string
std::set< std::string > S_string
pluginlib::ClassLoader::getName
virtual std::string getName(const std::string &lookup_name)
rtabmap_rviz_plugins::MapCloudDisplay::current_map_
std::map< int, rtabmap::Transform > current_map_
Definition: MapCloudDisplay.h:181
id
id
rtabmap_rviz_plugins::MapCloudDisplay::updateColorTransformer
void updateColorTransformer()
Definition: MapCloudDisplay.cpp:849
rtabmap_rviz_plugins::MapCloudDisplay::processMapData
void processMapData(const rtabmap_msgs::MapData &map)
Definition: MapCloudDisplay.cpp:276
ROS_ERROR
#define ROS_ERROR(...)
rtabmap_rviz_plugins::MapCloudDisplay::new_cloud_infos_
std::map< int, CloudInfoPtr > new_cloud_infos_
Definition: MapCloudDisplay.h:175
rviz::PointCloud::RM_BOXES
RM_BOXES
rtabmap_rviz_plugins::MapCloudDisplay::republishNodeDataPub_
ros::Publisher republishNodeDataPub_
Definition: MapCloudDisplay.h:171
pluginlib::ClassLoader::createUnmanagedInstance
T * createUnmanagedInstance(const std::string &lookup_name)
class_list_macros.hpp
uSleep
void uSleep(unsigned int ms)
rtabmap_rviz_plugins::MapCloudDisplay::xyz_transformer_property_
rviz::EnumProperty * xyz_transformer_property_
Definition: MapCloudDisplay.h:110
rviz::IntProperty::getInt
virtual int getInt() const
rviz::EnumProperty::setStringStd
void setStringStd(const std::string &str)
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
rtabmap_rviz_plugins::MapCloudDisplay::CloudInfo::CloudInfo
CloudInfo()
Definition: MapCloudDisplay.cpp:68
rtabmap_rviz_plugins::MapCloudDisplay
Displays point clouds from rtabmap::MapData.
Definition: MapCloudDisplay.h:76
rtabmap_rviz_plugins::MapCloudDisplay::spinner_
ros::AsyncSpinner spinner_
Definition: MapCloudDisplay.h:169
rtabmap_rviz_plugins::MapCloudDisplay::new_color_transformer_
bool new_color_transformer_
Definition: MapCloudDisplay.h:201
rtabmap_rviz_plugins::MapCloudDisplay::transformers_
M_TransformerInfo transformers_
Definition: MapCloudDisplay.h:199
rtabmap_rviz_plugins::MapCloudDisplay::updateAlpha
void updateAlpha()
Definition: MapCloudDisplay.cpp:490
NULL
#define NULL
false
#define false
rtabmap_rviz_plugins::MapCloudDisplay::onInitialize
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
Definition: MapCloudDisplay.cpp:255
rtabmap_rviz_plugins::MapCloudDisplay::reset
virtual void reset()
Definition: MapCloudDisplay.cpp:821
vector_property.h
rtabmap_rviz_plugins::MapCloudDisplay::causeRetransform
void causeRetransform()
Definition: MapCloudDisplay.cpp:647
rtabmap_rviz_plugins::MapCloudDisplay::downloadNamespaceChanged
void downloadNamespaceChanged()
Definition: MapCloudDisplay.cpp:602
rtabmap_rviz_plugins::MapCloudDisplay::CloudInfo::clear
void clear()
Definition: MapCloudDisplay.cpp:80
rtabmap::graph::radiusPosesFiltering
std::map< int, Transform > RTABMAP_CORE_EXPORT radiusPosesFiltering(const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)
rtabmap_rviz_plugins::MapCloudDisplay::cloud_from_scan_
rviz::BoolProperty * cloud_from_scan_
Definition: MapCloudDisplay.h:113
MsgConversion.h
rtabmap
util3d_transforms.h
rtabmap_rviz_plugins::MapCloudDisplay::cloud_infos_
std::map< int, CloudInfoPtr > cloud_infos_
Definition: MapCloudDisplay.h:173
Graph.h
i
int i
rtabmap_rviz_plugins::MapCloudDisplay::CloudInfo::~CloudInfo
~CloudInfo()
Definition: MapCloudDisplay.cpp:75
Transform.h
rviz::Display::update_nh_
ros::NodeHandle update_nh_
rtabmap_rviz_plugins::MapCloudDisplay::retransform
void retransform()
Definition: MapCloudDisplay.cpp:928
util3d.h
rtabmap::Signature
rviz::PointCloud::RenderMode
RenderMode
rviz::IntProperty
display_context.h
msg
msg
rviz::PointCloud::RM_FLAT_SQUARES
RM_FLAT_SQUARES
pcl_conversions.h
pluginlib::ClassLoader::getDeclaredClasses
std::vector< std::string > getDeclaredClasses()


rtabmap_rviz_plugins
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:37:14