Point Cloud Library (PCL)  1.3.1
PointCloud2.h
Go to the documentation of this file.
00001 #ifndef PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
00002 #define PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
00003 #include <string>
00004 #include <vector>
00005 #include <ostream>
00006 
00007 // Include the correct Header path here
00008 #include "std_msgs/Header.h"
00009 #include "sensor_msgs/PointField.h"
00010 
00011 namespace sensor_msgs
00012 {
00013 
00014 #if (defined(__powerpc) || defined(__powerpc__) || defined(__POWERPC__) || defined(__ppc__) || defined(_M_PPC) || defined(__ARCH_PPC))
00015 #  define PCL_BIG_ENDIAN
00016 #elif (defined(i386) || defined(__i386__) || defined(__i386) || defined(_M_IX86) || defined(_X86_) || defined(__THW_INTEL__) || defined(__I86__) || defined(__INTEL__)) \
00017   || (defined(__amd64__) || defined(__amd64) || defined(__x86_64__) || defined(__x86_64) || defined(_M_X64)) \
00018   || (defined(__ANDROID__))
00019 #  define PCL_LITTLE_ENDIAN
00020 #else
00021 #  error
00022 #endif
00023 
00024   struct PointCloud2
00025   {
00026     PointCloud2 () : header (), height (0), width (0), fields (),
00027                      point_step (0), row_step (0),
00028                      data (), is_dense (false)
00029     {
00030 #ifdef PCL_BIG_ENDIAN
00031       is_bigendian = true;
00032 #elif defined(PCL_LITTLE_ENDIAN)
00033       is_bigendian = false;
00034 #else
00035 #      error
00036 #endif
00037     }
00038 
00039 #undef PCL_BIG_ENDIAN
00040 #undef PCL_LITTLE_ENDIAN
00041 
00042     ::std_msgs::Header header;
00043 
00044     pcl::uint32_t height;
00045     pcl::uint32_t width;
00046 
00047     std::vector< ::sensor_msgs::PointField>  fields;
00048 
00049     pcl::uint8_t is_bigendian;
00050     pcl::uint32_t point_step;
00051     pcl::uint32_t row_step;
00052 
00053     std::vector<pcl::uint8_t> data;
00054 
00055     pcl::uint8_t is_dense;
00056 
00057   public:
00058     typedef boost::shared_ptr< ::sensor_msgs::PointCloud2> Ptr;
00059     typedef boost::shared_ptr< ::sensor_msgs::PointCloud2  const> ConstPtr;
00060   }; // struct PointCloud2
00061 
00062   typedef boost::shared_ptr< ::sensor_msgs::PointCloud2> PointCloud2Ptr;
00063   typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 const> PointCloud2ConstPtr;
00064 
00065   inline std::ostream& operator<<(std::ostream& s, const  ::sensor_msgs::PointCloud2 &v)
00066   {
00067     s << "header: " << std::endl;
00068     s << v.header;
00069     s << "height: ";
00070     s << "  " << v.height << std::endl;
00071     s << "width: ";
00072     s << "  " << v.width << std::endl;
00073     s << "fields[]" << std::endl;
00074     for (size_t i = 0; i < v.fields.size (); ++i)
00075     {
00076       s << "  fields[" << i << "]: ";
00077       s << std::endl;
00078       s << "    " << v.fields[i] << std::endl;
00079     }
00080     s << "is_bigendian: ";
00081     s << "  " << v.is_bigendian << std::endl;
00082     s << "point_step: ";
00083     s << "  " << v.point_step << std::endl;
00084     s << "row_step: ";
00085     s << "  " << v.row_step << std::endl;
00086     s << "data[]" << std::endl;
00087     for (size_t i = 0; i < v.data.size (); ++i)
00088     {
00089       s << "  data[" << i << "]: ";
00090       s << "  " << v.data[i] << std::endl;
00091     }
00092     s << "is_dense: ";
00093     s << "  " << v.is_dense << std::endl;
00094     
00095     return (s);
00096   }
00097 
00098 } // namespace sensor_msgs
00099 
00100 #endif // PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
00101 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines