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>
33 
39 #include <rviz/validate_floats.h>
40 
42 
43 namespace rviz
44 {
45 static void getRainbowColor(float value, Ogre::ColourValue& color)
46 {
47  // this is HSV color palette with hue values going only from 0.0 to 0.833333.
48 
49  value = std::min(value, 1.0f);
50  value = std::max(value, 0.0f);
51 
52  float h = value * 5.0f + 1.0f;
53  int i = floor(h);
54  float f = h - i;
55  if (!(i & 1))
56  f = 1 - f; // if i is even
57  float n = 1 - f;
58 
59  if (i <= 1)
60  color[0] = n, color[1] = 0, color[2] = 1;
61  else if (i == 2)
62  color[0] = 0, color[1] = n, color[2] = 1;
63  else if (i == 3)
64  color[0] = 0, color[1] = 1, color[2] = n;
65  else if (i == 4)
66  color[0] = n, color[1] = 1, color[2] = 0;
67  else if (i >= 5)
68  color[0] = 1, color[1] = n, color[2] = 0;
69 }
70 
71 uint8_t IntensityPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
72 {
73  updateChannels(cloud);
74  return Support_Color;
75 }
76 
77 uint8_t IntensityPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& /*cloud*/)
78 {
79  return 255;
80 }
81 
82 bool IntensityPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
83  uint32_t mask,
84  const Ogre::Matrix4& /*transform*/,
85  V_PointCloudPoint& points_out)
86 {
87  if (!(mask & Support_Color))
88  {
89  return false;
90  }
91 
92  int32_t index = findChannelIndex(cloud, channel_name_property_->getStdString());
93 
94  if (index == -1)
95  {
96  if (channel_name_property_->getStdString() == "intensity")
97  {
98  index = findChannelIndex(cloud, "intensities");
99  if (index == -1)
100  {
101  return false;
102  }
103  }
104  else
105  {
106  return false;
107  }
108  }
109 
110  const uint32_t offset = cloud->fields[index].offset;
111  const uint8_t type = cloud->fields[index].datatype;
112  const uint32_t point_step = cloud->point_step;
113  const uint32_t num_points = cloud->width * cloud->height;
114 
115  float min_intensity = 999999.0f;
116  float max_intensity = -999999.0f;
118  {
119  for (uint32_t i = 0; i < num_points; ++i)
120  {
121  float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
122  min_intensity = std::min(val, min_intensity);
123  max_intensity = std::max(val, max_intensity);
124  }
125 
126  min_intensity = std::max(-999999.0f, min_intensity);
127  max_intensity = std::min(999999.0f, max_intensity);
128  min_intensity_property_->setFloat(min_intensity);
129  max_intensity_property_->setFloat(max_intensity);
130  }
131  else
132  {
133  min_intensity = min_intensity_property_->getFloat();
134  max_intensity = max_intensity_property_->getFloat();
135  }
136  float diff_intensity = max_intensity - min_intensity;
137  if (diff_intensity == 0)
138  {
139  // If min and max are equal, set the diff to something huge so
140  // when we divide by it, we effectively get zero. That way the
141  // point cloud coloring will be predictably uniform when min and
142  // max are equal.
143  diff_intensity = 1e20;
144  }
145  Ogre::ColourValue max_color = max_color_property_->getOgreColor();
146  Ogre::ColourValue min_color = min_color_property_->getOgreColor();
147 
149  {
150  for (uint32_t i = 0; i < num_points; ++i)
151  {
152  float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
153  float value = 1.0 - (val - min_intensity) / diff_intensity;
155  {
156  value = 1.0 - value;
157  }
158  getRainbowColor(value, points_out[i].color);
159  }
160  }
161  else
162  {
163  for (uint32_t i = 0; i < num_points; ++i)
164  {
165  float val = valueFromCloud<float>(cloud, offset, type, point_step, i);
166  float normalized_intensity = (val - min_intensity) / diff_intensity;
167  normalized_intensity = std::min(1.0f, std::max(0.0f, normalized_intensity));
168  points_out[i].color.r =
169  max_color.r * normalized_intensity + min_color.r * (1.0f - normalized_intensity);
170  points_out[i].color.g =
171  max_color.g * normalized_intensity + min_color.g * (1.0f - normalized_intensity);
172  points_out[i].color.b =
173  max_color.b * normalized_intensity + min_color.b * (1.0f - normalized_intensity);
174  }
175  }
176 
177  return true;
178 }
179 
181  uint32_t mask,
182  QList<Property*>& out_props)
183 {
184  if (mask & Support_Color)
185  {
187  new EditableEnumProperty("Channel Name", "intensity",
188  "Select the channel to use to compute the intensity", parent_property,
190 
192  new BoolProperty("Use rainbow", true,
193  "Whether to use a rainbow of colors or interpolate between two",
194  parent_property, &IntensityPCTransformer::updateUseRainbow, this);
196  new BoolProperty("Invert Rainbow", false, "Whether to invert rainbow colors", parent_property,
198 
200  new ColorProperty("Min Color", Qt::black,
201  "Color to assign the points with the minimum intensity. "
202  "Actual color is interpolated between this and Max Color.",
203  parent_property,
204  &IntensityPCTransformer::IntensityPCTransformer::needRetransform, this);
205 
207  new ColorProperty("Max Color", Qt::white,
208  "Color to assign the points with the maximum intensity. "
209  "Actual color is interpolated between this and Min Color.",
210  parent_property,
211  &IntensityPCTransformer::IntensityPCTransformer::needRetransform, this);
212 
214  new BoolProperty("Autocompute Intensity Bounds", true,
215  "Whether to automatically compute the intensity min/max values.",
217  this);
218 
220  "Min Intensity", 0,
221  "Minimum possible intensity value, used to interpolate from Min Color to Max Color for a point.",
222  parent_property);
223 
225  "Max Intensity", 4096,
226  "Maximum possible intensity value, used to interpolate from Min Color to Max Color for a point.",
227  parent_property);
228 
229  out_props.push_back(channel_name_property_);
230  out_props.push_back(use_rainbow_property_);
231  out_props.push_back(invert_rainbow_property_);
232  out_props.push_back(min_color_property_);
233  out_props.push_back(max_color_property_);
234  out_props.push_back(auto_compute_intensity_bounds_property_);
235  out_props.push_back(min_intensity_property_);
236  out_props.push_back(max_intensity_property_);
237 
240  }
241 }
242 
243 void IntensityPCTransformer::updateChannels(const sensor_msgs::PointCloud2ConstPtr& cloud)
244 {
245  V_string channels;
246  for (size_t i = 0; i < cloud->fields.size(); ++i)
247  {
248  channels.push_back(cloud->fields[i].name);
249  }
250  std::sort(channels.begin(), channels.end());
251 
252  if (channels != available_channels_)
253  {
255  for (V_string::const_iterator it = channels.begin(); it != channels.end(); ++it)
256  {
257  const std::string& channel = *it;
258  if (channel.empty())
259  {
260  continue;
261  }
263  }
264  available_channels_ = channels;
265  }
266 }
267 
269 {
270  bool auto_compute = auto_compute_intensity_bounds_property_->getBool();
271  min_intensity_property_->setReadOnly(auto_compute);
272  max_intensity_property_->setReadOnly(auto_compute);
273  if (auto_compute)
274  {
275  disconnect(min_intensity_property_, &Property::changed, this,
277  disconnect(max_intensity_property_, &Property::changed, this,
279  }
280  else
281  {
284  }
285  Q_EMIT needRetransform();
286 }
287 
289 {
290  bool use_rainbow = use_rainbow_property_->getBool();
291  invert_rainbow_property_->setHidden(!use_rainbow);
292  min_color_property_->setHidden(use_rainbow);
293  max_color_property_->setHidden(use_rainbow);
294  Q_EMIT needRetransform();
295 }
296 
297 uint8_t XYZPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
298 {
299  int32_t xi = findChannelIndex(cloud, "x");
300  int32_t yi = findChannelIndex(cloud, "y");
301  int32_t zi = findChannelIndex(cloud, "z");
302 
303  if (xi == -1 || yi == -1 || zi == -1)
304  {
305  return Support_None;
306  }
307 
308  if (cloud->fields[xi].datatype == sensor_msgs::PointField::FLOAT32)
309  {
310  return Support_XYZ;
311  }
312 
313  return Support_None;
314 }
315 
316 bool XYZPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
317  uint32_t mask,
318  const Ogre::Matrix4& /*transform*/,
319  V_PointCloudPoint& points_out)
320 {
321  if (!(mask & Support_XYZ))
322  {
323  return false;
324  }
325 
326  int32_t xi = findChannelIndex(cloud, "x");
327  int32_t yi = findChannelIndex(cloud, "y");
328  int32_t zi = findChannelIndex(cloud, "z");
329 
330  const uint32_t xoff = cloud->fields[xi].offset;
331  const uint32_t yoff = cloud->fields[yi].offset;
332  const uint32_t zoff = cloud->fields[zi].offset;
333  const uint32_t point_step = cloud->point_step;
334  uint8_t const* point_x = &cloud->data.front() + xoff;
335  uint8_t const* point_y = &cloud->data.front() + yoff;
336  uint8_t const* point_z = &cloud->data.front() + zoff;
337  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end();
338  ++iter, point_x += point_step, point_y += point_step, point_z += point_step)
339  {
340  iter->position.x = *reinterpret_cast<const float*>(point_x);
341  iter->position.y = *reinterpret_cast<const float*>(point_y);
342  iter->position.z = *reinterpret_cast<const float*>(point_z);
343  }
344 
345  return true;
346 }
347 
348 uint8_t RGB8PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
349 {
350  int32_t index = std::max(findChannelIndex(cloud, "rgb"), findChannelIndex(cloud, "rgba"));
351  if (index == -1)
352  {
353  return Support_None;
354  }
355 
356  if (cloud->fields[index].datatype == sensor_msgs::PointField::INT32 ||
357  cloud->fields[index].datatype == sensor_msgs::PointField::UINT32 ||
358  cloud->fields[index].datatype == sensor_msgs::PointField::FLOAT32)
359  {
360  return Support_Color;
361  }
362 
363  return Support_None;
364 }
365 
366 bool RGB8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
367  uint32_t mask,
368  const Ogre::Matrix4& /*transform*/,
369  V_PointCloudPoint& points_out)
370 {
371  if (!(mask & Support_Color))
372  {
373  return false;
374  }
375 
376  const int32_t rgb = findChannelIndex(cloud, "rgb");
377  const int32_t rgba = findChannelIndex(cloud, "rgba");
378  const int32_t index = std::max(rgb, rgba);
379 
380  const uint32_t off = cloud->fields[index].offset;
381  uint8_t const* rgb_ptr = &cloud->data.front() + off;
382  const uint32_t point_step = cloud->point_step;
383 
384  // Create a look-up table for colors
385  float rgb_lut[256];
386  for (int i = 0; i < 256; ++i)
387  {
388  rgb_lut[i] = float(i) / 255.0f;
389  }
390  if (rgb != -1) // rgb
391  {
392  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end();
393  ++iter, rgb_ptr += point_step)
394  {
395  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
396  iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
397  iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
398  iter->color.b = rgb_lut[rgb & 0xff];
399  iter->color.a = 1.0f;
400  }
401  }
402  else // rgba
403  {
404  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end();
405  ++iter, rgb_ptr += point_step)
406  {
407  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
408  iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
409  iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
410  iter->color.b = rgb_lut[rgb & 0xff];
411  iter->color.a = rgb_lut[rgb >> 24];
412  }
413  }
414 
415  return true;
416 }
417 
418 bool MONO8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
419  uint32_t mask,
420  const Ogre::Matrix4& /*transform*/,
421  V_PointCloudPoint& points_out)
422 {
423  if (!(mask & Support_Color))
424  {
425  return false;
426  }
427 
428  const int32_t rgb = findChannelIndex(cloud, "rgb");
429  const int32_t rgba = findChannelIndex(cloud, "rgba");
430  const int32_t index = std::max(rgb, rgba);
431 
432  const uint32_t off = cloud->fields[index].offset;
433  uint8_t const* rgb_ptr = &cloud->data.front() + off;
434  const uint32_t point_step = cloud->point_step;
435 
436  // Create a look-up table for colors
437  float rgb_lut[256];
438  for (int i = 0; i < 256; ++i)
439  {
440  rgb_lut[i] = float(i) / 255.0f;
441  }
442  if (rgb != -1) // rgb
443  {
444  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end();
445  ++iter, rgb_ptr += point_step)
446  {
447  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
448  float r = rgb_lut[(rgb >> 16) & 0xff];
449  float g = rgb_lut[(rgb >> 8) & 0xff];
450  float b = rgb_lut[rgb & 0xff];
451  float mono = 0.2989 * r + 0.5870 * g + 0.1140 * b;
452  iter->color.r = iter->color.g = iter->color.b = mono;
453  iter->color.a = 1.0f;
454  }
455  }
456  else // rgba
457  {
458  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end();
459  ++iter, rgb_ptr += point_step)
460  {
461  uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
462  float r = rgb_lut[(rgb >> 16) & 0xff];
463  float g = rgb_lut[(rgb >> 8) & 0xff];
464  float b = rgb_lut[rgb & 0xff];
465  float mono = 0.2989 * r + 0.5870 * g + 0.1140 * b;
466  iter->color.r = iter->color.g = iter->color.b = mono;
467  iter->color.a = rgb_lut[rgb >> 24];
468  }
469  }
470 
471  return true;
472 }
473 
474 uint8_t RGBF32PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
475 {
476  int32_t ri = findChannelIndex(cloud, "r");
477  int32_t gi = findChannelIndex(cloud, "g");
478  int32_t bi = findChannelIndex(cloud, "b");
479  if (ri == -1 || gi == -1 || bi == -1)
480  {
481  return Support_None;
482  }
483 
484  if (cloud->fields[ri].datatype == sensor_msgs::PointField::FLOAT32)
485  {
486  return Support_Color;
487  }
488 
489  return Support_None;
490 }
491 
492 bool RGBF32PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
493  uint32_t mask,
494  const Ogre::Matrix4& /*transform*/,
495  V_PointCloudPoint& points_out)
496 {
497  if (!(mask & Support_Color))
498  {
499  return false;
500  }
501 
502  int32_t ri = findChannelIndex(cloud, "r");
503  int32_t gi = findChannelIndex(cloud, "g");
504  int32_t bi = findChannelIndex(cloud, "b");
505 
506  const uint32_t roff = cloud->fields[ri].offset;
507  const uint32_t goff = cloud->fields[gi].offset;
508  const uint32_t boff = cloud->fields[bi].offset;
509  const uint32_t point_step = cloud->point_step;
510  const uint32_t num_points = cloud->width * cloud->height;
511  uint8_t const* point = &cloud->data.front();
512  for (uint32_t i = 0; i < num_points; ++i, point += point_step)
513  {
514  float r = *reinterpret_cast<const float*>(point + roff);
515  float g = *reinterpret_cast<const float*>(point + goff);
516  float b = *reinterpret_cast<const float*>(point + boff);
517  points_out[i].color = Ogre::ColourValue(r, g, b);
518  }
519 
520  return true;
521 }
522 
523 uint8_t FlatColorPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& /*cloud*/)
524 {
525  return Support_Color;
526 }
527 
528 uint8_t FlatColorPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& /*cloud*/)
529 {
530  return 0;
531 }
532 
533 bool FlatColorPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
534  uint32_t mask,
535  const Ogre::Matrix4& /*transform*/,
536  V_PointCloudPoint& points_out)
537 {
538  if (!(mask & Support_Color))
539  {
540  return false;
541  }
542 
543  Ogre::ColourValue color = color_property_->getOgreColor();
544 
545  const uint32_t num_points = cloud->width * cloud->height;
546  for (uint32_t i = 0; i < num_points; ++i)
547  {
548  points_out[i].color = color;
549  }
550 
551  return true;
552 }
553 
555  uint32_t mask,
556  QList<Property*>& out_props)
557 {
558  if (mask & Support_Color)
559  {
560  color_property_ = new ColorProperty("Color", Qt::white, "Color to assign to every point.",
561  parent_property, &IntensityPCTransformer::needRetransform, this);
562  out_props.push_back(color_property_);
563  }
564 }
565 
566 uint8_t AxisColorPCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& /*cloud*/)
567 {
568  return Support_Color;
569 }
570 
571 uint8_t AxisColorPCTransformer::score(const sensor_msgs::PointCloud2ConstPtr& /*cloud*/)
572 {
573  return 255;
574 }
575 
576 bool AxisColorPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
577  uint32_t mask,
578  const Ogre::Matrix4& transform,
579  V_PointCloudPoint& points_out)
580 {
581  if (!(mask & Support_Color))
582  {
583  return false;
584  }
585 
586  int32_t xi = findChannelIndex(cloud, "x");
587  int32_t yi = findChannelIndex(cloud, "y");
588  int32_t zi = findChannelIndex(cloud, "z");
589 
590  const uint32_t xoff = cloud->fields[xi].offset;
591  const uint32_t yoff = cloud->fields[yi].offset;
592  const uint32_t zoff = cloud->fields[zi].offset;
593  const uint32_t point_step = cloud->point_step;
594  const uint32_t num_points = cloud->width * cloud->height;
595  uint8_t const* point = &cloud->data.front();
596 
597  // Fill a vector of floats with values based on the chosen axis.
598  int axis = axis_property_->getOptionInt();
599  std::vector<float> values;
600  values.reserve(num_points);
601  Ogre::Vector3 pos;
603  {
604  for (uint32_t i = 0; i < num_points; ++i, point += point_step)
605  {
606  // TODO: optimize this by only doing the multiplication needed
607  // for the desired output value, instead of doing all of them
608  // and then throwing most away.
609  pos.x = *reinterpret_cast<const float*>(point + xoff);
610  pos.y = *reinterpret_cast<const float*>(point + yoff);
611  pos.z = *reinterpret_cast<const float*>(point + zoff);
612 
613  pos = transform * pos;
614  values.push_back(pos[axis]);
615  }
616  }
617  else
618  {
619  const uint32_t offsets[3] = {xoff, yoff, zoff};
620  const uint32_t off = offsets[axis];
621  for (uint32_t i = 0; i < num_points; ++i, point += point_step)
622  {
623  values.push_back(*reinterpret_cast<const float*>(point + off));
624  }
625  }
626  float min_value_current = 9999.0f;
627  float max_value_current = -9999.0f;
629  {
630  for (uint32_t i = 0; i < num_points; i++)
631  {
632  float val = values[i];
633  min_value_current = std::min(min_value_current, val);
634  max_value_current = std::max(max_value_current, val);
635  }
636  min_value_property_->setFloat(min_value_current);
637  max_value_property_->setFloat(max_value_current);
638  }
639  else
640  {
641  min_value_current = min_value_property_->getFloat();
642  max_value_current = max_value_property_->getFloat();
643  }
644 
645  float range = max_value_current - min_value_current;
646  if (range == 0)
647  {
648  range = 0.001f;
649  }
650  for (uint32_t i = 0; i < num_points; ++i)
651  {
652  float value = 1.0 - (values[i] - min_value_current) / range;
653  getRainbowColor(value, points_out[i].color);
654  }
655 
656  return true;
657 }
658 
660  uint32_t mask,
661  QList<Property*>& out_props)
662 {
663  if (mask & Support_Color)
664  {
665  axis_property_ = new EnumProperty("Axis", "Z", "The axis to interpolate the color along.",
666  parent_property, &IntensityPCTransformer::needRetransform, this);
670 
672  new BoolProperty("Autocompute Value Bounds", true,
673  "Whether to automatically compute the value min/max values.", parent_property,
675 
677  new FloatProperty("Min Value", -10,
678  "Minimum value value, used to interpolate the color of a point.",
680 
682  new FloatProperty("Max Value", 10,
683  "Maximum value value, used to interpolate the color of a point.",
685 
687  "Use Fixed Frame", true,
688  "Whether to color the cloud based on its fixed frame position or its local frame position.",
689  parent_property, &IntensityPCTransformer::needRetransform, this);
690 
691  out_props.push_back(axis_property_);
692  out_props.push_back(auto_compute_bounds_property_);
693  out_props.push_back(use_fixed_frame_property_);
694 
696  }
697 }
698 
700 {
701  bool auto_compute = auto_compute_bounds_property_->getBool();
702  min_value_property_->setHidden(auto_compute);
703  max_value_property_->setHidden(auto_compute);
704  if (auto_compute)
705  {
708  }
709  else
710  {
714  }
715  Q_EMIT needRetransform();
716 }
717 
718 } // end namespace rviz
719 
rviz::BoolProperty::getBool
virtual bool getBool() const
Definition: bool_property.cpp:48
rviz::EnumProperty::getOptionInt
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
Definition: enum_property.cpp:56
rviz::PointCloudTransformer::Support_None
@ Support_None
Definition: point_cloud_transformer.h:75
rviz::AxisColorPCTransformer::supports
uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Definition: point_cloud_transformers.cpp:566
rviz::findChannelIndex
int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr &cloud, const std::string &channel)
Definition: point_cloud_transformers.h:47
validate_floats.h
rviz::AxisColorPCTransformer::AXIS_X
@ AXIS_X
Definition: point_cloud_transformers.h:223
rviz::Property::setHidden
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Definition: property.cpp:566
rviz::FlatColorPCTransformer
Definition: point_cloud_transformers.h:193
rviz::IntensityPCTransformer
Definition: point_cloud_transformers.h:116
rviz::FlatColorPCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:533
rviz::AxisColorPCTransformer::use_fixed_frame_property_
BoolProperty * use_fixed_frame_property_
Definition: point_cloud_transformers.h:236
rviz::IntensityPCTransformer::max_color_property_
ColorProperty * max_color_property_
Definition: point_cloud_transformers.h:137
rviz::EditableEnumProperty
Editable Enum property.
Definition: editable_enum_property.h:43
rviz::BoolProperty
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
rviz::AxisColorPCTransformer
Definition: point_cloud_transformers.h:209
rviz::IntensityPCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:82
rviz::AxisColorPCTransformer::auto_compute_bounds_property_
BoolProperty * auto_compute_bounds_property_
Definition: point_cloud_transformers.h:232
rviz::RGB8PCTransformer
Definition: point_cloud_transformers.h:158
rviz::V_PointCloudPoint
std::vector< PointCloud::Point > V_PointCloudPoint
Definition: point_cloud_transformer.h:56
rviz::RGB8PCTransformer::supports
uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Definition: point_cloud_transformers.cpp:348
rviz::IntensityPCTransformer::max_intensity_property_
FloatProperty * max_intensity_property_
Definition: point_cloud_transformers.h:142
rviz::IntensityPCTransformer::supports
uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Definition: point_cloud_transformers.cpp:71
rviz::IntensityPCTransformer::updateAutoComputeIntensityBounds
void updateAutoComputeIntensityBounds()
Definition: point_cloud_transformers.cpp:268
rviz::AxisColorPCTransformer::min_value_property_
FloatProperty * min_value_property_
Definition: point_cloud_transformers.h:233
float_property.h
bool_property.h
rviz::PointCloudTransformer::needRetransform
void needRetransform()
Subclasses should emit this signal whenever they think the points should be re-transformed.
rviz::RGBF32PCTransformer
Definition: point_cloud_transformers.h:181
rviz::IntensityPCTransformer::updateChannels
void updateChannels(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: point_cloud_transformers.cpp:243
rviz::EditableEnumProperty::addOptionStd
void addOptionStd(const std::string &option)
Definition: editable_enum_property.h:78
f
f
rviz::ColorProperty
Definition: color_property.h:40
rviz::RGBF32PCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:492
rviz::MONO8PCTransformer
Definition: point_cloud_transformers.h:170
rviz::EnumProperty
Enum property.
Definition: enum_property.h:46
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::IntensityPCTransformer::score
uint8_t score(const sensor_msgs::PointCloud2ConstPtr &cloud) override
"Score" a message for how well supported the message is. For example, a "flat color" transformer can ...
Definition: point_cloud_transformers.cpp:77
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
rviz::IntensityPCTransformer::createProperties
void createProperties(Property *parent_property, uint32_t mask, QList< Property * > &out_props) override
Create any properties necessary for this transformer. Will be called once when the transformer is loa...
Definition: point_cloud_transformers.cpp:180
rviz::V_string
std::vector< std::string > V_string
Definition: effort_display.h:72
rviz::IntensityPCTransformer::invert_rainbow_property_
BoolProperty * invert_rainbow_property_
Definition: point_cloud_transformers.h:140
rviz::AxisColorPCTransformer::AXIS_Z
@ AXIS_Z
Definition: point_cloud_transformers.h:225
rviz::FlatColorPCTransformer::color_property_
ColorProperty * color_property_
Definition: point_cloud_transformers.h:206
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz::EnumProperty::addOption
virtual void addOption(const QString &option, int value=0)
Definition: enum_property.cpp:50
rviz::AxisColorPCTransformer::max_value_property_
FloatProperty * max_value_property_
Definition: point_cloud_transformers.h:234
rviz::Property::expand
virtual void expand()
Expand (show the children of) this Property.
Definition: property.cpp:578
rviz
Definition: add_display_dialog.cpp:54
color_property.h
rviz::IntensityPCTransformer::channel_name_property_
EditableEnumProperty * channel_name_property_
Definition: point_cloud_transformers.h:143
rviz::StringProperty::getStdString
std::string getStdString()
Definition: string_property.h:71
rviz::IntensityPCTransformer::updateUseRainbow
void updateUseRainbow()
Definition: point_cloud_transformers.cpp:288
rviz::EditableEnumProperty::clearOptions
virtual void clearOptions()
Definition: editable_enum_property.cpp:45
rviz::PointCloudTransformer
Definition: point_cloud_transformer.h:60
rviz::PointCloudTransformer::Support_XYZ
@ Support_XYZ
Definition: point_cloud_transformer.h:76
ogre_vector.h
rviz::AxisColorPCTransformer::createProperties
void createProperties(Property *parent_property, uint32_t mask, QList< Property * > &out_props) override
Create any properties necessary for this transformer. Will be called once when the transformer is loa...
Definition: point_cloud_transformers.cpp:659
rviz::IntensityPCTransformer::auto_compute_intensity_bounds_property_
BoolProperty * auto_compute_intensity_bounds_property_
Definition: point_cloud_transformers.h:138
rviz::XYZPCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:316
point_cloud_transformers.h
rviz::getRainbowColor
static void getRainbowColor(float value, Ogre::ColourValue &color)
Definition: point_cloud_transformers.cpp:45
rviz::IntensityPCTransformer::min_intensity_property_
FloatProperty * min_intensity_property_
Definition: point_cloud_transformers.h:141
rviz::AxisColorPCTransformer::score
uint8_t score(const sensor_msgs::PointCloud2ConstPtr &cloud) override
"Score" a message for how well supported the message is. For example, a "flat color" transformer can ...
Definition: point_cloud_transformers.cpp:571
rviz::FlatColorPCTransformer::supports
uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Definition: point_cloud_transformers.cpp:523
rviz::MONO8PCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:418
rviz::AxisColorPCTransformer::axis_property_
EnumProperty * axis_property_
Definition: point_cloud_transformers.h:235
rviz::IntensityPCTransformer::available_channels_
V_string available_channels_
Definition: point_cloud_transformers.h:134
rviz::PointCloudTransformer::Support_Color
@ Support_Color
Definition: point_cloud_transformer.h:77
rviz::AxisColorPCTransformer::updateAutoComputeBounds
void updateAutoComputeBounds()
Definition: point_cloud_transformers.cpp:699
rviz::AxisColorPCTransformer::AXIS_Y
@ AXIS_Y
Definition: point_cloud_transformers.h:224
values
std::vector< double > values
rviz::FloatProperty::setFloat
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
Definition: float_property.h:97
rviz::FlatColorPCTransformer::score
uint8_t score(const sensor_msgs::PointCloud2ConstPtr &cloud) override
"Score" a message for how well supported the message is. For example, a "flat color" transformer can ...
Definition: point_cloud_transformers.cpp:528
rviz::Property::setReadOnly
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:497
class_list_macros.hpp
editable_enum_property.h
rviz::Property::changed
void changed()
Emitted by setValue() just after the value has changed.
rviz::RGB8PCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:366
rviz::FlatColorPCTransformer::createProperties
void createProperties(Property *parent_property, uint32_t mask, QList< Property * > &out_props) override
Create any properties necessary for this transformer. Will be called once when the transformer is loa...
Definition: point_cloud_transformers.cpp:554
rviz::IntensityPCTransformer::use_rainbow_property_
BoolProperty * use_rainbow_property_
Definition: point_cloud_transformers.h:139
rviz::AxisColorPCTransformer::transform
bool transform(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preal...
Definition: point_cloud_transformers.cpp:576
rviz::IntensityPCTransformer::min_color_property_
ColorProperty * min_color_property_
Definition: point_cloud_transformers.h:136
rviz::XYZPCTransformer
Definition: point_cloud_transformers.h:146
rviz::XYZPCTransformer::supports
uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Definition: point_cloud_transformers.cpp:297
rviz::RGBF32PCTransformer::supports
uint8_t supports(const sensor_msgs::PointCloud2ConstPtr &cloud) override
Returns a level of support for a specific cloud. This level of support is a mask using the SupportLev...
Definition: point_cloud_transformers.cpp:474
rviz::ColorProperty::getOgreColor
Ogre::ColourValue getOgreColor() const
Definition: color_property.h:83
enum_property.h


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02