00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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
00095
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
00193
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
00272 for(unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
00273 {
00274 int id = map.nodes[i].id;
00275
00276
00277 rtabmap::Signature s = rtabmap_ros::nodeDataFromROS(map.nodes[i]);
00278 if(!s.sensorData().imageCompressed().empty() &&
00279 !s.sensorData().depthOrRightCompressed().empty() &&
00280 (s.sensorData().cameraModels().size() || s.sensorData().stereoCameraModel().isValidForProjection()))
00281 {
00282 cv::Mat image, depth;
00283 s.sensorData().uncompressData(&image, &depth, 0);
00284
00285
00286 if(!s.sensorData().imageRaw().empty() && !s.sensorData().depthOrRightRaw().empty())
00287 {
00288 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
00289 pcl::IndicesPtr validIndices(new std::vector<int>);
00290 cloud = rtabmap::util3d::cloudRGBFromSensorData(
00291 s.sensorData(),
00292 cloud_decimation_->getInt(),
00293 cloud_max_depth_->getFloat(),
00294 cloud_min_depth_->getFloat(),
00295 validIndices.get());
00296
00297 if(cloud_voxel_size_->getFloat())
00298 {
00299 cloud = rtabmap::util3d::voxelize(cloud, validIndices, cloud_voxel_size_->getFloat());
00300 }
00301
00302 if(cloud->size())
00303 {
00304 if(cloud_filter_floor_height_->getFloat() > 0.0f || cloud_filter_ceiling_height_->getFloat() > 0.0f)
00305 {
00306
00307 cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose());
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 cloud = rtabmap::util3d::transformPointCloud(cloud, s.getPose().inverse());
00313 }
00314
00315 sensor_msgs::PointCloud2::Ptr cloudMsg(new sensor_msgs::PointCloud2);
00316 pcl::toROSMsg(*cloud, *cloudMsg);
00317 cloudMsg->header = map.header;
00318
00319 CloudInfoPtr info(new CloudInfo);
00320 info->message_ = cloudMsg;
00321 info->pose_ = rtabmap::Transform::getIdentity();
00322 info->id_ = id;
00323
00324 if (transformCloud(info, true))
00325 {
00326 boost::mutex::scoped_lock lock(new_clouds_mutex_);
00327 new_cloud_infos_.erase(id);
00328 new_cloud_infos_.insert(std::make_pair(id, info));
00329 }
00330 }
00331 }
00332 }
00333 }
00334
00335
00336 if(node_filtering_angle_->getFloat() > 0.0f && node_filtering_radius_->getFloat() > 0.0f)
00337 {
00338 poses = rtabmap::graph::radiusPosesFiltering(poses,
00339 node_filtering_radius_->getFloat(),
00340 node_filtering_angle_->getFloat()*CV_PI/180.0);
00341 }
00342
00343 {
00344 boost::mutex::scoped_lock lock(current_map_mutex_);
00345 current_map_ = poses;
00346 }
00347 }
00348
00349 void MapCloudDisplay::setPropertiesHidden( const QList<Property*>& props, bool hide )
00350 {
00351 for( int i = 0; i < props.size(); i++ )
00352 {
00353 props[ i ]->setHidden( hide );
00354 }
00355 }
00356
00357 void MapCloudDisplay::updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud )
00358 {
00359 std::string xyz_name = xyz_transformer_property_->getStdString();
00360 std::string color_name = color_transformer_property_->getStdString();
00361
00362 xyz_transformer_property_->clearOptions();
00363 color_transformer_property_->clearOptions();
00364
00365
00366 typedef std::set<std::pair<uint8_t, std::string> > S_string;
00367 S_string valid_xyz, valid_color;
00368 bool cur_xyz_valid = false;
00369 bool cur_color_valid = false;
00370 bool has_rgb_transformer = false;
00371 M_TransformerInfo::iterator trans_it = transformers_.begin();
00372 M_TransformerInfo::iterator trans_end = transformers_.end();
00373 for(;trans_it != trans_end; ++trans_it)
00374 {
00375 const std::string& name = trans_it->first;
00376 const rviz::PointCloudTransformerPtr& trans = trans_it->second.transformer;
00377 uint32_t mask = trans->supports(cloud);
00378 if (mask & rviz::PointCloudTransformer::Support_XYZ)
00379 {
00380 valid_xyz.insert(std::make_pair(trans->score(cloud), name));
00381 if (name == xyz_name)
00382 {
00383 cur_xyz_valid = true;
00384 }
00385 xyz_transformer_property_->addOptionStd( name );
00386 }
00387
00388 if (mask & rviz::PointCloudTransformer::Support_Color)
00389 {
00390 valid_color.insert(std::make_pair(trans->score(cloud), name));
00391 if (name == color_name)
00392 {
00393 cur_color_valid = true;
00394 }
00395 if (name == "RGB8")
00396 {
00397 has_rgb_transformer = true;
00398 }
00399 color_transformer_property_->addOptionStd( name );
00400 }
00401 }
00402
00403 if( !cur_xyz_valid )
00404 {
00405 if( !valid_xyz.empty() )
00406 {
00407 xyz_transformer_property_->setStringStd( valid_xyz.rbegin()->second );
00408 }
00409 }
00410
00411 if( !cur_color_valid )
00412 {
00413 if( !valid_color.empty() )
00414 {
00415 if (has_rgb_transformer)
00416 {
00417 color_transformer_property_->setStringStd( "RGB8" );
00418 }
00419 else
00420 {
00421 color_transformer_property_->setStringStd( valid_color.rbegin()->second );
00422 }
00423 }
00424 }
00425 }
00426
00427 void MapCloudDisplay::updateAlpha()
00428 {
00429 for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00430 {
00431 it->second->cloud_->setAlpha( alpha_property_->getFloat() );
00432 }
00433 }
00434
00435 void MapCloudDisplay::updateStyle()
00436 {
00437 rviz::PointCloud::RenderMode mode = (rviz::PointCloud::RenderMode) style_property_->getOptionInt();
00438 if( mode == rviz::PointCloud::RM_POINTS )
00439 {
00440 point_world_size_property_->hide();
00441 point_pixel_size_property_->show();
00442 }
00443 else
00444 {
00445 point_world_size_property_->show();
00446 point_pixel_size_property_->hide();
00447 }
00448 for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00449 {
00450 it->second->cloud_->setRenderMode( mode );
00451 }
00452 updateBillboardSize();
00453 }
00454
00455 void MapCloudDisplay::updateBillboardSize()
00456 {
00457 rviz::PointCloud::RenderMode mode = (rviz::PointCloud::RenderMode) style_property_->getOptionInt();
00458 float size;
00459 if( mode == rviz::PointCloud::RM_POINTS )
00460 {
00461 size = point_pixel_size_property_->getFloat();
00462 }
00463 else
00464 {
00465 size = point_world_size_property_->getFloat();
00466 }
00467 for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00468 {
00469 it->second->cloud_->setDimensions( size, size, size );
00470 }
00471 context_->queueRender();
00472 }
00473
00474 void MapCloudDisplay::updateCloudParameters()
00475 {
00476
00477 }
00478
00479 void MapCloudDisplay::downloadMap()
00480 {
00481 if(download_map_->getBool())
00482 {
00483 rtabmap_ros::GetMap getMapSrv;
00484 getMapSrv.request.global = true;
00485 getMapSrv.request.optimized = true;
00486 getMapSrv.request.graphOnly = false;
00487 ros::NodeHandle nh;
00488 QMessageBox * messageBox = new QMessageBox(
00489 QMessageBox::NoIcon,
00490 tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map_data").c_str()),
00491 tr("Downloading the map... please wait (rviz could become gray!)"),
00492 QMessageBox::NoButton);
00493 messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
00494 messageBox->show();
00495 QApplication::processEvents();
00496 uSleep(100);
00497 QApplication::processEvents();
00498 if(!ros::service::call("rtabmap/get_map_data", getMapSrv))
00499 {
00500 ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
00501 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00502 "to \"get_map_data\" in the launch "
00503 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
00504 nh.resolveName("rtabmap/get_map_data").c_str());
00505 messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
00506 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00507 "to \"get_map_data\" in the launch "
00508 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
00509 arg(nh.resolveName("rtabmap/get_map_data").c_str()));
00510 }
00511 else
00512 {
00513 messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)...")
00514 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
00515 QApplication::processEvents();
00516 this->reset();
00517 processMapData(getMapSrv.response.data);
00518 messageBox->setText(tr("Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
00519 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
00520
00521 QTimer::singleShot(1000, messageBox, SLOT(close()));
00522 }
00523 download_map_->blockSignals(true);
00524 download_map_->setBool(false);
00525 download_map_->blockSignals(false);
00526 }
00527 else
00528 {
00529
00530
00531 download_map_->blockSignals(true);
00532 download_map_->setBool(true);
00533 download_map_->blockSignals(false);
00534 }
00535 }
00536
00537 void MapCloudDisplay::downloadGraph()
00538 {
00539 if(download_graph_->getBool())
00540 {
00541 rtabmap_ros::GetMap getMapSrv;
00542 getMapSrv.request.global = true;
00543 getMapSrv.request.optimized = true;
00544 getMapSrv.request.graphOnly = true;
00545 ros::NodeHandle nh;
00546 QMessageBox * messageBox = new QMessageBox(
00547 QMessageBox::NoIcon,
00548 tr("Calling \"%1\" service...").arg(nh.resolveName("rtabmap/get_map_data").c_str()),
00549 tr("Downloading the graph... please wait (rviz could become gray!)"),
00550 QMessageBox::NoButton);
00551 messageBox->setAttribute(Qt::WA_DeleteOnClose, true);
00552 messageBox->show();
00553 QApplication::processEvents();
00554 uSleep(100);
00555 QApplication::processEvents();
00556 if(!ros::service::call("rtabmap/get_map_data", getMapSrv))
00557 {
00558 ROS_ERROR("MapCloudDisplay: Can't call \"%s\" service. "
00559 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00560 "to \"get_map_data\" in the launch "
00561 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
00562 nh.resolveName("rtabmap/get_map_data").c_str());
00563 messageBox->setText(tr("MapCloudDisplay: Can't call \"%1\" service. "
00564 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service "
00565 "to \"get_map_data\" in the launch "
00566 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
00567 arg(nh.resolveName("rtabmap/get_map_data").c_str()));
00568 }
00569 else
00570 {
00571 messageBox->setText(tr("Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
00572 QApplication::processEvents();
00573 processMapData(getMapSrv.response.data);
00574 messageBox->setText(tr("Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
00575
00576 QTimer::singleShot(1000, messageBox, SLOT(close()));
00577 }
00578 download_graph_->blockSignals(true);
00579 download_graph_->setBool(false);
00580 download_graph_->blockSignals(false);
00581 }
00582 else
00583 {
00584
00585
00586 download_graph_->blockSignals(true);
00587 download_graph_->setBool(true);
00588 download_graph_->blockSignals(false);
00589 }
00590 }
00591
00592 void MapCloudDisplay::causeRetransform()
00593 {
00594 needs_retransform_ = true;
00595 }
00596
00597 void MapCloudDisplay::update( float wall_dt, float ros_dt )
00598 {
00599 rviz::PointCloud::RenderMode mode = (rviz::PointCloud::RenderMode) style_property_->getOptionInt();
00600
00601 if (needs_retransform_)
00602 {
00603 retransform();
00604 needs_retransform_ = false;
00605 }
00606
00607 {
00608 boost::mutex::scoped_lock lock(new_clouds_mutex_);
00609 if( !new_cloud_infos_.empty() )
00610 {
00611 float size;
00612 if( mode == rviz::PointCloud::RM_POINTS ) {
00613 size = point_pixel_size_property_->getFloat();
00614 } else {
00615 size = point_world_size_property_->getFloat();
00616 }
00617
00618 std::map<int, CloudInfoPtr>::iterator it = new_cloud_infos_.begin();
00619 std::map<int, CloudInfoPtr>::iterator end = new_cloud_infos_.end();
00620 for (; it != end; ++it)
00621 {
00622 CloudInfoPtr cloud_info = it->second;
00623
00624 cloud_info->cloud_.reset( new rviz::PointCloud() );
00625 cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
00626 cloud_info->cloud_->setRenderMode( mode );
00627 cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
00628 cloud_info->cloud_->setDimensions( size, size, size );
00629 cloud_info->cloud_->setAutoSize(false);
00630
00631 cloud_info->manager_ = context_->getSceneManager();
00632
00633 cloud_info->scene_node_ = scene_node_->createChildSceneNode();
00634
00635 cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
00636 cloud_info->scene_node_->setVisible(false);
00637
00638 cloud_infos_.erase(it->first);
00639 cloud_infos_.insert(*it);
00640 }
00641
00642 new_cloud_infos_.clear();
00643 }
00644 }
00645
00646 {
00647 boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ );
00648
00649 if( lock.owns_lock() )
00650 {
00651 if( new_xyz_transformer_ || new_color_transformer_ )
00652 {
00653 M_TransformerInfo::iterator it = transformers_.begin();
00654 M_TransformerInfo::iterator end = transformers_.end();
00655 for (; it != end; ++it)
00656 {
00657 const std::string& name = it->first;
00658 TransformerInfo& info = it->second;
00659
00660 setPropertiesHidden( info.xyz_props, name != xyz_transformer_property_->getStdString() );
00661 setPropertiesHidden( info.color_props, name != color_transformer_property_->getStdString() );
00662 }
00663 }
00664 }
00665
00666 new_xyz_transformer_ = false;
00667 new_color_transformer_ = false;
00668 }
00669
00670 int totalPoints = 0;
00671 int totalNodesShown = 0;
00672 {
00673
00674 boost::mutex::scoped_lock lock(current_map_mutex_);
00675 if(!current_map_.empty())
00676 {
00677 for (std::map<int, rtabmap::Transform>::iterator it=current_map_.begin(); it != current_map_.end(); ++it)
00678 {
00679 std::map<int, CloudInfoPtr>::iterator cloudInfoIt = cloud_infos_.find(it->first);
00680 if(cloudInfoIt != cloud_infos_.end())
00681 {
00682 totalPoints += cloudInfoIt->second->transformed_points_.size();
00683 cloudInfoIt->second->pose_ = it->second;
00684 Ogre::Vector3 framePosition;
00685 Ogre::Quaternion frameOrientation;
00686 if (context_->getFrameManager()->getTransform(cloudInfoIt->second->message_->header, framePosition, frameOrientation))
00687 {
00688
00689 Ogre::Matrix4 frameTransform;
00690 frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
00691 const rtabmap::Transform & p = cloudInfoIt->second->pose_;
00692 Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
00693 p[4], p[5], p[6], p[7],
00694 p[8], p[9], p[10], p[11],
00695 0, 0, 0, 1);
00696 frameTransform = frameTransform * pose;
00697 Ogre::Vector3 posePosition = frameTransform.getTrans();
00698 Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
00699 poseOrientation.normalise();
00700
00701 cloudInfoIt->second->scene_node_->setPosition(posePosition);
00702 cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
00703 cloudInfoIt->second->scene_node_->setVisible(true);
00704 ++totalNodesShown;
00705 }
00706 else
00707 {
00708 ROS_ERROR("MapCloudDisplay: Could not update pose of node %d", it->first);
00709 }
00710
00711 }
00712 }
00713
00714 for(std::map<int, CloudInfoPtr>::iterator iter = cloud_infos_.begin(); iter!=cloud_infos_.end(); ++iter)
00715 {
00716 if(current_map_.find(iter->first) == current_map_.end())
00717 {
00718 iter->second->scene_node_->setVisible(false);
00719 }
00720 }
00721 }
00722 }
00723
00724 this->setStatusStd(rviz::StatusProperty::Ok, "Points", tr("%1").arg(totalPoints).toStdString());
00725 this->setStatusStd(rviz::StatusProperty::Ok, "Nodes", tr("%1 shown of %2").arg(totalNodesShown).arg(cloud_infos_.size()).toStdString());
00726 }
00727
00728 void MapCloudDisplay::reset()
00729 {
00730 {
00731 boost::mutex::scoped_lock lock(new_clouds_mutex_);
00732 cloud_infos_.clear();
00733 new_cloud_infos_.clear();
00734 }
00735 {
00736 boost::mutex::scoped_lock lock(current_map_mutex_);
00737 current_map_.clear();
00738 }
00739 MFDClass::reset();
00740 }
00741
00742 void MapCloudDisplay::updateXyzTransformer()
00743 {
00744 boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00745 if( transformers_.count( xyz_transformer_property_->getStdString() ) == 0 )
00746 {
00747 return;
00748 }
00749 new_xyz_transformer_ = true;
00750 causeRetransform();
00751 }
00752
00753 void MapCloudDisplay::updateColorTransformer()
00754 {
00755 boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00756 if( transformers_.count( color_transformer_property_->getStdString() ) == 0 )
00757 {
00758 return;
00759 }
00760 new_color_transformer_ = true;
00761 causeRetransform();
00762 }
00763
00764 void MapCloudDisplay::setXyzTransformerOptions( EnumProperty* prop )
00765 {
00766 fillTransformerOptions( prop, rviz::PointCloudTransformer::Support_XYZ );
00767 }
00768
00769 void MapCloudDisplay::setColorTransformerOptions( EnumProperty* prop )
00770 {
00771 fillTransformerOptions( prop, rviz::PointCloudTransformer::Support_Color );
00772 }
00773
00774 void MapCloudDisplay::fillTransformerOptions( rviz::EnumProperty* prop, uint32_t mask )
00775 {
00776 prop->clearOptions();
00777
00778 if (cloud_infos_.empty())
00779 {
00780 return;
00781 }
00782
00783 boost::recursive_mutex::scoped_lock tlock(transformers_mutex_);
00784
00785 const sensor_msgs::PointCloud2ConstPtr& msg = cloud_infos_.begin()->second->message_;
00786
00787 M_TransformerInfo::iterator it = transformers_.begin();
00788 M_TransformerInfo::iterator end = transformers_.end();
00789 for (; it != end; ++it)
00790 {
00791 const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
00792 if ((trans->supports(msg) & mask) == mask)
00793 {
00794 prop->addOption( QString::fromStdString( it->first ));
00795 }
00796 }
00797 }
00798
00799 rviz::PointCloudTransformerPtr MapCloudDisplay::getXYZTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
00800 {
00801 boost::recursive_mutex::scoped_lock lock( transformers_mutex_);
00802 M_TransformerInfo::iterator it = transformers_.find( xyz_transformer_property_->getStdString() );
00803 if( it != transformers_.end() )
00804 {
00805 const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
00806 if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_XYZ )
00807 {
00808 return trans;
00809 }
00810 }
00811
00812 return rviz::PointCloudTransformerPtr();
00813 }
00814
00815 rviz::PointCloudTransformerPtr MapCloudDisplay::getColorTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
00816 {
00817 boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00818 M_TransformerInfo::iterator it = transformers_.find( color_transformer_property_->getStdString() );
00819 if( it != transformers_.end() )
00820 {
00821 const rviz::PointCloudTransformerPtr& trans = it->second.transformer;
00822 if( trans->supports( cloud ) & rviz::PointCloudTransformer::Support_Color )
00823 {
00824 return trans;
00825 }
00826 }
00827
00828 return rviz::PointCloudTransformerPtr();
00829 }
00830
00831
00832 void MapCloudDisplay::retransform()
00833 {
00834 boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
00835
00836 for( std::map<int, CloudInfoPtr>::iterator it = cloud_infos_.begin(); it != cloud_infos_.end(); ++it )
00837 {
00838 const CloudInfoPtr& cloud_info = it->second;
00839 transformCloud(cloud_info, false);
00840 cloud_info->cloud_->clear();
00841 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
00842 }
00843 }
00844
00845 bool MapCloudDisplay::transformCloud(const CloudInfoPtr& cloud_info, bool update_transformers)
00846 {
00847 rviz::V_PointCloudPoint& cloud_points = cloud_info->transformed_points_;
00848 cloud_points.clear();
00849
00850 size_t size = cloud_info->message_->width * cloud_info->message_->height;
00851 rviz::PointCloud::Point default_pt;
00852 default_pt.color = Ogre::ColourValue(1, 1, 1);
00853 default_pt.position = Ogre::Vector3::ZERO;
00854 cloud_points.resize(size, default_pt);
00855
00856 {
00857 boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
00858 if( update_transformers )
00859 {
00860 updateTransformers( cloud_info->message_ );
00861 }
00862 rviz::PointCloudTransformerPtr xyz_trans = getXYZTransformer(cloud_info->message_);
00863 rviz::PointCloudTransformerPtr color_trans = getColorTransformer(cloud_info->message_);
00864
00865 if (!xyz_trans)
00866 {
00867 std::stringstream ss;
00868 ss << "No position transformer available for cloud";
00869 this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
00870 return false;
00871 }
00872
00873 if (!color_trans)
00874 {
00875 std::stringstream ss;
00876 ss << "No color transformer available for cloud";
00877 this->setStatusStd(rviz::StatusProperty::Error, "Message", ss.str());
00878 return false;
00879 }
00880
00881 xyz_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_XYZ, Ogre::Matrix4::IDENTITY, cloud_points);
00882 color_trans->transform(cloud_info->message_, rviz::PointCloudTransformer::Support_Color, Ogre::Matrix4::IDENTITY, cloud_points);
00883 }
00884
00885 for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
00886 {
00887 if (!rviz::validateFloats(cloud_point->position))
00888 {
00889 cloud_point->position.x = 999999.0f;
00890 cloud_point->position.y = 999999.0f;
00891 cloud_point->position.z = 999999.0f;
00892 }
00893 }
00894
00895 return true;
00896 }
00897
00898 }
00899
00900 #include <pluginlib/class_list_macros.h>
00901 PLUGINLIB_EXPORT_CLASS( rtabmap_ros::MapCloudDisplay, rviz::Display )