$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_environment_perception/doc_stacks/2013-03-01_14-40-06.190572/cob_environment_perception/cob_3d_mapping_msgs/msg/ShapeArray.msg */ 00002 #ifndef COB_3D_MAPPING_MSGS_MESSAGE_SHAPEARRAY_H 00003 #define COB_3D_MAPPING_MSGS_MESSAGE_SHAPEARRAY_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 #include "std_msgs/Header.h" 00018 #include "cob_3d_mapping_msgs/Shape.h" 00019 00020 namespace cob_3d_mapping_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct ShapeArray_ { 00024 typedef ShapeArray_<ContainerAllocator> Type; 00025 00026 ShapeArray_() 00027 : header() 00028 , shapes() 00029 { 00030 } 00031 00032 ShapeArray_(const ContainerAllocator& _alloc) 00033 : header(_alloc) 00034 , shapes(_alloc) 00035 { 00036 } 00037 00038 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00039 ::std_msgs::Header_<ContainerAllocator> header; 00040 00041 typedef std::vector< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> >::other > _shapes_type; 00042 std::vector< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> >::other > shapes; 00043 00044 00045 ROS_DEPRECATED uint32_t get_shapes_size() const { return (uint32_t)shapes.size(); } 00046 ROS_DEPRECATED void set_shapes_size(uint32_t size) { shapes.resize((size_t)size); } 00047 ROS_DEPRECATED void get_shapes_vec(std::vector< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> >::other > & vec) const { vec = this->shapes; } 00048 ROS_DEPRECATED void set_shapes_vec(const std::vector< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> >::other > & vec) { this->shapes = vec; } 00049 private: 00050 static const char* __s_getDataType_() { return "cob_3d_mapping_msgs/ShapeArray"; } 00051 public: 00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00053 00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00055 00056 private: 00057 static const char* __s_getMD5Sum_() { return "24df939600330ea9ee1a25b046aef0f9"; } 00058 public: 00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00060 00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00062 00063 private: 00064 static const char* __s_getMessageDefinition_() { return "# An array of poses with a header for global reference.\n\ 00065 \n\ 00066 Header header\n\ 00067 \n\ 00068 cob_3d_mapping_msgs/Shape[] shapes\n\ 00069 ================================================================================\n\ 00070 MSG: std_msgs/Header\n\ 00071 # Standard metadata for higher-level stamped data types.\n\ 00072 # This is generally used to communicate timestamped data \n\ 00073 # in a particular coordinate frame.\n\ 00074 # \n\ 00075 # sequence ID: consecutively increasing ID \n\ 00076 uint32 seq\n\ 00077 #Two-integer timestamp that is expressed as:\n\ 00078 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00079 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00080 # time-handling sugar is provided by the client library\n\ 00081 time stamp\n\ 00082 #Frame this data is associated with\n\ 00083 # 0: no frame\n\ 00084 # 1: global frame\n\ 00085 string frame_id\n\ 00086 \n\ 00087 ================================================================================\n\ 00088 MSG: cob_3d_mapping_msgs/Shape\n\ 00089 Header header\n\ 00090 \n\ 00091 uint8 POLYGON=0\n\ 00092 uint8 LINE=1\n\ 00093 uint8 CURVED=2\n\ 00094 uint8 MESH=3\n\ 00095 uint8 OTHER=4\n\ 00096 uint8 CYLINDER=5\n\ 00097 # potential extensions: SPHERE, CYLINDER, BOX\n\ 00098 \n\ 00099 uint8 type\n\ 00100 \n\ 00101 \n\ 00102 int32 id\n\ 00103 # define shape parameters\n\ 00104 # for plane\n\ 00105 # normal vector = params[0],params[1],params[2]\n\ 00106 # d = params[3]\n\ 00107 # for line\n\ 00108 # direction vector = params[0],params[1],params[2]\n\ 00109 #\n\ 00110 #for cylinder\n\ 00111 # symmetry axis = params[0],params[1],params[2]\n\ 00112 # z axis = params[3], params[4], params[5]\n\ 00113 # origin = params[6], params[7], params[8]\n\ 00114 # radius = params[9]\n\ 00115 # \n\ 00116 float64[] params\n\ 00117 \n\ 00118 sensor_msgs/PointCloud2[] points\n\ 00119 \n\ 00120 #### define mesh ####\n\ 00121 # each three entries form a triangle; indices of points are stored\n\ 00122 int32[] vertices\n\ 00123 \n\ 00124 geometry_msgs/Point32 centroid\n\ 00125 std_msgs/ColorRGBA color\n\ 00126 bool[] holes\n\ 00127 \n\ 00128 ================================================================================\n\ 00129 MSG: sensor_msgs/PointCloud2\n\ 00130 # This message holds a collection of N-dimensional points, which may\n\ 00131 # contain additional information such as normals, intensity, etc. The\n\ 00132 # point data is stored as a binary blob, its layout described by the\n\ 00133 # contents of the \"fields\" array.\n\ 00134 \n\ 00135 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00136 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00137 # camera depth sensors such as stereo or time-of-flight.\n\ 00138 \n\ 00139 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00140 # points).\n\ 00141 Header header\n\ 00142 \n\ 00143 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00144 # 1 and width is the length of the point cloud.\n\ 00145 uint32 height\n\ 00146 uint32 width\n\ 00147 \n\ 00148 # Describes the channels and their layout in the binary data blob.\n\ 00149 PointField[] fields\n\ 00150 \n\ 00151 bool is_bigendian # Is this data bigendian?\n\ 00152 uint32 point_step # Length of a point in bytes\n\ 00153 uint32 row_step # Length of a row in bytes\n\ 00154 uint8[] data # Actual point data, size is (row_step*height)\n\ 00155 \n\ 00156 bool is_dense # True if there are no invalid points\n\ 00157 \n\ 00158 ================================================================================\n\ 00159 MSG: sensor_msgs/PointField\n\ 00160 # This message holds the description of one point entry in the\n\ 00161 # PointCloud2 message format.\n\ 00162 uint8 INT8 = 1\n\ 00163 uint8 UINT8 = 2\n\ 00164 uint8 INT16 = 3\n\ 00165 uint8 UINT16 = 4\n\ 00166 uint8 INT32 = 5\n\ 00167 uint8 UINT32 = 6\n\ 00168 uint8 FLOAT32 = 7\n\ 00169 uint8 FLOAT64 = 8\n\ 00170 \n\ 00171 string name # Name of field\n\ 00172 uint32 offset # Offset from start of point struct\n\ 00173 uint8 datatype # Datatype enumeration, see above\n\ 00174 uint32 count # How many elements in the field\n\ 00175 \n\ 00176 ================================================================================\n\ 00177 MSG: geometry_msgs/Point32\n\ 00178 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00179 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00180 # \n\ 00181 # This recommendation is to promote interoperability. \n\ 00182 #\n\ 00183 # This message is designed to take up less space when sending\n\ 00184 # lots of points at once, as in the case of a PointCloud. \n\ 00185 \n\ 00186 float32 x\n\ 00187 float32 y\n\ 00188 float32 z\n\ 00189 ================================================================================\n\ 00190 MSG: std_msgs/ColorRGBA\n\ 00191 float32 r\n\ 00192 float32 g\n\ 00193 float32 b\n\ 00194 float32 a\n\ 00195 \n\ 00196 "; } 00197 public: 00198 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00199 00200 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00201 00202 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00203 { 00204 ros::serialization::OStream stream(write_ptr, 1000000000); 00205 ros::serialization::serialize(stream, header); 00206 ros::serialization::serialize(stream, shapes); 00207 return stream.getData(); 00208 } 00209 00210 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00211 { 00212 ros::serialization::IStream stream(read_ptr, 1000000000); 00213 ros::serialization::deserialize(stream, header); 00214 ros::serialization::deserialize(stream, shapes); 00215 return stream.getData(); 00216 } 00217 00218 ROS_DEPRECATED virtual uint32_t serializationLength() const 00219 { 00220 uint32_t size = 0; 00221 size += ros::serialization::serializationLength(header); 00222 size += ros::serialization::serializationLength(shapes); 00223 return size; 00224 } 00225 00226 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > Ptr; 00227 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> const> ConstPtr; 00228 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00229 }; // struct ShapeArray 00230 typedef ::cob_3d_mapping_msgs::ShapeArray_<std::allocator<void> > ShapeArray; 00231 00232 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::ShapeArray> ShapeArrayPtr; 00233 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::ShapeArray const> ShapeArrayConstPtr; 00234 00235 00236 template<typename ContainerAllocator> 00237 std::ostream& operator<<(std::ostream& s, const ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> & v) 00238 { 00239 ros::message_operations::Printer< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> >::stream(s, "", v); 00240 return s;} 00241 00242 } // namespace cob_3d_mapping_msgs 00243 00244 namespace ros 00245 { 00246 namespace message_traits 00247 { 00248 template<class ContainerAllocator> struct IsMessage< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > : public TrueType {}; 00249 template<class ContainerAllocator> struct IsMessage< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> const> : public TrueType {}; 00250 template<class ContainerAllocator> 00251 struct MD5Sum< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > { 00252 static const char* value() 00253 { 00254 return "24df939600330ea9ee1a25b046aef0f9"; 00255 } 00256 00257 static const char* value(const ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> &) { return value(); } 00258 static const uint64_t static_value1 = 0x24df939600330ea9ULL; 00259 static const uint64_t static_value2 = 0xee1a25b046aef0f9ULL; 00260 }; 00261 00262 template<class ContainerAllocator> 00263 struct DataType< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > { 00264 static const char* value() 00265 { 00266 return "cob_3d_mapping_msgs/ShapeArray"; 00267 } 00268 00269 static const char* value(const ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> &) { return value(); } 00270 }; 00271 00272 template<class ContainerAllocator> 00273 struct Definition< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > { 00274 static const char* value() 00275 { 00276 return "# An array of poses with a header for global reference.\n\ 00277 \n\ 00278 Header header\n\ 00279 \n\ 00280 cob_3d_mapping_msgs/Shape[] shapes\n\ 00281 ================================================================================\n\ 00282 MSG: std_msgs/Header\n\ 00283 # Standard metadata for higher-level stamped data types.\n\ 00284 # This is generally used to communicate timestamped data \n\ 00285 # in a particular coordinate frame.\n\ 00286 # \n\ 00287 # sequence ID: consecutively increasing ID \n\ 00288 uint32 seq\n\ 00289 #Two-integer timestamp that is expressed as:\n\ 00290 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00291 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00292 # time-handling sugar is provided by the client library\n\ 00293 time stamp\n\ 00294 #Frame this data is associated with\n\ 00295 # 0: no frame\n\ 00296 # 1: global frame\n\ 00297 string frame_id\n\ 00298 \n\ 00299 ================================================================================\n\ 00300 MSG: cob_3d_mapping_msgs/Shape\n\ 00301 Header header\n\ 00302 \n\ 00303 uint8 POLYGON=0\n\ 00304 uint8 LINE=1\n\ 00305 uint8 CURVED=2\n\ 00306 uint8 MESH=3\n\ 00307 uint8 OTHER=4\n\ 00308 uint8 CYLINDER=5\n\ 00309 # potential extensions: SPHERE, CYLINDER, BOX\n\ 00310 \n\ 00311 uint8 type\n\ 00312 \n\ 00313 \n\ 00314 int32 id\n\ 00315 # define shape parameters\n\ 00316 # for plane\n\ 00317 # normal vector = params[0],params[1],params[2]\n\ 00318 # d = params[3]\n\ 00319 # for line\n\ 00320 # direction vector = params[0],params[1],params[2]\n\ 00321 #\n\ 00322 #for cylinder\n\ 00323 # symmetry axis = params[0],params[1],params[2]\n\ 00324 # z axis = params[3], params[4], params[5]\n\ 00325 # origin = params[6], params[7], params[8]\n\ 00326 # radius = params[9]\n\ 00327 # \n\ 00328 float64[] params\n\ 00329 \n\ 00330 sensor_msgs/PointCloud2[] points\n\ 00331 \n\ 00332 #### define mesh ####\n\ 00333 # each three entries form a triangle; indices of points are stored\n\ 00334 int32[] vertices\n\ 00335 \n\ 00336 geometry_msgs/Point32 centroid\n\ 00337 std_msgs/ColorRGBA color\n\ 00338 bool[] holes\n\ 00339 \n\ 00340 ================================================================================\n\ 00341 MSG: sensor_msgs/PointCloud2\n\ 00342 # This message holds a collection of N-dimensional points, which may\n\ 00343 # contain additional information such as normals, intensity, etc. The\n\ 00344 # point data is stored as a binary blob, its layout described by the\n\ 00345 # contents of the \"fields\" array.\n\ 00346 \n\ 00347 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00348 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00349 # camera depth sensors such as stereo or time-of-flight.\n\ 00350 \n\ 00351 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00352 # points).\n\ 00353 Header header\n\ 00354 \n\ 00355 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00356 # 1 and width is the length of the point cloud.\n\ 00357 uint32 height\n\ 00358 uint32 width\n\ 00359 \n\ 00360 # Describes the channels and their layout in the binary data blob.\n\ 00361 PointField[] fields\n\ 00362 \n\ 00363 bool is_bigendian # Is this data bigendian?\n\ 00364 uint32 point_step # Length of a point in bytes\n\ 00365 uint32 row_step # Length of a row in bytes\n\ 00366 uint8[] data # Actual point data, size is (row_step*height)\n\ 00367 \n\ 00368 bool is_dense # True if there are no invalid points\n\ 00369 \n\ 00370 ================================================================================\n\ 00371 MSG: sensor_msgs/PointField\n\ 00372 # This message holds the description of one point entry in the\n\ 00373 # PointCloud2 message format.\n\ 00374 uint8 INT8 = 1\n\ 00375 uint8 UINT8 = 2\n\ 00376 uint8 INT16 = 3\n\ 00377 uint8 UINT16 = 4\n\ 00378 uint8 INT32 = 5\n\ 00379 uint8 UINT32 = 6\n\ 00380 uint8 FLOAT32 = 7\n\ 00381 uint8 FLOAT64 = 8\n\ 00382 \n\ 00383 string name # Name of field\n\ 00384 uint32 offset # Offset from start of point struct\n\ 00385 uint8 datatype # Datatype enumeration, see above\n\ 00386 uint32 count # How many elements in the field\n\ 00387 \n\ 00388 ================================================================================\n\ 00389 MSG: geometry_msgs/Point32\n\ 00390 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00391 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00392 # \n\ 00393 # This recommendation is to promote interoperability. \n\ 00394 #\n\ 00395 # This message is designed to take up less space when sending\n\ 00396 # lots of points at once, as in the case of a PointCloud. \n\ 00397 \n\ 00398 float32 x\n\ 00399 float32 y\n\ 00400 float32 z\n\ 00401 ================================================================================\n\ 00402 MSG: std_msgs/ColorRGBA\n\ 00403 float32 r\n\ 00404 float32 g\n\ 00405 float32 b\n\ 00406 float32 a\n\ 00407 \n\ 00408 "; 00409 } 00410 00411 static const char* value(const ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> &) { return value(); } 00412 }; 00413 00414 template<class ContainerAllocator> struct HasHeader< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > : public TrueType {}; 00415 template<class ContainerAllocator> struct HasHeader< const ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > : public TrueType {}; 00416 } // namespace message_traits 00417 } // namespace ros 00418 00419 namespace ros 00420 { 00421 namespace serialization 00422 { 00423 00424 template<class ContainerAllocator> struct Serializer< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > 00425 { 00426 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00427 { 00428 stream.next(m.header); 00429 stream.next(m.shapes); 00430 } 00431 00432 ROS_DECLARE_ALLINONE_SERIALIZER; 00433 }; // struct ShapeArray_ 00434 } // namespace serialization 00435 } // namespace ros 00436 00437 namespace ros 00438 { 00439 namespace message_operations 00440 { 00441 00442 template<class ContainerAllocator> 00443 struct Printer< ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> > 00444 { 00445 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::cob_3d_mapping_msgs::ShapeArray_<ContainerAllocator> & v) 00446 { 00447 s << indent << "header: "; 00448 s << std::endl; 00449 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00450 s << indent << "shapes[]" << std::endl; 00451 for (size_t i = 0; i < v.shapes.size(); ++i) 00452 { 00453 s << indent << " shapes[" << i << "]: "; 00454 s << std::endl; 00455 s << indent; 00456 Printer< ::cob_3d_mapping_msgs::Shape_<ContainerAllocator> >::stream(s, indent + " ", v.shapes[i]); 00457 } 00458 } 00459 }; 00460 00461 00462 } // namespace message_operations 00463 } // namespace ros 00464 00465 #endif // COB_3D_MAPPING_MSGS_MESSAGE_SHAPEARRAY_H 00466