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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40