Go to the documentation of this file.00001
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 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > Ptr;
00044 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> const> ConstPtr;
00045 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00046 };
00047 typedef ::tabletop_object_detector::SegmentObjectInHandRequest_<std::allocator<void> > SegmentObjectInHandRequest;
00048
00049 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandRequest> SegmentObjectInHandRequestPtr;
00050 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandRequest const> SegmentObjectInHandRequestConstPtr;
00051
00052
00053 template <class ContainerAllocator>
00054 struct SegmentObjectInHandResponse_ {
00055 typedef SegmentObjectInHandResponse_<ContainerAllocator> Type;
00056
00057 SegmentObjectInHandResponse_()
00058 : cluster()
00059 , result(0)
00060 {
00061 }
00062
00063 SegmentObjectInHandResponse_(const ContainerAllocator& _alloc)
00064 : cluster(_alloc)
00065 , result(0)
00066 {
00067 }
00068
00069 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _cluster_type;
00070 ::sensor_msgs::PointCloud2_<ContainerAllocator> cluster;
00071
00072 typedef int32_t _result_type;
00073 int32_t result;
00074
00075 enum { SUCCESS = 0 };
00076 enum { NO_CLOUD_RECEIVED = 1 };
00077 enum { TF_ERROR = 2 };
00078 enum { OTHER_ERROR = 3 };
00079
00080 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > Ptr;
00081 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> const> ConstPtr;
00082 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00083 };
00084 typedef ::tabletop_object_detector::SegmentObjectInHandResponse_<std::allocator<void> > SegmentObjectInHandResponse;
00085
00086 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandResponse> SegmentObjectInHandResponsePtr;
00087 typedef boost::shared_ptr< ::tabletop_object_detector::SegmentObjectInHandResponse const> SegmentObjectInHandResponseConstPtr;
00088
00089 struct SegmentObjectInHand
00090 {
00091
00092 typedef SegmentObjectInHandRequest Request;
00093 typedef SegmentObjectInHandResponse Response;
00094 Request request;
00095 Response response;
00096
00097 typedef Request RequestType;
00098 typedef Response ResponseType;
00099 };
00100 }
00101
00102 namespace ros
00103 {
00104 namespace message_traits
00105 {
00106 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > : public TrueType {};
00107 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> const> : public TrueType {};
00108 template<class ContainerAllocator>
00109 struct MD5Sum< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > {
00110 static const char* value()
00111 {
00112 return "5653c37b6f08aa700c4b89db4ec53db6";
00113 }
00114
00115 static const char* value(const ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> &) { return value(); }
00116 static const uint64_t static_value1 = 0x5653c37b6f08aa70ULL;
00117 static const uint64_t static_value2 = 0x0c4b89db4ec53db6ULL;
00118 };
00119
00120 template<class ContainerAllocator>
00121 struct DataType< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > {
00122 static const char* value()
00123 {
00124 return "tabletop_object_detector/SegmentObjectInHandRequest";
00125 }
00126
00127 static const char* value(const ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> &) { return value(); }
00128 };
00129
00130 template<class ContainerAllocator>
00131 struct Definition< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > {
00132 static const char* value()
00133 {
00134 return "\n\
00135 string wrist_frame\n\
00136 \n\
00137 \n\
00138 ";
00139 }
00140
00141 static const char* value(const ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> &) { return value(); }
00142 };
00143
00144 }
00145 }
00146
00147
00148 namespace ros
00149 {
00150 namespace message_traits
00151 {
00152 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > : public TrueType {};
00153 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> const> : public TrueType {};
00154 template<class ContainerAllocator>
00155 struct MD5Sum< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > {
00156 static const char* value()
00157 {
00158 return "9503d54a94abc90c0593a7f7530fb70e";
00159 }
00160
00161 static const char* value(const ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> &) { return value(); }
00162 static const uint64_t static_value1 = 0x9503d54a94abc90cULL;
00163 static const uint64_t static_value2 = 0x0593a7f7530fb70eULL;
00164 };
00165
00166 template<class ContainerAllocator>
00167 struct DataType< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > {
00168 static const char* value()
00169 {
00170 return "tabletop_object_detector/SegmentObjectInHandResponse";
00171 }
00172
00173 static const char* value(const ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> &) { return value(); }
00174 };
00175
00176 template<class ContainerAllocator>
00177 struct Definition< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > {
00178 static const char* value()
00179 {
00180 return "\n\
00181 \n\
00182 sensor_msgs/PointCloud2 cluster\n\
00183 \n\
00184 \n\
00185 int32 SUCCESS = 0\n\
00186 int32 NO_CLOUD_RECEIVED = 1\n\
00187 int32 TF_ERROR = 2\n\
00188 int32 OTHER_ERROR = 3\n\
00189 int32 result\n\
00190 \n\
00191 \n\
00192 ================================================================================\n\
00193 MSG: sensor_msgs/PointCloud2\n\
00194 # This message holds a collection of N-dimensional points, which may\n\
00195 # contain additional information such as normals, intensity, etc. The\n\
00196 # point data is stored as a binary blob, its layout described by the\n\
00197 # contents of the \"fields\" array.\n\
00198 \n\
00199 # The point cloud data may be organized 2d (image-like) or 1d\n\
00200 # (unordered). Point clouds organized as 2d images may be produced by\n\
00201 # camera depth sensors such as stereo or time-of-flight.\n\
00202 \n\
00203 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
00204 # points).\n\
00205 Header header\n\
00206 \n\
00207 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
00208 # 1 and width is the length of the point cloud.\n\
00209 uint32 height\n\
00210 uint32 width\n\
00211 \n\
00212 # Describes the channels and their layout in the binary data blob.\n\
00213 PointField[] fields\n\
00214 \n\
00215 bool is_bigendian # Is this data bigendian?\n\
00216 uint32 point_step # Length of a point in bytes\n\
00217 uint32 row_step # Length of a row in bytes\n\
00218 uint8[] data # Actual point data, size is (row_step*height)\n\
00219 \n\
00220 bool is_dense # True if there are no invalid points\n\
00221 \n\
00222 ================================================================================\n\
00223 MSG: std_msgs/Header\n\
00224 # Standard metadata for higher-level stamped data types.\n\
00225 # This is generally used to communicate timestamped data \n\
00226 # in a particular coordinate frame.\n\
00227 # \n\
00228 # sequence ID: consecutively increasing ID \n\
00229 uint32 seq\n\
00230 #Two-integer timestamp that is expressed as:\n\
00231 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00232 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00233 # time-handling sugar is provided by the client library\n\
00234 time stamp\n\
00235 #Frame this data is associated with\n\
00236 # 0: no frame\n\
00237 # 1: global frame\n\
00238 string frame_id\n\
00239 \n\
00240 ================================================================================\n\
00241 MSG: sensor_msgs/PointField\n\
00242 # This message holds the description of one point entry in the\n\
00243 # PointCloud2 message format.\n\
00244 uint8 INT8 = 1\n\
00245 uint8 UINT8 = 2\n\
00246 uint8 INT16 = 3\n\
00247 uint8 UINT16 = 4\n\
00248 uint8 INT32 = 5\n\
00249 uint8 UINT32 = 6\n\
00250 uint8 FLOAT32 = 7\n\
00251 uint8 FLOAT64 = 8\n\
00252 \n\
00253 string name # Name of field\n\
00254 uint32 offset # Offset from start of point struct\n\
00255 uint8 datatype # Datatype enumeration, see above\n\
00256 uint32 count # How many elements in the field\n\
00257 \n\
00258 ";
00259 }
00260
00261 static const char* value(const ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> &) { return value(); }
00262 };
00263
00264 }
00265 }
00266
00267 namespace ros
00268 {
00269 namespace serialization
00270 {
00271
00272 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> >
00273 {
00274 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00275 {
00276 stream.next(m.wrist_frame);
00277 }
00278
00279 ROS_DECLARE_ALLINONE_SERIALIZER;
00280 };
00281 }
00282 }
00283
00284
00285 namespace ros
00286 {
00287 namespace serialization
00288 {
00289
00290 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> >
00291 {
00292 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00293 {
00294 stream.next(m.cluster);
00295 stream.next(m.result);
00296 }
00297
00298 ROS_DECLARE_ALLINONE_SERIALIZER;
00299 };
00300 }
00301 }
00302
00303 namespace ros
00304 {
00305 namespace service_traits
00306 {
00307 template<>
00308 struct MD5Sum<tabletop_object_detector::SegmentObjectInHand> {
00309 static const char* value()
00310 {
00311 return "3ce40b2b26a5a7d08d4f8e1e350c63f7";
00312 }
00313
00314 static const char* value(const tabletop_object_detector::SegmentObjectInHand&) { return value(); }
00315 };
00316
00317 template<>
00318 struct DataType<tabletop_object_detector::SegmentObjectInHand> {
00319 static const char* value()
00320 {
00321 return "tabletop_object_detector/SegmentObjectInHand";
00322 }
00323
00324 static const char* value(const tabletop_object_detector::SegmentObjectInHand&) { return value(); }
00325 };
00326
00327 template<class ContainerAllocator>
00328 struct MD5Sum<tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > {
00329 static const char* value()
00330 {
00331 return "3ce40b2b26a5a7d08d4f8e1e350c63f7";
00332 }
00333
00334 static const char* value(const tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> &) { return value(); }
00335 };
00336
00337 template<class ContainerAllocator>
00338 struct DataType<tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> > {
00339 static const char* value()
00340 {
00341 return "tabletop_object_detector/SegmentObjectInHand";
00342 }
00343
00344 static const char* value(const tabletop_object_detector::SegmentObjectInHandRequest_<ContainerAllocator> &) { return value(); }
00345 };
00346
00347 template<class ContainerAllocator>
00348 struct MD5Sum<tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > {
00349 static const char* value()
00350 {
00351 return "3ce40b2b26a5a7d08d4f8e1e350c63f7";
00352 }
00353
00354 static const char* value(const tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> &) { return value(); }
00355 };
00356
00357 template<class ContainerAllocator>
00358 struct DataType<tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> > {
00359 static const char* value()
00360 {
00361 return "tabletop_object_detector/SegmentObjectInHand";
00362 }
00363
00364 static const char* value(const tabletop_object_detector::SegmentObjectInHandResponse_<ContainerAllocator> &) { return value(); }
00365 };
00366
00367 }
00368 }
00369
00370 #endif // TABLETOP_OBJECT_DETECTOR_SERVICE_SEGMENTOBJECTINHAND_H
00371