$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-object_manipulation/doc_stacks/2013-03-01_16-13-18.345538/object_manipulation/object_manipulation_msgs/srv/FindClusterBoundingBox2.srv */ 00002 #ifndef OBJECT_MANIPULATION_MSGS_SERVICE_FINDCLUSTERBOUNDINGBOX2_H 00003 #define OBJECT_MANIPULATION_MSGS_SERVICE_FINDCLUSTERBOUNDINGBOX2_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 "ros/service_traits.h" 00018 00019 #include "sensor_msgs/PointCloud2.h" 00020 00021 00022 #include "geometry_msgs/PoseStamped.h" 00023 #include "geometry_msgs/Vector3.h" 00024 00025 namespace object_manipulation_msgs 00026 { 00027 template <class ContainerAllocator> 00028 struct FindClusterBoundingBox2Request_ { 00029 typedef FindClusterBoundingBox2Request_<ContainerAllocator> Type; 00030 00031 FindClusterBoundingBox2Request_() 00032 : cluster() 00033 { 00034 } 00035 00036 FindClusterBoundingBox2Request_(const ContainerAllocator& _alloc) 00037 : cluster(_alloc) 00038 { 00039 } 00040 00041 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _cluster_type; 00042 ::sensor_msgs::PointCloud2_<ContainerAllocator> cluster; 00043 00044 00045 private: 00046 static const char* __s_getDataType_() { return "object_manipulation_msgs/FindClusterBoundingBox2Request"; } 00047 public: 00048 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00049 00050 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00051 00052 private: 00053 static const char* __s_getMD5Sum_() { return "526994c9d06037106595eb6bae52d4e8"; } 00054 public: 00055 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00056 00057 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00058 00059 private: 00060 static const char* __s_getServerMD5Sum_() { return "e44a593509bdc6447cb33bb20d08e973"; } 00061 public: 00062 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00063 00064 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00065 00066 private: 00067 static const char* __s_getMessageDefinition_() { return "sensor_msgs/PointCloud2 cluster\n\ 00068 \n\ 00069 \n\ 00070 ================================================================================\n\ 00071 MSG: sensor_msgs/PointCloud2\n\ 00072 # This message holds a collection of N-dimensional points, which may\n\ 00073 # contain additional information such as normals, intensity, etc. The\n\ 00074 # point data is stored as a binary blob, its layout described by the\n\ 00075 # contents of the \"fields\" array.\n\ 00076 \n\ 00077 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00078 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00079 # camera depth sensors such as stereo or time-of-flight.\n\ 00080 \n\ 00081 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00082 # points).\n\ 00083 Header header\n\ 00084 \n\ 00085 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00086 # 1 and width is the length of the point cloud.\n\ 00087 uint32 height\n\ 00088 uint32 width\n\ 00089 \n\ 00090 # Describes the channels and their layout in the binary data blob.\n\ 00091 PointField[] fields\n\ 00092 \n\ 00093 bool is_bigendian # Is this data bigendian?\n\ 00094 uint32 point_step # Length of a point in bytes\n\ 00095 uint32 row_step # Length of a row in bytes\n\ 00096 uint8[] data # Actual point data, size is (row_step*height)\n\ 00097 \n\ 00098 bool is_dense # True if there are no invalid points\n\ 00099 \n\ 00100 ================================================================================\n\ 00101 MSG: std_msgs/Header\n\ 00102 # Standard metadata for higher-level stamped data types.\n\ 00103 # This is generally used to communicate timestamped data \n\ 00104 # in a particular coordinate frame.\n\ 00105 # \n\ 00106 # sequence ID: consecutively increasing ID \n\ 00107 uint32 seq\n\ 00108 #Two-integer timestamp that is expressed as:\n\ 00109 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00110 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00111 # time-handling sugar is provided by the client library\n\ 00112 time stamp\n\ 00113 #Frame this data is associated with\n\ 00114 # 0: no frame\n\ 00115 # 1: global frame\n\ 00116 string frame_id\n\ 00117 \n\ 00118 ================================================================================\n\ 00119 MSG: sensor_msgs/PointField\n\ 00120 # This message holds the description of one point entry in the\n\ 00121 # PointCloud2 message format.\n\ 00122 uint8 INT8 = 1\n\ 00123 uint8 UINT8 = 2\n\ 00124 uint8 INT16 = 3\n\ 00125 uint8 UINT16 = 4\n\ 00126 uint8 INT32 = 5\n\ 00127 uint8 UINT32 = 6\n\ 00128 uint8 FLOAT32 = 7\n\ 00129 uint8 FLOAT64 = 8\n\ 00130 \n\ 00131 string name # Name of field\n\ 00132 uint32 offset # Offset from start of point struct\n\ 00133 uint8 datatype # Datatype enumeration, see above\n\ 00134 uint32 count # How many elements in the field\n\ 00135 \n\ 00136 "; } 00137 public: 00138 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00139 00140 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00141 00142 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00143 { 00144 ros::serialization::OStream stream(write_ptr, 1000000000); 00145 ros::serialization::serialize(stream, cluster); 00146 return stream.getData(); 00147 } 00148 00149 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00150 { 00151 ros::serialization::IStream stream(read_ptr, 1000000000); 00152 ros::serialization::deserialize(stream, cluster); 00153 return stream.getData(); 00154 } 00155 00156 ROS_DEPRECATED virtual uint32_t serializationLength() const 00157 { 00158 uint32_t size = 0; 00159 size += ros::serialization::serializationLength(cluster); 00160 return size; 00161 } 00162 00163 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > Ptr; 00164 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> const> ConstPtr; 00165 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00166 }; // struct FindClusterBoundingBox2Request 00167 typedef ::object_manipulation_msgs::FindClusterBoundingBox2Request_<std::allocator<void> > FindClusterBoundingBox2Request; 00168 00169 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Request> FindClusterBoundingBox2RequestPtr; 00170 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Request const> FindClusterBoundingBox2RequestConstPtr; 00171 00172 00173 template <class ContainerAllocator> 00174 struct FindClusterBoundingBox2Response_ { 00175 typedef FindClusterBoundingBox2Response_<ContainerAllocator> Type; 00176 00177 FindClusterBoundingBox2Response_() 00178 : pose() 00179 , box_dims() 00180 , error_code(0) 00181 { 00182 } 00183 00184 FindClusterBoundingBox2Response_(const ContainerAllocator& _alloc) 00185 : pose(_alloc) 00186 , box_dims(_alloc) 00187 , error_code(0) 00188 { 00189 } 00190 00191 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_type; 00192 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose; 00193 00194 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _box_dims_type; 00195 ::geometry_msgs::Vector3_<ContainerAllocator> box_dims; 00196 00197 typedef int32_t _error_code_type; 00198 int32_t error_code; 00199 00200 enum { SUCCESS = 0 }; 00201 enum { TF_ERROR = 1 }; 00202 00203 private: 00204 static const char* __s_getDataType_() { return "object_manipulation_msgs/FindClusterBoundingBox2Response"; } 00205 public: 00206 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00207 00208 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00209 00210 private: 00211 static const char* __s_getMD5Sum_() { return "981e2c8ffa160e77589dcf98a63a81cd"; } 00212 public: 00213 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00214 00215 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00216 00217 private: 00218 static const char* __s_getServerMD5Sum_() { return "e44a593509bdc6447cb33bb20d08e973"; } 00219 public: 00220 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00221 00222 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00223 00224 private: 00225 static const char* __s_getMessageDefinition_() { return "\n\ 00226 \n\ 00227 geometry_msgs/PoseStamped pose\n\ 00228 \n\ 00229 \n\ 00230 geometry_msgs/Vector3 box_dims\n\ 00231 \n\ 00232 \n\ 00233 int32 SUCCESS=0\n\ 00234 int32 TF_ERROR=1\n\ 00235 int32 error_code\n\ 00236 \n\ 00237 ================================================================================\n\ 00238 MSG: geometry_msgs/PoseStamped\n\ 00239 # A Pose with reference coordinate frame and timestamp\n\ 00240 Header header\n\ 00241 Pose pose\n\ 00242 \n\ 00243 ================================================================================\n\ 00244 MSG: std_msgs/Header\n\ 00245 # Standard metadata for higher-level stamped data types.\n\ 00246 # This is generally used to communicate timestamped data \n\ 00247 # in a particular coordinate frame.\n\ 00248 # \n\ 00249 # sequence ID: consecutively increasing ID \n\ 00250 uint32 seq\n\ 00251 #Two-integer timestamp that is expressed as:\n\ 00252 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00253 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00254 # time-handling sugar is provided by the client library\n\ 00255 time stamp\n\ 00256 #Frame this data is associated with\n\ 00257 # 0: no frame\n\ 00258 # 1: global frame\n\ 00259 string frame_id\n\ 00260 \n\ 00261 ================================================================================\n\ 00262 MSG: geometry_msgs/Pose\n\ 00263 # A representation of pose in free space, composed of postion and orientation. \n\ 00264 Point position\n\ 00265 Quaternion orientation\n\ 00266 \n\ 00267 ================================================================================\n\ 00268 MSG: geometry_msgs/Point\n\ 00269 # This contains the position of a point in free space\n\ 00270 float64 x\n\ 00271 float64 y\n\ 00272 float64 z\n\ 00273 \n\ 00274 ================================================================================\n\ 00275 MSG: geometry_msgs/Quaternion\n\ 00276 # This represents an orientation in free space in quaternion form.\n\ 00277 \n\ 00278 float64 x\n\ 00279 float64 y\n\ 00280 float64 z\n\ 00281 float64 w\n\ 00282 \n\ 00283 ================================================================================\n\ 00284 MSG: geometry_msgs/Vector3\n\ 00285 # This represents a vector in free space. \n\ 00286 \n\ 00287 float64 x\n\ 00288 float64 y\n\ 00289 float64 z\n\ 00290 "; } 00291 public: 00292 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00293 00294 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00295 00296 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00297 { 00298 ros::serialization::OStream stream(write_ptr, 1000000000); 00299 ros::serialization::serialize(stream, pose); 00300 ros::serialization::serialize(stream, box_dims); 00301 ros::serialization::serialize(stream, error_code); 00302 return stream.getData(); 00303 } 00304 00305 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00306 { 00307 ros::serialization::IStream stream(read_ptr, 1000000000); 00308 ros::serialization::deserialize(stream, pose); 00309 ros::serialization::deserialize(stream, box_dims); 00310 ros::serialization::deserialize(stream, error_code); 00311 return stream.getData(); 00312 } 00313 00314 ROS_DEPRECATED virtual uint32_t serializationLength() const 00315 { 00316 uint32_t size = 0; 00317 size += ros::serialization::serializationLength(pose); 00318 size += ros::serialization::serializationLength(box_dims); 00319 size += ros::serialization::serializationLength(error_code); 00320 return size; 00321 } 00322 00323 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > Ptr; 00324 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> const> ConstPtr; 00325 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00326 }; // struct FindClusterBoundingBox2Response 00327 typedef ::object_manipulation_msgs::FindClusterBoundingBox2Response_<std::allocator<void> > FindClusterBoundingBox2Response; 00328 00329 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Response> FindClusterBoundingBox2ResponsePtr; 00330 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBox2Response const> FindClusterBoundingBox2ResponseConstPtr; 00331 00332 struct FindClusterBoundingBox2 00333 { 00334 00335 typedef FindClusterBoundingBox2Request Request; 00336 typedef FindClusterBoundingBox2Response Response; 00337 Request request; 00338 Response response; 00339 00340 typedef Request RequestType; 00341 typedef Response ResponseType; 00342 }; // struct FindClusterBoundingBox2 00343 } // namespace object_manipulation_msgs 00344 00345 namespace ros 00346 { 00347 namespace message_traits 00348 { 00349 template<class ContainerAllocator> struct IsMessage< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > : public TrueType {}; 00350 template<class ContainerAllocator> struct IsMessage< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> const> : public TrueType {}; 00351 template<class ContainerAllocator> 00352 struct MD5Sum< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > { 00353 static const char* value() 00354 { 00355 return "526994c9d06037106595eb6bae52d4e8"; 00356 } 00357 00358 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> &) { return value(); } 00359 static const uint64_t static_value1 = 0x526994c9d0603710ULL; 00360 static const uint64_t static_value2 = 0x6595eb6bae52d4e8ULL; 00361 }; 00362 00363 template<class ContainerAllocator> 00364 struct DataType< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > { 00365 static const char* value() 00366 { 00367 return "object_manipulation_msgs/FindClusterBoundingBox2Request"; 00368 } 00369 00370 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> &) { return value(); } 00371 }; 00372 00373 template<class ContainerAllocator> 00374 struct Definition< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > { 00375 static const char* value() 00376 { 00377 return "sensor_msgs/PointCloud2 cluster\n\ 00378 \n\ 00379 \n\ 00380 ================================================================================\n\ 00381 MSG: sensor_msgs/PointCloud2\n\ 00382 # This message holds a collection of N-dimensional points, which may\n\ 00383 # contain additional information such as normals, intensity, etc. The\n\ 00384 # point data is stored as a binary blob, its layout described by the\n\ 00385 # contents of the \"fields\" array.\n\ 00386 \n\ 00387 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00388 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00389 # camera depth sensors such as stereo or time-of-flight.\n\ 00390 \n\ 00391 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00392 # points).\n\ 00393 Header header\n\ 00394 \n\ 00395 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00396 # 1 and width is the length of the point cloud.\n\ 00397 uint32 height\n\ 00398 uint32 width\n\ 00399 \n\ 00400 # Describes the channels and their layout in the binary data blob.\n\ 00401 PointField[] fields\n\ 00402 \n\ 00403 bool is_bigendian # Is this data bigendian?\n\ 00404 uint32 point_step # Length of a point in bytes\n\ 00405 uint32 row_step # Length of a row in bytes\n\ 00406 uint8[] data # Actual point data, size is (row_step*height)\n\ 00407 \n\ 00408 bool is_dense # True if there are no invalid points\n\ 00409 \n\ 00410 ================================================================================\n\ 00411 MSG: std_msgs/Header\n\ 00412 # Standard metadata for higher-level stamped data types.\n\ 00413 # This is generally used to communicate timestamped data \n\ 00414 # in a particular coordinate frame.\n\ 00415 # \n\ 00416 # sequence ID: consecutively increasing ID \n\ 00417 uint32 seq\n\ 00418 #Two-integer timestamp that is expressed as:\n\ 00419 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00420 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00421 # time-handling sugar is provided by the client library\n\ 00422 time stamp\n\ 00423 #Frame this data is associated with\n\ 00424 # 0: no frame\n\ 00425 # 1: global frame\n\ 00426 string frame_id\n\ 00427 \n\ 00428 ================================================================================\n\ 00429 MSG: sensor_msgs/PointField\n\ 00430 # This message holds the description of one point entry in the\n\ 00431 # PointCloud2 message format.\n\ 00432 uint8 INT8 = 1\n\ 00433 uint8 UINT8 = 2\n\ 00434 uint8 INT16 = 3\n\ 00435 uint8 UINT16 = 4\n\ 00436 uint8 INT32 = 5\n\ 00437 uint8 UINT32 = 6\n\ 00438 uint8 FLOAT32 = 7\n\ 00439 uint8 FLOAT64 = 8\n\ 00440 \n\ 00441 string name # Name of field\n\ 00442 uint32 offset # Offset from start of point struct\n\ 00443 uint8 datatype # Datatype enumeration, see above\n\ 00444 uint32 count # How many elements in the field\n\ 00445 \n\ 00446 "; 00447 } 00448 00449 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> &) { return value(); } 00450 }; 00451 00452 } // namespace message_traits 00453 } // namespace ros 00454 00455 00456 namespace ros 00457 { 00458 namespace message_traits 00459 { 00460 template<class ContainerAllocator> struct IsMessage< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > : public TrueType {}; 00461 template<class ContainerAllocator> struct IsMessage< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> const> : public TrueType {}; 00462 template<class ContainerAllocator> 00463 struct MD5Sum< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > { 00464 static const char* value() 00465 { 00466 return "981e2c8ffa160e77589dcf98a63a81cd"; 00467 } 00468 00469 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> &) { return value(); } 00470 static const uint64_t static_value1 = 0x981e2c8ffa160e77ULL; 00471 static const uint64_t static_value2 = 0x589dcf98a63a81cdULL; 00472 }; 00473 00474 template<class ContainerAllocator> 00475 struct DataType< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > { 00476 static const char* value() 00477 { 00478 return "object_manipulation_msgs/FindClusterBoundingBox2Response"; 00479 } 00480 00481 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> &) { return value(); } 00482 }; 00483 00484 template<class ContainerAllocator> 00485 struct Definition< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > { 00486 static const char* value() 00487 { 00488 return "\n\ 00489 \n\ 00490 geometry_msgs/PoseStamped pose\n\ 00491 \n\ 00492 \n\ 00493 geometry_msgs/Vector3 box_dims\n\ 00494 \n\ 00495 \n\ 00496 int32 SUCCESS=0\n\ 00497 int32 TF_ERROR=1\n\ 00498 int32 error_code\n\ 00499 \n\ 00500 ================================================================================\n\ 00501 MSG: geometry_msgs/PoseStamped\n\ 00502 # A Pose with reference coordinate frame and timestamp\n\ 00503 Header header\n\ 00504 Pose pose\n\ 00505 \n\ 00506 ================================================================================\n\ 00507 MSG: std_msgs/Header\n\ 00508 # Standard metadata for higher-level stamped data types.\n\ 00509 # This is generally used to communicate timestamped data \n\ 00510 # in a particular coordinate frame.\n\ 00511 # \n\ 00512 # sequence ID: consecutively increasing ID \n\ 00513 uint32 seq\n\ 00514 #Two-integer timestamp that is expressed as:\n\ 00515 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00516 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00517 # time-handling sugar is provided by the client library\n\ 00518 time stamp\n\ 00519 #Frame this data is associated with\n\ 00520 # 0: no frame\n\ 00521 # 1: global frame\n\ 00522 string frame_id\n\ 00523 \n\ 00524 ================================================================================\n\ 00525 MSG: geometry_msgs/Pose\n\ 00526 # A representation of pose in free space, composed of postion and orientation. \n\ 00527 Point position\n\ 00528 Quaternion orientation\n\ 00529 \n\ 00530 ================================================================================\n\ 00531 MSG: geometry_msgs/Point\n\ 00532 # This contains the position of a point in free space\n\ 00533 float64 x\n\ 00534 float64 y\n\ 00535 float64 z\n\ 00536 \n\ 00537 ================================================================================\n\ 00538 MSG: geometry_msgs/Quaternion\n\ 00539 # This represents an orientation in free space in quaternion form.\n\ 00540 \n\ 00541 float64 x\n\ 00542 float64 y\n\ 00543 float64 z\n\ 00544 float64 w\n\ 00545 \n\ 00546 ================================================================================\n\ 00547 MSG: geometry_msgs/Vector3\n\ 00548 # This represents a vector in free space. \n\ 00549 \n\ 00550 float64 x\n\ 00551 float64 y\n\ 00552 float64 z\n\ 00553 "; 00554 } 00555 00556 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> &) { return value(); } 00557 }; 00558 00559 } // namespace message_traits 00560 } // namespace ros 00561 00562 namespace ros 00563 { 00564 namespace serialization 00565 { 00566 00567 template<class ContainerAllocator> struct Serializer< ::object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > 00568 { 00569 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00570 { 00571 stream.next(m.cluster); 00572 } 00573 00574 ROS_DECLARE_ALLINONE_SERIALIZER; 00575 }; // struct FindClusterBoundingBox2Request_ 00576 } // namespace serialization 00577 } // namespace ros 00578 00579 00580 namespace ros 00581 { 00582 namespace serialization 00583 { 00584 00585 template<class ContainerAllocator> struct Serializer< ::object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > 00586 { 00587 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00588 { 00589 stream.next(m.pose); 00590 stream.next(m.box_dims); 00591 stream.next(m.error_code); 00592 } 00593 00594 ROS_DECLARE_ALLINONE_SERIALIZER; 00595 }; // struct FindClusterBoundingBox2Response_ 00596 } // namespace serialization 00597 } // namespace ros 00598 00599 namespace ros 00600 { 00601 namespace service_traits 00602 { 00603 template<> 00604 struct MD5Sum<object_manipulation_msgs::FindClusterBoundingBox2> { 00605 static const char* value() 00606 { 00607 return "e44a593509bdc6447cb33bb20d08e973"; 00608 } 00609 00610 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox2&) { return value(); } 00611 }; 00612 00613 template<> 00614 struct DataType<object_manipulation_msgs::FindClusterBoundingBox2> { 00615 static const char* value() 00616 { 00617 return "object_manipulation_msgs/FindClusterBoundingBox2"; 00618 } 00619 00620 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox2&) { return value(); } 00621 }; 00622 00623 template<class ContainerAllocator> 00624 struct MD5Sum<object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > { 00625 static const char* value() 00626 { 00627 return "e44a593509bdc6447cb33bb20d08e973"; 00628 } 00629 00630 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> &) { return value(); } 00631 }; 00632 00633 template<class ContainerAllocator> 00634 struct DataType<object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> > { 00635 static const char* value() 00636 { 00637 return "object_manipulation_msgs/FindClusterBoundingBox2"; 00638 } 00639 00640 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox2Request_<ContainerAllocator> &) { return value(); } 00641 }; 00642 00643 template<class ContainerAllocator> 00644 struct MD5Sum<object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > { 00645 static const char* value() 00646 { 00647 return "e44a593509bdc6447cb33bb20d08e973"; 00648 } 00649 00650 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> &) { return value(); } 00651 }; 00652 00653 template<class ContainerAllocator> 00654 struct DataType<object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> > { 00655 static const char* value() 00656 { 00657 return "object_manipulation_msgs/FindClusterBoundingBox2"; 00658 } 00659 00660 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox2Response_<ContainerAllocator> &) { return value(); } 00661 }; 00662 00663 } // namespace service_traits 00664 } // namespace ros 00665 00666 #endif // OBJECT_MANIPULATION_MSGS_SERVICE_FINDCLUSTERBOUNDINGBOX2_H 00667