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 
28 #include <QApplication>
29 #include <QMessageBox>
30 #include <QTimer>
31 
32 #include <OgreSceneNode.h>
33 #include <OgreSceneManager.h>
34 
35 #include <ros/time.h>
36 
37 #include <tf/transform_listener.h>
38 
39 #include <rviz/display_context.h>
40 #include <rviz/frame_manager.h>
42 #include <rviz/validate_floats.h>
48 
50 
51 #include "MapCloudDisplay.h"
52 #include <rtabmap/core/Transform.h>
55 #include <rtabmap/core/util3d.h>
57 #include <rtabmap/core/Graph.h>
59 #include <rtabmap_ros/GetMap.h>
60 
61 
62 namespace rtabmap_ros
63 {
64 
65 
67  manager_(0),
68  pose_(rtabmap::Transform::getIdentity()),
69  id_(0),
70  scene_node_(0)
71 {}
72 
74 {
75  clear();
76 }
77 
79 {
80  if ( scene_node_ )
81  {
82  manager_->destroySceneNode( scene_node_ );
83  scene_node_=0;
84  }
85 }
86 
88  : spinner_(1, &cbqueue_),
93 {
94  //QIcon icon;
95  //this->setIcon(icon);
96 
97  style_property_ = new rviz::EnumProperty( "Style", "Flat Squares",
98  "Rendering mode to use, in order of computational complexity.",
99  this, SLOT( updateStyle() ), this );
105 
106  point_world_size_property_ = new rviz::FloatProperty( "Size (m)", 0.01,
107  "Point size in meters.",
108  this, SLOT( updateBillboardSize() ), this );
110 
111  point_pixel_size_property_ = new rviz::FloatProperty( "Size (Pixels)", 3,
112  "Point size in pixels.",
113  this, SLOT( updateBillboardSize() ), this );
115 
116  alpha_property_ = new rviz::FloatProperty( "Alpha", 1.0,
117  "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
118  this, SLOT( updateAlpha() ), this );
119  alpha_property_->setMin( 0 );
120  alpha_property_->setMax( 1 );
121 
122  xyz_transformer_property_ = new rviz::EnumProperty( "Position Transformer", "",
123  "Set the transformer to use to set the position of the points.",
124  this, SLOT( updateXyzTransformer() ), this );
125  connect( xyz_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
126  this, SLOT( setXyzTransformerOptions( EnumProperty* )));
127 
128  color_transformer_property_ = new rviz::EnumProperty( "Color Transformer", "",
129  "Set the transformer to use to set the color of the points.",
130  this, SLOT( updateColorTransformer() ), this );
131  connect( color_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
132  this, SLOT( setColorTransformerOptions( EnumProperty* )));
133 
134  cloud_decimation_ = new rviz::IntProperty( "Cloud decimation", 4,
135  "Decimation of the input RGB and depth images before creating the cloud.",
136  this, SLOT( updateCloudParameters() ), this );
138  cloud_decimation_->setMax( 16 );
139 
140  cloud_max_depth_ = new rviz::FloatProperty( "Cloud max depth (m)", 4.0f,
141  "Maximum depth of the generated clouds.",
142  this, SLOT( updateCloudParameters() ), this );
143  cloud_max_depth_->setMin( 0.0f );
144  cloud_max_depth_->setMax( 999.0f );
145 
146  cloud_min_depth_ = new rviz::FloatProperty( "Cloud min depth (m)", 0.0f,
147  "Minimum depth of the generated clouds.",
148  this, SLOT( updateCloudParameters() ), this );
149  cloud_min_depth_->setMin( 0.0f );
150  cloud_min_depth_->setMax( 999.0f );
151 
152  cloud_voxel_size_ = new rviz::FloatProperty( "Cloud voxel size (m)", 0.01f,
153  "Voxel size of the generated clouds.",
154  this, SLOT( updateCloudParameters() ), this );
155  cloud_voxel_size_->setMin( 0.0f );
156  cloud_voxel_size_->setMax( 1.0f );
157 
158  cloud_filter_floor_height_ = new rviz::FloatProperty( "Filter floor (m)", 0.0f,
159  "Filter the floor up to maximum height set here "
160  "(only appropriate for 2D mapping).",
161  this, SLOT( updateCloudParameters() ), this );
164 
165  cloud_filter_ceiling_height_ = new rviz::FloatProperty( "Filter ceiling (m)", 0.0f,
166  "Filter the ceiling at the specified height set here "
167  "(only appropriate for 2D mapping).",
168  this, SLOT( updateCloudParameters() ), this );
171 
172  node_filtering_radius_ = new rviz::FloatProperty( "Node filtering radius (m)", 0.0f,
173  "(Disabled=0) Only keep one node in the specified radius.",
174  this, SLOT( updateCloudParameters() ), this );
177 
178  node_filtering_angle_ = new rviz::FloatProperty( "Node filtering angle (degrees)", 30.0f,
179  "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
180  this, SLOT( updateCloudParameters() ), this );
182  node_filtering_angle_->setMax( 359.0f );
183 
184  download_map_ = new rviz::BoolProperty( "Download map", false,
185  "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
186  this, SLOT( downloadMap() ), this );
187 
188  download_graph_ = new rviz::BoolProperty( "Download graph", false,
189  "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
190  this, SLOT( downloadGraph() ), this );
191 
192  // PointCloudCommon sets up a callback queue with a thread for each
193  // instance. Use that for processing incoming messages.
195 }
196 
198 {
200  {
202  }
203 
204  spinner_.stop();
205 }
206 
208 {
209  std::vector<std::string> classes = transformer_class_loader_->getDeclaredClasses();
210  std::vector<std::string>::iterator ci;
211 
212  for( ci = classes.begin(); ci != classes.end(); ci++ )
213  {
214  const std::string& lookup_name = *ci;
215  std::string name = transformer_class_loader_->getName( lookup_name );
216 
217  if( transformers_.count( name ) > 0 )
218  {
219  ROS_ERROR( "Transformer type [%s] is already loaded.", name.c_str() );
220  continue;
221  }
222 
224  trans->init();
225  connect( trans.get(), SIGNAL( needRetransform() ), this, SLOT( causeRetransform() ));
226 
227  TransformerInfo info;
228  info.transformer = trans;
229  info.readable_name = name;
230  info.lookup_name = lookup_name;
231 
232  info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_XYZ, info.xyz_props );
233  setPropertiesHidden( info.xyz_props, true );
234 
235  info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_Color, info.color_props );
236  setPropertiesHidden( info.color_props, true );
237 
238  transformers_[ name ] = info;
239  }
240 }
241 
243 {
245 
246  transformer_class_loader_ = new pluginlib::ClassLoader<rviz::PointCloudTransformer>( "rviz", "rviz::PointCloudTransformer" );
248 
249  updateStyle();
251  updateAlpha();
252 
253  spinner_.start();
254 }
255 
256 void MapCloudDisplay::processMessage( const rtabmap_ros::MapDataConstPtr& msg )
257 {
258  processMapData(*msg);
259 
260  this->emitTimeSignal(msg->header.stamp);
261 }
262 
263 void MapCloudDisplay::processMapData(const rtabmap_ros::MapData& map)
264 {
265  std::map<int, rtabmap::Transform> poses;
266  for(unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
267  {
268  poses.insert(std::make_pair(map.graph.posesId[i], rtabmap_ros::transformFromPoseMsg(map.graph.poses[i])));
269  }
270 
271  // Add new clouds...
272  for(unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
273  {
274  int id = map.nodes[i].id;
275 
276  // Always refresh the cloud if there are data
278  if(!s.sensorData().imageCompressed().empty() &&
279  !s.sensorData().depthOrRightCompressed().empty() &&
281  {
282  cv::Mat image, depth;
283  s.sensorData().uncompressData(&image, &depth, 0);
284 
285 
286  if(!s.sensorData().imageRaw().empty() && !s.sensorData().depthOrRightRaw().empty())
287  {
288  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
289  pcl::IndicesPtr validIndices(new std::vector<int>);
291  s.sensorData(),
295  validIndices.get());
296 
298  {
299  cloud = rtabmap::util3d::voxelize(cloud, validIndices, cloud_voxel_size_->getFloat());
300  }
301 
302  if(cloud->size())
303  {
305  {
306  // convert in /odom frame
307  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose());
308  cloud = rtabmap::util3d::passThrough(cloud, "z",
311  // convert back in /base_link frame
313  }
314 
315  sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
316  pcl::toROSMsg(*cloud, *cloudMsg);
317  cloudMsg->header = map.header;
318 
319  CloudInfoPtr info(new CloudInfo);
320  info->message_ = cloudMsg;
321  info->pose_ = rtabmap::Transform::getIdentity();
322  info->id_ = id;
323 
324  if (transformCloud(info, true))
325  {
326  boost::mutex::scoped_lock lock(new_clouds_mutex_);
327  new_cloud_infos_.erase(id);
328  new_cloud_infos_.insert(std::make_pair(id, info));
329  }
330  }
331  }
332  }
333  }
334 
335  // Update graph
337  {
340  node_filtering_angle_->getFloat()*CV_PI/180.0);
341  }
342 
343  {
344  boost::mutex::scoped_lock lock(current_map_mutex_);
345  current_map_ = poses;
346  }
347 }
348 
349 void MapCloudDisplay::setPropertiesHidden( const QList<Property*>& props, bool hide )
350 {
351  for( int i = 0; i < props.size(); i++ )
352  {
353  props[ i ]->setHidden( hide );
354  }
355 }
356 
357 void MapCloudDisplay::updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud )
358 {
359  std::string xyz_name = xyz_transformer_property_->getStdString();
360  std::string color_name = color_transformer_property_->getStdString();
361 
364 
365  // Get the channels that we could potentially render
366  typedef std::set<std::pair<uint8_t, std::string> > S_string;
367  S_string valid_xyz, valid_color;
368  bool cur_xyz_valid = false;
369  bool cur_color_valid = false;
370  bool has_rgb_transformer = false;
371  M_TransformerInfo::iterator trans_it = transformers_.begin();
372  M_TransformerInfo::iterator trans_end = transformers_.end();
373  for(;trans_it != trans_end; ++trans_it)
374  {
375  const std::string& name = trans_it->first;
376  const rviz::PointCloudTransformerPtr& trans = trans_it->second.transformer;
377  uint32_t mask = trans->supports(cloud);
379  {
380  valid_xyz.insert(std::make_pair(trans->score(cloud), name));
381  if (name == xyz_name)
382  {
383  cur_xyz_valid = true;
384  }
386  }
387 
389  {
390  valid_color.insert(std::make_pair(trans->score(cloud), name));
391  if (name == color_name)
392  {
393  cur_color_valid = true;
394  }
395  if (name == "RGB8")
396  {
397  has_rgb_transformer = true;
398  }
400  }
401  }
402 
403  if( !cur_xyz_valid )
404  {
405  if( !valid_xyz.empty() )
406  {
407  xyz_transformer_property_->setStringStd( valid_xyz.rbegin()->second );
408  }
409  }
410 
411  if( !cur_color_valid )
412  {
413  if( !valid_color.empty() )
414  {
415  if (has_rgb_transformer)
416  {
418  }
419  else
420  {
421  color_transformer_property_->setStringStd( valid_color.rbegin()->second );
422  }
423  }
424  }
425 }
426 
428 {
429  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
430  {
431  it->second->cloud_->setAlpha( alpha_property_->getFloat() );
432  }
433 }
434 
436 {
438  if( mode == rviz::PointCloud::RM_POINTS )
439  {
442  }
443  else
444  {
447  }
448  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
449  {
450  it->second->cloud_->setRenderMode( mode );
451  }
453 }
454 
456 {
458  float size;
459  if( mode == rviz::PointCloud::RM_POINTS )
460  {
462  }
463  else
464  {
466  }
467  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
468  {
469  it->second->cloud_->setDimensions( size, size, size );
470  }
472 }
473 
475 {
476  // do nothing... only take effect on next generated clouds
477 }
478 
480 {
481  if(download_map_->getBool())
482  {
483  rtabmap_ros::GetMap getMapSrv;
484  getMapSrv.request.global = true;
485  getMapSrv.request.optimized = true;
486  getMapSrv.request.graphOnly = false;
487  ros::NodeHandle nh;
488  QMessageBox * messageBox = new QMessageBox(
489  QMessageBox::NoIcon,
490  tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map_data").c_str()),
491  tr("Downloading the map... please wait (rviz could become gray!)"),
492  QMessageBox::NoButton);
493  messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
494  messageBox->show();
495  QApplication::processEvents();
496  uSleep(100); // hack make sure the text in the QMessageBox is shown...
497  QApplication::processEvents();
498  if(!ros::service::call("rtabmap/get_map_data", getMapSrv))
499  {
500  ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
501  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
502  "to \"get_map_data\" in the launch "
503  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
504  nh.resolveName("rtabmap/get_map_data").c_str());
505  messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
506  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
507  "to \"get_map_data\" in the launch "
508  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
509  arg(nh.resolveName("rtabmap/get_map_data").c_str()));
510  }
511  else
512  {
513  messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)...")
514  .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
515  QApplication::processEvents();
516  this->reset();
517  processMapData(getMapSrv.response.data);
518  messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
519  .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
520 
521  QTimer::singleShot(1000, messageBox, SLOT(close()));
522  }
523  download_map_->blockSignals(true);
524  download_map_->setBool(false);
525  download_map_->blockSignals(false);
526  }
527  else
528  {
529  // just stay true if double-clicked on DownloadMap property, let the
530  // first process above finishes
531  download_map_->blockSignals(true);
532  download_map_->setBool(true);
533  download_map_->blockSignals(false);
534  }
535 }
536 
538 {
539  if(download_graph_->getBool())
540  {
541  rtabmap_ros::GetMap getMapSrv;
542  getMapSrv.request.global = true;
543  getMapSrv.request.optimized = true;
544  getMapSrv.request.graphOnly = true;
545  ros::NodeHandle nh;
546  QMessageBox * messageBox = new QMessageBox(
547  QMessageBox::NoIcon,
548  tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map_data").c_str()),
549  tr("Downloading the graph... please wait (rviz could become gray!)"),
550  QMessageBox::NoButton);
551  messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
552  messageBox->show();
553  QApplication::processEvents();
554  uSleep(100); // hack make sure the text in the QMessageBox is shown...
555  QApplication::processEvents();
556  if(!ros::service::call("rtabmap/get_map_data", getMapSrv))
557  {
558  ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
559  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
560  "to \"get_map_data\" in the launch "
561  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
562  nh.resolveName("rtabmap/get_map_data").c_str());
563  messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
564  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
565  "to \"get_map_data\" in the launch "
566  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
567  arg(nh.resolveName("rtabmap/get_map_data").c_str()));
568  }
569  else
570  {
571  messageBox->setText(tr("Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
572  QApplication::processEvents();
573  processMapData(getMapSrv.response.data);
574  messageBox->setText(tr("Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
575 
576  QTimer::singleShot(1000, messageBox, SLOT(close()));
577  }
578  download_graph_->blockSignals(true);
579  download_graph_->setBool(false);
580  download_graph_->blockSignals(false);
581  }
582  else
583  {
584  // just stay true if double-clicked on DownloadGraph property, let the
585  // first process above finishes
586  download_graph_->blockSignals(true);
587  download_graph_->setBool(true);
588  download_graph_->blockSignals(false);
589  }
590 }
591 
593 {
594  needs_retransform_ = true;
595 }
596 
597 void MapCloudDisplay::update( float wall_dt, float ros_dt )
598 {
600 
601  if (needs_retransform_)
602  {
603  retransform();
604  needs_retransform_ = false;
605  }
606 
607  {
608  boost::mutex::scoped_lock lock(new_clouds_mutex_);
609  if( !new_cloud_infos_.empty() )
610  {
611  float size;
612  if( mode == rviz::PointCloud::RM_POINTS ) {
614  } else {
616  }
617 
618  std::map<int, CloudInfoPtr>::iterator it = new_cloud_infos_.begin();
619  std::map<int, CloudInfoPtr>::iterator end = new_cloud_infos_.end();
620  for (; it != end; ++it)
621  {
622  CloudInfoPtr cloud_info = it->second;
623 
624  cloud_info->cloud_.reset( new rviz::PointCloud() );
625  cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
626  cloud_info->cloud_->setRenderMode( mode );
627  cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
628  cloud_info->cloud_->setDimensions( size, size, size );
629  cloud_info->cloud_->setAutoSize(false);
630 
631  cloud_info->manager_ = context_->getSceneManager();
632 
633  cloud_info->scene_node_ = scene_node_->createChildSceneNode();
634 
635  cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
636  cloud_info->scene_node_->setVisible(false);
637 
638  cloud_infos_.erase(it->first);
639  cloud_infos_.insert(*it);
640  }
641 
642  new_cloud_infos_.clear();
643  }
644  }
645 
646  {
647  boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ );
648 
649  if( lock.owns_lock() )
650  {
652  {
653  M_TransformerInfo::iterator it = transformers_.begin();
654  M_TransformerInfo::iterator end = transformers_.end();
655  for (; it != end; ++it)
656  {
657  const std::string& name = it->first;
658  TransformerInfo& info = it->second;
659 
662  }
663  }
664  }
665 
666  new_xyz_transformer_ = false;
667  new_color_transformer_ = false;
668  }
669 
670  int totalPoints = 0;
671  int totalNodesShown = 0;
672  {
673  // update poses
674  boost::mutex::scoped_lock lock(current_map_mutex_);
675  if(!current_map_.empty())
676  {
677  for (std::map<int, rtabmap::Transform>::iterator it=current_map_.begin(); it != current_map_.end(); ++it)
678  {
679  std::map<int, CloudInfoPtr>::iterator cloudInfoIt = cloud_infos_.find(it->first);
680  if(cloudInfoIt != cloud_infos_.end())
681  {
682  totalPoints += cloudInfoIt->second->transformed_points_.size();
683  cloudInfoIt->second->pose_ = it->second;
684  Ogre::Vector3 framePosition;
685  Ogre::Quaternion frameOrientation;
686  if (context_->getFrameManager()->getTransform(cloudInfoIt->second->message_->header, framePosition, frameOrientation))
687  {
688  // Multiply frame with pose
689  Ogre::Matrix4 frameTransform;
690  frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
691  const rtabmap::Transform & p = cloudInfoIt->second->pose_;
692  Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
693  p[4], p[5], p[6], p[7],
694  p[8], p[9], p[10], p[11],
695  0, 0, 0, 1);
696  frameTransform = frameTransform * pose;
697  Ogre::Vector3 posePosition = frameTransform.getTrans();
698  Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
699  poseOrientation.normalise();
700 
701  cloudInfoIt->second->scene_node_->setPosition(posePosition);
702  cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
703  cloudInfoIt->second->scene_node_->setVisible(true);
704  ++totalNodesShown;
705  }
706  else
707  {
708  ROS_ERROR("MapCloudDisplay: Could not update pose of node %d", it->first);
709  }
710 
711  }
712  }
713  //hide not used clouds
714  for(std::map<int, CloudInfoPtr>::iterator iter = cloud_infos_.begin(); iter!=cloud_infos_.end(); ++iter)
715  {
716  if(current_map_.find(iter->first) == current_map_.end())
717  {
718  iter->second->scene_node_->setVisible(false);
719  }
720  }
721  }
722  }
723 
724  this->setStatusStd(rviz::StatusProperty::Ok, "Points", tr("%1").arg(totalPoints).toStdString());
725  this->setStatusStd(rviz::StatusProperty::Ok, "Nodes", tr("%1 shown of %2").arg(totalNodesShown).arg(cloud_infos_.size()).toStdString());
726 }
727 
729 {
730  {
731  boost::mutex::scoped_lock lock(new_clouds_mutex_);
732  cloud_infos_.clear();
733  new_cloud_infos_.clear();
734  }
735  {
736  boost::mutex::scoped_lock lock(current_map_mutex_);
737  current_map_.clear();
738  }
739  MFDClass::reset();
740 }
741 
743 {
744  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
746  {
747  return;
748  }
749  new_xyz_transformer_ = true;
751 }
752 
754 {
755  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
757  {
758  return;
759  }
760  new_color_transformer_ = true;
762 }
763 
765 {
767 }
768 
770 {
772 }
773 
775 {
776  prop->clearOptions();
777 
778  if (cloud_infos_.empty())
779  {
780  return;
781  }
782 
783  boost::recursive_mutex::scoped_lock tlock(transformers_mutex_);
784 
785  const sensor_msgs::PointCloud2ConstPtr& msg = cloud_infos_.begin()->second->message_;
786 
787  M_TransformerInfo::iterator it = transformers_.begin();
788  M_TransformerInfo::iterator end = transformers_.end();
789  for (; it != end; ++it)
790  {
791  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
792  if ((trans->supports(msg) & mask) == mask)
793  {
794  prop->addOption( QString::fromStdString( it->first ));
795  }
796  }
797 }
798 
799 rviz::PointCloudTransformerPtr MapCloudDisplay::getXYZTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
800 {
801  boost::recursive_mutex::scoped_lock lock( transformers_mutex_);
802  M_TransformerInfo::iterator it = transformers_.find( xyz_transformer_property_->getStdString() );
803  if( it != transformers_.end() )
804  {
805  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
806  if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_XYZ )
807  {
808  return trans;
809  }
810  }
811 
813 }
814 
815 rviz::PointCloudTransformerPtr MapCloudDisplay::getColorTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
816 {
817  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
818  M_TransformerInfo::iterator it = transformers_.find( color_transformer_property_->getStdString() );
819  if( it != transformers_.end() )
820  {
821  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
822  if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_Color )
823  {
824  return trans;
825  }
826  }
827 
829 }
830 
831 
833 {
834  boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
835 
836  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
837  {
838  const CloudInfoPtr& cloud_info = it->second;
839  transformCloud(cloud_info, false);
840  cloud_info->cloud_->clear();
841  cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
842  }
843 }
844 
845 bool MapCloudDisplay::transformCloud(const CloudInfoPtr& cloud_info, bool update_transformers)
846 {
847  rviz::V_PointCloudPoint& cloud_points = cloud_info->transformed_points_;
848  cloud_points.clear();
849 
850  size_t size = cloud_info->message_->width * cloud_info->message_->height;
851  rviz::PointCloud::Point default_pt;
852  default_pt.color = Ogre::ColourValue(1, 1, 1);
853  default_pt.position = Ogre::Vector3::ZERO;
854  cloud_points.resize(size, default_pt);
855 
856  {
857  boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
858  if( update_transformers )
859  {
860  updateTransformers( cloud_info->message_ );
861  }
862  rviz::PointCloudTransformerPtr xyz_trans = getXYZTransformer(cloud_info->message_);
863  rviz::PointCloudTransformerPtr color_trans = getColorTransformer(cloud_info->message_);
864 
865  if (!xyz_trans)
866  {
867  std::stringstream ss;
868  ss << "No position transformer available for cloud";
869  this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
870  return false;
871  }
872 
873  if (!color_trans)
874  {
875  std::stringstream ss;
876  ss << "No color transformer available for cloud";
877  this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
878  return false;
879  }
880 
881  xyz_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_XYZ, Ogre::Matrix4::IDENTITY, cloud_points);
882  color_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_Color, Ogre::Matrix4::IDENTITY, cloud_points);
883  }
884 
885  for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
886  {
887  if (!rviz::validateFloats(cloud_point->position))
888  {
889  cloud_point->position.x = 999999.0f;
890  cloud_point->position.y = 999999.0f;
891  cloud_point->position.z = 999999.0f;
892  }
893  }
894 
895  return true;
896 }
897 
898 } // namespace rtabmap
899 
void updateTransformers(const sensor_msgs::PointCloud2ConstPtr &cloud)
GLM_FUNC_DECL genIType mask(genIType const &count)
#define NULL
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
void setMin(float min)
void setStringStd(const std::string &str)
std::set< std::string > S_string
void setMax(float max)
rviz::EnumProperty * style_property_
std::map< int, Transform > RTABMAP_EXP radiusPosesFiltering(const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)
rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData &msg)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pluginlib::ClassLoader< rviz::PointCloudTransformer > * transformer_class_loader_
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
Displays point clouds from rtabmap::MapData.
f
rviz::FloatProperty * cloud_voxel_size_
DisplayContext * context_
std::string resolveName(const std::string &name, bool remap=true) const
static Transform getIdentity()
rviz::FloatProperty * cloud_max_depth_
bool call(const std::string &service_name, MReq &req, MRes &res)
void emitTimeSignal(ros::Time time)
virtual int getInt() const
XmlRpcServer s
ros::NodeHandle update_nh_
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
virtual float getFloat() const
virtual void clearOptions()
rviz::IntProperty * cloud_decimation_
rviz::EnumProperty * xyz_transformer_property_
rviz::PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
T * createUnmanagedInstance(const std::string &lookup_name)
void setMin(int min)
rviz::FloatProperty * cloud_filter_ceiling_height_
rviz::FloatProperty * alpha_property_
std::map< int, CloudInfoPtr > cloud_infos_
rviz::FloatProperty * point_pixel_size_property_
M_TransformerInfo transformers_
rviz::FloatProperty * node_filtering_radius_
const cv::Mat & imageRaw() const
std::map< int, rtabmap::Transform > current_map_
rviz::BoolProperty * download_map_
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
rviz::PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
rviz::PointCloudTransformerPtr transformer
Ogre::SceneNode * scene_node_
std::string getStdString()
void setMax(int max)
rviz::FloatProperty * node_filtering_angle_
virtual bool getBool() const
bool isValidForProjection() const
rviz::FloatProperty * point_world_size_property_
bool transformCloud(const CloudInfoPtr &cloud, bool fully_update_transformers)
Transforms the cloud into the correct frame, and sets up our renderable cloud.
const cv::Mat & depthOrRightCompressed() const
virtual void addOption(const QString &option, int value=0)
boost::recursive_mutex transformers_mutex_
void fillTransformerOptions(rviz::EnumProperty *prop, uint32_t mask)
void setCallbackQueue(CallbackQueueInterface *queue)
rviz::FloatProperty * cloud_min_depth_
std::vector< std::string > getDeclaredClasses()
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP 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 >())
std::map< int, CloudInfoPtr > new_cloud_infos_
std::vector< PointCloud::Point > V_PointCloudPoint
Ogre::Vector3 position
virtual FrameManager * getFrameManager() const =0
const cv::Mat & depthOrRightRaw() const
bool validateFloats(const visualization_msgs::InteractiveMarker &msg)
void addOptionStd(const std::string &option, int value=0)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg)
virtual std::string getName(const std::string &lookup_name)
void processMapData(const rtabmap_ros::MapData &map)
virtual void update(float wall_dt, float ros_dt)
detail::uint32 uint32_t
#define false
void uSleep(unsigned int ms)
virtual Ogre::SceneManager * getSceneManager() const =0
const std::vector< CameraModel > & cameraModels() const
const Transform & getPose() const
virtual void queueRender()=0
rviz::FloatProperty * cloud_filter_floor_height_
Ogre::ColourValue color
SensorData & sensorData()
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
const StereoCameraModel & stereoCameraModel() const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
rviz::EnumProperty * color_transformer_property_
const cv::Mat & imageCompressed() const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
Transform inverse() const
virtual int getOptionInt()
bool setBool(bool value)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
#define ROS_ERROR(...)
rviz::BoolProperty * download_graph_
void setColorTransformerOptions(EnumProperty *prop)
virtual void processMessage(const rtabmap_ros::MapDataConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
void setPropertiesHidden(const QList< Property * > &props, bool hide)
void setXyzTransformerOptions(EnumProperty *prop)


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