point_cloud_common.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
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  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <QColor>
00031 
00032 #include <OGRE/OgreSceneManager.h>
00033 #include <OGRE/OgreSceneNode.h>
00034 #include <OGRE/OgreWireBoundingBox.h>
00035 
00036 #include <ros/time.h>
00037 
00038 #include <tf/transform_listener.h>
00039 
00040 #include <pluginlib/class_loader.h>
00041 
00042 #include "rviz/default_plugin/point_cloud_transformer.h"
00043 #include "rviz/default_plugin/point_cloud_transformers.h"
00044 #include "rviz/display.h"
00045 #include "rviz/display_context.h"
00046 #include "rviz/frame_manager.h"
00047 #include "rviz/ogre_helpers/point_cloud.h"
00048 #include "rviz/properties/bool_property.h"
00049 #include "rviz/properties/enum_property.h"
00050 #include "rviz/properties/float_property.h"
00051 #include "rviz/properties/vector_property.h"
00052 #include "rviz/uniform_string_stream.h"
00053 #include "rviz/validate_floats.h"
00054 
00055 #include "rviz/default_plugin/point_cloud_common.h"
00056 
00057 namespace rviz
00058 {
00059 
00060 struct IndexAndMessage
00061 {
00062   IndexAndMessage( int _index, const void* _message )
00063     : index( _index )
00064     , message( (uint64_t) _message )
00065     {}
00066 
00067   int index;
00068   uint64_t message;
00069 };
00070 
00071 uint qHash( IndexAndMessage iam )
00072 {
00073   return
00074     ((uint) iam.index) +
00075     ((uint) (iam.message >> 32)) +
00076     ((uint) (iam.message & 0xffffffff));
00077 }
00078 
00079 bool operator==( IndexAndMessage a, IndexAndMessage b )
00080 {
00081   return a.index == b.index && a.message == b.message;
00082 }
00083 
00084 PointCloudSelectionHandler::PointCloudSelectionHandler(
00085     float box_size,
00086     PointCloudCommon::CloudInfo *cloud_info,
00087     DisplayContext* context )
00088   : SelectionHandler( context )
00089   , cloud_info_( cloud_info )
00090   , box_size_(box_size)
00091 {
00092 }
00093 
00094 PointCloudSelectionHandler::~PointCloudSelectionHandler()
00095 {
00096   // delete all the Property objects on our way out.
00097   QHash<IndexAndMessage, Property*>::const_iterator iter;
00098   for( iter = property_hash_.begin(); iter != property_hash_.end(); iter++ )
00099   {
00100     delete iter.value();
00101   }
00102 }
00103 
00104 void PointCloudSelectionHandler::preRenderPass(uint32_t pass)
00105 {
00106   SelectionHandler::preRenderPass(pass);
00107 
00108   switch( pass )
00109   {
00110   case 0:
00111     cloud_info_->cloud_->setPickColor( SelectionManager::handleToColor( getHandle() ));
00112     break;
00113   case 1:
00114     cloud_info_->cloud_->setColorByIndex(true);
00115     break;
00116   default:
00117     break;
00118   }
00119 }
00120 
00121 void PointCloudSelectionHandler::postRenderPass(uint32_t pass)
00122 {
00123   SelectionHandler::postRenderPass(pass);
00124 
00125   if (pass == 1)
00126   {
00127     cloud_info_->cloud_->setColorByIndex(false);
00128   }
00129 }
00130 
00131 Ogre::Vector3 pointFromCloud(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t index)
00132 {
00133   int32_t xi = findChannelIndex(cloud, "x");
00134   int32_t yi = findChannelIndex(cloud, "y");
00135   int32_t zi = findChannelIndex(cloud, "z");
00136 
00137   const uint32_t xoff = cloud->fields[xi].offset;
00138   const uint32_t yoff = cloud->fields[yi].offset;
00139   const uint32_t zoff = cloud->fields[zi].offset;
00140   const uint8_t type = cloud->fields[xi].datatype;
00141   const uint32_t point_step = cloud->point_step;
00142   float x = valueFromCloud<float>(cloud, xoff, type, point_step, index);
00143   float y = valueFromCloud<float>(cloud, yoff, type, point_step, index);
00144   float z = valueFromCloud<float>(cloud, zoff, type, point_step, index);
00145   return Ogre::Vector3(x, y, z);
00146 }
00147 
00148 void PointCloudSelectionHandler::createProperties( const Picked& obj, Property* parent_property )
00149 {
00150   typedef std::set<int> S_int;
00151   S_int indices;
00152   {
00153     S_uint64::const_iterator it = obj.extra_handles.begin();
00154     S_uint64::const_iterator end = obj.extra_handles.end();
00155     for (; it != end; ++it)
00156     {
00157       uint64_t handle = *it;
00158       indices.insert((handle & 0xffffffff) - 1);
00159     }
00160   }
00161 
00162   {
00163     S_int::iterator it = indices.begin();
00164     S_int::iterator end = indices.end();
00165     for (; it != end; ++it)
00166     {
00167       int index = *it;
00168       const sensor_msgs::PointCloud2ConstPtr& message = cloud_info_->message_;
00169 
00170       IndexAndMessage hash_key( index, message.get() );
00171       if( !property_hash_.contains( hash_key ))
00172       {
00173         Property* cat = new Property( QString( "Point %1 [cloud 0x%2]" ).arg( index ).arg( (uint64_t) message.get() ),
00174                                       QVariant(), "", parent_property );
00175         property_hash_.insert( hash_key, cat );
00176 
00177         // First add the position.
00178         VectorProperty* pos_prop = new VectorProperty( "Position", cloud_info_->transformed_points_[index].position, "", cat );
00179         pos_prop->setReadOnly( true );
00180 
00181         // Then add all other fields as well.
00182         for( size_t field = 0; field < message->fields.size(); ++field )
00183         {
00184           const sensor_msgs::PointField& f = message->fields[ field ];
00185           const std::string& name = f.name;
00186 
00187           if( name == "x" || name == "y" || name == "z" || name == "X" || name == "Y" || name == "Z" )
00188           {
00189             continue;
00190           }
00191           if( name == "rgb" )
00192           {
00193             uint32_t val;
00194 
00195             // float is still just packed uint8s, so prevent static_cast from manipulating data
00196             if (f.datatype == sensor_msgs::PointField::FLOAT32)
00197             {
00198               float raw_val = valueFromCloud<float>( message, f.offset, f.datatype, message->point_step, index );
00199               val = *(reinterpret_cast<uint32_t*>(&raw_val));
00200             }
00201             else
00202             {
00203               val = valueFromCloud<uint32_t>( message, f.offset, f.datatype, message->point_step, index );
00204             }
00205 
00206             // Mask out any information stored in the upper 8 bits
00207             ColorProperty* prop = new ColorProperty( QString( "%1: %2" ).arg( field ).arg( QString::fromStdString( name )),
00208                                                      QColor( (val >> 16) & 0xff, (val >> 8) & 0xff, val & 0xff ), "", cat );
00209             prop->setReadOnly( true );
00210           }
00211           else
00212           {
00213             float val = valueFromCloud<float>( message, f.offset, f.datatype, message->point_step, index );
00214 
00215             FloatProperty* prop = new FloatProperty( QString( "%1: %2" ).arg( field ).arg( QString::fromStdString( name )),
00216                                                      val, "", cat );
00217             prop->setReadOnly( true );
00218           }
00219         }
00220       }
00221     }
00222   }
00223 }
00224 
00225 void PointCloudSelectionHandler::destroyProperties( const Picked& obj, Property* parent_property )
00226 {
00227   typedef std::set<int> S_int;
00228   S_int indices;
00229   {
00230     S_uint64::const_iterator it = obj.extra_handles.begin();
00231     S_uint64::const_iterator end = obj.extra_handles.end();
00232     for (; it != end; ++it)
00233     {
00234       uint64_t handle = *it;
00235       indices.insert((handle & 0xffffffff) - 1);
00236     }
00237   }
00238 
00239   {
00240     S_int::iterator it = indices.begin();
00241     S_int::iterator end = indices.end();
00242     for (; it != end; ++it)
00243     {
00244       int index = *it;
00245       const sensor_msgs::PointCloud2ConstPtr& message = cloud_info_->message_;
00246 
00247       IndexAndMessage hash_key( index, message.get() );
00248       
00249       Property* prop = property_hash_.take( hash_key );
00250       delete prop;
00251     }
00252   }
00253 }
00254 
00255 void PointCloudSelectionHandler::getAABBs(const Picked& obj, V_AABB& aabbs)
00256 {
00257   S_uint64::iterator it = obj.extra_handles.begin();
00258   S_uint64::iterator end = obj.extra_handles.end();
00259   for (; it != end; ++it)
00260   {
00261     M_HandleToBox::iterator find_it = boxes_.find(std::make_pair(obj.handle, *it - 1));
00262     if (find_it != boxes_.end())
00263     {
00264       Ogre::WireBoundingBox* box = find_it->second.second;
00265 
00266       aabbs.push_back(box->getWorldBoundingBox());
00267     }
00268   }
00269 }
00270 
00271 void PointCloudSelectionHandler::onSelect(const Picked& obj)
00272 {
00273   S_uint64::iterator it = obj.extra_handles.begin();
00274   S_uint64::iterator end = obj.extra_handles.end();
00275   for (; it != end; ++it)
00276   {
00277     int index = (*it & 0xffffffff) - 1;
00278 
00279     sensor_msgs::PointCloud2ConstPtr message = cloud_info_->message_;
00280 
00281     Ogre::Vector3 pos = cloud_info_->transformed_points_[index].position;
00282     pos = cloud_info_->scene_node_->convertLocalToWorldPosition( pos );
00283 
00284     float size = box_size_ * 0.5f;
00285 
00286     Ogre::AxisAlignedBox aabb(pos - size, pos + size);
00287 
00288     createBox(std::make_pair(obj.handle, index), aabb, "RVIZ/Cyan" );
00289   }
00290 }
00291 
00292 void PointCloudSelectionHandler::onDeselect(const Picked& obj)
00293 {
00294   S_uint64::iterator it = obj.extra_handles.begin();
00295   S_uint64::iterator end = obj.extra_handles.end();
00296   for (; it != end; ++it)
00297   {
00298     int global_index = (*it & 0xffffffff) - 1;
00299 
00300     destroyBox(std::make_pair(obj.handle, global_index));
00301   }
00302 }
00303 
00304 PointCloudCommon::CloudInfo::CloudInfo()
00305 : manager_(0)
00306 , scene_node_(0)
00307 {}
00308 
00309 PointCloudCommon::CloudInfo::~CloudInfo()
00310 {
00311   clear();
00312 }
00313 
00314 void PointCloudCommon::CloudInfo::clear()
00315 {
00316   if ( scene_node_ )
00317   {
00318     manager_->destroySceneNode( scene_node_ );
00319     scene_node_=0;
00320   }
00321 }
00322 
00323 PointCloudCommon::PointCloudCommon( Display* display )
00324 : spinner_(1, &cbqueue_)
00325 , new_xyz_transformer_(false)
00326 , new_color_transformer_(false)
00327 , needs_retransform_(false)
00328 , transformer_class_loader_( new pluginlib::ClassLoader<PointCloudTransformer>( "rviz", "rviz::PointCloudTransformer" ))
00329 , display_( display )
00330 , auto_size_(false)
00331 {
00332   selectable_property_ = new BoolProperty( "Selectable", true,
00333                                            "Whether or not the points in this point cloud are selectable.",
00334                                            display_, SLOT( updateSelectable() ), this );
00335 
00336   style_property_ = new EnumProperty( "Style", "Flat Squares",
00337                                       "Rendering mode to use, in order of computational complexity.",
00338                                       display_, SLOT( updateStyle() ), this );
00339   style_property_->addOption( "Points", PointCloud::RM_POINTS );
00340   style_property_->addOption( "Squares", PointCloud::RM_SQUARES );
00341   style_property_->addOption( "Flat Squares", PointCloud::RM_FLAT_SQUARES );
00342   style_property_->addOption( "Spheres", PointCloud::RM_SPHERES );
00343   style_property_->addOption( "Boxes", PointCloud::RM_BOXES );
00344 
00345   point_world_size_property_ = new FloatProperty( "Size (m)", 0.01,
00346                                                 "Point size in meters.",
00347                                                 display_, SLOT( updateBillboardSize() ), this );
00348   point_world_size_property_->setMin( 0.0001 );
00349 
00350   point_pixel_size_property_ = new FloatProperty( "Size (Pixels)", 3,
00351                                                 "Point size in pixels.",
00352                                                 display_, SLOT( updateBillboardSize() ), this );
00353   point_pixel_size_property_->setMin( 1 );
00354 
00355   alpha_property_ = new FloatProperty( "Alpha", 1.0,
00356                                        "Amount of transparency to apply to the points.  Note that this is experimental and does not always look correct.",
00357                                        display_, SLOT( updateAlpha() ), this );
00358   alpha_property_->setMin( 0 );
00359   alpha_property_->setMax( 1 );
00360 
00361   decay_time_property_ = new FloatProperty( "Decay Time", 0,
00362                                             "Duration, in seconds, to keep the incoming points.  0 means only show the latest points.",
00363                                             display_, SLOT( queueRender() ));
00364   decay_time_property_->setMin( 0 );
00365 
00366   xyz_transformer_property_ = new EnumProperty( "Position Transformer", "",
00367                                                 "Set the transformer to use to set the position of the points.",
00368                                                 display_, SLOT( updateXyzTransformer() ), this );
00369   connect( xyz_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
00370            this, SLOT( setXyzTransformerOptions( EnumProperty* )));
00371 
00372   color_transformer_property_ = new EnumProperty( "Color Transformer", "",
00373                                                   "Set the transformer to use to set the color of the points.",
00374                                                   display_, SLOT( updateColorTransformer() ), this );
00375   connect( color_transformer_property_, SIGNAL( requestOptions( EnumProperty* )),
00376            this, SLOT( setColorTransformerOptions( EnumProperty* )));
00377 
00378   loadTransformers();
00379 }
00380 
00381 void PointCloudCommon::initialize( DisplayContext* context, Ogre::SceneNode* scene_node )
00382 {
00383   context_ = context;
00384   scene_node_ = scene_node;
00385 
00386   updateStyle();
00387   updateBillboardSize();
00388   updateAlpha();
00389   updateSelectable();
00390 
00391   spinner_.start();
00392 }
00393 
00394 PointCloudCommon::~PointCloudCommon()
00395 {
00396   spinner_.stop();
00397 
00398   delete transformer_class_loader_;
00399 }
00400 
00401 void PointCloudCommon::loadTransformers()
00402 {
00403   std::vector<std::string> classes = transformer_class_loader_->getDeclaredClasses();
00404   std::vector<std::string>::iterator ci;
00405   
00406   for( ci = classes.begin(); ci != classes.end(); ci++ )
00407   {
00408     const std::string& lookup_name = *ci;
00409     std::string name = transformer_class_loader_->getName( lookup_name );
00410 
00411     if( transformers_.count( name ) > 0 )
00412     {
00413       ROS_ERROR( "Transformer type [%s] is already loaded.", name.c_str() );
00414       continue;
00415     }
00416 
00417     PointCloudTransformerPtr trans( transformer_class_loader_->createUnmanagedInstance( lookup_name ));
00418     trans->init();
00419     connect( trans.get(), SIGNAL( needRetransform() ), this, SLOT( causeRetransform() ));
00420 
00421     TransformerInfo info;
00422     info.transformer = trans;
00423     info.readable_name = name;
00424     info.lookup_name = lookup_name;
00425 
00426     info.transformer->createProperties( display_, PointCloudTransformer::Support_XYZ, info.xyz_props );
00427     setPropertiesHidden( info.xyz_props, true );
00428 
00429     info.transformer->createProperties( display_, PointCloudTransformer::Support_Color, info.color_props );
00430     setPropertiesHidden( info.color_props, true );
00431 
00432     transformers_[ name ] = info;
00433   }
00434 }
00435 
00436 void PointCloudCommon::setAutoSize( bool auto_size )
00437 {
00438   auto_size_ = auto_size;
00439   for ( unsigned i=0; i<cloud_infos_.size(); i++ )
00440   {
00441     cloud_infos_[i]->cloud_->setAutoSize( auto_size );
00442   }
00443 }
00444 
00445 
00446 
00447 void PointCloudCommon::updateAlpha()
00448 {
00449   for ( unsigned i=0; i<cloud_infos_.size(); i++ )
00450   {
00451     cloud_infos_[i]->cloud_->setAlpha( alpha_property_->getFloat() );
00452   }
00453 }
00454 
00455 void PointCloudCommon::updateSelectable()
00456 {
00457   bool selectable = selectable_property_->getBool();
00458 
00459   if( selectable )
00460   {
00461     for ( unsigned i=0; i<cloud_infos_.size(); i++ )
00462     {
00463       cloud_infos_[i]->selection_handler_.reset( new PointCloudSelectionHandler( getSelectionBoxSize(), cloud_infos_[i].get(), context_ ));
00464       cloud_infos_[i]->cloud_->setPickColor( SelectionManager::handleToColor( cloud_infos_[i]->selection_handler_->getHandle() ));
00465     }
00466   }
00467   else
00468   {
00469     for ( unsigned i=0; i<cloud_infos_.size(); i++ )
00470     {
00471       cloud_infos_[i]->selection_handler_.reset( );
00472       cloud_infos_[i]->cloud_->setPickColor( Ogre::ColourValue( 0.0f, 0.0f, 0.0f, 0.0f ) );
00473     }
00474   }
00475 }
00476 
00477 void PointCloudCommon::updateStyle()
00478 {
00479   PointCloud::RenderMode mode = (PointCloud::RenderMode) style_property_->getOptionInt();
00480   if( mode == PointCloud::RM_POINTS )
00481   {
00482     point_world_size_property_->hide();
00483     point_pixel_size_property_->show();
00484   }
00485   else
00486   {
00487     point_world_size_property_->show();
00488     point_pixel_size_property_->hide();
00489   }
00490   for( unsigned int i = 0; i < cloud_infos_.size(); i++ )
00491   {
00492     cloud_infos_[i]->cloud_->setRenderMode( mode );
00493   }
00494   updateBillboardSize();
00495 }
00496 
00497 void PointCloudCommon::updateBillboardSize()
00498 {
00499   PointCloud::RenderMode mode = (PointCloud::RenderMode) style_property_->getOptionInt();
00500   float size;
00501   if( mode == PointCloud::RM_POINTS ) {
00502     size = point_pixel_size_property_->getFloat();
00503   } else {
00504     size = point_world_size_property_->getFloat();
00505   }
00506   for ( unsigned i=0; i<cloud_infos_.size(); i++ )
00507   {
00508     cloud_infos_[i]->cloud_->setDimensions( size, size, size );
00509     cloud_infos_[i]->selection_handler_->setBoxSize( getSelectionBoxSize() );
00510   }
00511   context_->queueRender();
00512 }
00513 
00514 void PointCloudCommon::reset()
00515 {
00516   boost::mutex::scoped_lock lock(new_clouds_mutex_);
00517   cloud_infos_.clear();
00518   new_cloud_infos_.clear();
00519 }
00520 
00521 void PointCloudCommon::causeRetransform()
00522 {
00523   needs_retransform_ = true;
00524 }
00525 
00526 void PointCloudCommon::update(float wall_dt, float ros_dt)
00527 {
00528   PointCloud::RenderMode mode = (PointCloud::RenderMode) style_property_->getOptionInt();
00529 
00530   float point_decay_time = decay_time_property_->getFloat();
00531   if (needs_retransform_)
00532   {
00533     retransform();
00534     needs_retransform_ = false;
00535   }
00536 
00537   // instead of deleting cloud infos, we just clear them
00538   // and put them into obsolete_cloud_infos, so active selections
00539   // are preserved
00540 
00541   ros::Time now = ros::Time::now();
00542 
00543   // if decay time == 0, clear the old cloud when we get a new one
00544   // otherwise, clear all the outdated ones
00545   {
00546     boost::mutex::scoped_lock lock(new_clouds_mutex_);
00547     if ( point_decay_time > 0.0 || !new_cloud_infos_.empty() )
00548     {
00549       while( !cloud_infos_.empty() && now.toSec() - cloud_infos_.front()->receive_time_.toSec() > point_decay_time )
00550       {
00551         cloud_infos_.front()->clear();
00552         obsolete_cloud_infos_.push_back( cloud_infos_.front() );
00553         cloud_infos_.pop_front();
00554         context_->queueRender();
00555       }
00556     }
00557   }
00558 
00559   // garbage-collect old point clouds that don't have an active selection
00560   L_CloudInfo::iterator it = obsolete_cloud_infos_.begin();
00561   L_CloudInfo::iterator end = obsolete_cloud_infos_.end();
00562   for (; it != end; ++it)
00563   {
00564     if ( !(*it)->selection_handler_.get() ||
00565          !(*it)->selection_handler_->hasSelections() )
00566     {
00567       it = obsolete_cloud_infos_.erase(it);
00568     }
00569   }
00570 
00571   {
00572     boost::mutex::scoped_lock lock(new_clouds_mutex_);
00573     if( !new_cloud_infos_.empty() )
00574     {
00575       float size;
00576       if( mode == PointCloud::RM_POINTS ) {
00577         size = point_pixel_size_property_->getFloat();
00578       } else {
00579         size = point_world_size_property_->getFloat();
00580       }
00581 
00582       V_CloudInfo::iterator it = new_cloud_infos_.begin();
00583       V_CloudInfo::iterator end = new_cloud_infos_.end();
00584       for (; it != end; ++it)
00585       {
00586         CloudInfoPtr cloud_info = *it;
00587 
00588         V_CloudInfo::iterator next = it; next++;
00589         // ignore point clouds that are too old, but keep at least one
00590         if ( next != end && now.toSec() - cloud_info->receive_time_.toSec() > point_decay_time ) {
00591           continue;
00592         }
00593 
00594         cloud_info->cloud_.reset( new PointCloud() );
00595         cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
00596         cloud_info->cloud_->setRenderMode( mode );
00597         cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
00598         cloud_info->cloud_->setDimensions( size, size, size );
00599         cloud_info->cloud_->setAutoSize(auto_size_);
00600 
00601         cloud_info->manager_ = context_->getSceneManager();
00602 
00603         cloud_info->scene_node_ = scene_node_->createChildSceneNode( cloud_info->position_, cloud_info->orientation_ );
00604 
00605         cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
00606 
00607         cloud_info->selection_handler_.reset( new PointCloudSelectionHandler( getSelectionBoxSize(), cloud_info.get(), context_ ));
00608 
00609         cloud_infos_.push_back(*it);
00610       }
00611 
00612       new_cloud_infos_.clear();
00613     }
00614   }
00615 
00616   {
00617     boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ );
00618 
00619     if( lock.owns_lock() )
00620     {
00621       if( new_xyz_transformer_ || new_color_transformer_ )
00622       {
00623         M_TransformerInfo::iterator it = transformers_.begin();
00624         M_TransformerInfo::iterator end = transformers_.end();
00625         for (; it != end; ++it)
00626         {
00627           const std::string& name = it->first;
00628           TransformerInfo& info = it->second;
00629 
00630           setPropertiesHidden( info.xyz_props, name != xyz_transformer_property_->getStdString() );
00631           setPropertiesHidden( info.color_props, name != color_transformer_property_->getStdString() );
00632         }
00633       }
00634     }
00635 
00636     new_xyz_transformer_ = false;
00637     new_color_transformer_ = false;
00638   }
00639 
00640   updateStatus();
00641 }
00642 
00643 void PointCloudCommon::setPropertiesHidden( const QList<Property*>& props, bool hide )
00644 {
00645   for( int i = 0; i < props.size(); i++ )
00646   {
00647     props[ i ]->setHidden( hide );
00648   }
00649 }
00650 
00651 void PointCloudCommon::updateTransformers( const sensor_msgs::PointCloud2ConstPtr& cloud )
00652 {
00653   std::string xyz_name = xyz_transformer_property_->getStdString();
00654   std::string color_name = color_transformer_property_->getStdString();
00655 
00656   xyz_transformer_property_->clearOptions();
00657   color_transformer_property_->clearOptions();
00658 
00659   // Get the channels that we could potentially render
00660   typedef std::set<std::pair<uint8_t, std::string> > S_string;
00661   S_string valid_xyz, valid_color;
00662   bool cur_xyz_valid = false;
00663   bool cur_color_valid = false;
00664   bool has_rgb_transformer = false;
00665   M_TransformerInfo::iterator trans_it = transformers_.begin();
00666   M_TransformerInfo::iterator trans_end = transformers_.end();
00667   for(;trans_it != trans_end; ++trans_it)
00668   {
00669     const std::string& name = trans_it->first;
00670     const PointCloudTransformerPtr& trans = trans_it->second.transformer;
00671     uint32_t mask = trans->supports(cloud);
00672     if (mask & PointCloudTransformer::Support_XYZ)
00673     {
00674       valid_xyz.insert(std::make_pair(trans->score(cloud), name));
00675       if (name == xyz_name)
00676       {
00677         cur_xyz_valid = true;
00678       }
00679       xyz_transformer_property_->addOptionStd( name );
00680     }
00681 
00682     if (mask & PointCloudTransformer::Support_Color)
00683     {
00684       valid_color.insert(std::make_pair(trans->score(cloud), name));
00685       if (name == color_name)
00686       {
00687         cur_color_valid = true;
00688       }
00689       if (name == "RGB8")
00690       {
00691         has_rgb_transformer = true;
00692       }
00693       color_transformer_property_->addOptionStd( name );
00694     }
00695   }
00696 
00697   if( !cur_xyz_valid )
00698   {
00699     if( !valid_xyz.empty() )
00700     {
00701       xyz_transformer_property_->setStringStd( valid_xyz.rbegin()->second );
00702     }
00703   }
00704 
00705   if( !cur_color_valid )
00706   {
00707     if( !valid_color.empty() )
00708     {
00709       if (has_rgb_transformer)
00710       {
00711         color_transformer_property_->setStringStd( "RGB8" );
00712       } else
00713       {
00714         color_transformer_property_->setStringStd( valid_color.rbegin()->second );
00715       }
00716     }
00717   }
00718 }
00719 
00720 void PointCloudCommon::updateStatus()
00721 {
00722   std::stringstream ss;
00723   //ss << "Showing [" << total_point_count_ << "] points from [" << clouds_.size() << "] messages";
00724   display_->setStatusStd(StatusProperty::Ok, "Points", ss.str());
00725 }
00726 
00727 void PointCloudCommon::processMessage(const sensor_msgs::PointCloud2ConstPtr& cloud)
00728 {
00729   CloudInfoPtr info(new CloudInfo);
00730   info->message_ = cloud;
00731   info->receive_time_ = ros::Time::now();
00732 
00733   if (transformCloud(info, true))
00734   {
00735     boost::mutex::scoped_lock lock(new_clouds_mutex_);
00736     new_cloud_infos_.push_back(info);
00737     display_->emitTimeSignal( cloud->header.stamp );
00738   }
00739 }
00740 
00741 void PointCloudCommon::updateXyzTransformer()
00742 {
00743   boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00744   if( transformers_.count( xyz_transformer_property_->getStdString() ) == 0 )
00745   {
00746     return;
00747   }
00748   new_xyz_transformer_ = true;
00749   causeRetransform();
00750 }
00751 
00752 void PointCloudCommon::updateColorTransformer()
00753 {
00754   boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00755   if( transformers_.count( color_transformer_property_->getStdString() ) == 0 )
00756   {
00757     return;
00758   }
00759   new_color_transformer_ = true;
00760   causeRetransform();
00761 }
00762 
00763 PointCloudTransformerPtr PointCloudCommon::getXYZTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
00764 {
00765   boost::recursive_mutex::scoped_lock lock( transformers_mutex_);
00766   M_TransformerInfo::iterator it = transformers_.find( xyz_transformer_property_->getStdString() );
00767   if( it != transformers_.end() )
00768   {
00769     const PointCloudTransformerPtr& trans = it->second.transformer;
00770     if( trans->supports( cloud ) & PointCloudTransformer::Support_XYZ )
00771     {
00772       return trans;
00773     }
00774   }
00775 
00776   return PointCloudTransformerPtr();
00777 }
00778 
00779 PointCloudTransformerPtr PointCloudCommon::getColorTransformer( const sensor_msgs::PointCloud2ConstPtr& cloud )
00780 {
00781   boost::recursive_mutex::scoped_lock lock( transformers_mutex_ );
00782   M_TransformerInfo::iterator it = transformers_.find( color_transformer_property_->getStdString() );
00783   if( it != transformers_.end() )
00784   {
00785     const PointCloudTransformerPtr& trans = it->second.transformer;
00786     if( trans->supports( cloud ) & PointCloudTransformer::Support_Color )
00787     {
00788       return trans;
00789     }
00790   }
00791 
00792   return PointCloudTransformerPtr();
00793 }
00794 
00795 
00796 void PointCloudCommon::retransform()
00797 {
00798   boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
00799 
00800   D_CloudInfo::iterator it = cloud_infos_.begin();
00801   D_CloudInfo::iterator end = cloud_infos_.end();
00802   for (; it != end; ++it)
00803   {
00804     const CloudInfoPtr& cloud_info = *it;
00805     transformCloud(cloud_info, false);
00806     cloud_info->cloud_->clear();
00807     cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
00808   }
00809 }
00810 
00811 bool PointCloudCommon::transformCloud(const CloudInfoPtr& cloud_info, bool update_transformers)
00812 {
00813 
00814   if ( !cloud_info->scene_node_ )
00815   {
00816     if (!context_->getFrameManager()->getTransform(cloud_info->message_->header, cloud_info->position_, cloud_info->orientation_))
00817     {
00818       std::stringstream ss;
00819       ss << "Failed to transform from frame [" << cloud_info->message_->header.frame_id << "] to frame [" << context_->getFrameManager()->getFixedFrame() << "]";
00820       display_->setStatusStd(StatusProperty::Error, "Message", ss.str());
00821       return false;
00822     }
00823   }
00824 
00825   Ogre::Matrix4 transform;
00826   transform.makeTransform( cloud_info->position_, Ogre::Vector3(1,1,1), cloud_info->orientation_ );
00827 
00828   V_PointCloudPoint& cloud_points = cloud_info->transformed_points_;
00829   cloud_points.clear();
00830 
00831   size_t size = cloud_info->message_->width * cloud_info->message_->height;
00832   PointCloud::Point default_pt;
00833   default_pt.color = Ogre::ColourValue(1, 1, 1);
00834   default_pt.position = Ogre::Vector3::ZERO;
00835   cloud_points.resize(size, default_pt);
00836 
00837   {
00838     boost::recursive_mutex::scoped_lock lock(transformers_mutex_);
00839     if( update_transformers )
00840     {
00841       updateTransformers( cloud_info->message_ );
00842     }
00843     PointCloudTransformerPtr xyz_trans = getXYZTransformer(cloud_info->message_);
00844     PointCloudTransformerPtr color_trans = getColorTransformer(cloud_info->message_);
00845 
00846     if (!xyz_trans)
00847     {
00848       std::stringstream ss;
00849       ss << "No position transformer available for cloud";
00850       display_->setStatusStd(StatusProperty::Error, "Message", ss.str());
00851       return false;
00852     }
00853 
00854     if (!color_trans)
00855     {
00856       std::stringstream ss;
00857       ss << "No color transformer available for cloud";
00858       display_->setStatusStd(StatusProperty::Error, "Message", ss.str());
00859       return false;
00860     }
00861 
00862     xyz_trans->transform(cloud_info->message_, PointCloudTransformer::Support_XYZ, transform, cloud_points);
00863     color_trans->transform(cloud_info->message_, PointCloudTransformer::Support_Color, transform, cloud_points);
00864   }
00865 
00866   for (size_t i = 0; i < size; ++i)
00867   {
00868     if (!validateFloats(cloud_points[i].position))
00869     {
00870       cloud_points[i].position.x = 999999.0f;
00871       cloud_points[i].position.y = 999999.0f;
00872       cloud_points[i].position.z = 999999.0f;
00873     }
00874   }
00875 
00876   return true;
00877 }
00878 
00879 bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud& input, sensor_msgs::PointCloud2& output)
00880 {
00881   output.header = input.header;
00882   output.width  = input.points.size ();
00883   output.height = 1;
00884   output.fields.resize (3 + input.channels.size ());
00885   // Convert x/y/z to fields
00886   output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z";
00887   int offset = 0;
00888   // All offsets are *4, as all field data types are float32
00889   for (size_t d = 0; d < output.fields.size (); ++d, offset += 4)
00890   {
00891     output.fields[d].offset = offset;
00892     output.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
00893   }
00894   output.point_step = offset;
00895   output.row_step   = output.point_step * output.width;
00896   // Convert the remaining of the channels to fields
00897   for (size_t d = 0; d < input.channels.size (); ++d)
00898     output.fields[3 + d].name = input.channels[d].name;
00899   output.data.resize (input.points.size () * output.point_step);
00900   output.is_bigendian = false;  // @todo ?
00901   output.is_dense     = false;
00902 
00903   // Copy the data points
00904   for (size_t cp = 0; cp < input.points.size (); ++cp)
00905   {
00906     memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float));
00907     memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float));
00908     memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float));
00909     for (size_t d = 0; d < input.channels.size (); ++d)
00910     {
00911       if (input.channels[d].values.size() == input.points.size())
00912       {
00913         memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float));
00914       }
00915     }
00916   }
00917   return (true);
00918 }
00919 
00920 void PointCloudCommon::addMessage(const sensor_msgs::PointCloudConstPtr& cloud)
00921 {
00922   sensor_msgs::PointCloud2Ptr out(new sensor_msgs::PointCloud2);
00923   convertPointCloudToPointCloud2(*cloud, *out);
00924   addMessage(out);
00925 }
00926 
00927 void PointCloudCommon::addMessage(const sensor_msgs::PointCloud2ConstPtr& cloud)
00928 {
00929   if (cloud->width * cloud->height == 0)
00930   {
00931     return;
00932   }
00933 
00934   processMessage(cloud);
00935 }
00936 
00937 void PointCloudCommon::fixedFrameChanged()
00938 {
00939   reset();
00940 }
00941 
00942 void PointCloudCommon::setXyzTransformerOptions( EnumProperty* prop )
00943 {
00944   fillTransformerOptions( prop, PointCloudTransformer::Support_XYZ );
00945 }
00946 
00947 void PointCloudCommon::setColorTransformerOptions( EnumProperty* prop )
00948 {
00949   fillTransformerOptions( prop, PointCloudTransformer::Support_Color );
00950 }
00951 
00952 void PointCloudCommon::fillTransformerOptions( EnumProperty* prop, uint32_t mask )
00953 {
00954   prop->clearOptions();
00955 
00956   if (cloud_infos_.empty())
00957   {
00958     return;
00959   }
00960 
00961   boost::recursive_mutex::scoped_lock tlock(transformers_mutex_);
00962 
00963   const sensor_msgs::PointCloud2ConstPtr& msg = cloud_infos_.front()->message_;
00964 
00965   M_TransformerInfo::iterator it = transformers_.begin();
00966   M_TransformerInfo::iterator end = transformers_.end();
00967   for (; it != end; ++it)
00968   {
00969     const PointCloudTransformerPtr& trans = it->second.transformer;
00970     if ((trans->supports(msg) & mask) == mask)
00971     {
00972       prop->addOption( QString::fromStdString( it->first ));
00973     }
00974   }
00975 }
00976 
00977 float PointCloudCommon::getSelectionBoxSize()
00978 {
00979   if( style_property_->getOptionInt() != PointCloud::RM_POINTS )
00980   {
00981     return point_world_size_property_->getFloat();
00982   }
00983   else
00984   {
00985     return 0.004;
00986   }
00987 }
00988 
00989 } // namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35