$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-common_msgs/doc_stacks/2013-03-01_14-58-52.505545/common_msgs/sensor_msgs/msg/PointField.msg */ 00002 #ifndef SENSOR_MSGS_MESSAGE_POINTFIELD_H 00003 #define SENSOR_MSGS_MESSAGE_POINTFIELD_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 00018 namespace sensor_msgs 00019 { 00020 template <class ContainerAllocator> 00021 struct PointField_ { 00022 typedef PointField_<ContainerAllocator> Type; 00023 00024 PointField_() 00025 : name() 00026 , offset(0) 00027 , datatype(0) 00028 , count(0) 00029 { 00030 } 00031 00032 PointField_(const ContainerAllocator& _alloc) 00033 : name(_alloc) 00034 , offset(0) 00035 , datatype(0) 00036 , count(0) 00037 { 00038 } 00039 00040 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type; 00041 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name; 00042 00043 typedef uint32_t _offset_type; 00044 uint32_t offset; 00045 00046 typedef uint8_t _datatype_type; 00047 uint8_t datatype; 00048 00049 typedef uint32_t _count_type; 00050 uint32_t count; 00051 00052 enum { INT8 = 1 }; 00053 enum { UINT8 = 2 }; 00054 enum { INT16 = 3 }; 00055 enum { UINT16 = 4 }; 00056 enum { INT32 = 5 }; 00057 enum { UINT32 = 6 }; 00058 enum { FLOAT32 = 7 }; 00059 enum { FLOAT64 = 8 }; 00060 00061 private: 00062 static const char* __s_getDataType_() { return "sensor_msgs/PointField"; } 00063 public: 00064 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00065 00066 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00067 00068 private: 00069 static const char* __s_getMD5Sum_() { return "268eacb2962780ceac86cbd17e328150"; } 00070 public: 00071 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00072 00073 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00074 00075 private: 00076 static const char* __s_getMessageDefinition_() { return "# This message holds the description of one point entry in the\n\ 00077 # PointCloud2 message format.\n\ 00078 uint8 INT8 = 1\n\ 00079 uint8 UINT8 = 2\n\ 00080 uint8 INT16 = 3\n\ 00081 uint8 UINT16 = 4\n\ 00082 uint8 INT32 = 5\n\ 00083 uint8 UINT32 = 6\n\ 00084 uint8 FLOAT32 = 7\n\ 00085 uint8 FLOAT64 = 8\n\ 00086 \n\ 00087 string name # Name of field\n\ 00088 uint32 offset # Offset from start of point struct\n\ 00089 uint8 datatype # Datatype enumeration, see above\n\ 00090 uint32 count # How many elements in the field\n\ 00091 \n\ 00092 "; } 00093 public: 00094 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00095 00096 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00097 00098 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00099 { 00100 ros::serialization::OStream stream(write_ptr, 1000000000); 00101 ros::serialization::serialize(stream, name); 00102 ros::serialization::serialize(stream, offset); 00103 ros::serialization::serialize(stream, datatype); 00104 ros::serialization::serialize(stream, count); 00105 return stream.getData(); 00106 } 00107 00108 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00109 { 00110 ros::serialization::IStream stream(read_ptr, 1000000000); 00111 ros::serialization::deserialize(stream, name); 00112 ros::serialization::deserialize(stream, offset); 00113 ros::serialization::deserialize(stream, datatype); 00114 ros::serialization::deserialize(stream, count); 00115 return stream.getData(); 00116 } 00117 00118 ROS_DEPRECATED virtual uint32_t serializationLength() const 00119 { 00120 uint32_t size = 0; 00121 size += ros::serialization::serializationLength(name); 00122 size += ros::serialization::serializationLength(offset); 00123 size += ros::serialization::serializationLength(datatype); 00124 size += ros::serialization::serializationLength(count); 00125 return size; 00126 } 00127 00128 typedef boost::shared_ptr< ::sensor_msgs::PointField_<ContainerAllocator> > Ptr; 00129 typedef boost::shared_ptr< ::sensor_msgs::PointField_<ContainerAllocator> const> ConstPtr; 00130 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00131 }; // struct PointField 00132 typedef ::sensor_msgs::PointField_<std::allocator<void> > PointField; 00133 00134 typedef boost::shared_ptr< ::sensor_msgs::PointField> PointFieldPtr; 00135 typedef boost::shared_ptr< ::sensor_msgs::PointField const> PointFieldConstPtr; 00136 00137 00138 template<typename ContainerAllocator> 00139 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointField_<ContainerAllocator> & v) 00140 { 00141 ros::message_operations::Printer< ::sensor_msgs::PointField_<ContainerAllocator> >::stream(s, "", v); 00142 return s;} 00143 00144 } // namespace sensor_msgs 00145 00146 namespace ros 00147 { 00148 namespace message_traits 00149 { 00150 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::PointField_<ContainerAllocator> > : public TrueType {}; 00151 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::PointField_<ContainerAllocator> const> : public TrueType {}; 00152 template<class ContainerAllocator> 00153 struct MD5Sum< ::sensor_msgs::PointField_<ContainerAllocator> > { 00154 static const char* value() 00155 { 00156 return "268eacb2962780ceac86cbd17e328150"; 00157 } 00158 00159 static const char* value(const ::sensor_msgs::PointField_<ContainerAllocator> &) { return value(); } 00160 static const uint64_t static_value1 = 0x268eacb2962780ceULL; 00161 static const uint64_t static_value2 = 0xac86cbd17e328150ULL; 00162 }; 00163 00164 template<class ContainerAllocator> 00165 struct DataType< ::sensor_msgs::PointField_<ContainerAllocator> > { 00166 static const char* value() 00167 { 00168 return "sensor_msgs/PointField"; 00169 } 00170 00171 static const char* value(const ::sensor_msgs::PointField_<ContainerAllocator> &) { return value(); } 00172 }; 00173 00174 template<class ContainerAllocator> 00175 struct Definition< ::sensor_msgs::PointField_<ContainerAllocator> > { 00176 static const char* value() 00177 { 00178 return "# This message holds the description of one point entry in the\n\ 00179 # PointCloud2 message format.\n\ 00180 uint8 INT8 = 1\n\ 00181 uint8 UINT8 = 2\n\ 00182 uint8 INT16 = 3\n\ 00183 uint8 UINT16 = 4\n\ 00184 uint8 INT32 = 5\n\ 00185 uint8 UINT32 = 6\n\ 00186 uint8 FLOAT32 = 7\n\ 00187 uint8 FLOAT64 = 8\n\ 00188 \n\ 00189 string name # Name of field\n\ 00190 uint32 offset # Offset from start of point struct\n\ 00191 uint8 datatype # Datatype enumeration, see above\n\ 00192 uint32 count # How many elements in the field\n\ 00193 \n\ 00194 "; 00195 } 00196 00197 static const char* value(const ::sensor_msgs::PointField_<ContainerAllocator> &) { return value(); } 00198 }; 00199 00200 } // namespace message_traits 00201 } // namespace ros 00202 00203 namespace ros 00204 { 00205 namespace serialization 00206 { 00207 00208 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::PointField_<ContainerAllocator> > 00209 { 00210 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00211 { 00212 stream.next(m.name); 00213 stream.next(m.offset); 00214 stream.next(m.datatype); 00215 stream.next(m.count); 00216 } 00217 00218 ROS_DECLARE_ALLINONE_SERIALIZER; 00219 }; // struct PointField_ 00220 } // namespace serialization 00221 } // namespace ros 00222 00223 namespace ros 00224 { 00225 namespace message_operations 00226 { 00227 00228 template<class ContainerAllocator> 00229 struct Printer< ::sensor_msgs::PointField_<ContainerAllocator> > 00230 { 00231 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::PointField_<ContainerAllocator> & v) 00232 { 00233 s << indent << "name: "; 00234 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name); 00235 s << indent << "offset: "; 00236 Printer<uint32_t>::stream(s, indent + " ", v.offset); 00237 s << indent << "datatype: "; 00238 Printer<uint8_t>::stream(s, indent + " ", v.datatype); 00239 s << indent << "count: "; 00240 Printer<uint32_t>::stream(s, indent + " ", v.count); 00241 } 00242 }; 00243 00244 00245 } // namespace message_operations 00246 } // namespace ros 00247 00248 #endif // SENSOR_MSGS_MESSAGE_POINTFIELD_H 00249