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 
40 class BoolProperty;
41 class ColorProperty;
42 class EditableEnumProperty;
43 class EnumProperty;
44 class FloatProperty;
45 
46 typedef std::vector<std::string> V_string;
47 
48 inline int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr& cloud, const std::string& channel)
49 {
50  for (size_t i = 0; i < cloud->fields.size(); ++i)
51  {
52  if (cloud->fields[i].name == channel)
53  {
54  return i;
55  }
56  }
57 
58  return -1;
59 }
60 
61 template<typename T>
62 inline T valueFromCloud(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t offset, uint8_t type, uint32_t point_step, uint32_t index)
63 {
64  const uint8_t* data = &cloud->data[(point_step * index) + offset];
65  T ret = 0;
66 
67  switch (type)
68  {
69  case sensor_msgs::PointField::INT8:
70  case sensor_msgs::PointField::UINT8:
71  {
72  uint8_t val = *reinterpret_cast<const uint8_t*>(data);
73  ret = static_cast<T>(val);
74  break;
75  }
76 
77  case sensor_msgs::PointField::INT16:
78  case sensor_msgs::PointField::UINT16:
79  {
80  uint16_t val = *reinterpret_cast<const uint16_t*>(data);
81  ret = static_cast<T>(val);
82  break;
83  }
84 
85  case sensor_msgs::PointField::INT32:
86  case sensor_msgs::PointField::UINT32:
87  {
88  uint32_t val = *reinterpret_cast<const uint32_t*>(data);
89  ret = static_cast<T>(val);
90  break;
91  }
92 
93  case sensor_msgs::PointField::FLOAT32:
94  {
95  float val = *reinterpret_cast<const float*>(data);
96  ret = static_cast<T>(val);
97  break;
98  }
99 
100  case sensor_msgs::PointField::FLOAT64:
101  {
102  double val = *reinterpret_cast<const double*>(data);
103  ret = static_cast<T>(val);
104  break;
105  }
106  default:
107  break;
108  }
109 
110  return ret;
111 }
112 
114 {
115 Q_OBJECT
116 public:
117  virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud);
118  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
119  uint32_t mask,
120  const Ogre::Matrix4& transform,
121  V_PointCloudPoint& points_out);
122  virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud);
123  virtual void createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props );
124  void updateChannels(const sensor_msgs::PointCloud2ConstPtr& cloud);
125 
126 private Q_SLOTS:
127  void updateUseRainbow();
129 
130 private:
132 
141 };
142 
144 {
145 Q_OBJECT
146 public:
147  virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud);
148  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out);
149 };
150 
151 
152 
154 {
155 Q_OBJECT
156 public:
157  virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud);
158  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out);
159 };
160 
161 
162 
164 {
165 Q_OBJECT
166 public:
167  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out);
168 };
169 
170 
171 
173 {
174 Q_OBJECT
175 public:
176  virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud);
177  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out);
178 };
179 
180 
181 
183 {
184 Q_OBJECT
185 public:
186  virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud);
187  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out);
188  virtual void createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props );
189  virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud);
190 
191 private:
193 };
194 
196 {
197 Q_OBJECT
198 public:
199  virtual uint8_t supports(const sensor_msgs::PointCloud2ConstPtr& cloud);
200  virtual bool transform(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t mask, const Ogre::Matrix4& transform, V_PointCloudPoint& points_out);
201  virtual void createProperties( Property* parent_property, uint32_t mask, QList<Property*>& out_props );
202  virtual uint8_t score(const sensor_msgs::PointCloud2ConstPtr& cloud);
203 
204  enum Axis
205  {
208  AXIS_Z
209  };
210 
211 private Q_SLOTS:
212  void updateAutoComputeBounds();
213 
214 private:
220 };
221 
222 }
223 
224 #endif // POINT_CLOUD_TRANSFORMERS_H
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 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
EditableEnumProperty * channel_name_property_
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...
Property specialized to enforce floating point max/min.
void updateChannels(const sensor_msgs::PointCloud2ConstPtr &cloud)
std::vector< PointCloud::Point > V_PointCloudPoint
std::vector< std::string > V_string
T valueFromCloud(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t offset, uint8_t type, uint32_t point_step, uint32_t index)
int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr &cloud, const std::string &channel)
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
BoolProperty * auto_compute_intensity_bounds_property_
Enum property.
Definition: enum_property.h:47


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51