00001 #ifndef PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H
00002 #define PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H
00003 #include <string>
00004 #include <vector>
00005 #include <ostream>
00006 #include <stdint.h>
00007 #include <boost/shared_ptr.hpp>
00008
00009 namespace sensor_msgs
00010 {
00011 template <class ContainerAllocator>
00012 struct PointField_
00013 {
00014 typedef PointField_<ContainerAllocator> Type;
00015
00016 PointField_()
00017 : name()
00018 , offset(0)
00019 , datatype(0)
00020 , count(0)
00021 {
00022 }
00023
00024 PointField_(const ContainerAllocator& _alloc)
00025 : name(_alloc)
00026 , offset(0)
00027 , datatype(0)
00028 , count(0)
00029 {
00030 }
00031
00032 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type;
00033 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name;
00034
00035 typedef uint32_t _offset_type;
00036 uint32_t offset;
00037
00038 typedef uint8_t _datatype_type;
00039 uint8_t datatype;
00040
00041 typedef uint32_t _count_type;
00042 uint32_t count;
00043
00044 enum { INT8 = 1 };
00045 enum { UINT8 = 2 };
00046 enum { INT16 = 3 };
00047 enum { UINT16 = 4 };
00048 enum { INT32 = 5 };
00049 enum { UINT32 = 6 };
00050 enum { FLOAT32 = 7 };
00051 enum { FLOAT64 = 8 };
00052
00053 public:
00054 typedef boost::shared_ptr< ::sensor_msgs::PointField_<ContainerAllocator> > Ptr;
00055 typedef boost::shared_ptr< ::sensor_msgs::PointField_<ContainerAllocator> const> ConstPtr;
00056 };
00057 typedef ::sensor_msgs::PointField_<std::allocator<void> > PointField;
00058
00059 typedef boost::shared_ptr< ::sensor_msgs::PointField> PointFieldPtr;
00060 typedef boost::shared_ptr< ::sensor_msgs::PointField const> PointFieldConstPtr;
00061
00062 }
00063
00064 #endif // PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H
00065