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