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