PointCloud2.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 // Generated by gencpp from file sensor_msgs/PointCloud2.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
7 #define SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
8 
9 
10 #include <string>
11 #include <vector>
12 #include <map>
13 
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
18 
19 #include <std_msgs/Header.h>
20 #include <sensor_msgs/PointField.h>
21 
22 namespace sensor_msgs
23 {
24 template <class ContainerAllocator>
26 {
28 
30  : header()
31  , height(0)
32  , width(0)
33  , fields()
34  , is_bigendian(false)
35  , point_step(0)
36  , row_step(0)
37  , data()
38  , is_dense(false) {
39  }
40  PointCloud2_(const ContainerAllocator& _alloc)
41  : header(_alloc)
42  , height(0)
43  , width(0)
44  , fields(_alloc)
45  , is_bigendian(false)
46  , point_step(0)
47  , row_step(0)
48  , data(_alloc)
49  , is_dense(false) {
50  (void)_alloc;
51  }
52 
53 
54 
55  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
57 
58  typedef uint32_t _height_type;
60 
61  typedef uint32_t _width_type;
63 
64  typedef std::vector< ::sensor_msgs::PointField_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_<ContainerAllocator> >::other > _fields_type;
66 
67  typedef uint8_t _is_bigendian_type;
69 
70  typedef uint32_t _point_step_type;
72 
73  typedef uint32_t _row_step_type;
75 
76  typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _data_type;
78 
79  typedef uint8_t _is_dense_type;
81 
82 
83 
84 
85  typedef std::shared_ptr< ::sensor_msgs::PointCloud2_<ContainerAllocator> > Ptr;
86  typedef std::shared_ptr< ::sensor_msgs::PointCloud2_<ContainerAllocator> const> ConstPtr;
87 
88 }; // struct PointCloud2_
89 
90 typedef ::sensor_msgs::PointCloud2_<std::allocator<void> > PointCloud2;
91 
92 typedef std::shared_ptr< ::sensor_msgs::PointCloud2 > PointCloud2Ptr;
93 typedef std::shared_ptr< ::sensor_msgs::PointCloud2 const> PointCloud2ConstPtr;
94 
95 // constants requiring out of line definition
96 
97 
98 
99 template<typename ContainerAllocator>
100 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointCloud2_<ContainerAllocator> & v)
101 {
103 return s;
104 }
105 
106 } // namespace sensor_msgs
107 
108 namespace roswrap
109 {
110 namespace message_traits
111 {
112 
113 
114 
115 // BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True}
116 // {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']}
117 
118 // !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
119 
120 
121 
122 
123 template <class ContainerAllocator>
124 struct IsFixedSize< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
125  : FalseType
126  { };
127 
128 template <class ContainerAllocator>
129 struct IsFixedSize< ::sensor_msgs::PointCloud2_<ContainerAllocator> const>
130  : FalseType
131  { };
132 
133 template <class ContainerAllocator>
134 struct IsMessage< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
135  : TrueType
136  { };
137 
138 template <class ContainerAllocator>
139 struct IsMessage< ::sensor_msgs::PointCloud2_<ContainerAllocator> const>
140  : TrueType
141  { };
142 
143 template <class ContainerAllocator>
144 struct HasHeader< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
145  : TrueType
146  { };
147 
148 template <class ContainerAllocator>
149 struct HasHeader< ::sensor_msgs::PointCloud2_<ContainerAllocator> const>
150  : TrueType
151  { };
152 
153 
154 template<class ContainerAllocator>
155 struct MD5Sum< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
156 {
157  static const char* value()
158  {
159  return "1158d486dd51d683ce2f1be655c3c181";
160  }
161 
162  static const char* value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) { return value(); }
163  static const uint64_t static_value1 = 0x1158d486dd51d683ULL;
164  static const uint64_t static_value2 = 0xce2f1be655c3c181ULL;
165 };
166 
167 template<class ContainerAllocator>
168 struct DataType< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
169 {
170  static const char* value()
171  {
172  return "sensor_msgs/PointCloud2";
173  }
174 
175  static const char* value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) { return value(); }
176 };
177 
178 template<class ContainerAllocator>
179 struct Definition< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
180 {
181  static const char* value()
182  {
183  return "# This message holds a collection of N-dimensional points, which may\n\
184 # contain additional information such as normals, intensity, etc. The\n\
185 # point data is stored as a binary blob, its layout described by the\n\
186 # contents of the \"fields\" array.\n\
187 \n\
188 # The point cloud data may be organized 2d (image-like) or 1d\n\
189 # (unordered). Point clouds organized as 2d images may be produced by\n\
190 # camera depth sensors such as stereo or time-of-flight.\n\
191 \n\
192 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
193 # points).\n\
194 Header header\n\
195 \n\
196 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
197 # 1 and width is the length of the point cloud.\n\
198 uint32 height\n\
199 uint32 width\n\
200 \n\
201 # Describes the channels and their layout in the binary data blob.\n\
202 PointField[] fields\n\
203 \n\
204 bool is_bigendian # Is this data bigendian?\n\
205 uint32 point_step # Length of a point in bytes\n\
206 uint32 row_step # Length of a row in bytes\n\
207 uint8[] data # Actual point data, size is (row_step*height)\n\
208 \n\
209 bool is_dense # True if there are no invalid points\n\
210 \n\
211 ================================================================================\n\
212 MSG: std_msgs/Header\n\
213 # Standard metadata for higher-level stamped data types.\n\
214 # This is generally used to communicate timestamped data \n\
215 # in a particular coordinate frame.\n\
216 # \n\
217 # sequence ID: consecutively increasing ID \n\
218 uint32 seq\n\
219 #Two-integer timestamp that is expressed as:\n\
220 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
221 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
222 # time-handling sugar is provided by the client library\n\
223 time stamp\n\
224 #Frame this data is associated with\n\
225 # 0: no frame\n\
226 # 1: global frame\n\
227 string frame_id\n\
228 \n\
229 ================================================================================\n\
230 MSG: sensor_msgs/PointField\n\
231 # This message holds the description of one point entry in the\n\
232 # PointCloud2 message format.\n\
233 uint8 INT8 = 1\n\
234 uint8 UINT8 = 2\n\
235 uint8 INT16 = 3\n\
236 uint8 UINT16 = 4\n\
237 uint8 INT32 = 5\n\
238 uint8 UINT32 = 6\n\
239 uint8 FLOAT32 = 7\n\
240 uint8 FLOAT64 = 8\n\
241 \n\
242 string name # Name of field\n\
243 uint32 offset # Offset from start of point struct\n\
244 uint8 datatype # Datatype enumeration, see above\n\
245 uint32 count # How many elements in the field\n\
246 ";
247  }
248 
249  static const char* value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) { return value(); }
250 };
251 
252 } // namespace message_traits
253 } // namespace roswrap
254 
255 namespace roswrap
256 {
257 namespace serialization
258 {
259 
260  template<class ContainerAllocator> struct Serializer< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
261  {
262  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
263  {
264  stream.next(m.header);
265  stream.next(m.height);
266  stream.next(m.width);
267  stream.next(m.fields);
268  stream.next(m.is_bigendian);
269  stream.next(m.point_step);
270  stream.next(m.row_step);
271  stream.next(m.data);
272  stream.next(m.is_dense);
273  }
274 
276  }; // struct PointCloud2_
277 
278 } // namespace serialization
279 } // namespace roswrap
280 
281 namespace roswrap
282 {
283 namespace message_operations
284 {
285 
286 template<class ContainerAllocator>
287 struct Printer< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
288 {
289  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::PointCloud2_<ContainerAllocator>& v)
290  {
291  s << indent << "header: ";
292  s << std::endl;
294  s << indent << "height: ";
295  Printer<uint32_t>::stream(s, indent + " ", v.height);
296  s << indent << "width: ";
297  Printer<uint32_t>::stream(s, indent + " ", v.width);
298  s << indent << "fields[]" << std::endl;
299  for (size_t i = 0; i < v.fields.size(); ++i)
300  {
301  s << indent << " fields[" << i << "]: ";
302  s << std::endl;
303  s << indent;
305  }
306  s << indent << "is_bigendian: ";
307  Printer<uint8_t>::stream(s, indent + " ", v.is_bigendian);
308  s << indent << "point_step: ";
309  Printer<uint32_t>::stream(s, indent + " ", v.point_step);
310  s << indent << "row_step: ";
311  Printer<uint32_t>::stream(s, indent + " ", v.row_step);
312  s << indent << "data[]" << std::endl;
313  for (size_t i = 0; i < v.data.size(); ++i)
314  {
315  s << indent << " data[" << i << "]: ";
316  Printer<uint8_t>::stream(s, indent + " ", v.data[i]);
317  }
318  s << indent << "is_dense: ";
319  Printer<uint8_t>::stream(s, indent + " ", v.is_dense);
320  }
321 };
322 
323 } // namespace message_operations
324 } // namespace roswrap
325 
326 #endif // SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
roswrap::message_traits::FalseType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:89
roswrap::message_traits::Definition< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::value
static const char * value()
Definition: PointCloud2.h:181
sensor_msgs::PointCloud2_::row_step
_row_step_type row_step
Definition: PointCloud2.h:74
multiscan_pcap_player.indent
indent
Definition: multiscan_pcap_player.py:252
sensor_msgs::PointCloud2_::width
_width_type width
Definition: PointCloud2.h:62
roswrap::serialization::Serializer
Templated serialization class. Default implementation provides backwards compatibility with old messa...
Definition: serialization.h:120
roswrap::message_traits::HasHeader
HasHeader informs whether or not there is a header that gets serialized as the first thing in the mes...
Definition: message_traits.h:107
sensor_msgs::PointCloud2_::point_step
_point_step_type point_step
Definition: PointCloud2.h:71
const
#define const
Definition: getopt.c:38
s
XmlRpcServer s
roswrap::message_traits::DataType< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
Definition: PointCloud2.h:175
sensor_msgs::PointCloud2
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
Definition: PointCloud2.h:90
roswrap::message_operations::Printer::stream
static void stream(Stream &s, const std::string &indent, const M &value)
Definition: message_operations.h:43
roswrap::message_traits::IsFixedSize
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Definition: message_traits.h:103
sensor_msgs::PointCloud2_::fields
_fields_type fields
Definition: PointCloud2.h:65
ros::message_operations::Printer
ROS_DECLARE_ALLINONE_SERIALIZER
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
Definition: serialization.h:74
sensor_msgs::PointCloud2_::height
_height_type height
Definition: PointCloud2.h:59
sensor_msgs::PointCloud2_::Ptr
std::shared_ptr< ::sensor_msgs::PointCloud2_< ContainerAllocator > > Ptr
Definition: PointCloud2.h:85
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
sensor_msgs::PointCloud2_::_row_step_type
uint32_t _row_step_type
Definition: PointCloud2.h:73
sensor_msgs::PointCloud2_::PointCloud2_
PointCloud2_(const ContainerAllocator &_alloc)
Definition: PointCloud2.h:40
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
sensor_msgs::PointCloud2_::data
_data_type data
Definition: PointCloud2.h:77
sensor_msgs::PointCloud2_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: PointCloud2.h:55
sensor_msgs::operator<<
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
Definition: BatteryState.h:187
roswrap::message_traits::MD5Sum< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::value
static const char * value()
Definition: PointCloud2.h:157
sensor_msgs::PointCloud2_::_is_dense_type
uint8_t _is_dense_type
Definition: PointCloud2.h:79
sensor_msgs::PointCloud2_::_height_type
uint32_t _height_type
Definition: PointCloud2.h:58
sensor_msgs::PointCloud2_::_is_bigendian_type
uint8_t _is_bigendian_type
Definition: PointCloud2.h:67
PointField.h
sensor_msgs::PointCloud2_::PointCloud2_
PointCloud2_()
Definition: PointCloud2.h:29
sensor_msgs::PointCloud2_::Type
PointCloud2_< ContainerAllocator > Type
Definition: PointCloud2.h:27
sensor_msgs::PointCloud2_::_data_type
std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > _data_type
Definition: PointCloud2.h:76
sensor_msgs::PointCloud2_::ConstPtr
std::shared_ptr< ::sensor_msgs::PointCloud2_< ContainerAllocator > const > ConstPtr
Definition: PointCloud2.h:86
sensor_msgs::PointCloud2_::_point_step_type
uint32_t _point_step_type
Definition: PointCloud2.h:70
sensor_msgs::PointCloud2_::is_bigendian
_is_bigendian_type is_bigendian
Definition: PointCloud2.h:68
roswrap
Definition: param_modi.cpp:41
roswrap::message_traits::MD5Sum< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
Definition: PointCloud2.h:162
roswrap::message_operations::Printer
Definition: message_operations.h:40
std_msgs::Header_
Definition: Header.h:23
sensor_msgs::PointCloud2_::_width_type
uint32_t _width_type
Definition: PointCloud2.h:61
sensor_msgs::PointCloud2_::_fields_type
std::vector< ::sensor_msgs::PointField_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_< ContainerAllocator > >::other > _fields_type
Definition: PointCloud2.h:64
roswrap::message_traits::TrueType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:79
roswrap::message_traits::MD5Sum
Specialize to provide the md5sum for a message.
Definition: message_traits.h:118
sensor_msgs::PointCloud2_
Definition: PointCloud2.h:25
sensor_msgs::PointCloud2Ptr
std::shared_ptr< ::sensor_msgs::PointCloud2 > PointCloud2Ptr
Definition: PointCloud2.h:92
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
roswrap::message_operations::Printer< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::PointCloud2_< ContainerAllocator > &v)
Definition: PointCloud2.h:289
roswrap::serialization::Serializer< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: PointCloud2.h:262
sick_scan_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
sensor_msgs::PointCloud2_::header
_header_type header
Definition: PointCloud2.h:56
sensor_msgs
Tools for manipulating sensor_msgs.
roswrap::message_traits::DataType< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::value
static const char * value()
Definition: PointCloud2.h:170
Header.h
sensor_msgs::PointCloud2ConstPtr
std::shared_ptr< ::sensor_msgs::PointCloud2 const > PointCloud2ConstPtr
Definition: PointCloud2.h:93
sensor_msgs::PointCloud2_::is_dense
_is_dense_type is_dense
Definition: PointCloud2.h:80
roswrap::message_traits::Definition< ::sensor_msgs::PointCloud2_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
Definition: PointCloud2.h:249


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09