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