point_cloud_transformers.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <OgreColourValue.h>
31 #include <OgreMatrix4.h>
32 #include <OgreVector3.h>
33 
39 #include "rviz/validate_floats.h"
40 
42 
43 namespace rviz
44 {
45 
46 static void getRainbowColor(float value, Ogre::ColourValue& color)
47 {
48  // this is HSV color palette with hue values going only from 0.0 to 0.833333.
49 
50  value = std::min(value, 1.0f);
51  value = std::max(value, 0.0f);
52 
53  float h = value * 5.0f + 1.0f;
54  int i = floor(h);
55  float f = h - i;
56  if ( !(i&1) ) f = 1 - f; // if i is even
57  float n = 1 - f;
58 
59  if (i <= 1) color[0] = n, color[1] = 0, color[2] = 1;
60  else if (i == 2) color[0] = 0, color[1] = n, color[2] = 1;
61  else if (i == 3) color[0] = 0, color[1] = 1, color[2] = n;
62  else if (i == 4) color[0] = n, color[1] = 1, color[2] = 0;
63  else if (i >= 5) color[0] = 1, color[1] = n, color[2] = 0;
64 }
65 
66 uint8_t IntensityPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
67 {
68  updateChannels(cloud);
69  return Support_Color;
70 }
71 
72 uint8_t IntensityPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& cloud)
73 {
74  return 255;
75 }
76 
77 bool IntensityPCTransformer::transform( const sensor_msgs::PointCloud2ConstPtr& cloud,
78  uint32_t mask,
79  const Ogre::Matrix4& transform,
80  V_PointCloudPoint& points_out )
81 {
82  if( !( mask & Support_Color ))
83  {
84  return false;
85  }
86 
87  int32_t index = findChannelIndex( cloud, channel_name_property_->getStdString() );
88 
89  if( index == -1 )
90  {
91  if( channel_name_property_->getStdString() == "intensity" )
92  {
93  index = findChannelIndex( cloud, "intensities" );
94  if( index == -1 )
95  {
96  return false;
97  }
98  }
99  else
100  {
101  return false;
102  }
103  }
104 
105  const uint32_t offset = cloud->fields[index].offset;
106  const uint8_t type = cloud->fields[index].datatype;
107  const uint32_t point_step = cloud->point_step;
108  const uint32_t num_points = cloud->width * cloud->height;
109 
110  float min_intensity = 999999.0f;
111  float max_intensity = -999999.0f;
113  {
114  for( uint32_t i = 0; i < num_points; ++i )
115  {
116  float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
117  min_intensity = std::min(val, min_intensity);
118  max_intensity = std::max(val, max_intensity);
119  }
120 
121  min_intensity = std::max(-999999.0f, min_intensity);
122  max_intensity = std::min(999999.0f, max_intensity);
123  min_intensity_property_->setFloat( min_intensity );
124  max_intensity_property_->setFloat( max_intensity );
125  }
126  else
127  {
128  min_intensity = min_intensity_property_->getFloat();
129  max_intensity = max_intensity_property_->getFloat();
130  }
131  float diff_intensity = max_intensity - min_intensity;
132  if( diff_intensity == 0 )
133  {
134  // If min and max are equal, set the diff to something huge so
135  // when we divide by it, we effectively get zero. That way the
136  // point cloud coloring will be predictably uniform when min and
137  // max are equal.
138  diff_intensity = 1e20;
139  }
140  Ogre::ColourValue max_color = max_color_property_->getOgreColor();
141  Ogre::ColourValue min_color = min_color_property_->getOgreColor();
142 
144  {
145  for (uint32_t i = 0; i < num_points; ++i)
146  {
147  float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
148  float value = 1.0 - (val - min_intensity)/diff_intensity;
150  value = 1.0 - value;
151  }
152  getRainbowColor(value, points_out[i].color);
153  }
154  }
155  else
156  {
157  for (uint32_t i = 0; i < num_points; ++i)
158  {
159  float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
160  float normalized_intensity = ( val - min_intensity ) / diff_intensity;
161  normalized_intensity = std::min(1.0f, std::max(0.0f, normalized_intensity));
162  points_out[i].color.r = max_color.r * normalized_intensity + min_color.r * (1.0f - normalized_intensity);
163  points_out[i].color.g = max_color.g * normalized_intensity + min_color.g * (1.0f - normalized_intensity);
164  points_out[i].color.b = max_color.b * normalized_intensity + min_color.b * (1.0f - normalized_intensity);
165  }
166  }
167 
168  return true;
169 }
170 
171 void IntensityPCTransformer::createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props )
172 {
173  if( mask & Support_Color )
174  {
175  channel_name_property_ = new EditableEnumProperty( "Channel Name", "intensity",
176  "Select the channel to use to compute the intensity",
177  parent_property, SIGNAL( needRetransform() ), this );
178 
179  use_rainbow_property_ = new BoolProperty( "Use rainbow", true,
180  "Whether to use a rainbow of colors or interpolate between two",
181  parent_property, SLOT( updateUseRainbow() ), this );
182  invert_rainbow_property_ = new BoolProperty( "Invert Rainbow", false,
183  "Whether to invert rainbow colors",
184  parent_property, SLOT( updateUseRainbow() ), this );
185 
186  min_color_property_ = new ColorProperty( "Min Color", Qt::black,
187  "Color to assign the points with the minimum intensity. "
188  "Actual color is interpolated between this and Max Color.",
189  parent_property, SIGNAL( needRetransform() ), this );
190 
191  max_color_property_ = new ColorProperty( "Max Color", Qt::white,
192  "Color to assign the points with the maximum intensity. "
193  "Actual color is interpolated between this and Min Color.",
194  parent_property, SIGNAL( needRetransform() ), this );
195 
196  auto_compute_intensity_bounds_property_ = new BoolProperty( "Autocompute Intensity Bounds", true,
197  "Whether to automatically compute the intensity min/max values.",
198  parent_property, SLOT( updateAutoComputeIntensityBounds() ), this );
199 
200  min_intensity_property_ = new FloatProperty( "Min Intensity", 0,
201  "Minimum possible intensity value, used to interpolate from Min Color to Max Color for a point.",
202  parent_property );
203 
204  max_intensity_property_ = new FloatProperty( "Max Intensity", 4096,
205  "Maximum possible intensity value, used to interpolate from Min Color to Max Color for a point.",
206  parent_property );
207 
208  out_props.push_back( channel_name_property_ );
209  out_props.push_back( use_rainbow_property_ );
210  out_props.push_back( invert_rainbow_property_ );
211  out_props.push_back( min_color_property_ );
212  out_props.push_back( max_color_property_ );
213  out_props.push_back( auto_compute_intensity_bounds_property_ );
214  out_props.push_back( min_intensity_property_ );
215  out_props.push_back( max_intensity_property_ );
216 
219  }
220 }
221 
222 void IntensityPCTransformer::updateChannels( const sensor_msgs::PointCloud2ConstPtr& cloud )
223 {
224  V_string channels;
225  for(size_t i = 0; i < cloud->fields.size(); ++i )
226  {
227  channels.push_back(cloud->fields[i].name );
228  }
229  std::sort(channels.begin(), channels.end());
230 
231  if( channels != available_channels_ )
232  {
234  for( V_string::const_iterator it = channels.begin(); it != channels.end(); ++it )
235  {
236  const std::string& channel = *it;
237  if( channel.empty() )
238  {
239  continue;
240  }
242  }
243  available_channels_ = channels;
244  }
245 }
246 
248 {
249  bool auto_compute = auto_compute_intensity_bounds_property_->getBool();
250  min_intensity_property_->setHidden( auto_compute );
251  max_intensity_property_->setHidden( auto_compute );
252  if( auto_compute )
253  {
254  disconnect( min_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
255  disconnect( max_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
256  }
257  else
258  {
259  connect( min_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
260  connect( max_intensity_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
261  }
262  Q_EMIT needRetransform();
263 }
264 
266 {
267  bool use_rainbow = use_rainbow_property_->getBool();
268  invert_rainbow_property_->setHidden( !use_rainbow );
269  min_color_property_->setHidden( use_rainbow );
270  max_color_property_->setHidden( use_rainbow );
271  Q_EMIT needRetransform();
272 }
273 
274 uint8_t XYZPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
275 {
276  int32_t xi = findChannelIndex(cloud, "x");
277  int32_t yi = findChannelIndex(cloud, "y");
278  int32_t zi = findChannelIndex(cloud, "z");
279 
280  if (xi == -1 || yi == -1 || zi == -1)
281  {
282  return Support_None;
283  }
284 
285  if (cloud->fields[xi].datatype == sensor_msgs::PointField::FLOAT32)
286  {
287  return Support_XYZ;
288  }
289 
290  return Support_None;
291 }
292 
293 bool XYZPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
294 {
295  if (!(mask & Support_XYZ))
296  {
297  return false;
298  }
299 
300  int32_t xi = findChannelIndex(cloud, "x");
301  int32_t yi = findChannelIndex(cloud, "y");
302  int32_t zi = findChannelIndex(cloud, "z");
303 
304  const uint32_t xoff = cloud->fields[xi].offset;
305  const uint32_t yoff = cloud->fields[yi].offset;
306  const uint32_t zoff = cloud->fields[zi].offset;
307  const uint32_t point_step = cloud->point_step;
308  const uint32_t num_points = cloud->width * cloud->height;
309  uint8_t const* point_x = &cloud->data.front() + xoff;
310  uint8_t const* point_y = &cloud->data.front() + yoff;
311  uint8_t const* point_z = &cloud->data.front() + zoff;
312  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, point_x += point_step,
313  point_y += point_step, point_z += point_step)
314  {
315  iter->position.x = *reinterpret_cast<const float*>(point_x);
316  iter->position.y = *reinterpret_cast<const float*>(point_y);
317  iter->position.z = *reinterpret_cast<const float*>(point_z);
318  }
319 
320  return true;
321 }
322 
323 uint8_t RGB8PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
324 {
325  int32_t index = std::max(findChannelIndex(cloud, "rgb"), findChannelIndex(cloud, "rgba"));
326  if (index == -1)
327  {
328  return Support_None;
329  }
330 
331  if (cloud->fields[index].datatype == sensor_msgs::PointField::INT32 ||
332  cloud->fields[index].datatype == sensor_msgs::PointField::UINT32 ||
333  cloud->fields[index].datatype == sensor_msgs::PointField::FLOAT32)
334  {
335  return Support_Color;
336  }
337 
338  return Support_None;
339 }
340 
341 bool RGB8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
342 {
343  if (!(mask & Support_Color))
344  {
345  return false;
346  }
347 
348  const int32_t rgb = findChannelIndex(cloud, "rgb");
349  const int32_t rgba = findChannelIndex(cloud, "rgba");
350  const int32_t index = std::max(rgb, rgba);
351 
352  const uint32_t off = cloud->fields[index].offset;
353  uint8_t const* rgb_ptr = &cloud->data.front() + off;
354  const uint32_t point_step = cloud->point_step;
355 
356  // Create a look-up table for colors
357  float rgb_lut[256];
358  for(int i = 0; i < 256; ++i)
359  {
360  rgb_lut[i] = float(i)/255.0f;
361  }
362  if (rgb != -1) // rgb
363  {
364  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
365  {
366  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
367  iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
368  iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
369  iter->color.b = rgb_lut[rgb & 0xff];
370  iter->color.a = 1.0f;
371  }
372  }
373  else // rgba
374  {
375  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
376  {
377  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
378  iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
379  iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
380  iter->color.b = rgb_lut[rgb & 0xff];
381  iter->color.a = rgb_lut[rgb >> 24];
382  }
383  }
384 
385  return true;
386 }
387 
388 bool MONO8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
389 {
390  if (!(mask & Support_Color))
391  {
392  return false;
393  }
394 
395  const int32_t rgb = findChannelIndex(cloud, "rgb");
396  const int32_t rgba = findChannelIndex(cloud, "rgba");
397  const int32_t index = std::max(rgb, rgba);
398 
399  const uint32_t off = cloud->fields[index].offset;
400  uint8_t const* rgb_ptr = &cloud->data.front() + off;
401  const uint32_t point_step = cloud->point_step;
402 
403  // Create a look-up table for colors
404  float rgb_lut[256];
405  for(int i = 0; i < 256; ++i)
406  {
407  rgb_lut[i] = float(i)/255.0f;
408  }
409  if (rgb != -1) // rgb
410  {
411  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
412  {
413  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
414  float r = rgb_lut[(rgb >> 16) & 0xff];
415  float g = rgb_lut[(rgb >> 8) & 0xff];
416  float b = rgb_lut[rgb & 0xff];
417  float mono = 0.2989 * r + 0.5870 * g + 0.1140 * b;
418  iter->color.r = iter->color.g = iter->color.b = mono;
419  iter->color.a = 1.0f;
420  }
421  }
422  else // rgba
423  {
424  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
425  {
426  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
427  float r = rgb_lut[(rgb >> 16) & 0xff];
428  float g = rgb_lut[(rgb >> 8) & 0xff];
429  float b = rgb_lut[rgb & 0xff];
430  float mono = 0.2989 * r + 0.5870 * g + 0.1140 * b;
431  iter->color.r = iter->color.g = iter->color.b = mono;
432  iter->color.a = rgb_lut[rgb >> 24];
433  }
434  }
435 
436  return true;
437 }
438 
439 uint8_t RGBF32PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
440 {
441  int32_t ri = findChannelIndex(cloud, "r");
442  int32_t gi = findChannelIndex(cloud, "g");
443  int32_t bi = findChannelIndex(cloud, "b");
444  if (ri == -1 || gi == -1 || bi == -1)
445  {
446  return Support_None;
447  }
448 
449  if (cloud->fields[ri].datatype == sensor_msgs::PointField::FLOAT32)
450  {
451  return Support_Color;
452  }
453 
454  return Support_None;
455 }
456 
457 bool RGBF32PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out)
458 {
459  if (!(mask & Support_Color))
460  {
461  return false;
462  }
463 
464  int32_t ri = findChannelIndex(cloud, "r");
465  int32_t gi = findChannelIndex(cloud, "g");
466  int32_t bi = findChannelIndex(cloud, "b");
467 
468  const uint32_t roff = cloud->fields[ri].offset;
469  const uint32_t goff = cloud->fields[gi].offset;
470  const uint32_t boff = cloud->fields[bi].offset;
471  const uint32_t point_step = cloud->point_step;
472  const uint32_t num_points = cloud->width * cloud->height;
473  uint8_t const* point = &cloud->data.front();
474  for (uint32_t i = 0; i < num_points; ++i, point += point_step)
475  {
476  float r = *reinterpret_cast<const float*>(point + roff);
477  float g = *reinterpret_cast<const float*>(point + goff);
478  float b = *reinterpret_cast<const float*>(point + boff);
479  points_out[i].color = Ogre::ColourValue(r, g, b);
480  }
481 
482  return true;
483 }
484 
485 uint8_t FlatColorPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
486 {
487  return Support_Color;
488 }
489 
490 uint8_t FlatColorPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& cloud)
491 {
492  return 0;
493 }
494 
495 bool FlatColorPCTransformer::transform( const sensor_msgs::PointCloud2ConstPtr& cloud,
496  uint32_t mask,
497  const Ogre::Matrix4& transform,
498  V_PointCloudPoint& points_out )
499 {
500  if( !( mask & Support_Color ))
501  {
502  return false;
503  }
504 
505  Ogre::ColourValue color = color_property_->getOgreColor();
506 
507  const uint32_t num_points = cloud->width * cloud->height;
508  for( uint32_t i = 0; i < num_points; ++i )
509  {
510  points_out[i].color = color;
511  }
512 
513  return true;
514 }
515 
516 void FlatColorPCTransformer::createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props )
517 {
518  if( mask & Support_Color )
519  {
520  color_property_ = new ColorProperty( "Color", Qt::white,
521  "Color to assign to every point.",
522  parent_property, SIGNAL( needRetransform() ), this );
523  out_props.push_back( color_property_ );
524  }
525 }
526 
527 uint8_t AxisColorPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
528 {
529  return Support_Color;
530 }
531 
532 uint8_t AxisColorPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& cloud)
533 {
534  return 255;
535 }
536 
537 bool AxisColorPCTransformer::transform( const sensor_msgs::PointCloud2ConstPtr& cloud,
538  uint32_t mask,
539  const Ogre::Matrix4& transform,
540  V_PointCloudPoint& points_out )
541 {
542  if( !( mask & Support_Color ))
543  {
544  return false;
545  }
546 
547  int32_t xi = findChannelIndex( cloud, "x" );
548  int32_t yi = findChannelIndex( cloud, "y" );
549  int32_t zi = findChannelIndex( cloud, "z" );
550 
551  const uint32_t xoff = cloud->fields[xi].offset;
552  const uint32_t yoff = cloud->fields[yi].offset;
553  const uint32_t zoff = cloud->fields[zi].offset;
554  const uint32_t point_step = cloud->point_step;
555  const uint32_t num_points = cloud->width * cloud->height;
556  uint8_t const* point = &cloud->data.front();
557 
558  // Fill a vector of floats with values based on the chosen axis.
559  int axis = axis_property_->getOptionInt();
560  std::vector<float> values;
561  values.reserve( num_points );
562  Ogre::Vector3 pos;
563  if( use_fixed_frame_property_->getBool() )
564  {
565  for (uint32_t i = 0; i < num_points; ++i, point += point_step)
566  {
567  // TODO: optimize this by only doing the multiplication needed
568  // for the desired output value, instead of doing all of them
569  // and then throwing most away.
570  pos.x = *reinterpret_cast<const float*>(point + xoff);
571  pos.y = *reinterpret_cast<const float*>(point + yoff);
572  pos.z = *reinterpret_cast<const float*>(point + zoff);
573 
574  pos = transform * pos;
575  values.push_back( pos[ axis ]);
576  }
577  }
578  else
579  {
580  const uint32_t offsets[ 3 ] = { xoff, yoff, zoff };
581  const uint32_t off = offsets[ axis ];
582  for (uint32_t i = 0; i < num_points; ++i, point += point_step)
583  {
584  values.push_back( *reinterpret_cast<const float*>( point + off ));
585  }
586  }
587  float min_value_current = 9999.0f;
588  float max_value_current = -9999.0f;
589  if( auto_compute_bounds_property_->getBool() )
590  {
591  for( uint32_t i = 0; i < num_points; i++ )
592  {
593  float val = values[ i ];
594  min_value_current = std::min( min_value_current, val );
595  max_value_current = std::max( max_value_current, val );
596  }
597  min_value_property_->setFloat( min_value_current );
598  max_value_property_->setFloat( max_value_current );
599  }
600  else
601  {
602  min_value_current = min_value_property_->getFloat();
603  max_value_current = max_value_property_->getFloat();
604  }
605 
606  float range = max_value_current - min_value_current;
607  if( range == 0 )
608  {
609  range = 0.001f;
610  }
611  for( uint32_t i = 0; i < num_points; ++i )
612  {
613  float value = 1.0 - ( values[ i ] - min_value_current ) / range;
614  getRainbowColor( value, points_out[i].color );
615  }
616 
617  return true;
618 }
619 
620 void AxisColorPCTransformer::createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props )
621 {
622  if( mask & Support_Color )
623  {
624  axis_property_ = new EnumProperty( "Axis", "Z",
625  "The axis to interpolate the color along.",
626  parent_property, SIGNAL( needRetransform() ), this );
627  axis_property_->addOption( "X", AXIS_X );
628  axis_property_->addOption( "Y", AXIS_Y );
629  axis_property_->addOption( "Z", AXIS_Z );
630 
631  auto_compute_bounds_property_ = new BoolProperty( "Autocompute Value Bounds", true,
632  "Whether to automatically compute the value min/max values.",
633  parent_property, SLOT( updateAutoComputeBounds() ), this );
634 
635  min_value_property_ = new FloatProperty( "Min Value", -10,
636  "Minimum value value, used to interpolate the color of a point.",
637  auto_compute_bounds_property_ );
638 
639  max_value_property_ = new FloatProperty( "Max Value", 10,
640  "Maximum value value, used to interpolate the color of a point.",
641  auto_compute_bounds_property_ );
642 
643  use_fixed_frame_property_ = new BoolProperty( "Use Fixed Frame", true,
644  "Whether to color the cloud based on its fixed frame position or its local frame position.",
645  parent_property, SIGNAL( needRetransform() ), this );
646 
647  out_props.push_back( axis_property_ );
648  out_props.push_back( auto_compute_bounds_property_ );
649  out_props.push_back( use_fixed_frame_property_ );
650 
651  updateAutoComputeBounds();
652  }
653 }
654 
656 {
657  bool auto_compute = auto_compute_bounds_property_->getBool();
658  min_value_property_->setHidden( auto_compute );
659  max_value_property_->setHidden( auto_compute );
660  if( auto_compute )
661  {
662  disconnect( min_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
663  disconnect( max_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
664  }
665  else
666  {
667  connect( min_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
668  connect( max_value_property_, SIGNAL( changed() ), this, SIGNAL( needRetransform() ));
669  auto_compute_bounds_property_->expand();
670  }
671  Q_EMIT needRetransform();
672 }
673 
674 } // end namespace rviz
675 
virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud)
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud)
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud)
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Ogre::ColourValue getOgreColor() const
virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud)
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
f
std::vector< double > values
virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr &cloud)
"Score" a message for how well supported the message is. For example, a "flat color" transformer can ...
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr &cloud)
"Score" a message for how well supported the message is. For example, a "flat color" transformer can ...
EditableEnumProperty * channel_name_property_
virtual float getFloat() const
void needRetransform()
Subclasses should emit this signal whenever they think the points should be re-transformed.
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Editable Enum property.
virtual void createProperties(Property *parent_property, uint32_t mask, QList< Property * > &out_props)
Create any properties necessary for this transformer. Will be called once when the transformer is loa...
void addOptionStd(const std::string &option)
Property specialized to enforce floating point max/min.
virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud)
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
std::string getStdString()
virtual bool getBool() const
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr &cloud)
"Score" a message for how well supported the message is. For example, a "flat color" transformer can ...
void updateChannels(const sensor_msgs::PointCloud2ConstPtr &cloud)
virtual void createProperties(Property *parent_property, uint32_t mask, QList< Property * > &out_props)
Create any properties necessary for this transformer. Will be called once when the transformer is loa...
std::vector< PointCloud::Point > V_PointCloudPoint
std::vector< std::string > V_string
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Definition: property.cpp:530
int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr &cloud, const std::string &channel)
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
BoolProperty * auto_compute_intensity_bounds_property_
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
virtual bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
r
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static void getRainbowColor(float value, Ogre::ColourValue &color)
Enum property.
Definition: enum_property.h:47
virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud)
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
virtual void createProperties(Property *parent_property, uint32_t mask, QList< Property * > &out_props)
Create any properties necessary for this transformer. Will be called once when the transformer is loa...


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat Apr 27 2019 02:33:42