Point Cloud Library (PCL)
1.3.1
|
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 <boost/shared_ptr.hpp> 00007 #include <pcl/win32_macros.h> 00008 00009 namespace sensor_msgs 00010 { 00011 struct PointField 00012 { 00013 PointField () : name (), offset (0), datatype (0), count (0) 00014 {} 00015 00016 std::string name; 00017 00018 pcl::uint32_t offset; 00019 pcl::uint8_t datatype; 00020 pcl::uint32_t count; 00021 00022 enum { INT8 = 1 }; 00023 enum { UINT8 = 2 }; 00024 enum { INT16 = 3 }; 00025 enum { UINT16 = 4 }; 00026 enum { INT32 = 5 }; 00027 enum { UINT32 = 6 }; 00028 enum { FLOAT32 = 7 }; 00029 enum { FLOAT64 = 8 }; 00030 00031 public: 00032 typedef boost::shared_ptr< ::sensor_msgs::PointField> Ptr; 00033 typedef boost::shared_ptr< ::sensor_msgs::PointField const> ConstPtr; 00034 }; // struct PointField 00035 00036 typedef boost::shared_ptr< ::sensor_msgs::PointField> PointFieldPtr; 00037 typedef boost::shared_ptr< ::sensor_msgs::PointField const> PointFieldConstPtr; 00038 00039 inline std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointField & v) 00040 { 00041 s << "name: "; 00042 s << " " << v.name << std::endl; 00043 s << "offset: "; 00044 s << " " << v.offset << std::endl; 00045 s << "datatype: "; 00046 s << " " << v.datatype << std::endl; 00047 s << "count: "; 00048 s << " " << v.count << std::endl; 00049 return (s); 00050 } 00051 } // namespace sensor_msgs 00052 00053 #endif // PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H 00054