$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-ias_common/doc_stacks/2013-03-01_15-41-55.252100/ias_common/ias_table_msgs/msg/TableObject.msg */ 00002 #ifndef IAS_TABLE_MSGS_MESSAGE_TABLEOBJECT_H 00003 #define IAS_TABLE_MSGS_MESSAGE_TABLEOBJECT_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 "geometry_msgs/Point32.h" 00018 #include "geometry_msgs/Point32.h" 00019 #include "geometry_msgs/Point32.h" 00020 #include "sensor_msgs/PointCloud.h" 00021 #include "sensor_msgs/Image.h" 00022 00023 namespace ias_table_msgs 00024 { 00025 template <class ContainerAllocator> 00026 struct TableObject_ { 00027 typedef TableObject_<ContainerAllocator> Type; 00028 00029 TableObject_() 00030 : center() 00031 , min_bound() 00032 , max_bound() 00033 , object_cop_id(0) 00034 , lo_id(0) 00035 , points() 00036 , roi() 00037 , perception_method() 00038 , sensor_type() 00039 , object_type() 00040 , object_color() 00041 , object_geometric_type() 00042 , table_id(0) 00043 { 00044 } 00045 00046 TableObject_(const ContainerAllocator& _alloc) 00047 : center(_alloc) 00048 , min_bound(_alloc) 00049 , max_bound(_alloc) 00050 , object_cop_id(0) 00051 , lo_id(0) 00052 , points(_alloc) 00053 , roi(_alloc) 00054 , perception_method(_alloc) 00055 , sensor_type(_alloc) 00056 , object_type(_alloc) 00057 , object_color(_alloc) 00058 , object_geometric_type(_alloc) 00059 , table_id(0) 00060 { 00061 } 00062 00063 typedef ::geometry_msgs::Point32_<ContainerAllocator> _center_type; 00064 ::geometry_msgs::Point32_<ContainerAllocator> center; 00065 00066 typedef ::geometry_msgs::Point32_<ContainerAllocator> _min_bound_type; 00067 ::geometry_msgs::Point32_<ContainerAllocator> min_bound; 00068 00069 typedef ::geometry_msgs::Point32_<ContainerAllocator> _max_bound_type; 00070 ::geometry_msgs::Point32_<ContainerAllocator> max_bound; 00071 00072 typedef uint64_t _object_cop_id_type; 00073 uint64_t object_cop_id; 00074 00075 typedef uint64_t _lo_id_type; 00076 uint64_t lo_id; 00077 00078 typedef ::sensor_msgs::PointCloud_<ContainerAllocator> _points_type; 00079 ::sensor_msgs::PointCloud_<ContainerAllocator> points; 00080 00081 typedef ::sensor_msgs::Image_<ContainerAllocator> _roi_type; 00082 ::sensor_msgs::Image_<ContainerAllocator> roi; 00083 00084 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _perception_method_type; 00085 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > perception_method; 00086 00087 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _sensor_type_type; 00088 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > sensor_type; 00089 00090 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_type_type; 00091 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_type; 00092 00093 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_color_type; 00094 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_color; 00095 00096 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_geometric_type_type; 00097 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_geometric_type; 00098 00099 typedef uint64_t _table_id_type; 00100 uint64_t table_id; 00101 00102 00103 private: 00104 static const char* __s_getDataType_() { return "ias_table_msgs/TableObject"; } 00105 public: 00106 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00107 00108 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00109 00110 private: 00111 static const char* __s_getMD5Sum_() { return "3ce72124397384b196976e00d07c3482"; } 00112 public: 00113 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00114 00115 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00116 00117 private: 00118 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Point32 center\n\ 00119 geometry_msgs/Point32 min_bound\n\ 00120 geometry_msgs/Point32 max_bound\n\ 00121 \n\ 00122 uint64 object_cop_id\n\ 00123 uint64 lo_id\n\ 00124 \n\ 00125 sensor_msgs/PointCloud points\n\ 00126 sensor_msgs/Image roi\n\ 00127 \n\ 00128 string perception_method\n\ 00129 string sensor_type\n\ 00130 string object_type\n\ 00131 string object_color\n\ 00132 string object_geometric_type\n\ 00133 uint64 table_id\n\ 00134 \n\ 00135 ================================================================================\n\ 00136 MSG: geometry_msgs/Point32\n\ 00137 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00138 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00139 # \n\ 00140 # This recommendation is to promote interoperability. \n\ 00141 #\n\ 00142 # This message is designed to take up less space when sending\n\ 00143 # lots of points at once, as in the case of a PointCloud. \n\ 00144 \n\ 00145 float32 x\n\ 00146 float32 y\n\ 00147 float32 z\n\ 00148 ================================================================================\n\ 00149 MSG: sensor_msgs/PointCloud\n\ 00150 # This message holds a collection of 3d points, plus optional additional\n\ 00151 # information about each point.\n\ 00152 \n\ 00153 # Time of sensor data acquisition, coordinate frame ID.\n\ 00154 Header header\n\ 00155 \n\ 00156 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00157 # in the frame given in the header.\n\ 00158 geometry_msgs/Point32[] points\n\ 00159 \n\ 00160 # Each channel should have the same number of elements as points array,\n\ 00161 # and the data in each channel should correspond 1:1 with each point.\n\ 00162 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00163 ChannelFloat32[] channels\n\ 00164 \n\ 00165 ================================================================================\n\ 00166 MSG: std_msgs/Header\n\ 00167 # Standard metadata for higher-level stamped data types.\n\ 00168 # This is generally used to communicate timestamped data \n\ 00169 # in a particular coordinate frame.\n\ 00170 # \n\ 00171 # sequence ID: consecutively increasing ID \n\ 00172 uint32 seq\n\ 00173 #Two-integer timestamp that is expressed as:\n\ 00174 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00175 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00176 # time-handling sugar is provided by the client library\n\ 00177 time stamp\n\ 00178 #Frame this data is associated with\n\ 00179 # 0: no frame\n\ 00180 # 1: global frame\n\ 00181 string frame_id\n\ 00182 \n\ 00183 ================================================================================\n\ 00184 MSG: sensor_msgs/ChannelFloat32\n\ 00185 # This message is used by the PointCloud message to hold optional data\n\ 00186 # associated with each point in the cloud. The length of the values\n\ 00187 # array should be the same as the length of the points array in the\n\ 00188 # PointCloud, and each value should be associated with the corresponding\n\ 00189 # point.\n\ 00190 \n\ 00191 # Channel names in existing practice include:\n\ 00192 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00193 # This is opposite to usual conventions but remains for\n\ 00194 # historical reasons. The newer PointCloud2 message has no\n\ 00195 # such problem.\n\ 00196 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00197 # (R,G,B) values packed into the least significant 24 bits,\n\ 00198 # in order.\n\ 00199 # \"intensity\" - laser or pixel intensity.\n\ 00200 # \"distance\"\n\ 00201 \n\ 00202 # The channel name should give semantics of the channel (e.g.\n\ 00203 # \"intensity\" instead of \"value\").\n\ 00204 string name\n\ 00205 \n\ 00206 # The values array should be 1-1 with the elements of the associated\n\ 00207 # PointCloud.\n\ 00208 float32[] values\n\ 00209 \n\ 00210 ================================================================================\n\ 00211 MSG: sensor_msgs/Image\n\ 00212 # This message contains an uncompressed image\n\ 00213 # (0, 0) is at top-left corner of image\n\ 00214 #\n\ 00215 \n\ 00216 Header header # Header timestamp should be acquisition time of image\n\ 00217 # Header frame_id should be optical frame of camera\n\ 00218 # origin of frame should be optical center of cameara\n\ 00219 # +x should point to the right in the image\n\ 00220 # +y should point down in the image\n\ 00221 # +z should point into to plane of the image\n\ 00222 # If the frame_id here and the frame_id of the CameraInfo\n\ 00223 # message associated with the image conflict\n\ 00224 # the behavior is undefined\n\ 00225 \n\ 00226 uint32 height # image height, that is, number of rows\n\ 00227 uint32 width # image width, that is, number of columns\n\ 00228 \n\ 00229 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00230 # If you want to standardize a new string format, join\n\ 00231 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00232 \n\ 00233 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00234 # taken from the list of strings in src/image_encodings.cpp\n\ 00235 \n\ 00236 uint8 is_bigendian # is this data bigendian?\n\ 00237 uint32 step # Full row length in bytes\n\ 00238 uint8[] data # actual matrix data, size is (step * rows)\n\ 00239 \n\ 00240 "; } 00241 public: 00242 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00243 00244 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00245 00246 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00247 { 00248 ros::serialization::OStream stream(write_ptr, 1000000000); 00249 ros::serialization::serialize(stream, center); 00250 ros::serialization::serialize(stream, min_bound); 00251 ros::serialization::serialize(stream, max_bound); 00252 ros::serialization::serialize(stream, object_cop_id); 00253 ros::serialization::serialize(stream, lo_id); 00254 ros::serialization::serialize(stream, points); 00255 ros::serialization::serialize(stream, roi); 00256 ros::serialization::serialize(stream, perception_method); 00257 ros::serialization::serialize(stream, sensor_type); 00258 ros::serialization::serialize(stream, object_type); 00259 ros::serialization::serialize(stream, object_color); 00260 ros::serialization::serialize(stream, object_geometric_type); 00261 ros::serialization::serialize(stream, table_id); 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, center); 00269 ros::serialization::deserialize(stream, min_bound); 00270 ros::serialization::deserialize(stream, max_bound); 00271 ros::serialization::deserialize(stream, object_cop_id); 00272 ros::serialization::deserialize(stream, lo_id); 00273 ros::serialization::deserialize(stream, points); 00274 ros::serialization::deserialize(stream, roi); 00275 ros::serialization::deserialize(stream, perception_method); 00276 ros::serialization::deserialize(stream, sensor_type); 00277 ros::serialization::deserialize(stream, object_type); 00278 ros::serialization::deserialize(stream, object_color); 00279 ros::serialization::deserialize(stream, object_geometric_type); 00280 ros::serialization::deserialize(stream, table_id); 00281 return stream.getData(); 00282 } 00283 00284 ROS_DEPRECATED virtual uint32_t serializationLength() const 00285 { 00286 uint32_t size = 0; 00287 size += ros::serialization::serializationLength(center); 00288 size += ros::serialization::serializationLength(min_bound); 00289 size += ros::serialization::serializationLength(max_bound); 00290 size += ros::serialization::serializationLength(object_cop_id); 00291 size += ros::serialization::serializationLength(lo_id); 00292 size += ros::serialization::serializationLength(points); 00293 size += ros::serialization::serializationLength(roi); 00294 size += ros::serialization::serializationLength(perception_method); 00295 size += ros::serialization::serializationLength(sensor_type); 00296 size += ros::serialization::serializationLength(object_type); 00297 size += ros::serialization::serializationLength(object_color); 00298 size += ros::serialization::serializationLength(object_geometric_type); 00299 size += ros::serialization::serializationLength(table_id); 00300 return size; 00301 } 00302 00303 typedef boost::shared_ptr< ::ias_table_msgs::TableObject_<ContainerAllocator> > Ptr; 00304 typedef boost::shared_ptr< ::ias_table_msgs::TableObject_<ContainerAllocator> const> ConstPtr; 00305 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00306 }; // struct TableObject 00307 typedef ::ias_table_msgs::TableObject_<std::allocator<void> > TableObject; 00308 00309 typedef boost::shared_ptr< ::ias_table_msgs::TableObject> TableObjectPtr; 00310 typedef boost::shared_ptr< ::ias_table_msgs::TableObject const> TableObjectConstPtr; 00311 00312 00313 template<typename ContainerAllocator> 00314 std::ostream& operator<<(std::ostream& s, const ::ias_table_msgs::TableObject_<ContainerAllocator> & v) 00315 { 00316 ros::message_operations::Printer< ::ias_table_msgs::TableObject_<ContainerAllocator> >::stream(s, "", v); 00317 return s;} 00318 00319 } // namespace ias_table_msgs 00320 00321 namespace ros 00322 { 00323 namespace message_traits 00324 { 00325 template<class ContainerAllocator> struct IsMessage< ::ias_table_msgs::TableObject_<ContainerAllocator> > : public TrueType {}; 00326 template<class ContainerAllocator> struct IsMessage< ::ias_table_msgs::TableObject_<ContainerAllocator> const> : public TrueType {}; 00327 template<class ContainerAllocator> 00328 struct MD5Sum< ::ias_table_msgs::TableObject_<ContainerAllocator> > { 00329 static const char* value() 00330 { 00331 return "3ce72124397384b196976e00d07c3482"; 00332 } 00333 00334 static const char* value(const ::ias_table_msgs::TableObject_<ContainerAllocator> &) { return value(); } 00335 static const uint64_t static_value1 = 0x3ce72124397384b1ULL; 00336 static const uint64_t static_value2 = 0x96976e00d07c3482ULL; 00337 }; 00338 00339 template<class ContainerAllocator> 00340 struct DataType< ::ias_table_msgs::TableObject_<ContainerAllocator> > { 00341 static const char* value() 00342 { 00343 return "ias_table_msgs/TableObject"; 00344 } 00345 00346 static const char* value(const ::ias_table_msgs::TableObject_<ContainerAllocator> &) { return value(); } 00347 }; 00348 00349 template<class ContainerAllocator> 00350 struct Definition< ::ias_table_msgs::TableObject_<ContainerAllocator> > { 00351 static const char* value() 00352 { 00353 return "geometry_msgs/Point32 center\n\ 00354 geometry_msgs/Point32 min_bound\n\ 00355 geometry_msgs/Point32 max_bound\n\ 00356 \n\ 00357 uint64 object_cop_id\n\ 00358 uint64 lo_id\n\ 00359 \n\ 00360 sensor_msgs/PointCloud points\n\ 00361 sensor_msgs/Image roi\n\ 00362 \n\ 00363 string perception_method\n\ 00364 string sensor_type\n\ 00365 string object_type\n\ 00366 string object_color\n\ 00367 string object_geometric_type\n\ 00368 uint64 table_id\n\ 00369 \n\ 00370 ================================================================================\n\ 00371 MSG: geometry_msgs/Point32\n\ 00372 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00373 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00374 # \n\ 00375 # This recommendation is to promote interoperability. \n\ 00376 #\n\ 00377 # This message is designed to take up less space when sending\n\ 00378 # lots of points at once, as in the case of a PointCloud. \n\ 00379 \n\ 00380 float32 x\n\ 00381 float32 y\n\ 00382 float32 z\n\ 00383 ================================================================================\n\ 00384 MSG: sensor_msgs/PointCloud\n\ 00385 # This message holds a collection of 3d points, plus optional additional\n\ 00386 # information about each point.\n\ 00387 \n\ 00388 # Time of sensor data acquisition, coordinate frame ID.\n\ 00389 Header header\n\ 00390 \n\ 00391 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00392 # in the frame given in the header.\n\ 00393 geometry_msgs/Point32[] points\n\ 00394 \n\ 00395 # Each channel should have the same number of elements as points array,\n\ 00396 # and the data in each channel should correspond 1:1 with each point.\n\ 00397 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00398 ChannelFloat32[] channels\n\ 00399 \n\ 00400 ================================================================================\n\ 00401 MSG: std_msgs/Header\n\ 00402 # Standard metadata for higher-level stamped data types.\n\ 00403 # This is generally used to communicate timestamped data \n\ 00404 # in a particular coordinate frame.\n\ 00405 # \n\ 00406 # sequence ID: consecutively increasing ID \n\ 00407 uint32 seq\n\ 00408 #Two-integer timestamp that is expressed as:\n\ 00409 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00410 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00411 # time-handling sugar is provided by the client library\n\ 00412 time stamp\n\ 00413 #Frame this data is associated with\n\ 00414 # 0: no frame\n\ 00415 # 1: global frame\n\ 00416 string frame_id\n\ 00417 \n\ 00418 ================================================================================\n\ 00419 MSG: sensor_msgs/ChannelFloat32\n\ 00420 # This message is used by the PointCloud message to hold optional data\n\ 00421 # associated with each point in the cloud. The length of the values\n\ 00422 # array should be the same as the length of the points array in the\n\ 00423 # PointCloud, and each value should be associated with the corresponding\n\ 00424 # point.\n\ 00425 \n\ 00426 # Channel names in existing practice include:\n\ 00427 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00428 # This is opposite to usual conventions but remains for\n\ 00429 # historical reasons. The newer PointCloud2 message has no\n\ 00430 # such problem.\n\ 00431 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00432 # (R,G,B) values packed into the least significant 24 bits,\n\ 00433 # in order.\n\ 00434 # \"intensity\" - laser or pixel intensity.\n\ 00435 # \"distance\"\n\ 00436 \n\ 00437 # The channel name should give semantics of the channel (e.g.\n\ 00438 # \"intensity\" instead of \"value\").\n\ 00439 string name\n\ 00440 \n\ 00441 # The values array should be 1-1 with the elements of the associated\n\ 00442 # PointCloud.\n\ 00443 float32[] values\n\ 00444 \n\ 00445 ================================================================================\n\ 00446 MSG: sensor_msgs/Image\n\ 00447 # This message contains an uncompressed image\n\ 00448 # (0, 0) is at top-left corner of image\n\ 00449 #\n\ 00450 \n\ 00451 Header header # Header timestamp should be acquisition time of image\n\ 00452 # Header frame_id should be optical frame of camera\n\ 00453 # origin of frame should be optical center of cameara\n\ 00454 # +x should point to the right in the image\n\ 00455 # +y should point down in the image\n\ 00456 # +z should point into to plane of the image\n\ 00457 # If the frame_id here and the frame_id of the CameraInfo\n\ 00458 # message associated with the image conflict\n\ 00459 # the behavior is undefined\n\ 00460 \n\ 00461 uint32 height # image height, that is, number of rows\n\ 00462 uint32 width # image width, that is, number of columns\n\ 00463 \n\ 00464 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00465 # If you want to standardize a new string format, join\n\ 00466 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00467 \n\ 00468 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00469 # taken from the list of strings in src/image_encodings.cpp\n\ 00470 \n\ 00471 uint8 is_bigendian # is this data bigendian?\n\ 00472 uint32 step # Full row length in bytes\n\ 00473 uint8[] data # actual matrix data, size is (step * rows)\n\ 00474 \n\ 00475 "; 00476 } 00477 00478 static const char* value(const ::ias_table_msgs::TableObject_<ContainerAllocator> &) { return value(); } 00479 }; 00480 00481 } // namespace message_traits 00482 } // namespace ros 00483 00484 namespace ros 00485 { 00486 namespace serialization 00487 { 00488 00489 template<class ContainerAllocator> struct Serializer< ::ias_table_msgs::TableObject_<ContainerAllocator> > 00490 { 00491 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00492 { 00493 stream.next(m.center); 00494 stream.next(m.min_bound); 00495 stream.next(m.max_bound); 00496 stream.next(m.object_cop_id); 00497 stream.next(m.lo_id); 00498 stream.next(m.points); 00499 stream.next(m.roi); 00500 stream.next(m.perception_method); 00501 stream.next(m.sensor_type); 00502 stream.next(m.object_type); 00503 stream.next(m.object_color); 00504 stream.next(m.object_geometric_type); 00505 stream.next(m.table_id); 00506 } 00507 00508 ROS_DECLARE_ALLINONE_SERIALIZER; 00509 }; // struct TableObject_ 00510 } // namespace serialization 00511 } // namespace ros 00512 00513 namespace ros 00514 { 00515 namespace message_operations 00516 { 00517 00518 template<class ContainerAllocator> 00519 struct Printer< ::ias_table_msgs::TableObject_<ContainerAllocator> > 00520 { 00521 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::ias_table_msgs::TableObject_<ContainerAllocator> & v) 00522 { 00523 s << indent << "center: "; 00524 s << std::endl; 00525 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.center); 00526 s << indent << "min_bound: "; 00527 s << std::endl; 00528 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.min_bound); 00529 s << indent << "max_bound: "; 00530 s << std::endl; 00531 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.max_bound); 00532 s << indent << "object_cop_id: "; 00533 Printer<uint64_t>::stream(s, indent + " ", v.object_cop_id); 00534 s << indent << "lo_id: "; 00535 Printer<uint64_t>::stream(s, indent + " ", v.lo_id); 00536 s << indent << "points: "; 00537 s << std::endl; 00538 Printer< ::sensor_msgs::PointCloud_<ContainerAllocator> >::stream(s, indent + " ", v.points); 00539 s << indent << "roi: "; 00540 s << std::endl; 00541 Printer< ::sensor_msgs::Image_<ContainerAllocator> >::stream(s, indent + " ", v.roi); 00542 s << indent << "perception_method: "; 00543 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.perception_method); 00544 s << indent << "sensor_type: "; 00545 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.sensor_type); 00546 s << indent << "object_type: "; 00547 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_type); 00548 s << indent << "object_color: "; 00549 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_color); 00550 s << indent << "object_geometric_type: "; 00551 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_geometric_type); 00552 s << indent << "table_id: "; 00553 Printer<uint64_t>::stream(s, indent + " ", v.table_id); 00554 } 00555 }; 00556 00557 00558 } // namespace message_operations 00559 } // namespace ros 00560 00561 #endif // IAS_TABLE_MSGS_MESSAGE_TABLEOBJECT_H 00562