MapCloudDisplay.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <QApplication>
00029 #include <QMessageBox>
00030 #include <QTimer>
00031 
00032 #include <OgreSceneNode.h>
00033 #include <OgreSceneManager.h>
00034 
00035 #include <ros/time.h>
00036 
00037 #include <tf/transform_listener.h>
00038 
00039 #include <rviz/display_context.h>
00040 #include <rviz/frame_manager.h>
00041 #include <rviz/ogre_helpers/point_cloud.h>
00042 #include <rviz/validate_floats.h>
00043 #include <rviz/properties/int_property.h>
00044 #include "rviz/properties/bool_property.h"
00045 #include "rviz/properties/enum_property.h"
00046 #include "rviz/properties/float_property.h"
00047 #include "rviz/properties/vector_property.h"
00048 
00049 #include <pcl_conversions/pcl_conversions.h>
00050 
00051 #include "MapCloudDisplay.h"
00052 #include <rtabmap/core/Transform.h>
00053 #include <rtabmap/core/util3d_transforms.h>
00054 #include <rtabmap/core/util3d_filtering.h>
00055 #include <rtabmap/core/util3d.h>
00056 #include <rtabmap/core/Compression.h>
00057 #include <rtabmap/core/Graph.h>
00058 #include <rtabmap_ros/MsgConversion.h>
00059 #include <rtabmap_ros/GetMap.h>
00060 
00061 
00062 namespace rtabmap_ros
00063 {
00064 
00065 
00066 MapCloudDisplay::CloudInfo::CloudInfo() :
00067                 manager_(0),
00068                 pose_(rtabmap::Transform::getIdentity()),
00069                 id_(0),
00070                 scene_node_(0)
00071 {}
00072 
00073 MapCloudDisplay::CloudInfo::~CloudInfo()
00074 {
00075         clear();
00076 }
00077 
00078 void MapCloudDisplay::CloudInfo::clear()
00079 {
00080         if ( scene_node_ )
00081         {
00082                 manager_->destroySceneNode( scene_node_ );
00083                 scene_node_=0;
00084         }
00085 }
00086 
00087 MapCloudDisplay::MapCloudDisplay()
00088   : spinner_(1, &cbqueue_),
00089     new_xyz_transformer_(false),
00090     new_color_transformer_(false),
00091     needs_retransform_(false),
00092     transformer_class_loader_(NULL)
00093 {
00094         //QIcon icon;
00095         //this->setIcon(icon);
00096 
00097         style_property_ = new rviz::EnumProperty( "Style", "Flat Squares",
00098                                                                                 "Rendering mode to use, in order of computational complexity.",
00099                                                                                 this, SLOT( updateStyle() ), this );
00100         style_property_->addOption( "Points", rviz::PointCloud::RM_POINTS );
00101         style_property_->addOption( "Squares", rviz::PointCloud::RM_SQUARES );
00102         style_property_->addOption( "Flat Squares", rviz::PointCloud::RM_FLAT_SQUARES );
00103         style_property_->addOption( "Spheres", rviz::PointCloud::RM_SPHERES );
00104         style_property_->addOption( "Boxes", rviz::PointCloud::RM_BOXES );
00105 
00106         point_world_size_property_ = new rviz::FloatProperty( "Size (m)", 0.01,
00107                                                                                                   "Point size in meters.",
00108                                                                                                   this, SLOT( updateBillboardSize() ), this );
00109         point_world_size_property_->setMin( 0.0001 );
00110 
00111         point_pixel_size_property_ = new rviz::FloatProperty( "Size (Pixels)", 3,
00112                                                                                                   "Point size in pixels.",
00113                                                                                                   this, SLOT( updateBillboardSize() ), this );
00114         point_pixel_size_property_->setMin( 1 );
00115 
00116         alpha_property_ = new rviz::FloatProperty( "Alpha", 1.0,
00117                                                                                  "Amount of transparency to apply to the points.  Note that this is experimental and does not always look correct.",
00118                                                                                  this, SLOT( updateAlpha() ), this );
00119         alpha_property_->setMin( 0 );
00120         alpha_property_->setMax( 1 );
00121 
00122         xyz_transformer_property_ = new rviz::EnumProperty( "Position Transformer", "",
00123                                                                                                   "Set the transformer to use to set the position of the points.",
00124                                                                                                   this, SLOT( updateXyzTransformer() ), this );
00125         connect( xyz_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
00126                          this, SLOT( setXyzTransformerOptions( EnumProperty* )));
00127 
00128         color_transformer_property_ = new rviz::EnumProperty( "Color Transformer", "",
00129                                                                                                         "Set the transformer to use to set the color of the points.",
00130                                                                                                         this, SLOT( updateColorTransformer() ), this );
00131         connect( color_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
00132                          this, SLOT( setColorTransformerOptions( EnumProperty* )));
00133 
00134         cloud_decimation_ = new rviz::IntProperty( "Cloud decimation", 4,
00135                                                                                  "Decimation of the input RGB and depth images before creating the cloud.",
00136                                                                                  this, SLOT( updateCloudParameters() ), this );
00137         cloud_decimation_->setMin( 1 );
00138         cloud_decimation_->setMax( 16 );
00139 
00140         cloud_max_depth_ = new rviz::FloatProperty( "Cloud max depth (m)", 4.0f,
00141                                                                                  "Maximum depth of the generated clouds.",
00142                                                                                  this, SLOT( updateCloudParameters() ), this );
00143         cloud_max_depth_->setMin( 0.0f );
00144         cloud_max_depth_->setMax( 999.0f );
00145 
00146         cloud_min_depth_ = new rviz::FloatProperty( "Cloud min depth (m)", 0.0f,
00147                                                                                          "Minimum depth of the generated clouds.",
00148                                                                                          this, SLOT( updateCloudParameters() ), this );
00149         cloud_min_depth_->setMin( 0.0f );
00150         cloud_min_depth_->setMax( 999.0f );
00151 
00152         cloud_voxel_size_ = new rviz::FloatProperty( "Cloud voxel size (m)", 0.01f,
00153                                                                                  "Voxel size of the generated clouds.",
00154                                                                                  this, SLOT( updateCloudParameters() ), this );
00155         cloud_voxel_size_->setMin( 0.0f );
00156         cloud_voxel_size_->setMax( 1.0f );
00157 
00158         cloud_filter_floor_height_ = new rviz::FloatProperty( "Filter floor (m)", 0.0f,
00159                                                                                  "Filter the floor up to maximum height set here "
00160                                                                                  "(only appropriate for 2D mapping).",
00161                                                                                  this, SLOT( updateCloudParameters() ), this );
00162         cloud_filter_floor_height_->setMin( 0.0f );
00163         cloud_filter_floor_height_->setMax( 999.0f );
00164 
00165         cloud_filter_ceiling_height_ = new rviz::FloatProperty( "Filter ceiling (m)", 0.0f,
00166                                                                                  "Filter the ceiling at the specified height set here "
00167                                                                                  "(only appropriate for 2D mapping).",
00168                                                                                  this, SLOT( updateCloudParameters() ), this );
00169         cloud_filter_ceiling_height_->setMin( 0.0f );
00170         cloud_filter_ceiling_height_->setMax( 999.0f );
00171 
00172         node_filtering_radius_ = new rviz::FloatProperty( "Node filtering radius (m)", 0.0f,
00173                                                                                  "(Disabled=0) Only keep one node in the specified radius.",
00174                                                                                  this, SLOT( updateCloudParameters() ), this );
00175         node_filtering_radius_->setMin( 0.0f );
00176         node_filtering_radius_->setMax( 10.0f );
00177 
00178         node_filtering_angle_ = new rviz::FloatProperty( "Node filtering angle (degrees)", 30.0f,
00179                                                                                  "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
00180                                                                                  this, SLOT( updateCloudParameters() ), this );
00181         node_filtering_angle_->setMin( 0.0f );
00182         node_filtering_angle_->setMax( 359.0f );
00183 
00184         download_map_ = new rviz::BoolProperty( "Download map", false,
00185                                                                                  "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
00186                                                                                  this, SLOT( downloadMap() ), this );
00187 
00188         download_graph_ = new rviz::BoolProperty( "Download graph", false,
00189                                                                                          "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
00190                                                                                          this, SLOT( downloadGraph() ), this );
00191 
00192         // PointCloudCommon sets up a callback queue with a thread for each
00193         // instance.  Use that for processing incoming messages.
00194         update_nh_.setCallbackQueue( &cbqueue_ );
00195 }
00196 
00197 MapCloudDisplay::~MapCloudDisplay()
00198 {
00199         if ( transformer_class_loader_ )
00200         {
00201                 delete transformer_class_loader_;
00202         }
00203 
00204         spinner_.stop();
00205 }
00206 
00207 void MapCloudDisplay::loadTransformers()
00208 {
00209         std::vector<std::string> classes = transformer_class_loader_->getDeclaredClasses();
00210         std::vector<std::string>::iterator ci;
00211 
00212         for( ci = classes.begin(); ci != classes.end(); ci++ )
00213         {
00214                 const std::string& lookup_name = *ci;
00215                 std::string name = transformer_class_loader_->getName( lookup_name );
00216 
00217                 if( transformers_.count( name ) > 0 )
00218                 {
00219                         ROS_ERROR( "Transformer type [%s] is already loaded.", name.c_str() );
00220                         continue;
00221                 }
00222 
00223                 rviz::PointCloudTransformerPtr trans( transformer_class_loader_->createUnmanagedInstance( lookup_name ));
00224                 trans->init();
00225                 connect( trans.get(), SIGNAL( needRetransform() ), this, SLOT( causeRetransform() ));
00226 
00227                 TransformerInfo info;
00228                 info.transformer = trans;
00229                 info.readable_name = name;
00230                 info.lookup_name = lookup_name;
00231 
00232                 info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_XYZ, info.xyz_props );
00233                 setPropertiesHidden( info.xyz_props, true );
00234 
00235                 info.transformer->createProperties( this, rviz::PointCloudTransformer::Support_Color, info.color_props );
00236                 setPropertiesHidden( info.color_props, true );
00237 
00238                 transformers_[ name ] = info;
00239         }
00240 }
00241 
00242 void MapCloudDisplay::onInitialize()
00243 {
00244         MFDClass::onInitialize();
00245 
00246         transformer_class_loader_ = new pluginlib::ClassLoader<rviz::PointCloudTransformer>( "rviz", "rviz::PointCloudTransformer" );
00247         loadTransformers();
00248 
00249         updateStyle();
00250         updateBillboardSize();
00251         updateAlpha();
00252 
00253         spinner_.start();
00254 }
00255 
00256 void MapCloudDisplay::processMessage( const rtabmap_ros::MapDataConstPtr& msg )
00257 {
00258         processMapData(*msg);
00259 
00260         this->emitTimeSignal(msg->header.stamp);
00261 }
00262 
00263 void MapCloudDisplay::processMapData(const rtabmap_ros::MapData& map)
00264 {
00265         std::map<int, rtabmap::Transform> poses;
00266         for(unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
00267         {
00268                 poses.insert(std::make_pair(map.graph.posesId[i], rtabmap_ros::transformFromPoseMsg(map.graph.poses[i])));
00269         }
00270 
00271         // Add new clouds...
00272         for(unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
00273         {
00274                 int id = map.nodes[i].id;
00275                 if(poses.find(id) != poses.end() &&
00276                    cloud_infos_.find(id) == cloud_infos_.end())
00277                 {
00278                         // Cloud not added to RVIZ, add it!
00279                         rtabmap::Signature s = rtabmap_ros::nodeDataFromROS(map.nodes[i]);
00280                         if(!s.sensorData().imageCompressed().empty() &&
00281                            !s.sensorData().depthOrRightCompressed().empty() &&
00282                            (s.sensorData().cameraModels().size() || s.sensorData().stereoCameraModel().isValidForProjection()))
00283                         {
00284                                 cv::Mat image, depth;
00285                                 s.sensorData().uncompressData(&image, &depth, 0);
00286 
00287 
00288                                 if(!s.sensorData().imageRaw().empty() && !s.sensorData().depthOrRightRaw().empty())
00289                                 {
00290                                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
00291                                         pcl::IndicesPtr validIndices(new std::vector<int>);
00292                                         cloud = rtabmap::util3d::cloudRGBFromSensorData(
00293                                                         s.sensorData(),
00294                                                         cloud_decimation_->getInt(),
00295                                                         cloud_max_depth_->getFloat(),
00296                                                         cloud_min_depth_->getFloat(),
00297                                                         validIndices.get());
00298 
00299                                         if(cloud_voxel_size_->getFloat())
00300                                         {
00301                                                 cloud = rtabmap::util3d::voxelize(cloud, validIndices, cloud_voxel_size_->getFloat());
00302                                         }
00303 
00304                                         if(cloud->size())
00305                                         {
00306                                                 if(cloud_filter_floor_height_->getFloat() > 0.0f || cloud_filter_ceiling_height_->getFloat() > 0.0f)
00307                                                 {
00308                                                         cloud = rtabmap::util3d::passThrough(cloud, "z",
00309                                                                         cloud_filter_floor_height_->getFloat()>0.0f?cloud_filter_floor_height_->getFloat():-999.0f,
00310                                                                         cloud_filter_ceiling_height_->getFloat()>0.0f && (cloud_filter_floor_height_->getFloat()<=0.0f || cloud_filter_ceiling_height_->getFloat()>cloud_filter_floor_height_->getFloat())?cloud_filter_ceiling_height_->getFloat():999.0f);
00311                                                 }
00312 
00313                                                 sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
00314                                                 pcl::toROSMsg(*cloud, *cloudMsg);
00315                                                 cloudMsg->header = map.header;
00316 
00317                                                 CloudInfoPtr info(new CloudInfo);
00318                                                 info->message_ = cloudMsg;
00319                                                 info->pose_ = rtabmap::Transform::getIdentity();
00320                                                 info->id_ = id;
00321 
00322                                                 if (transformCloud(info, true))
00323                                                 {
00324                                                         boost::mutex::scoped_lock lock(new_clouds_mutex_);
00325                                                         new_cloud_infos_.insert(std::make_pair(id, info));
00326                                                 }
00327                                         }
00328                                 }
00329                         }
00330                 }
00331         }
00332 
00333         // Update graph
00334         if(node_filtering_angle_->getFloat() > 0.0f && node_filtering_radius_->getFloat() > 0.0f)
00335         {
00336                 poses = rtabmap::graph::radiusPosesFiltering(poses,
00337                                 node_filtering_radius_->getFloat(),
00338                                 node_filtering_angle_->getFloat()*CV_PI/180.0);
00339         }
00340 
00341         {
00342                 boost::mutex::scoped_lock lock(current_map_mutex_);
00343                 current_map_ = poses;
00344         }
00345 }
00346 
00347 void MapCloudDisplay::setPropertiesHidden( const QList<Property*>& props, bool hide )
00348 {
00349         for( int i = 0; i < props.size(); i++ )
00350         {
00351                 props[ i ]->setHidden( hide );
00352         }
00353 }
00354 
00355 void MapCloudDisplay::updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud )
00356 {
00357         std::string xyz_name = xyz_transformer_property_->getStdString();
00358         std::string color_name = color_transformer_property_->getStdString();
00359 
00360         xyz_transformer_property_->clearOptions();
00361         color_transformer_property_->clearOptions();
00362 
00363         // Get the channels that we could potentially render
00364         typedef std::set<std::pair<uint8_t, std::string> > S_string;
00365         S_string valid_xyz, valid_color;
00366         bool cur_xyz_valid = false;
00367         bool cur_color_valid = false;
00368         bool has_rgb_transformer = false;
00369         M_TransformerInfo::iterator trans_it = transformers_.begin();
00370         M_TransformerInfo::iterator trans_end = transformers_.end();
00371         for(;trans_it != trans_end; ++trans_it)
00372         {
00373                 const std::string& name = trans_it->first;
00374                 const rviz::PointCloudTransformerPtr& trans = trans_it->second.transformer;
00375                 uint32_t mask = trans->supports(cloud);
00376                 if (mask & rviz::PointCloudTransformer::Support_XYZ)
00377                 {
00378                         valid_xyz.insert(std::make_pair(trans->score(cloud), name));
00379                         if (name == xyz_name)
00380                         {
00381                                 cur_xyz_valid = true;
00382                         }
00383                         xyz_transformer_property_->addOptionStd( name );
00384                 }
00385 
00386                 if (mask & rviz::PointCloudTransformer::Support_Color)
00387                 {
00388                         valid_color.insert(std::make_pair(trans->score(cloud), name));
00389                         if (name == color_name)
00390                         {
00391                                 cur_color_valid = true;
00392                         }
00393                         if (name == "RGB8")
00394                         {
00395                                 has_rgb_transformer = true;
00396                         }
00397                         color_transformer_property_->addOptionStd( name );
00398                 }
00399         }
00400 
00401         if( !cur_xyz_valid )
00402         {
00403                 if( !valid_xyz.empty() )
00404                 {
00405                         xyz_transformer_property_->setStringStd( valid_xyz.rbegin()->second );
00406                 }
00407         }
00408 
00409         if( !cur_color_valid )
00410         {
00411                 if( !valid_color.empty() )
00412                 {
00413                         if (has_rgb_transformer)
00414                         {
00415                                 color_transformer_property_->setStringStd( "RGB8" );
00416                         }
00417                         else
00418                         {
00419                                 color_transformer_property_->setStringStd( valid_color.rbegin()->second );
00420                         }
00421                 }
00422         }
00423 }
00424 
00425 void MapCloudDisplay::updateAlpha()
00426 {
00427         for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00428         {
00429                 it->second->cloud_->setAlpha( alpha_property_->getFloat() );
00430         }
00431 }
00432 
00433 void MapCloudDisplay::updateStyle()
00434 {
00435         rviz::PointCloud::RenderMode mode = (rviz::PointCloud::RenderMode) style_property_->getOptionInt();
00436         if( mode == rviz::PointCloud::RM_POINTS )
00437         {
00438                 point_world_size_property_->hide();
00439                 point_pixel_size_property_->show();
00440         }
00441         else
00442         {
00443                 point_world_size_property_->show();
00444                 point_pixel_size_property_->hide();
00445         }
00446         for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00447         {
00448                 it->second->cloud_->setRenderMode( mode );
00449         }
00450         updateBillboardSize();
00451 }
00452 
00453 void MapCloudDisplay::updateBillboardSize()
00454 {
00455         rviz::PointCloud::RenderMode mode = (rviz::PointCloud::RenderMode) style_property_->getOptionInt();
00456         float size;
00457         if( mode == rviz::PointCloud::RM_POINTS )
00458         {
00459                 size = point_pixel_size_property_->getFloat();
00460         }
00461         else
00462         {
00463                 size = point_world_size_property_->getFloat();
00464         }
00465          for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00466         {
00467                 it->second->cloud_->setDimensions( size, size, size );
00468         }
00469         context_->queueRender();
00470 }
00471 
00472 void MapCloudDisplay::updateCloudParameters()
00473 {
00474         // do nothing... only take effect on next generated clouds
00475 }
00476 
00477 void MapCloudDisplay::downloadMap()
00478 {
00479         if(download_map_->getBool())
00480         {
00481                 rtabmap_ros::GetMap getMapSrv;
00482                 getMapSrv.request.global = true;
00483                 getMapSrv.request.optimized = true;
00484                 getMapSrv.request.graphOnly = false;
00485                 ros::NodeHandle nh;
00486                 QMessageBox * messageBox = new QMessageBox(
00487                                 QMessageBox::NoIcon,
00488                                 tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map").c_str()),
00489                                 tr("Downloading the map... please wait (rviz could become gray!)"),
00490                                 QMessageBox::NoButton);
00491                 messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
00492                 messageBox->show();
00493                 QApplication::processEvents();
00494                 uSleep(100); // hack make sure the text in the QMessageBox is shown...
00495                 QApplication::processEvents();
00496                 if(!ros::service::call("rtabmap/get_map", getMapSrv))
00497                 {
00498                         ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
00499                                           "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00500                                           "to \"get_map\" in the launch "
00501                                           "file like: <remap from=\"rtabmap/get_map\" to=\"get_map\"/>.",
00502                                           nh.resolveName("rtabmap/get_map").c_str());
00503                         messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
00504                                           "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00505                                           "to \"get_map\" in the launch "
00506                                           "file like: <remap from=\"rtabmap/get_map\" to=\"get_map\"/>.").
00507                                           arg(nh.resolveName("rtabmap/get_map").c_str()));
00508                 }
00509                 else
00510                 {
00511                         messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)...")
00512                                         .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
00513                         QApplication::processEvents();
00514                         this->reset();
00515                         processMapData(getMapSrv.response.data);
00516                         messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
00517                                         .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
00518 
00519                         QTimer::singleShot(1000, messageBox, SLOT(close()));
00520                 }
00521                 download_map_->blockSignals(true);
00522                 download_map_->setBool(false);
00523                 download_map_->blockSignals(false);
00524         }
00525         else
00526         {
00527                 // just stay true if double-clicked on DownloadMap property, let the
00528                 // first process above finishes
00529                 download_map_->blockSignals(true);
00530                 download_map_->setBool(true);
00531                 download_map_->blockSignals(false);
00532         }
00533 }
00534 
00535 void MapCloudDisplay::downloadGraph()
00536 {
00537         if(download_graph_->getBool())
00538         {
00539                 rtabmap_ros::GetMap getMapSrv;
00540                 getMapSrv.request.global = true;
00541                 getMapSrv.request.optimized = true;
00542                 getMapSrv.request.graphOnly = true;
00543                 ros::NodeHandle nh;
00544                 QMessageBox * messageBox = new QMessageBox(
00545                                 QMessageBox::NoIcon,
00546                                 tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map").c_str()),
00547                                 tr("Downloading the graph... please wait (rviz could become gray!)"),
00548                                 QMessageBox::NoButton);
00549                 messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
00550                 messageBox->show();
00551                 QApplication::processEvents();
00552                 uSleep(100); // hack make sure the text in the QMessageBox is shown...
00553                 QApplication::processEvents();
00554                 if(!ros::service::call("rtabmap/get_map", getMapSrv))
00555                 {
00556                         ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
00557                                           "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00558                                           "to \"get_map\" in the launch "
00559                                           "file like: <remap from=\"rtabmap/get_map\" to=\"get_map\"/>.",
00560                                           nh.resolveName("rtabmap/get_map").c_str());
00561                         messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
00562                                           "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00563                                           "to \"get_map\" in the launch "
00564                                           "file like: <remap from=\"rtabmap/get_map\" to=\"get_map\"/>.").
00565                                           arg(nh.resolveName("rtabmap/get_map").c_str()));
00566                 }
00567                 else
00568                 {
00569                         messageBox->setText(tr("Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
00570                         QApplication::processEvents();
00571                         processMapData(getMapSrv.response.data);
00572                         messageBox->setText(tr("Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
00573 
00574                         QTimer::singleShot(1000, messageBox, SLOT(close()));
00575                 }
00576                 download_graph_->blockSignals(true);
00577                 download_graph_->setBool(false);
00578                 download_graph_->blockSignals(false);
00579         }
00580         else
00581         {
00582                 // just stay true if double-clicked on DownloadGraph property, let the
00583                 // first process above finishes
00584                 download_graph_->blockSignals(true);
00585                 download_graph_->setBool(true);
00586                 download_graph_->blockSignals(false);
00587         }
00588 }
00589 
00590 void MapCloudDisplay::causeRetransform()
00591 {
00592   needs_retransform_ = true;
00593 }
00594 
00595 void MapCloudDisplay::update( float wall_dt, float ros_dt )
00596 {
00597         rviz::PointCloud::RenderMode mode = (rviz::PointCloud::RenderMode) style_property_->getOptionInt();
00598 
00599         if (needs_retransform_)
00600         {
00601                 retransform();
00602                 needs_retransform_ = false;
00603         }
00604 
00605         {
00606                 boost::mutex::scoped_lock lock(new_clouds_mutex_);
00607                 if( !new_cloud_infos_.empty() )
00608                 {
00609                         float size;
00610                         if( mode == rviz::PointCloud::RM_POINTS ) {
00611                                 size = point_pixel_size_property_->getFloat();
00612                         } else {
00613                                 size = point_world_size_property_->getFloat();
00614                         }
00615 
00616                         std::map<int, CloudInfoPtr>::iterator it = new_cloud_infos_.begin();
00617                         std::map<int, CloudInfoPtr>::iterator end = new_cloud_infos_.end();
00618                         for (; it != end; ++it)
00619                         {
00620                                 CloudInfoPtr cloud_info = it->second;
00621 
00622                                 cloud_info->cloud_.reset( new rviz::PointCloud() );
00623                                 cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
00624                                 cloud_info->cloud_->setRenderMode( mode );
00625                                 cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
00626                                 cloud_info->cloud_->setDimensions( size, size, size );
00627                                 cloud_info->cloud_->setAutoSize(false);
00628 
00629                                 cloud_info->manager_ = context_->getSceneManager();
00630 
00631                                 cloud_info->scene_node_ = scene_node_->createChildSceneNode();
00632 
00633                                 cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
00634                                 cloud_info->scene_node_->setVisible(false);
00635 
00636                                 cloud_infos_.insert(*it);
00637                         }
00638 
00639                         new_cloud_infos_.clear();
00640                 }
00641         }
00642 
00643         {
00644                 boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ );
00645 
00646                 if( lock.owns_lock() )
00647                 {
00648                         if( new_xyz_transformer_ || new_color_transformer_ )
00649                         {
00650                                 M_TransformerInfo::iterator it = transformers_.begin();
00651                                 M_TransformerInfo::iterator end = transformers_.end();
00652                                 for (; it != end; ++it)
00653                                 {
00654                                         const std::string& name = it->first;
00655                                         TransformerInfo& info = it->second;
00656 
00657                                         setPropertiesHidden( info.xyz_props, name != xyz_transformer_property_->getStdString() );
00658                                         setPropertiesHidden( info.color_props, name != color_transformer_property_->getStdString() );
00659                                 }
00660                         }
00661                 }
00662 
00663                 new_xyz_transformer_ = false;
00664                 new_color_transformer_ = false;
00665         }
00666 
00667         int totalPoints = 0;
00668         int totalNodesShown = 0;
00669         {
00670                 // update poses
00671                 boost::mutex::scoped_lock lock(current_map_mutex_);
00672                 if(!current_map_.empty())
00673                 {
00674                         for (std::map<int, rtabmap::Transform>::iterator it=current_map_.begin(); it != current_map_.end(); ++it)
00675                         {
00676                                 std::map<int, CloudInfoPtr>::iterator cloudInfoIt = cloud_infos_.find(it->first);
00677                                 if(cloudInfoIt != cloud_infos_.end())
00678                                 {
00679                                         totalPoints += cloudInfoIt->second->transformed_points_.size();
00680                                         cloudInfoIt->second->pose_ = it->second;
00681                                         Ogre::Vector3 framePosition;
00682                                         Ogre::Quaternion frameOrientation;
00683                                         if (context_->getFrameManager()->getTransform(cloudInfoIt->second->message_->header, framePosition, frameOrientation))
00684                                         {
00685                                                 // Multiply frame with pose
00686                                                 Ogre::Matrix4 frameTransform;
00687                                                 frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
00688                                                 const rtabmap::Transform & p = cloudInfoIt->second->pose_;
00689                                                 Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
00690                                                                                  p[4], p[5], p[6], p[7],
00691                                                                                  p[8], p[9], p[10], p[11],
00692                                                                                  0, 0, 0, 1);
00693                                                 frameTransform = frameTransform * pose;
00694                                                 Ogre::Vector3 posePosition = frameTransform.getTrans();
00695                                                 Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
00696                                                 poseOrientation.normalise();
00697 
00698                                                 cloudInfoIt->second->scene_node_->setPosition(posePosition);
00699                                                 cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
00700                                                 cloudInfoIt->second->scene_node_->setVisible(true);
00701                                                 ++totalNodesShown;
00702                                         }
00703                                         else
00704                                         {
00705                                                 ROS_ERROR("MapCloudDisplay: Could not update pose of node %d", it->first);
00706                                         }
00707 
00708                                 }
00709                         }
00710                         //hide not used clouds
00711                         for(std::map<int, CloudInfoPtr>::iterator iter = cloud_infos_.begin(); iter!=cloud_infos_.end(); ++iter)
00712                         {
00713                                 if(current_map_.find(iter->first) == current_map_.end())
00714                                 {
00715                                         iter->second->scene_node_->setVisible(false);
00716                                 }
00717                         }
00718                 }
00719         }
00720 
00721         this->setStatusStd(rviz::StatusProperty::Ok, "Points", tr("%1").arg(totalPoints).toStdString());
00722         this->setStatusStd(rviz::StatusProperty::Ok, "Nodes", tr("%1 shown of %2").arg(totalNodesShown).arg(cloud_infos_.size()).toStdString());
00723 }
00724 
00725 void MapCloudDisplay::reset()
00726 {
00727         {
00728                 boost::mutex::scoped_lock lock(new_clouds_mutex_);
00729                 cloud_infos_.clear();
00730                 new_cloud_infos_.clear();
00731         }
00732         {
00733                 boost::mutex::scoped_lock lock(current_map_mutex_);
00734                 current_map_.clear();
00735         }
00736         MFDClass::reset();
00737 }
00738 
00739 void MapCloudDisplay::updateXyzTransformer()
00740 {
00741         boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00742         if( transformers_.count( xyz_transformer_property_->getStdString() ) == 0 )
00743         {
00744                 return;
00745         }
00746         new_xyz_transformer_ = true;
00747         causeRetransform();
00748 }
00749 
00750 void MapCloudDisplay::updateColorTransformer()
00751 {
00752         boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00753         if( transformers_.count( color_transformer_property_->getStdString() ) == 0 )
00754         {
00755                 return;
00756         }
00757         new_color_transformer_ = true;
00758         causeRetransform();
00759 }
00760 
00761 void MapCloudDisplay::setXyzTransformerOptions( EnumProperty* prop )
00762 {
00763         fillTransformerOptions( prop, rviz::PointCloudTransformer::Support_XYZ );
00764 }
00765 
00766 void MapCloudDisplay::setColorTransformerOptions( EnumProperty* prop )
00767 {
00768         fillTransformerOptions( prop, rviz::PointCloudTransformer::Support_Color );
00769 }
00770 
00771 void MapCloudDisplay::fillTransformerOptions( rviz::EnumProperty* prop, uint32_t mask )
00772 {
00773         prop->clearOptions();
00774 
00775         if (cloud_infos_.empty())
00776         {
00777                 return;
00778         }
00779 
00780         boost::recursive_mutex::scoped_lock tlock(transformers_mutex_);
00781 
00782         const sensor_msgs::PointCloud2ConstPtr& msg = cloud_infos_.begin()->second->message_;
00783 
00784         M_TransformerInfo::iterator it = transformers_.begin();
00785         M_TransformerInfo::iterator end = transformers_.end();
00786         for (; it != end; ++it)
00787         {
00788                 const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
00789                 if ((trans->supports(msg) & mask) == mask)
00790                 {
00791                         prop->addOption( QString::fromStdString( it->first ));
00792                 }
00793         }
00794 }
00795 
00796 rviz::PointCloudTransformerPtr MapCloudDisplay::getXYZTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
00797 {
00798         boost::recursive_mutex::scoped_lock lock( transformers_mutex_);
00799         M_TransformerInfo::iterator it = transformers_.find( xyz_transformer_property_->getStdString() );
00800         if( it != transformers_.end() )
00801         {
00802                 const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
00803                 if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_XYZ )
00804                 {
00805                         return trans;
00806                 }
00807         }
00808 
00809         return rviz::PointCloudTransformerPtr();
00810 }
00811 
00812 rviz::PointCloudTransformerPtr MapCloudDisplay::getColorTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
00813 {
00814         boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00815         M_TransformerInfo::iterator it = transformers_.find( color_transformer_property_->getStdString() );
00816         if( it != transformers_.end() )
00817         {
00818                 const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
00819                 if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_Color )
00820                 {
00821                         return trans;
00822                 }
00823         }
00824 
00825         return rviz::PointCloudTransformerPtr();
00826 }
00827 
00828 
00829 void MapCloudDisplay::retransform()
00830 {
00831         boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
00832 
00833         for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00834         {
00835                 const CloudInfoPtr& cloud_info = it->second;
00836                 transformCloud(cloud_info, false);
00837                 cloud_info->cloud_->clear();
00838                 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
00839         }
00840 }
00841 
00842 bool MapCloudDisplay::transformCloud(const CloudInfoPtr& cloud_info, bool update_transformers)
00843 {
00844         rviz::V_PointCloudPoint& cloud_points = cloud_info->transformed_points_;
00845         cloud_points.clear();
00846 
00847         size_t size = cloud_info->message_->width * cloud_info->message_->height;
00848         rviz::PointCloud::Point default_pt;
00849         default_pt.color = Ogre::ColourValue(1, 1, 1);
00850         default_pt.position = Ogre::Vector3::ZERO;
00851         cloud_points.resize(size, default_pt);
00852 
00853         {
00854                 boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
00855                 if( update_transformers )
00856                 {
00857                         updateTransformers( cloud_info->message_ );
00858                 }
00859                 rviz::PointCloudTransformerPtr xyz_trans = getXYZTransformer(cloud_info->message_);
00860                 rviz::PointCloudTransformerPtr color_trans = getColorTransformer(cloud_info->message_);
00861 
00862                 if (!xyz_trans)
00863                 {
00864                         std::stringstream ss;
00865                         ss << "No position transformer available for cloud";
00866                         this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
00867                         return false;
00868                 }
00869 
00870                 if (!color_trans)
00871                 {
00872                         std::stringstream ss;
00873                         ss << "No color transformer available for cloud";
00874                         this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
00875                         return false;
00876                 }
00877 
00878                 xyz_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_XYZ, Ogre::Matrix4::IDENTITY, cloud_points);
00879                 color_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_Color, Ogre::Matrix4::IDENTITY, cloud_points);
00880         }
00881 
00882         for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
00883         {
00884                 if (!rviz::validateFloats(cloud_point->position))
00885                 {
00886                         cloud_point->position.x = 999999.0f;
00887                         cloud_point->position.y = 999999.0f;
00888                         cloud_point->position.z = 999999.0f;
00889                 }
00890         }
00891 
00892         return true;
00893 }
00894 
00895 } // namespace rtabmap
00896 
00897 #include <pluginlib/class_list_macros.h>
00898 PLUGINLIB_EXPORT_CLASS( rtabmap_ros::MapCloudDisplay, rviz::Display )


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Sun Jul 24 2016 03:49:08