point_cloud_transformers.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, 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 <OGRE/OgreColourValue.h>
00031 #include <OGRE/OgreMatrix4.h>
00032 #include <OGRE/OgreVector3.h>
00033 
00034 #include "rviz/properties/bool_property.h"
00035 #include "rviz/properties/color_property.h"
00036 #include "rviz/properties/editable_enum_property.h"
00037 #include "rviz/properties/enum_property.h"
00038 #include "rviz/properties/float_property.h"
00039 #include "rviz/validate_floats.h"
00040 
00041 #include "point_cloud_transformers.h"
00042 
00043 namespace rviz
00044 {
00045 
00046 static void getRainbowColor(float value, Ogre::ColourValue& color)
00047 {
00048   value = std::min(value, 1.0f);
00049   value = std::max(value, 0.0f);
00050 
00051   float h = value * 5.0f + 1.0f;
00052   int i = floor(h);
00053   float f = h - i;
00054   if ( !(i&1) ) f = 1 - f; // if i is even
00055   float n = 1 - f;
00056 
00057   if      (i <= 1) color[0] = n, color[1] = 0, color[2] = 1;
00058   else if (i == 2) color[0] = 0, color[1] = n, color[2] = 1;
00059   else if (i == 3) color[0] = 0, color[1] = 1, color[2] = n;
00060   else if (i == 4) color[0] = n, color[1] = 1, color[2] = 0;
00061   else if (i >= 5) color[0] = 1, color[1] = n, color[2] = 0;
00062 }
00063 
00064 uint8_t IntensityPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
00065 {
00066   updateChannels(cloud);
00067   return Support_Color;
00068 }
00069 
00070 uint8_t IntensityPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& cloud)
00071 {
00072   return 255;
00073 }
00074 
00075 bool IntensityPCTransformer::transform( const sensor_msgs::PointCloud2ConstPtr& cloud,
00076                                         uint32_t mask,
00077                                         const Ogre::Matrix4& transform,
00078                                         V_PointCloudPoint& points_out )
00079 {
00080   if( !( mask & Support_Color ))
00081   {
00082     return false;
00083   }
00084 
00085   int32_t index = findChannelIndex( cloud, channel_name_property_->getStdString() );
00086 
00087   if( index == -1 )
00088   {
00089     if( channel_name_property_->getStdString() == "intensity" )
00090     {
00091       index = findChannelIndex( cloud, "intensities" );
00092       if( index == -1 )
00093       {
00094         return false;
00095       }
00096     }
00097     else
00098     {
00099       return false;
00100     }
00101   }
00102 
00103   const uint32_t offset = cloud->fields[index].offset;
00104   const uint8_t type = cloud->fields[index].datatype;
00105   const uint32_t point_step = cloud->point_step;
00106   const uint32_t num_points = cloud->width * cloud->height;
00107 
00108   float min_intensity = 999999.0f;
00109   float max_intensity = -999999.0f;
00110   if( auto_compute_intensity_bounds_property_->getBool() )
00111   {
00112     for( uint32_t i = 0; i < num_points; ++i )
00113     {
00114       float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
00115       min_intensity = std::min(val, min_intensity);
00116       max_intensity = std::max(val, max_intensity);
00117     }
00118 
00119     min_intensity = std::max(-999999.0f, min_intensity);
00120     max_intensity = std::min(999999.0f, max_intensity);
00121     min_intensity_property_->setFloat( min_intensity );
00122     max_intensity_property_->setFloat( max_intensity );
00123   }
00124   else
00125   {
00126     min_intensity = min_intensity_property_->getFloat();
00127     max_intensity = max_intensity_property_->getFloat();
00128   }
00129   float diff_intensity = max_intensity - min_intensity;
00130   if( diff_intensity == 0 )
00131   {
00132     // If min and max are equal, set the diff to something huge so
00133     // when we divide by it, we effectively get zero.  That way the
00134     // point cloud coloring will be predictably uniform when min and
00135     // max are equal.
00136     diff_intensity = 1e20;
00137   }
00138   Ogre::ColourValue max_color = max_color_property_->getOgreColor();
00139   Ogre::ColourValue min_color = min_color_property_->getOgreColor();
00140 
00141   if( use_rainbow_property_->getBool() )
00142   {
00143     for (uint32_t i = 0; i < num_points; ++i)
00144     {
00145       float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
00146       float value = 1.0 - (val - min_intensity)/diff_intensity;
00147       getRainbowColor(value, points_out[i].color);
00148     }
00149   }
00150   else
00151   {
00152     for (uint32_t i = 0; i < num_points; ++i)
00153     {
00154       float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
00155       float normalized_intensity = ( val - min_intensity ) / diff_intensity;
00156       normalized_intensity = std::min(1.0f, std::max(0.0f, normalized_intensity));
00157       points_out[i].color.r = max_color.r * normalized_intensity + min_color.r * (1.0f - normalized_intensity);
00158       points_out[i].color.g = max_color.g * normalized_intensity + min_color.g * (1.0f - normalized_intensity);
00159       points_out[i].color.b = max_color.b * normalized_intensity + min_color.b * (1.0f - normalized_intensity);
00160     }
00161   }
00162 
00163   return true;
00164 }
00165 
00166 void IntensityPCTransformer::createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props )
00167 {
00168   if( mask & Support_Color )
00169   {
00170     channel_name_property_ = new EditableEnumProperty( "Channel Name", "intensity",
00171                                                        "Select the channel to use to compute the intensity",
00172                                                        parent_property, SIGNAL( needRetransform() ), this );
00173 
00174     use_rainbow_property_ = new BoolProperty( "Use rainbow", true,
00175                                               "Whether to use a rainbow of colors or interpolate between two",
00176                                               parent_property, SLOT( updateUseRainbow() ), this );
00177 
00178     min_color_property_ = new ColorProperty( "Min Color", Qt::black,
00179                                              "Color to assign the points with the minimum intensity.  "
00180                                              "Actual color is interpolated between this and Max Color.",
00181                                              parent_property, SIGNAL( needRetransform() ), this );
00182 
00183     max_color_property_ = new ColorProperty( "Max Color", Qt::white,
00184                                              "Color to assign the points with the maximum intensity.  "
00185                                              "Actual color is interpolated between this and Min Color.",
00186                                              parent_property, SIGNAL( needRetransform() ), this );
00187 
00188     auto_compute_intensity_bounds_property_ = new BoolProperty( "Autocompute Intensity Bounds", true,
00189                                                                 "Whether to automatically compute the intensity min/max values.",
00190                                                                 parent_property, SLOT( updateAutoComputeIntensityBounds() ), this );
00191 
00192     min_intensity_property_ = new FloatProperty( "Min Intensity", 0,
00193                                                  "Minimum possible intensity value, used to interpolate from Min Color to Max Color for a point.",
00194                                                  parent_property );
00195 
00196     max_intensity_property_ = new FloatProperty( "Max Intensity", 4096,
00197                                                  "Maximum possible intensity value, used to interpolate from Min Color to Max Color for a point.",
00198                                                  parent_property );
00199 
00200     out_props.push_back( channel_name_property_ );
00201     out_props.push_back( use_rainbow_property_ );
00202     out_props.push_back( min_color_property_ );
00203     out_props.push_back( max_color_property_ );
00204     out_props.push_back( auto_compute_intensity_bounds_property_ );
00205     out_props.push_back( min_intensity_property_ );
00206     out_props.push_back( max_intensity_property_ );
00207 
00208     updateUseRainbow();
00209     updateAutoComputeIntensityBounds();
00210   }
00211 }
00212 
00213 void IntensityPCTransformer::updateChannels( const sensor_msgs::PointCloud2ConstPtr& cloud )
00214 {
00215   V_string channels;
00216   for(size_t i = 0; i < cloud->fields.size(); ++i )
00217   {
00218     channels.push_back(cloud->fields[i].name );
00219   }
00220   std::sort(channels.begin(), channels.end());
00221 
00222   if( channels != available_channels_ )
00223   {
00224     channel_name_property_->clearOptions();
00225     for( V_string::const_iterator it = channels.begin(); it != channels.end(); ++it )
00226     {
00227       const std::string& channel = *it;
00228       if( channel.empty() )
00229       {
00230         continue;
00231       }
00232       channel_name_property_->addOptionStd( channel );
00233     }
00234     available_channels_ = channels;
00235   }
00236 }
00237 
00238 void IntensityPCTransformer::updateAutoComputeIntensityBounds()
00239 {
00240   bool auto_compute = auto_compute_intensity_bounds_property_->getBool();
00241   min_intensity_property_->setHidden( auto_compute );
00242   max_intensity_property_->setHidden( auto_compute );
00243   if( auto_compute )
00244   {
00245     disconnect( min_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00246     disconnect( max_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00247   }
00248   else
00249   {
00250     connect( min_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00251     connect( max_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00252   }
00253   Q_EMIT needRetransform();
00254 }
00255 
00256 void IntensityPCTransformer::updateUseRainbow()
00257 {
00258   bool use_rainbow = use_rainbow_property_->getBool();
00259   min_color_property_->setHidden( use_rainbow );
00260   max_color_property_->setHidden( use_rainbow );
00261   Q_EMIT needRetransform();
00262 }
00263 
00264 uint8_t XYZPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
00265 {
00266   int32_t xi = findChannelIndex(cloud, "x");
00267   int32_t yi = findChannelIndex(cloud, "y");
00268   int32_t zi = findChannelIndex(cloud, "z");
00269 
00270   if (xi == -1 || yi == -1 || zi == -1)
00271   {
00272     return Support_None;
00273   }
00274 
00275   if (cloud->fields[xi].datatype == sensor_msgs::PointField::FLOAT32)
00276   {
00277     return Support_XYZ;
00278   }
00279 
00280   return Support_None;
00281 }
00282 
00283 bool XYZPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
00284 {
00285   if (!(mask & Support_XYZ))
00286   {
00287     return false;
00288   }
00289 
00290   int32_t xi = findChannelIndex(cloud, "x");
00291   int32_t yi = findChannelIndex(cloud, "y");
00292   int32_t zi = findChannelIndex(cloud, "z");
00293 
00294   const uint32_t xoff = cloud->fields[xi].offset;
00295   const uint32_t yoff = cloud->fields[yi].offset;
00296   const uint32_t zoff = cloud->fields[zi].offset;
00297   const uint32_t point_step = cloud->point_step;
00298   const uint32_t num_points = cloud->width * cloud->height;
00299   uint8_t const* point = &cloud->data.front();
00300   for (uint32_t i = 0; i < num_points; ++i, point += point_step)
00301   {
00302     float x = *reinterpret_cast<const float*>(point + xoff);
00303     float y = *reinterpret_cast<const float*>(point + yoff);
00304     float z = *reinterpret_cast<const float*>(point + zoff);
00305 
00306     Ogre::Vector3 pos(x, y, z);
00307     points_out[i].position = pos;
00308   }
00309 
00310   return true;
00311 }
00312 
00313 uint8_t RGB8PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
00314 {
00315   int32_t index = findChannelIndex(cloud, "rgb");
00316   if (index == -1)
00317   {
00318     return Support_None;
00319   }
00320 
00321   if (cloud->fields[index].datatype == sensor_msgs::PointField::INT32 ||
00322       cloud->fields[index].datatype == sensor_msgs::PointField::UINT32 ||
00323       cloud->fields[index].datatype == sensor_msgs::PointField::FLOAT32)
00324   {
00325     return Support_Color;
00326   }
00327 
00328   return Support_None;
00329 }
00330 
00331 bool RGB8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
00332 {
00333   if (!(mask & Support_Color))
00334   {
00335     return false;
00336   }
00337 
00338   int32_t index = findChannelIndex(cloud, "rgb");
00339 
00340   const uint32_t off = cloud->fields[index].offset;
00341   const uint32_t point_step = cloud->point_step;
00342   const uint32_t num_points = cloud->width * cloud->height;
00343   uint8_t const* point = &cloud->data.front();
00344   for (uint32_t i = 0; i < num_points; ++i, point += point_step)
00345   {
00346     uint32_t rgb = *reinterpret_cast<const uint32_t*>(point + off);
00347     float r = ((rgb >> 16) & 0xff) / 255.0f;
00348     float g = ((rgb >> 8) & 0xff) / 255.0f;
00349     float b = (rgb & 0xff) / 255.0f;
00350     points_out[i].color = Ogre::ColourValue(r, g, b);
00351   }
00352 
00353   return true;
00354 }
00355 
00356 uint8_t RGBF32PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
00357 {
00358   int32_t ri = findChannelIndex(cloud, "r");
00359   int32_t gi = findChannelIndex(cloud, "g");
00360   int32_t bi = findChannelIndex(cloud, "b");
00361   if (ri == -1 || gi == -1 || bi == -1)
00362   {
00363     return Support_None;
00364   }
00365 
00366   if (cloud->fields[ri].datatype == sensor_msgs::PointField::FLOAT32)
00367   {
00368     return Support_Color;
00369   }
00370 
00371   return Support_None;
00372 }
00373 
00374 bool RGBF32PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
00375 {
00376   if (!(mask & Support_Color))
00377   {
00378     return false;
00379   }
00380 
00381   int32_t ri = findChannelIndex(cloud, "r");
00382   int32_t gi = findChannelIndex(cloud, "g");
00383   int32_t bi = findChannelIndex(cloud, "b");
00384 
00385   const uint32_t roff = cloud->fields[ri].offset;
00386   const uint32_t goff = cloud->fields[gi].offset;
00387   const uint32_t boff = cloud->fields[bi].offset;
00388   const uint32_t point_step = cloud->point_step;
00389   const uint32_t num_points = cloud->width * cloud->height;
00390   uint8_t const* point = &cloud->data.front();
00391   for (uint32_t i = 0; i < num_points; ++i, point += point_step)
00392   {
00393     float r = *reinterpret_cast<const float*>(point + roff);
00394     float g = *reinterpret_cast<const float*>(point + goff);
00395     float b = *reinterpret_cast<const float*>(point + boff);
00396     points_out[i].color = Ogre::ColourValue(r, g, b);
00397   }
00398 
00399   return true;
00400 }
00401 
00402 uint8_t FlatColorPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
00403 {
00404   return Support_Color;
00405 }
00406 
00407 uint8_t FlatColorPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& cloud)
00408 {
00409   return 0;
00410 }
00411 
00412 bool FlatColorPCTransformer::transform( const sensor_msgs::PointCloud2ConstPtr& cloud,
00413                                         uint32_t mask,
00414                                         const Ogre::Matrix4& transform,
00415                                         V_PointCloudPoint& points_out )
00416 {
00417   if( !( mask & Support_Color ))
00418   {
00419     return false;
00420   }
00421 
00422   Ogre::ColourValue color = color_property_->getOgreColor();
00423 
00424   const uint32_t num_points = cloud->width * cloud->height;
00425   for( uint32_t i = 0; i < num_points; ++i )
00426   {
00427     points_out[i].color = color;
00428   }
00429 
00430   return true;
00431 }
00432 
00433 void FlatColorPCTransformer::createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props )
00434 {
00435   if( mask & Support_Color )
00436   {
00437     color_property_ = new ColorProperty( "Color", Qt::white,
00438                                          "Color to assign to every point.",
00439                                          parent_property, SIGNAL( needRetransform() ), this );
00440     out_props.push_back( color_property_ );
00441   }
00442 }
00443 
00444 uint8_t AxisColorPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
00445 {
00446   return Support_Color;
00447 }
00448 
00449 uint8_t AxisColorPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& cloud)
00450 {
00451   return 255;
00452 }
00453 
00454 bool AxisColorPCTransformer::transform( const sensor_msgs::PointCloud2ConstPtr& cloud,
00455                                         uint32_t mask,
00456                                         const Ogre::Matrix4& transform,
00457                                         V_PointCloudPoint& points_out )
00458 {
00459   if( !( mask & Support_Color ))
00460   {
00461     return false;
00462   }
00463 
00464   int32_t xi = findChannelIndex( cloud, "x" );
00465   int32_t yi = findChannelIndex( cloud, "y" );
00466   int32_t zi = findChannelIndex( cloud, "z" );
00467 
00468   const uint32_t xoff = cloud->fields[xi].offset;
00469   const uint32_t yoff = cloud->fields[yi].offset;
00470   const uint32_t zoff = cloud->fields[zi].offset;
00471   const uint32_t point_step = cloud->point_step;
00472   const uint32_t num_points = cloud->width * cloud->height;
00473   uint8_t const* point = &cloud->data.front();
00474 
00475   // Fill a vector of floats with values based on the chosen axis.
00476   int axis = axis_property_->getOptionInt();
00477   std::vector<float> values;
00478   values.reserve( num_points );
00479   Ogre::Vector3 pos;
00480   if( use_fixed_frame_property_->getBool() )
00481   {
00482     for (uint32_t i = 0; i < num_points; ++i, point += point_step)
00483     {
00484       // TODO: optimize this by only doing the multiplication needed
00485       // for the desired output value, instead of doing all of them
00486       // and then throwing most away.
00487       pos.x = *reinterpret_cast<const float*>(point + xoff);
00488       pos.y = *reinterpret_cast<const float*>(point + yoff);
00489       pos.z = *reinterpret_cast<const float*>(point + zoff);
00490 
00491       pos = transform * pos;
00492       values.push_back( pos[ axis ]);
00493     }
00494   }
00495   else
00496   {
00497     const uint32_t offsets[ 3 ] = { xoff, yoff, zoff };
00498     const uint32_t off = offsets[ axis ];
00499     for (uint32_t i = 0; i < num_points; ++i, point += point_step)
00500     {
00501       values.push_back( *reinterpret_cast<const float*>( point + off ));
00502     }
00503   }
00504   float min_value_current = 9999.0f;
00505   float max_value_current = -9999.0f;
00506   if( auto_compute_bounds_property_->getBool() )
00507   {
00508     for( uint32_t i = 0; i < num_points; i++ )
00509     {
00510       float val = values[ i ];
00511       min_value_current = std::min( min_value_current, val );
00512       max_value_current = std::max( max_value_current, val );
00513     }
00514     min_value_property_->setFloat( min_value_current );
00515     max_value_property_->setFloat( max_value_current );
00516   }
00517   else
00518   {
00519     min_value_current = min_value_property_->getFloat();
00520     max_value_current = max_value_property_->getFloat();
00521   }
00522 
00523   float range = max_value_current - min_value_current;
00524   if( range == 0 )
00525   {
00526     range = 0.001f;
00527   }
00528   for( uint32_t i = 0; i < num_points; ++i )
00529   {
00530     float value = 1.0 - ( values[ i ] - min_value_current ) / range;
00531     getRainbowColor( value, points_out[i].color );
00532   }
00533 
00534   return true;
00535 }
00536 
00537 void AxisColorPCTransformer::createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props )
00538 {
00539   if( mask & Support_Color )
00540   {
00541     axis_property_ = new EnumProperty( "Axis", "Z",
00542                                        "The axis to interpolate the color along.",
00543                                        parent_property, SIGNAL( needRetransform() ), this );
00544     axis_property_->addOption( "X", AXIS_X );
00545     axis_property_->addOption( "Y", AXIS_Y );
00546     axis_property_->addOption( "Z", AXIS_Z );
00547 
00548     auto_compute_bounds_property_ = new BoolProperty( "Autocompute Value Bounds", true,
00549                                                       "Whether to automatically compute the value min/max values.",
00550                                                       parent_property, SLOT( updateAutoComputeBounds() ), this );
00551 
00552     min_value_property_ = new FloatProperty( "Min Value", -10,
00553                                              "Minimum value value, used to interpolate the color of a point.",
00554                                              auto_compute_bounds_property_ );
00555 
00556     max_value_property_ = new FloatProperty( "Max Value", 10,
00557                                              "Maximum value value, used to interpolate the color of a point.",
00558                                              auto_compute_bounds_property_ );
00559 
00560     use_fixed_frame_property_ = new BoolProperty( "Use Fixed Frame", true,
00561                                                   "Whether to color the cloud based on its fixed frame position or its local frame position.",
00562                                                   parent_property, SIGNAL( needRetransform() ), this );
00563 
00564     out_props.push_back( axis_property_ );
00565     out_props.push_back( auto_compute_bounds_property_ );
00566     out_props.push_back( use_fixed_frame_property_ );
00567 
00568     updateAutoComputeBounds();
00569   }
00570 }
00571 
00572 void AxisColorPCTransformer::updateAutoComputeBounds()
00573 {
00574   bool auto_compute = auto_compute_bounds_property_->getBool();
00575   min_value_property_->setHidden( auto_compute );
00576   max_value_property_->setHidden( auto_compute );
00577   if( auto_compute )
00578   {
00579     disconnect( min_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00580     disconnect( max_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00581   }
00582   else
00583   {
00584     connect( min_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00585     connect( max_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
00586     auto_compute_bounds_property_->expand();
00587   }
00588   Q_EMIT needRetransform();
00589 }
00590 
00591 } // end namespace rviz
00592 
00593 #include <pluginlib/class_list_macros.h>
00594 PLUGINLIB_EXPORT_CLASS( rviz::AxisColorPCTransformer, rviz::PointCloudTransformer )
00595 PLUGINLIB_EXPORT_CLASS( rviz::FlatColorPCTransformer, rviz::PointCloudTransformer )
00596 PLUGINLIB_EXPORT_CLASS( rviz::IntensityPCTransformer, rviz::PointCloudTransformer )
00597 PLUGINLIB_EXPORT_CLASS(      rviz::RGB8PCTransformer,      rviz::PointCloudTransformer )
00598 PLUGINLIB_EXPORT_CLASS(    rviz::RGBF32PCTransformer,    rviz::PointCloudTransformer )
00599 PLUGINLIB_EXPORT_CLASS(       rviz::XYZPCTransformer,       rviz::PointCloudTransformer )


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