00001
00002 #ifndef OBJECT_MANIPULATION_MSGS_SERVICE_FINDCLUSTERBOUNDINGBOX_H
00003 #define OBJECT_MANIPULATION_MSGS_SERVICE_FINDCLUSTERBOUNDINGBOX_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015 #include "sensor_msgs/PointCloud.h"
00016
00017
00018 #include "geometry_msgs/PoseStamped.h"
00019 #include "geometry_msgs/Vector3.h"
00020
00021 namespace object_manipulation_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct FindClusterBoundingBoxRequest_ : public ros::Message
00025 {
00026 typedef FindClusterBoundingBoxRequest_<ContainerAllocator> Type;
00027
00028 FindClusterBoundingBoxRequest_()
00029 : cluster()
00030 {
00031 }
00032
00033 FindClusterBoundingBoxRequest_(const ContainerAllocator& _alloc)
00034 : cluster(_alloc)
00035 {
00036 }
00037
00038 typedef ::sensor_msgs::PointCloud_<ContainerAllocator> _cluster_type;
00039 ::sensor_msgs::PointCloud_<ContainerAllocator> cluster;
00040
00041
00042 private:
00043 static const char* __s_getDataType_() { return "object_manipulation_msgs/FindClusterBoundingBoxRequest"; }
00044 public:
00045 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00046
00047 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00048
00049 private:
00050 static const char* __s_getMD5Sum_() { return "c9b8a24dd6ede958d3710cdb47643a01"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00053
00054 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00055
00056 private:
00057 static const char* __s_getServerMD5Sum_() { return "b3e1553121201f262f1cdaafb1409115"; }
00058 public:
00059 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00060
00061 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00062
00063 private:
00064 static const char* __s_getMessageDefinition_() { return "sensor_msgs/PointCloud cluster\n\
00065 \n\
00066 \n\
00067 ================================================================================\n\
00068 MSG: sensor_msgs/PointCloud\n\
00069 # This message holds a collection of 3d points, plus optional additional\n\
00070 # information about each point.\n\
00071 \n\
00072 # Time of sensor data acquisition, coordinate frame ID.\n\
00073 Header header\n\
00074 \n\
00075 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00076 # in the frame given in the header.\n\
00077 geometry_msgs/Point32[] points\n\
00078 \n\
00079 # Each channel should have the same number of elements as points array,\n\
00080 # and the data in each channel should correspond 1:1 with each point.\n\
00081 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00082 ChannelFloat32[] channels\n\
00083 \n\
00084 ================================================================================\n\
00085 MSG: std_msgs/Header\n\
00086 # Standard metadata for higher-level stamped data types.\n\
00087 # This is generally used to communicate timestamped data \n\
00088 # in a particular coordinate frame.\n\
00089 # \n\
00090 # sequence ID: consecutively increasing ID \n\
00091 uint32 seq\n\
00092 #Two-integer timestamp that is expressed as:\n\
00093 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00094 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00095 # time-handling sugar is provided by the client library\n\
00096 time stamp\n\
00097 #Frame this data is associated with\n\
00098 # 0: no frame\n\
00099 # 1: global frame\n\
00100 string frame_id\n\
00101 \n\
00102 ================================================================================\n\
00103 MSG: geometry_msgs/Point32\n\
00104 # This contains the position of a point in free space(with 32 bits of precision).\n\
00105 # It is recommeded to use Point wherever possible instead of Point32. \n\
00106 # \n\
00107 # This recommendation is to promote interoperability. \n\
00108 #\n\
00109 # This message is designed to take up less space when sending\n\
00110 # lots of points at once, as in the case of a PointCloud. \n\
00111 \n\
00112 float32 x\n\
00113 float32 y\n\
00114 float32 z\n\
00115 ================================================================================\n\
00116 MSG: sensor_msgs/ChannelFloat32\n\
00117 # This message is used by the PointCloud message to hold optional data\n\
00118 # associated with each point in the cloud. The length of the values\n\
00119 # array should be the same as the length of the points array in the\n\
00120 # PointCloud, and each value should be associated with the corresponding\n\
00121 # point.\n\
00122 \n\
00123 # Channel names in existing practice include:\n\
00124 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00125 # This is opposite to usual conventions but remains for\n\
00126 # historical reasons. The newer PointCloud2 message has no\n\
00127 # such problem.\n\
00128 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00129 # (R,G,B) values packed into the least significant 24 bits,\n\
00130 # in order.\n\
00131 # \"intensity\" - laser or pixel intensity.\n\
00132 # \"distance\"\n\
00133 \n\
00134 # The channel name should give semantics of the channel (e.g.\n\
00135 # \"intensity\" instead of \"value\").\n\
00136 string name\n\
00137 \n\
00138 # The values array should be 1-1 with the elements of the associated\n\
00139 # PointCloud.\n\
00140 float32[] values\n\
00141 \n\
00142 "; }
00143 public:
00144 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00145
00146 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00147
00148 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00149 {
00150 ros::serialization::OStream stream(write_ptr, 1000000000);
00151 ros::serialization::serialize(stream, cluster);
00152 return stream.getData();
00153 }
00154
00155 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00156 {
00157 ros::serialization::IStream stream(read_ptr, 1000000000);
00158 ros::serialization::deserialize(stream, cluster);
00159 return stream.getData();
00160 }
00161
00162 ROS_DEPRECATED virtual uint32_t serializationLength() const
00163 {
00164 uint32_t size = 0;
00165 size += ros::serialization::serializationLength(cluster);
00166 return size;
00167 }
00168
00169 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> > Ptr;
00170 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> const> ConstPtr;
00171 };
00172 typedef ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<std::allocator<void> > FindClusterBoundingBoxRequest;
00173
00174 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxRequest> FindClusterBoundingBoxRequestPtr;
00175 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxRequest const> FindClusterBoundingBoxRequestConstPtr;
00176
00177
00178 template <class ContainerAllocator>
00179 struct FindClusterBoundingBoxResponse_ : public ros::Message
00180 {
00181 typedef FindClusterBoundingBoxResponse_<ContainerAllocator> Type;
00182
00183 FindClusterBoundingBoxResponse_()
00184 : pose()
00185 , box_dims()
00186 , error_code(0)
00187 {
00188 }
00189
00190 FindClusterBoundingBoxResponse_(const ContainerAllocator& _alloc)
00191 : pose(_alloc)
00192 , box_dims(_alloc)
00193 , error_code(0)
00194 {
00195 }
00196
00197 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_type;
00198 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose;
00199
00200 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _box_dims_type;
00201 ::geometry_msgs::Vector3_<ContainerAllocator> box_dims;
00202
00203 typedef int32_t _error_code_type;
00204 int32_t error_code;
00205
00206 enum { SUCCESS = 0 };
00207 enum { TF_ERROR = 1 };
00208
00209 private:
00210 static const char* __s_getDataType_() { return "object_manipulation_msgs/FindClusterBoundingBoxResponse"; }
00211 public:
00212 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00213
00214 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00215
00216 private:
00217 static const char* __s_getMD5Sum_() { return "981e2c8ffa160e77589dcf98a63a81cd"; }
00218 public:
00219 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00220
00221 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00222
00223 private:
00224 static const char* __s_getServerMD5Sum_() { return "b3e1553121201f262f1cdaafb1409115"; }
00225 public:
00226 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00227
00228 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00229
00230 private:
00231 static const char* __s_getMessageDefinition_() { return "\n\
00232 \n\
00233 geometry_msgs/PoseStamped pose\n\
00234 \n\
00235 \n\
00236 geometry_msgs/Vector3 box_dims\n\
00237 \n\
00238 \n\
00239 int32 SUCCESS=0\n\
00240 int32 TF_ERROR=1\n\
00241 int32 error_code\n\
00242 \n\
00243 ================================================================================\n\
00244 MSG: geometry_msgs/PoseStamped\n\
00245 # A Pose with reference coordinate frame and timestamp\n\
00246 Header header\n\
00247 Pose pose\n\
00248 \n\
00249 ================================================================================\n\
00250 MSG: std_msgs/Header\n\
00251 # Standard metadata for higher-level stamped data types.\n\
00252 # This is generally used to communicate timestamped data \n\
00253 # in a particular coordinate frame.\n\
00254 # \n\
00255 # sequence ID: consecutively increasing ID \n\
00256 uint32 seq\n\
00257 #Two-integer timestamp that is expressed as:\n\
00258 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00259 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00260 # time-handling sugar is provided by the client library\n\
00261 time stamp\n\
00262 #Frame this data is associated with\n\
00263 # 0: no frame\n\
00264 # 1: global frame\n\
00265 string frame_id\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: geometry_msgs/Pose\n\
00269 # A representation of pose in free space, composed of postion and orientation. \n\
00270 Point position\n\
00271 Quaternion orientation\n\
00272 \n\
00273 ================================================================================\n\
00274 MSG: geometry_msgs/Point\n\
00275 # This contains the position of a point in free space\n\
00276 float64 x\n\
00277 float64 y\n\
00278 float64 z\n\
00279 \n\
00280 ================================================================================\n\
00281 MSG: geometry_msgs/Quaternion\n\
00282 # This represents an orientation in free space in quaternion form.\n\
00283 \n\
00284 float64 x\n\
00285 float64 y\n\
00286 float64 z\n\
00287 float64 w\n\
00288 \n\
00289 ================================================================================\n\
00290 MSG: geometry_msgs/Vector3\n\
00291 # This represents a vector in free space. \n\
00292 \n\
00293 float64 x\n\
00294 float64 y\n\
00295 float64 z\n\
00296 "; }
00297 public:
00298 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00299
00300 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00301
00302 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00303 {
00304 ros::serialization::OStream stream(write_ptr, 1000000000);
00305 ros::serialization::serialize(stream, pose);
00306 ros::serialization::serialize(stream, box_dims);
00307 ros::serialization::serialize(stream, error_code);
00308 return stream.getData();
00309 }
00310
00311 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00312 {
00313 ros::serialization::IStream stream(read_ptr, 1000000000);
00314 ros::serialization::deserialize(stream, pose);
00315 ros::serialization::deserialize(stream, box_dims);
00316 ros::serialization::deserialize(stream, error_code);
00317 return stream.getData();
00318 }
00319
00320 ROS_DEPRECATED virtual uint32_t serializationLength() const
00321 {
00322 uint32_t size = 0;
00323 size += ros::serialization::serializationLength(pose);
00324 size += ros::serialization::serializationLength(box_dims);
00325 size += ros::serialization::serializationLength(error_code);
00326 return size;
00327 }
00328
00329 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> > Ptr;
00330 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> const> ConstPtr;
00331 };
00332 typedef ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<std::allocator<void> > FindClusterBoundingBoxResponse;
00333
00334 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxResponse> FindClusterBoundingBoxResponsePtr;
00335 typedef boost::shared_ptr< ::object_manipulation_msgs::FindClusterBoundingBoxResponse const> FindClusterBoundingBoxResponseConstPtr;
00336
00337 struct FindClusterBoundingBox
00338 {
00339
00340 typedef FindClusterBoundingBoxRequest Request;
00341 typedef FindClusterBoundingBoxResponse Response;
00342 Request request;
00343 Response response;
00344
00345 typedef Request RequestType;
00346 typedef Response ResponseType;
00347 };
00348 }
00349
00350 namespace ros
00351 {
00352 namespace message_traits
00353 {
00354 template<class ContainerAllocator>
00355 struct MD5Sum< ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> > {
00356 static const char* value()
00357 {
00358 return "c9b8a24dd6ede958d3710cdb47643a01";
00359 }
00360
00361 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> &) { return value(); }
00362 static const uint64_t static_value1 = 0xc9b8a24dd6ede958ULL;
00363 static const uint64_t static_value2 = 0xd3710cdb47643a01ULL;
00364 };
00365
00366 template<class ContainerAllocator>
00367 struct DataType< ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> > {
00368 static const char* value()
00369 {
00370 return "object_manipulation_msgs/FindClusterBoundingBoxRequest";
00371 }
00372
00373 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> &) { return value(); }
00374 };
00375
00376 template<class ContainerAllocator>
00377 struct Definition< ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> > {
00378 static const char* value()
00379 {
00380 return "sensor_msgs/PointCloud cluster\n\
00381 \n\
00382 \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: geometry_msgs/Point32\n\
00420 # This contains the position of a point in free space(with 32 bits of precision).\n\
00421 # It is recommeded to use Point wherever possible instead of Point32. \n\
00422 # \n\
00423 # This recommendation is to promote interoperability. \n\
00424 #\n\
00425 # This message is designed to take up less space when sending\n\
00426 # lots of points at once, as in the case of a PointCloud. \n\
00427 \n\
00428 float32 x\n\
00429 float32 y\n\
00430 float32 z\n\
00431 ================================================================================\n\
00432 MSG: sensor_msgs/ChannelFloat32\n\
00433 # This message is used by the PointCloud message to hold optional data\n\
00434 # associated with each point in the cloud. The length of the values\n\
00435 # array should be the same as the length of the points array in the\n\
00436 # PointCloud, and each value should be associated with the corresponding\n\
00437 # point.\n\
00438 \n\
00439 # Channel names in existing practice include:\n\
00440 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00441 # This is opposite to usual conventions but remains for\n\
00442 # historical reasons. The newer PointCloud2 message has no\n\
00443 # such problem.\n\
00444 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00445 # (R,G,B) values packed into the least significant 24 bits,\n\
00446 # in order.\n\
00447 # \"intensity\" - laser or pixel intensity.\n\
00448 # \"distance\"\n\
00449 \n\
00450 # The channel name should give semantics of the channel (e.g.\n\
00451 # \"intensity\" instead of \"value\").\n\
00452 string name\n\
00453 \n\
00454 # The values array should be 1-1 with the elements of the associated\n\
00455 # PointCloud.\n\
00456 float32[] values\n\
00457 \n\
00458 ";
00459 }
00460
00461 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> &) { return value(); }
00462 };
00463
00464 }
00465 }
00466
00467
00468 namespace ros
00469 {
00470 namespace message_traits
00471 {
00472 template<class ContainerAllocator>
00473 struct MD5Sum< ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> > {
00474 static const char* value()
00475 {
00476 return "981e2c8ffa160e77589dcf98a63a81cd";
00477 }
00478
00479 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> &) { return value(); }
00480 static const uint64_t static_value1 = 0x981e2c8ffa160e77ULL;
00481 static const uint64_t static_value2 = 0x589dcf98a63a81cdULL;
00482 };
00483
00484 template<class ContainerAllocator>
00485 struct DataType< ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> > {
00486 static const char* value()
00487 {
00488 return "object_manipulation_msgs/FindClusterBoundingBoxResponse";
00489 }
00490
00491 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> &) { return value(); }
00492 };
00493
00494 template<class ContainerAllocator>
00495 struct Definition< ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> > {
00496 static const char* value()
00497 {
00498 return "\n\
00499 \n\
00500 geometry_msgs/PoseStamped pose\n\
00501 \n\
00502 \n\
00503 geometry_msgs/Vector3 box_dims\n\
00504 \n\
00505 \n\
00506 int32 SUCCESS=0\n\
00507 int32 TF_ERROR=1\n\
00508 int32 error_code\n\
00509 \n\
00510 ================================================================================\n\
00511 MSG: geometry_msgs/PoseStamped\n\
00512 # A Pose with reference coordinate frame and timestamp\n\
00513 Header header\n\
00514 Pose pose\n\
00515 \n\
00516 ================================================================================\n\
00517 MSG: std_msgs/Header\n\
00518 # Standard metadata for higher-level stamped data types.\n\
00519 # This is generally used to communicate timestamped data \n\
00520 # in a particular coordinate frame.\n\
00521 # \n\
00522 # sequence ID: consecutively increasing ID \n\
00523 uint32 seq\n\
00524 #Two-integer timestamp that is expressed as:\n\
00525 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00526 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00527 # time-handling sugar is provided by the client library\n\
00528 time stamp\n\
00529 #Frame this data is associated with\n\
00530 # 0: no frame\n\
00531 # 1: global frame\n\
00532 string frame_id\n\
00533 \n\
00534 ================================================================================\n\
00535 MSG: geometry_msgs/Pose\n\
00536 # A representation of pose in free space, composed of postion and orientation. \n\
00537 Point position\n\
00538 Quaternion orientation\n\
00539 \n\
00540 ================================================================================\n\
00541 MSG: geometry_msgs/Point\n\
00542 # This contains the position of a point in free space\n\
00543 float64 x\n\
00544 float64 y\n\
00545 float64 z\n\
00546 \n\
00547 ================================================================================\n\
00548 MSG: geometry_msgs/Quaternion\n\
00549 # This represents an orientation in free space in quaternion form.\n\
00550 \n\
00551 float64 x\n\
00552 float64 y\n\
00553 float64 z\n\
00554 float64 w\n\
00555 \n\
00556 ================================================================================\n\
00557 MSG: geometry_msgs/Vector3\n\
00558 # This represents a vector in free space. \n\
00559 \n\
00560 float64 x\n\
00561 float64 y\n\
00562 float64 z\n\
00563 ";
00564 }
00565
00566 static const char* value(const ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> &) { return value(); }
00567 };
00568
00569 }
00570 }
00571
00572 namespace ros
00573 {
00574 namespace serialization
00575 {
00576
00577 template<class ContainerAllocator> struct Serializer< ::object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> >
00578 {
00579 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00580 {
00581 stream.next(m.cluster);
00582 }
00583
00584 ROS_DECLARE_ALLINONE_SERIALIZER;
00585 };
00586 }
00587 }
00588
00589
00590 namespace ros
00591 {
00592 namespace serialization
00593 {
00594
00595 template<class ContainerAllocator> struct Serializer< ::object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> >
00596 {
00597 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00598 {
00599 stream.next(m.pose);
00600 stream.next(m.box_dims);
00601 stream.next(m.error_code);
00602 }
00603
00604 ROS_DECLARE_ALLINONE_SERIALIZER;
00605 };
00606 }
00607 }
00608
00609 namespace ros
00610 {
00611 namespace service_traits
00612 {
00613 template<>
00614 struct MD5Sum<object_manipulation_msgs::FindClusterBoundingBox> {
00615 static const char* value()
00616 {
00617 return "b3e1553121201f262f1cdaafb1409115";
00618 }
00619
00620 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox&) { return value(); }
00621 };
00622
00623 template<>
00624 struct DataType<object_manipulation_msgs::FindClusterBoundingBox> {
00625 static const char* value()
00626 {
00627 return "object_manipulation_msgs/FindClusterBoundingBox";
00628 }
00629
00630 static const char* value(const object_manipulation_msgs::FindClusterBoundingBox&) { return value(); }
00631 };
00632
00633 template<class ContainerAllocator>
00634 struct MD5Sum<object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> > {
00635 static const char* value()
00636 {
00637 return "b3e1553121201f262f1cdaafb1409115";
00638 }
00639
00640 static const char* value(const object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> &) { return value(); }
00641 };
00642
00643 template<class ContainerAllocator>
00644 struct DataType<object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> > {
00645 static const char* value()
00646 {
00647 return "object_manipulation_msgs/FindClusterBoundingBox";
00648 }
00649
00650 static const char* value(const object_manipulation_msgs::FindClusterBoundingBoxRequest_<ContainerAllocator> &) { return value(); }
00651 };
00652
00653 template<class ContainerAllocator>
00654 struct MD5Sum<object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> > {
00655 static const char* value()
00656 {
00657 return "b3e1553121201f262f1cdaafb1409115";
00658 }
00659
00660 static const char* value(const object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> &) { return value(); }
00661 };
00662
00663 template<class ContainerAllocator>
00664 struct DataType<object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> > {
00665 static const char* value()
00666 {
00667 return "object_manipulation_msgs/FindClusterBoundingBox";
00668 }
00669
00670 static const char* value(const object_manipulation_msgs::FindClusterBoundingBoxResponse_<ContainerAllocator> &) { return value(); }
00671 };
00672
00673 }
00674 }
00675
00676 #endif // OBJECT_MANIPULATION_MSGS_SERVICE_FINDCLUSTERBOUNDINGBOX_H
00677