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