Point Cloud Library (PCL)  1.9.1
PCLPointCloud2.h
1 #ifndef PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
2 #define PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
3 
4 #ifdef USE_ROS
5  #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated
6 #endif
7 
8 #include <string>
9 #include <vector>
10 #include <ostream>
11 #include <boost/predef/other/endian.h>
12 
13 // Include the correct Header path here
14 #include <pcl/PCLHeader.h>
15 #include <pcl/PCLPointField.h>
16 
17 namespace pcl
18 {
19 
21  {
22  PCLPointCloud2 () : header (), height (0), width (0), fields (),
23  is_bigendian (false), point_step (0), row_step (0),
24  data (), is_dense (false)
25  {
26 #if BOOST_ENDIAN_BIG_BYTE
27  is_bigendian = true;
28 #elif BOOST_ENDIAN_LITTLE_BYTE
29  is_bigendian = false;
30 #else
31 #error "unable to determine system endianness"
32 #endif
33  }
34 
36 
37  pcl::uint32_t height;
38  pcl::uint32_t width;
39 
40  std::vector< ::pcl::PCLPointField> fields;
41 
42  pcl::uint8_t is_bigendian;
43  pcl::uint32_t point_step;
44  pcl::uint32_t row_step;
45 
46  std::vector<pcl::uint8_t> data;
47 
48  pcl::uint8_t is_dense;
49 
50  public:
51  typedef boost::shared_ptr< ::pcl::PCLPointCloud2> Ptr;
52  typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> ConstPtr;
53  }; // struct PCLPointCloud2
54 
55  typedef boost::shared_ptr< ::pcl::PCLPointCloud2> PCLPointCloud2Ptr;
56  typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> PCLPointCloud2ConstPtr;
57 
58  inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLPointCloud2 &v)
59  {
60  s << "header: " << std::endl;
61  s << v.header;
62  s << "height: ";
63  s << " " << v.height << std::endl;
64  s << "width: ";
65  s << " " << v.width << std::endl;
66  s << "fields[]" << std::endl;
67  for (size_t i = 0; i < v.fields.size (); ++i)
68  {
69  s << " fields[" << i << "]: ";
70  s << std::endl;
71  s << " " << v.fields[i] << std::endl;
72  }
73  s << "is_bigendian: ";
74  s << " " << v.is_bigendian << std::endl;
75  s << "point_step: ";
76  s << " " << v.point_step << std::endl;
77  s << "row_step: ";
78  s << " " << v.row_step << std::endl;
79  s << "data[]" << std::endl;
80  for (size_t i = 0; i < v.data.size (); ++i)
81  {
82  s << " data[" << i << "]: ";
83  s << " " << v.data[i] << std::endl;
84  }
85  s << "is_dense: ";
86  s << " " << v.is_dense << std::endl;
87 
88  return (s);
89  }
90 
91 } // namespace pcl
92 
93 #endif // PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
94 
pcl
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
pcl::PCLPointCloud2::height
pcl::uint32_t height
Definition: PCLPointCloud2.h:37
pcl::PCLPointCloud2::row_step
pcl::uint32_t row_step
Definition: PCLPointCloud2.h:44
pcl::PCLPointCloud2ConstPtr
boost::shared_ptr< ::pcl::PCLPointCloud2 const > PCLPointCloud2ConstPtr
Definition: PCLPointCloud2.h:56
pcl::PCLPointCloud2::fields
std::vector< ::pcl::PCLPointField > fields
Definition: PCLPointCloud2.h:40
pcl::PCLPointCloud2::header
::pcl::PCLHeader header
Definition: PCLPointCloud2.h:35
pcl::operator<<
std::ostream & operator<<(std::ostream &os, const BivariatePolynomialT< real > &p)
Definition: bivariate_polynomial.hpp:230
pcl::PCLPointCloud2::is_dense
pcl::uint8_t is_dense
Definition: PCLPointCloud2.h:48
pcl::PCLPointCloud2::point_step
pcl::uint32_t point_step
Definition: PCLPointCloud2.h:43
pcl::PCLPointCloud2::PCLPointCloud2
PCLPointCloud2()
Definition: PCLPointCloud2.h:22
pcl::PCLPointCloud2::is_bigendian
pcl::uint8_t is_bigendian
Definition: PCLPointCloud2.h:42
pcl::PCLPointCloud2
Definition: PCLPointCloud2.h:20
pcl::PCLPointCloud2::width
pcl::uint32_t width
Definition: PCLPointCloud2.h:38
pcl::PCLPointCloud2::data
std::vector< pcl::uint8_t > data
Definition: PCLPointCloud2.h:46
pcl::PCLPointCloud2Ptr
boost::shared_ptr< ::pcl::PCLPointCloud2 > PCLPointCloud2Ptr
Definition: PCLPointCloud2.h:55
pcl::PCLPointCloud2::ConstPtr
boost::shared_ptr< ::pcl::PCLPointCloud2 const > ConstPtr
Definition: PCLPointCloud2.h:52
pcl::PCLHeader
Definition: PCLHeader.h:16
pcl::PCLPointCloud2::Ptr
boost::shared_ptr< ::pcl::PCLPointCloud2 > Ptr
Definition: PCLPointCloud2.h:51