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