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