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