point_cloud_transformers.h
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 #ifndef POINT_CLOUD_TRANSFORMERS_H
31 #define POINT_CLOUD_TRANSFORMERS_H
32 
33 #include <sensor_msgs/PointCloud2.h>
34 
36 
37 namespace rviz
38 {
39 class BoolProperty;
40 class ColorProperty;
41 class EditableEnumProperty;
42 class EnumProperty;
43 class FloatProperty;
44 
45 typedef std::vector<std::string> V_string;
46 
47 inline int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr& cloud, const std::string& channel)
48 {
49  for (size_t i = 0; i < cloud->fields.size(); ++i)
50  {
51  if (cloud->fields[i].name == channel)
52  {
53  return i;
54  }
55  }
56 
57  return -1;
58 }
59 
60 template <typename T>
61 inline T valueFromCloud(const sensor_msgs::PointCloud2ConstPtr& cloud,
62  uint32_t offset,
63  uint8_t type,
64  uint32_t point_step,
65  uint32_t index)
66 {
67  const uint8_t* data = &cloud->data[(point_step * index) + offset];
68  T ret = 0;
69 
70  switch (type)
71  {
72  case sensor_msgs::PointField::INT8:
73  case sensor_msgs::PointField::UINT8:
74  {
75  uint8_t val = *reinterpret_cast<const uint8_t*>(data);
76  ret = static_cast<T>(val);
77  break;
78  }
79 
80  case sensor_msgs::PointField::INT16:
81  case sensor_msgs::PointField::UINT16:
82  {
83  uint16_t val = *reinterpret_cast<const uint16_t*>(data);
84  ret = static_cast<T>(val);
85  break;
86  }
87 
88  case sensor_msgs::PointField::INT32:
89  case sensor_msgs::PointField::UINT32:
90  {
91  uint32_t val = *reinterpret_cast<const uint32_t*>(data);
92  ret = static_cast<T>(val);
93  break;
94  }
95 
96  case sensor_msgs::PointField::FLOAT32:
97  {
98  float val = *reinterpret_cast<const float*>(data);
99  ret = static_cast<T>(val);
100  break;
101  }
102 
103  case sensor_msgs::PointField::FLOAT64:
104  {
105  double val = *reinterpret_cast<const double*>(data);
106  ret = static_cast<T>(val);
107  break;
108  }
109  default:
110  break;
111  }
112 
113  return ret;
114 }
115 
117 {
118  Q_OBJECT
119 public:
120  uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
121  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
122  uint32_t mask,
123  const Ogre::Matrix4& transform,
124  V_PointCloudPoint& points_out) override;
125  uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
126  void createProperties(Property* parent_property, uint32_t mask, QList<Property*>& out_props) override;
127  void updateChannels(const sensor_msgs::PointCloud2ConstPtr& cloud);
128 
129 private Q_SLOTS:
130  void updateUseRainbow();
132 
133 private:
135 
144 };
145 
147 {
148  Q_OBJECT
149 public:
150  uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
151  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
152  uint32_t mask,
153  const Ogre::Matrix4& transform,
154  V_PointCloudPoint& points_out) override;
155 };
156 
157 
159 {
160  Q_OBJECT
161 public:
162  uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
163  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
164  uint32_t mask,
165  const Ogre::Matrix4& transform,
166  V_PointCloudPoint& points_out) override;
167 };
168 
169 
171 {
172  Q_OBJECT
173 public:
174  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
175  uint32_t mask,
176  const Ogre::Matrix4& transform,
177  V_PointCloudPoint& points_out) override;
178 };
179 
180 
182 {
183  Q_OBJECT
184 public:
185  uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
186  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
187  uint32_t mask,
188  const Ogre::Matrix4& transform,
189  V_PointCloudPoint& points_out) override;
190 };
191 
192 
194 {
195  Q_OBJECT
196 public:
197  uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
198  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
199  uint32_t mask,
200  const Ogre::Matrix4& transform,
201  V_PointCloudPoint& points_out) override;
202  void createProperties(Property* parent_property, uint32_t mask, QList<Property*>& out_props) override;
203  uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
204 
205 private:
207 };
208 
210 {
211  Q_OBJECT
212 public:
213  uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
214  bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
215  uint32_t mask,
216  const Ogre::Matrix4& transform,
217  V_PointCloudPoint& points_out) override;
218  void createProperties(Property* parent_property, uint32_t mask, QList<Property*>& out_props) override;
219  uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud) override;
220 
221  enum Axis
222  {
226  };
227 
228 private Q_SLOTS:
230 
231 private:
237 };
238 
239 } // namespace rviz
240 
241 #endif // POINT_CLOUD_TRANSFORMERS_H
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
rviz::AxisColorPCTransformer::AXIS_X
@ AXIS_X
Definition: point_cloud_transformers.h:223
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
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::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::valueFromCloud
T valueFromCloud(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t offset, uint8_t type, uint32_t point_step, uint32_t index)
Definition: point_cloud_transformers.h:61
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
rviz::AxisColorPCTransformer::max_value_property_
FloatProperty * max_value_property_
Definition: point_cloud_transformers.h:234
rviz
Definition: add_display_dialog.cpp:54
rviz::IntensityPCTransformer::channel_name_property_
EditableEnumProperty * channel_name_property_
Definition: point_cloud_transformers.h:143
rviz::IntensityPCTransformer::updateUseRainbow
void updateUseRainbow()
Definition: point_cloud_transformers.cpp:288
rviz::PointCloudTransformer
Definition: point_cloud_transformer.h:60
rviz::AxisColorPCTransformer::Axis
Axis
Definition: point_cloud_transformers.h:221
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
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::AxisColorPCTransformer::updateAutoComputeBounds
void updateAutoComputeBounds()
Definition: point_cloud_transformers.cpp:699
rviz::AxisColorPCTransformer::AXIS_Y
@ AXIS_Y
Definition: point_cloud_transformers.h:224
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::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
point_cloud_transformer.h
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
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53