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
00008 #include "Header.h"
00009 #include "PointField.h"
00010
00011 namespace sensor_msgs
00012 {
00013 template <class ContainerAllocator>
00014 struct PointCloud2_
00015 {
00016 typedef PointCloud2_<ContainerAllocator> Type;
00017
00018 PointCloud2_()
00019 : header()
00020 , height(0)
00021 , width(0)
00022 , fields()
00023 , is_bigendian(false)
00024 , point_step(0)
00025 , row_step(0)
00026 , data()
00027 , is_dense(false)
00028 {
00029 }
00030
00031 PointCloud2_(const ContainerAllocator& _alloc)
00032 : header(_alloc)
00033 , height(0)
00034 , width(0)
00035 , fields(_alloc)
00036 , is_bigendian(false)
00037 , point_step(0)
00038 , row_step(0)
00039 , data(_alloc)
00040 , is_dense(false)
00041 {
00042 }
00043
00044 typedef ::roslib::Header_<ContainerAllocator> _header_type;
00045 ::roslib::Header_<ContainerAllocator> header;
00046
00047 typedef uint32_t _height_type;
00048 uint32_t height;
00049
00050 typedef uint32_t _width_type;
00051 uint32_t width;
00052
00053 typedef std::vector< ::sensor_msgs::PointField_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_<ContainerAllocator> >::other > _fields_type;
00054 std::vector< ::sensor_msgs::PointField_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_<ContainerAllocator> >::other > fields;
00055
00056 typedef uint8_t _is_bigendian_type;
00057 uint8_t is_bigendian;
00058
00059 typedef uint32_t _point_step_type;
00060 uint32_t point_step;
00061
00062 typedef uint32_t _row_step_type;
00063 uint32_t row_step;
00064
00065 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > _data_type;
00066 std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > data;
00067
00068 typedef uint8_t _is_dense_type;
00069 uint8_t is_dense;
00070
00071 public:
00072 typedef boost::shared_ptr< ::sensor_msgs::PointCloud2_<ContainerAllocator> > Ptr;
00073 typedef boost::shared_ptr< ::sensor_msgs::PointCloud2_<ContainerAllocator> const> ConstPtr;
00074 };
00075 typedef ::sensor_msgs::PointCloud2_<std::allocator<void> > PointCloud2;
00076
00077 typedef boost::shared_ptr< ::sensor_msgs::PointCloud2> PointCloud2Ptr;
00078 typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 const> PointCloud2ConstPtr;
00079
00080 }
00081
00082 #endif // PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
00083