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_),
89  lastCloudAdded_(-1),
94 {
95  //QIcon icon;
96  //this->setIcon(icon);
97 
98  style_property_ = new rviz::EnumProperty( "Style", "Flat Squares",
99  "Rendering mode to use, in order of computational complexity.",
100  this, SLOT( updateStyle() ), this );
106 
107  point_world_size_property_ = new rviz::FloatProperty( "Size (m)", 0.01,
108  "Point size in meters.",
109  this, SLOT( updateBillboardSize() ), this );
111 
112  point_pixel_size_property_ = new rviz::FloatProperty( "Size (Pixels)", 3,
113  "Point size in pixels.",
114  this, SLOT( updateBillboardSize() ), this );
116 
117  alpha_property_ = new rviz::FloatProperty( "Alpha", 1.0,
118  "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
119  this, SLOT( updateAlpha() ), this );
120  alpha_property_->setMin( 0 );
121  alpha_property_->setMax( 1 );
122 
123  xyz_transformer_property_ = new rviz::EnumProperty( "Position Transformer", "",
124  "Set the transformer to use to set the position of the points.",
125  this, SLOT( updateXyzTransformer() ), this );
126  connect( xyz_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
127  this, SLOT( setXyzTransformerOptions( EnumProperty* )));
128 
129  color_transformer_property_ = new rviz::EnumProperty( "Color Transformer", "",
130  "Set the transformer to use to set the color of the points.",
131  this, SLOT( updateColorTransformer() ), this );
132  connect( color_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
133  this, SLOT( setColorTransformerOptions( EnumProperty* )));
134 
135  cloud_from_scan_ = new rviz::BoolProperty( "Cloud from scan", false,
136  "Create the cloud from laser scans instead of the RGB-D/Stereo images.",
137  this, SLOT( updateCloudParameters() ), this );
138 
139  cloud_decimation_ = new rviz::IntProperty( "Cloud decimation", 4,
140  "Decimation of the input RGB and depth images before creating the cloud.",
141  this, SLOT( updateCloudParameters() ), this );
143  cloud_decimation_->setMax( 16 );
144 
145  cloud_max_depth_ = new rviz::FloatProperty( "Cloud max depth (m)", 4.0f,
146  "Maximum depth of the generated clouds.",
147  this, SLOT( updateCloudParameters() ), this );
148  cloud_max_depth_->setMin( 0.0f );
149  cloud_max_depth_->setMax( 999.0f );
150 
151  cloud_min_depth_ = new rviz::FloatProperty( "Cloud min depth (m)", 0.0f,
152  "Minimum depth of the generated clouds.",
153  this, SLOT( updateCloudParameters() ), this );
154  cloud_min_depth_->setMin( 0.0f );
155  cloud_min_depth_->setMax( 999.0f );
156 
157  cloud_voxel_size_ = new rviz::FloatProperty( "Cloud voxel size (m)", 0.01f,
158  "Voxel size of the generated clouds.",
159  this, SLOT( updateCloudParameters() ), this );
160  cloud_voxel_size_->setMin( 0.0f );
161  cloud_voxel_size_->setMax( 1.0f );
162 
163  cloud_filter_floor_height_ = new rviz::FloatProperty( "Filter floor (m)", 0.0f,
164  "Filter the floor up to maximum height set here "
165  "(only appropriate for 2D mapping).",
166  this, SLOT( updateCloudParameters() ), this );
169 
170  cloud_filter_ceiling_height_ = new rviz::FloatProperty( "Filter ceiling (m)", 0.0f,
171  "Filter the ceiling at the specified height set here "
172  "(only appropriate for 2D mapping).",
173  this, SLOT( updateCloudParameters() ), this );
176 
177  node_filtering_radius_ = new rviz::FloatProperty( "Node filtering radius (m)", 0.0f,
178  "(Disabled=0) Only keep one node in the specified radius.",
179  this, SLOT( updateCloudParameters() ), this );
182 
183  node_filtering_angle_ = new rviz::FloatProperty( "Node filtering angle (degrees)", 30.0f,
184  "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
185  this, SLOT( updateCloudParameters() ), this );
187  node_filtering_angle_->setMax( 359.0f );
188 
189  download_map_ = new rviz::BoolProperty( "Download map", false,
190  "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
191  this, SLOT( downloadMap() ), this );
192 
193  download_graph_ = new rviz::BoolProperty( "Download graph", false,
194  "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
195  this, SLOT( downloadGraph() ), this );
196 
197  // PointCloudCommon sets up a callback queue with a thread for each
198  // instance. Use that for processing incoming messages.
200 }
201 
203 {
205  {
207  }
208 
209  spinner_.stop();
210 }
211 
213 {
214  std::vector<std::string> classes = transformer_class_loader_->getDeclaredClasses();
215  std::vector<std::string>::iterator ci;
216 
217  for( ci = classes.begin(); ci != classes.end(); ci++ )
218  {
219  const std::string& lookup_name = *ci;
220  std::string name = transformer_class_loader_->getName( lookup_name );
221 
222  if( transformers_.count( name ) > 0 )
223  {
224  ROS_ERROR( "Transformer type [%s] is already loaded.", name.c_str() );
225  continue;
226  }
227 
229  trans->init();
230  connect( trans.get(), SIGNAL( needRetransform() ), this, SLOT( causeRetransform() ));
231 
232  TransformerInfo info;
233  info.transformer = trans;
234  info.readable_name = name;
235  info.lookup_name = lookup_name;
236 
237  info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_XYZ, info.xyz_props );
238  setPropertiesHidden( info.xyz_props, true );
239 
240  info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_Color, info.color_props );
241  setPropertiesHidden( info.color_props, true );
242 
243  transformers_[ name ] = info;
244  }
245 }
246 
248 {
250 
251  transformer_class_loader_ = new pluginlib::ClassLoader<rviz::PointCloudTransformer>( "rviz", "rviz::PointCloudTransformer" );
253 
254  updateStyle();
256  updateAlpha();
257 
258  spinner_.start();
259 }
260 
261 void MapCloudDisplay::processMessage( const rtabmap_ros::MapDataConstPtr& msg )
262 {
263  processMapData(*msg);
264 
265  this->emitTimeSignal(msg->header.stamp);
266 }
267 
268 void MapCloudDisplay::processMapData(const rtabmap_ros::MapData& map)
269 {
270  std::map<int, rtabmap::Transform> poses;
271  for(unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
272  {
273  poses.insert(std::make_pair(map.graph.posesId[i], rtabmap_ros::transformFromPoseMsg(map.graph.poses[i])));
274  }
275 
276  // Add new clouds...
277  bool fromDepth = !cloud_from_scan_->getBool();
278  for(unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
279  {
280  int id = map.nodes[i].id;
281 
282  // Always refresh the cloud if there are data
284  if((fromDepth &&
285  !s.sensorData().imageCompressed().empty() &&
286  !s.sensorData().depthOrRightCompressed().empty() &&
288  (!fromDepth && !s.sensorData().laserScanCompressed().isEmpty()))
289  {
290  cv::Mat image, depth;
291  rtabmap::LaserScan scan;
292 
293  s.sensorData().uncompressData(fromDepth?&image:0, fromDepth?&depth:0, !fromDepth?&scan:0);
294 
295  sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
296  if(fromDepth && !s.sensorData().imageRaw().empty() && !s.sensorData().depthOrRightRaw().empty())
297  {
298  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
299  pcl::IndicesPtr validIndices(new std::vector<int>);
300 
302  s.sensorData(),
306  validIndices.get());
307 
308  if(!cloud->empty())
309  {
311  {
312  cloud = rtabmap::util3d::voxelize(cloud, validIndices, cloud_voxel_size_->getFloat());
313  }
314 
316  {
317  // convert in /odom frame
318  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose());
319  cloud = rtabmap::util3d::passThrough(cloud, "z",
322  // convert back in /base_link frame
324  }
325 
326  if(!cloud->empty())
327  {
328  pcl::toROSMsg(*cloud, *cloudMsg);
329  }
330  }
331  }
332  else if(!fromDepth && !scan.isEmpty())
333  {
335  scan,
336  1,
340  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud;
341  cloud = rtabmap::util3d::laserScanToPointCloudI(scan, scan.localTransform());
343  {
344  // convert in /odom frame
345  cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose());
346  cloud = rtabmap::util3d::passThrough(cloud, "z",
349  // convert back in /base_link frame
351  }
352 
353  if(!cloud->empty())
354  {
355  pcl::toROSMsg(*cloud, *cloudMsg);
356  }
357  }
358 
359  if(!cloudMsg->data.empty())
360  {
361  cloudMsg->header = map.header;
362  CloudInfoPtr info(new CloudInfo);
363  info->message_ = cloudMsg;
364  info->pose_ = rtabmap::Transform::getIdentity();
365  info->id_ = id;
366 
367  if (transformCloud(info, true))
368  {
369  boost::mutex::scoped_lock lock(new_clouds_mutex_);
370  new_cloud_infos_.erase(id);
371  new_cloud_infos_.insert(std::make_pair(id, info));
372  }
373  }
374  }
375  }
376 
377  // Update graph
379  {
382  node_filtering_angle_->getFloat()*CV_PI/180.0);
383  }
384 
385  {
386  boost::mutex::scoped_lock lock(current_map_mutex_);
387  current_map_ = poses;
388  }
389 }
390 
391 void MapCloudDisplay::setPropertiesHidden( const QList<Property*>& props, bool hide )
392 {
393  for( int i = 0; i < props.size(); i++ )
394  {
395  props[ i ]->setHidden( hide );
396  }
397 }
398 
399 void MapCloudDisplay::updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud )
400 {
401  std::string xyz_name = xyz_transformer_property_->getStdString();
402  std::string color_name = color_transformer_property_->getStdString();
403 
406 
407  // Get the channels that we could potentially render
408  typedef std::set<std::pair<uint8_t, std::string> > S_string;
409  S_string valid_xyz, valid_color;
410  bool cur_xyz_valid = false;
411  bool cur_color_valid = false;
412  bool has_rgb_transformer = false;
413  bool has_intensity_transformer = false;
414  M_TransformerInfo::iterator trans_it = transformers_.begin();
415  M_TransformerInfo::iterator trans_end = transformers_.end();
416  for(;trans_it != trans_end; ++trans_it)
417  {
418  const std::string& name = trans_it->first;
419  const rviz::PointCloudTransformerPtr& trans = trans_it->second.transformer;
420  uint32_t mask = trans->supports(cloud);
422  {
423  valid_xyz.insert(std::make_pair(trans->score(cloud), name));
424  if (name == xyz_name)
425  {
426  cur_xyz_valid = true;
427  }
429  }
430 
432  {
433  valid_color.insert(std::make_pair(trans->score(cloud), name));
434  if (name == color_name)
435  {
436  cur_color_valid = true;
437  }
438  if (name == "RGB8")
439  {
440  has_rgb_transformer = true;
441  }
442  else if (name == "Intensity")
443  {
444  has_intensity_transformer = true;
445  }
447  }
448  }
449 
450  if( !cur_xyz_valid )
451  {
452  if( !valid_xyz.empty() )
453  {
454  xyz_transformer_property_->setStringStd( valid_xyz.rbegin()->second );
455  }
456  }
457 
458  if( !cur_color_valid )
459  {
460  if( !valid_color.empty() )
461  {
462  if (has_rgb_transformer)
463  {
465  }
466  else if (has_intensity_transformer)
467  {
469  }
470  else
471  {
472  color_transformer_property_->setStringStd( valid_color.rbegin()->second );
473  }
474  }
475  }
476 }
477 
479 {
480  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
481  {
482  it->second->cloud_->setAlpha( alpha_property_->getFloat() );
483  }
484 }
485 
487 {
489  if( mode == rviz::PointCloud::RM_POINTS )
490  {
493  }
494  else
495  {
498  }
499  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
500  {
501  it->second->cloud_->setRenderMode( mode );
502  }
504 }
505 
507 {
509  float size;
510  if( mode == rviz::PointCloud::RM_POINTS )
511  {
513  }
514  else
515  {
517  }
518  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
519  {
520  it->second->cloud_->setDimensions( size, size, size );
521  }
523 }
524 
526 {
527  // do nothing... only take effect on next generated clouds
528 }
529 
531 {
532  if(download_map_->getBool())
533  {
534  rtabmap_ros::GetMap getMapSrv;
535  getMapSrv.request.global = true;
536  getMapSrv.request.optimized = true;
537  getMapSrv.request.graphOnly = false;
538  ros::NodeHandle nh;
539  QMessageBox * messageBox = new QMessageBox(
540  QMessageBox::NoIcon,
541  tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map_data").c_str()),
542  tr("Downloading the map... please wait (rviz could become gray!)"),
543  QMessageBox::NoButton);
544  messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
545  messageBox->show();
546  QApplication::processEvents();
547  uSleep(100); // hack make sure the text in the QMessageBox is shown...
548  QApplication::processEvents();
549  if(!ros::service::call("rtabmap/get_map_data", getMapSrv))
550  {
551  ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
552  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
553  "to \"get_map_data\" in the launch "
554  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
555  nh.resolveName("rtabmap/get_map_data").c_str());
556  messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
557  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
558  "to \"get_map_data\" in the launch "
559  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
560  arg(nh.resolveName("rtabmap/get_map_data").c_str()));
561  }
562  else
563  {
564  messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)...")
565  .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
566  QApplication::processEvents();
567  this->reset();
568  processMapData(getMapSrv.response.data);
569  messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
570  .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
571 
572  QTimer::singleShot(1000, messageBox, SLOT(close()));
573  }
574  download_map_->blockSignals(true);
575  download_map_->setBool(false);
576  download_map_->blockSignals(false);
577  }
578  else
579  {
580  // just stay true if double-clicked on DownloadMap property, let the
581  // first process above finishes
582  download_map_->blockSignals(true);
583  download_map_->setBool(true);
584  download_map_->blockSignals(false);
585  }
586 }
587 
589 {
590  if(download_graph_->getBool())
591  {
592  rtabmap_ros::GetMap getMapSrv;
593  getMapSrv.request.global = true;
594  getMapSrv.request.optimized = true;
595  getMapSrv.request.graphOnly = true;
596  ros::NodeHandle nh;
597  QMessageBox * messageBox = new QMessageBox(
598  QMessageBox::NoIcon,
599  tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map_data").c_str()),
600  tr("Downloading the graph... please wait (rviz could become gray!)"),
601  QMessageBox::NoButton);
602  messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
603  messageBox->show();
604  QApplication::processEvents();
605  uSleep(100); // hack make sure the text in the QMessageBox is shown...
606  QApplication::processEvents();
607  if(!ros::service::call("rtabmap/get_map_data", getMapSrv))
608  {
609  ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
610  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
611  "to \"get_map_data\" in the launch "
612  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
613  nh.resolveName("rtabmap/get_map_data").c_str());
614  messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
615  "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
616  "to \"get_map_data\" in the launch "
617  "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
618  arg(nh.resolveName("rtabmap/get_map_data").c_str()));
619  }
620  else
621  {
622  messageBox->setText(tr("Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
623  QApplication::processEvents();
624  processMapData(getMapSrv.response.data);
625  messageBox->setText(tr("Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
626 
627  QTimer::singleShot(1000, messageBox, SLOT(close()));
628  }
629  download_graph_->blockSignals(true);
630  download_graph_->setBool(false);
631  download_graph_->blockSignals(false);
632  }
633  else
634  {
635  // just stay true if double-clicked on DownloadGraph property, let the
636  // first process above finishes
637  download_graph_->blockSignals(true);
638  download_graph_->setBool(true);
639  download_graph_->blockSignals(false);
640  }
641 }
642 
644 {
645  needs_retransform_ = true;
646 }
647 
648 void MapCloudDisplay::update( float wall_dt, float ros_dt )
649 {
651 
652  int lastCloudAdded = -1;
653 
654  if (needs_retransform_)
655  {
656  retransform();
657  needs_retransform_ = false;
658  }
659 
660  {
661  boost::mutex::scoped_lock lock(new_clouds_mutex_);
662  if( !new_cloud_infos_.empty() )
663  {
664  float size;
665  if( mode == rviz::PointCloud::RM_POINTS ) {
667  } else {
669  }
670 
671  std::map<int, CloudInfoPtr>::iterator it = new_cloud_infos_.begin();
672  std::map<int, CloudInfoPtr>::iterator end = new_cloud_infos_.end();
673  for (; it != end; ++it)
674  {
675  CloudInfoPtr cloud_info = it->second;
676 
677  cloud_info->cloud_.reset( new rviz::PointCloud() );
678  cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
679  cloud_info->cloud_->setRenderMode( mode );
680  cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
681  cloud_info->cloud_->setDimensions( size, size, size );
682  cloud_info->cloud_->setAutoSize(false);
683 
684  cloud_info->manager_ = context_->getSceneManager();
685 
686  cloud_info->scene_node_ = scene_node_->createChildSceneNode();
687 
688  cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
689  cloud_info->scene_node_->setVisible(false);
690 
691  cloud_infos_.erase(it->first);
692  cloud_infos_.insert(*it);
693  lastCloudAdded = it->first;
694  }
695 
696  new_cloud_infos_.clear();
697  }
698  }
699 
700  {
701  boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ );
702 
703  if( lock.owns_lock() )
704  {
706  {
707  M_TransformerInfo::iterator it = transformers_.begin();
708  M_TransformerInfo::iterator end = transformers_.end();
709  for (; it != end; ++it)
710  {
711  const std::string& name = it->first;
712  TransformerInfo& info = it->second;
713 
716  }
717  }
718  }
719 
720  new_xyz_transformer_ = false;
721  new_color_transformer_ = false;
722  }
723 
724  int totalPoints = 0;
725  int totalNodesShown = 0;
726  {
727  // update poses
728  boost::mutex::scoped_lock lock(current_map_mutex_);
729  if(!current_map_.empty())
730  {
731  for (std::map<int, rtabmap::Transform>::iterator it=current_map_.begin(); it != current_map_.end(); ++it)
732  {
733  std::map<int, CloudInfoPtr>::iterator cloudInfoIt = cloud_infos_.find(it->first);
734  if(cloudInfoIt != cloud_infos_.end())
735  {
736  totalPoints += cloudInfoIt->second->transformed_points_.size();
737  cloudInfoIt->second->pose_ = it->second;
738  Ogre::Vector3 framePosition;
739  Ogre::Quaternion frameOrientation;
740  if (context_->getFrameManager()->getTransform(cloudInfoIt->second->message_->header, framePosition, frameOrientation))
741  {
742  // Multiply frame with pose
743  Ogre::Matrix4 frameTransform;
744  frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
745  const rtabmap::Transform & p = cloudInfoIt->second->pose_;
746  Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
747  p[4], p[5], p[6], p[7],
748  p[8], p[9], p[10], p[11],
749  0, 0, 0, 1);
750  frameTransform = frameTransform * pose;
751  Ogre::Vector3 posePosition = frameTransform.getTrans();
752  Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
753  poseOrientation.normalise();
754 
755  cloudInfoIt->second->scene_node_->setPosition(posePosition);
756  cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
757  cloudInfoIt->second->scene_node_->setVisible(true);
758  ++totalNodesShown;
759  }
760  else
761  {
762  ROS_ERROR("MapCloudDisplay: Could not update pose of node %d", it->first);
763  }
764 
765  }
766  }
767  //hide not used clouds
768  for(std::map<int, CloudInfoPtr>::iterator iter = cloud_infos_.begin(); iter!=cloud_infos_.end();)
769  {
770  if(current_map_.find(iter->first) == current_map_.end())
771  {
772  if(iter->first == lastCloudAdded_)
773  {
774  // remove from cache, the node has been discarded
775  cloud_infos_.erase(iter++);
776  lastCloudAdded_ = -1;
777  }
778  else
779  {
780  iter->second->scene_node_->setVisible(false);
781  ++iter;
782  }
783  }
784  else
785  {
786  ++iter;
787  }
788  }
789  }
790  }
791  if(lastCloudAdded>0)
792  {
793  lastCloudAdded_ = lastCloudAdded;
794  }
795 
796  this->setStatusStd(rviz::StatusProperty::Ok, "Points", tr("%1").arg(totalPoints).toStdString());
797  this->setStatusStd(rviz::StatusProperty::Ok, "Nodes", tr("%1 shown of %2").arg(totalNodesShown).arg(cloud_infos_.size()).toStdString());
798 }
799 
801 {
802  lastCloudAdded_ = -1;
803  {
804  boost::mutex::scoped_lock lock(new_clouds_mutex_);
805  cloud_infos_.clear();
806  new_cloud_infos_.clear();
807  }
808  {
809  boost::mutex::scoped_lock lock(current_map_mutex_);
810  current_map_.clear();
811  }
812  MFDClass::reset();
813 }
814 
816 {
817  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
819  {
820  return;
821  }
822  new_xyz_transformer_ = true;
824 }
825 
827 {
828  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
830  {
831  return;
832  }
833  new_color_transformer_ = true;
835 }
836 
838 {
840 }
841 
843 {
845 }
846 
848 {
849  prop->clearOptions();
850 
851  if (cloud_infos_.empty())
852  {
853  return;
854  }
855 
856  boost::recursive_mutex::scoped_lock tlock(transformers_mutex_);
857 
858  const sensor_msgs::PointCloud2ConstPtr& msg = cloud_infos_.begin()->second->message_;
859 
860  M_TransformerInfo::iterator it = transformers_.begin();
861  M_TransformerInfo::iterator end = transformers_.end();
862  for (; it != end; ++it)
863  {
864  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
865  if ((trans->supports(msg) & mask) == mask)
866  {
867  prop->addOption( QString::fromStdString( it->first ));
868  }
869  }
870 }
871 
872 rviz::PointCloudTransformerPtr MapCloudDisplay::getXYZTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
873 {
874  boost::recursive_mutex::scoped_lock lock( transformers_mutex_);
875  M_TransformerInfo::iterator it = transformers_.find( xyz_transformer_property_->getStdString() );
876  if( it != transformers_.end() )
877  {
878  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
879  if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_XYZ )
880  {
881  return trans;
882  }
883  }
884 
886 }
887 
888 rviz::PointCloudTransformerPtr MapCloudDisplay::getColorTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
889 {
890  boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
891  M_TransformerInfo::iterator it = transformers_.find( color_transformer_property_->getStdString() );
892  if( it != transformers_.end() )
893  {
894  const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
895  if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_Color )
896  {
897  return trans;
898  }
899  }
900 
902 }
903 
904 
906 {
907  boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
908 
909  for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
910  {
911  const CloudInfoPtr& cloud_info = it->second;
912  transformCloud(cloud_info, false);
913  cloud_info->cloud_->clear();
914  cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
915  }
916 }
917 
918 bool MapCloudDisplay::transformCloud(const CloudInfoPtr& cloud_info, bool update_transformers)
919 {
920  rviz::V_PointCloudPoint& cloud_points = cloud_info->transformed_points_;
921  cloud_points.clear();
922 
923  size_t size = cloud_info->message_->width * cloud_info->message_->height;
924  rviz::PointCloud::Point default_pt;
925  default_pt.color = Ogre::ColourValue(1, 1, 1);
926  default_pt.position = Ogre::Vector3::ZERO;
927  cloud_points.resize(size, default_pt);
928 
929  {
930  boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
931  if( update_transformers )
932  {
933  updateTransformers( cloud_info->message_ );
934  }
935  rviz::PointCloudTransformerPtr xyz_trans = getXYZTransformer(cloud_info->message_);
936  rviz::PointCloudTransformerPtr color_trans = getColorTransformer(cloud_info->message_);
937 
938  if (!xyz_trans)
939  {
940  std::stringstream ss;
941  ss << "No position transformer available for cloud";
942  this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
943  return false;
944  }
945 
946  if (!color_trans)
947  {
948  std::stringstream ss;
949  ss << "No color transformer available for cloud";
950  this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
951  return false;
952  }
953 
954  xyz_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_XYZ, Ogre::Matrix4::IDENTITY, cloud_points);
955  color_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_Color, Ogre::Matrix4::IDENTITY, cloud_points);
956  }
957 
958  for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
959  {
960  if (!rviz::validateFloats(cloud_point->position))
961  {
962  cloud_point->position.x = 999999.0f;
963  cloud_point->position.y = 999999.0f;
964  cloud_point->position.z = 999999.0f;
965  }
966  }
967 
968  return true;
969 }
970 
971 } // namespace rtabmap
972 
ros::ServiceClient getMapSrv
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)
const LaserScan & laserScanCompressed() const
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_
bool isEmpty() const
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
virtual float getFloat() const
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
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_
rviz::BoolProperty * cloud_from_scan_
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.
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
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)
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
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
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 Mon Dec 14 2020 03:42:19