Go to the documentation of this file.00001
00002 #ifndef IRI_BOW_OBJECT_DETECTOR_SERVICE_REFINEGRASPPOINT_H
00003 #define IRI_BOW_OBJECT_DETECTOR_SERVICE_REFINEGRASPPOINT_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 "iri_bow_object_detector/ObjectBox.h"
00020 #include "sensor_msgs/Image.h"
00021 #include "iri_perception_msgs/DescriptorSet.h"
00022
00023
00024 #include "iri_perception_msgs/ImagePoint.h"
00025
00026 namespace iri_bow_object_detector
00027 {
00028 template <class ContainerAllocator>
00029 struct RefineGraspPointRequest_ {
00030 typedef RefineGraspPointRequest_<ContainerAllocator> Type;
00031
00032 RefineGraspPointRequest_()
00033 : posible_solutions()
00034 , image()
00035 , descriptor_set()
00036 {
00037 }
00038
00039 RefineGraspPointRequest_(const ContainerAllocator& _alloc)
00040 : posible_solutions(_alloc)
00041 , image(_alloc)
00042 , descriptor_set(_alloc)
00043 {
00044 }
00045
00046 typedef std::vector< ::iri_bow_object_detector::ObjectBox_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::iri_bow_object_detector::ObjectBox_<ContainerAllocator> >::other > _posible_solutions_type;
00047 std::vector< ::iri_bow_object_detector::ObjectBox_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::iri_bow_object_detector::ObjectBox_<ContainerAllocator> >::other > posible_solutions;
00048
00049 typedef ::sensor_msgs::Image_<ContainerAllocator> _image_type;
00050 ::sensor_msgs::Image_<ContainerAllocator> image;
00051
00052 typedef ::iri_perception_msgs::DescriptorSet_<ContainerAllocator> _descriptor_set_type;
00053 ::iri_perception_msgs::DescriptorSet_<ContainerAllocator> descriptor_set;
00054
00055
00056 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > Ptr;
00057 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> const> ConstPtr;
00058 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00059 };
00060 typedef ::iri_bow_object_detector::RefineGraspPointRequest_<std::allocator<void> > RefineGraspPointRequest;
00061
00062 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointRequest> RefineGraspPointRequestPtr;
00063 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointRequest const> RefineGraspPointRequestConstPtr;
00064
00065
00066 template <class ContainerAllocator>
00067 struct RefineGraspPointResponse_ {
00068 typedef RefineGraspPointResponse_<ContainerAllocator> Type;
00069
00070 RefineGraspPointResponse_()
00071 : grasp_point()
00072 {
00073 }
00074
00075 RefineGraspPointResponse_(const ContainerAllocator& _alloc)
00076 : grasp_point(_alloc)
00077 {
00078 }
00079
00080 typedef ::iri_perception_msgs::ImagePoint_<ContainerAllocator> _grasp_point_type;
00081 ::iri_perception_msgs::ImagePoint_<ContainerAllocator> grasp_point;
00082
00083
00084 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > Ptr;
00085 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> const> ConstPtr;
00086 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00087 };
00088 typedef ::iri_bow_object_detector::RefineGraspPointResponse_<std::allocator<void> > RefineGraspPointResponse;
00089
00090 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointResponse> RefineGraspPointResponsePtr;
00091 typedef boost::shared_ptr< ::iri_bow_object_detector::RefineGraspPointResponse const> RefineGraspPointResponseConstPtr;
00092
00093 struct RefineGraspPoint
00094 {
00095
00096 typedef RefineGraspPointRequest Request;
00097 typedef RefineGraspPointResponse Response;
00098 Request request;
00099 Response response;
00100
00101 typedef Request RequestType;
00102 typedef Response ResponseType;
00103 };
00104 }
00105
00106 namespace ros
00107 {
00108 namespace message_traits
00109 {
00110 template<class ContainerAllocator> struct IsMessage< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > : public TrueType {};
00111 template<class ContainerAllocator> struct IsMessage< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> const> : public TrueType {};
00112 template<class ContainerAllocator>
00113 struct MD5Sum< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > {
00114 static const char* value()
00115 {
00116 return "0526af87c7b6cc76c0da62278b22490c";
00117 }
00118
00119 static const char* value(const ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> &) { return value(); }
00120 static const uint64_t static_value1 = 0x0526af87c7b6cc76ULL;
00121 static const uint64_t static_value2 = 0xc0da62278b22490cULL;
00122 };
00123
00124 template<class ContainerAllocator>
00125 struct DataType< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > {
00126 static const char* value()
00127 {
00128 return "iri_bow_object_detector/RefineGraspPointRequest";
00129 }
00130
00131 static const char* value(const ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> &) { return value(); }
00132 };
00133
00134 template<class ContainerAllocator>
00135 struct Definition< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > {
00136 static const char* value()
00137 {
00138 return "\n\
00139 \n\
00140 iri_bow_object_detector/ObjectBox[] posible_solutions\n\
00141 sensor_msgs/Image image\n\
00142 iri_perception_msgs/DescriptorSet descriptor_set\n\
00143 \n\
00144 ================================================================================\n\
00145 MSG: iri_bow_object_detector/ObjectBox\n\
00146 iri_perception_msgs/ImagePoint point1\n\
00147 iri_perception_msgs/ImagePoint point2\n\
00148 float32 value\n\
00149 ================================================================================\n\
00150 MSG: iri_perception_msgs/ImagePoint\n\
00151 uint32 x\n\
00152 uint32 y\n\
00153 ================================================================================\n\
00154 MSG: sensor_msgs/Image\n\
00155 # This message contains an uncompressed image\n\
00156 # (0, 0) is at top-left corner of image\n\
00157 #\n\
00158 \n\
00159 Header header # Header timestamp should be acquisition time of image\n\
00160 # Header frame_id should be optical frame of camera\n\
00161 # origin of frame should be optical center of cameara\n\
00162 # +x should point to the right in the image\n\
00163 # +y should point down in the image\n\
00164 # +z should point into to plane of the image\n\
00165 # If the frame_id here and the frame_id of the CameraInfo\n\
00166 # message associated with the image conflict\n\
00167 # the behavior is undefined\n\
00168 \n\
00169 uint32 height # image height, that is, number of rows\n\
00170 uint32 width # image width, that is, number of columns\n\
00171 \n\
00172 # The legal values for encoding are in file src/image_encodings.cpp\n\
00173 # If you want to standardize a new string format, join\n\
00174 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00175 \n\
00176 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
00177 # taken from the list of strings in src/image_encodings.cpp\n\
00178 \n\
00179 uint8 is_bigendian # is this data bigendian?\n\
00180 uint32 step # Full row length in bytes\n\
00181 uint8[] data # actual matrix data, size is (step * rows)\n\
00182 \n\
00183 ================================================================================\n\
00184 MSG: std_msgs/Header\n\
00185 # Standard metadata for higher-level stamped data types.\n\
00186 # This is generally used to communicate timestamped data \n\
00187 # in a particular coordinate frame.\n\
00188 # \n\
00189 # sequence ID: consecutively increasing ID \n\
00190 uint32 seq\n\
00191 #Two-integer timestamp that is expressed as:\n\
00192 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00193 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00194 # time-handling sugar is provided by the client library\n\
00195 time stamp\n\
00196 #Frame this data is associated with\n\
00197 # 0: no frame\n\
00198 # 1: global frame\n\
00199 string frame_id\n\
00200 \n\
00201 ================================================================================\n\
00202 MSG: iri_perception_msgs/DescriptorSet\n\
00203 Header header\n\
00204 int32 num_orient_bins\n\
00205 int32 num_spa_bins\n\
00206 int32 num\n\
00207 int32 len\n\
00208 int32 width\n\
00209 int32 height\n\
00210 iri_perception_msgs/Descriptor[] descriptors\n\
00211 \n\
00212 ================================================================================\n\
00213 MSG: iri_perception_msgs/Descriptor\n\
00214 float32[] descriptor\n\
00215 geometry_msgs/Vector3 point3d\n\
00216 int32 u\n\
00217 int32 v\n\
00218 float32 orientation\n\
00219 \n\
00220 ================================================================================\n\
00221 MSG: geometry_msgs/Vector3\n\
00222 # This represents a vector in free space. \n\
00223 \n\
00224 float64 x\n\
00225 float64 y\n\
00226 float64 z\n\
00227 ";
00228 }
00229
00230 static const char* value(const ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> &) { return value(); }
00231 };
00232
00233 }
00234 }
00235
00236
00237 namespace ros
00238 {
00239 namespace message_traits
00240 {
00241 template<class ContainerAllocator> struct IsMessage< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > : public TrueType {};
00242 template<class ContainerAllocator> struct IsMessage< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> const> : public TrueType {};
00243 template<class ContainerAllocator>
00244 struct MD5Sum< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > {
00245 static const char* value()
00246 {
00247 return "a1d3d6d5081395c0c4a6d2daa9a86c56";
00248 }
00249
00250 static const char* value(const ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> &) { return value(); }
00251 static const uint64_t static_value1 = 0xa1d3d6d5081395c0ULL;
00252 static const uint64_t static_value2 = 0xc4a6d2daa9a86c56ULL;
00253 };
00254
00255 template<class ContainerAllocator>
00256 struct DataType< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > {
00257 static const char* value()
00258 {
00259 return "iri_bow_object_detector/RefineGraspPointResponse";
00260 }
00261
00262 static const char* value(const ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> &) { return value(); }
00263 };
00264
00265 template<class ContainerAllocator>
00266 struct Definition< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > {
00267 static const char* value()
00268 {
00269 return "\n\
00270 iri_perception_msgs/ImagePoint grasp_point\n\
00271 \n\
00272 \n\
00273 ================================================================================\n\
00274 MSG: iri_perception_msgs/ImagePoint\n\
00275 uint32 x\n\
00276 uint32 y\n\
00277 ";
00278 }
00279
00280 static const char* value(const ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> &) { return value(); }
00281 };
00282
00283 template<class ContainerAllocator> struct IsFixedSize< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > : public TrueType {};
00284 }
00285 }
00286
00287 namespace ros
00288 {
00289 namespace serialization
00290 {
00291
00292 template<class ContainerAllocator> struct Serializer< ::iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> >
00293 {
00294 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00295 {
00296 stream.next(m.posible_solutions);
00297 stream.next(m.image);
00298 stream.next(m.descriptor_set);
00299 }
00300
00301 ROS_DECLARE_ALLINONE_SERIALIZER;
00302 };
00303 }
00304 }
00305
00306
00307 namespace ros
00308 {
00309 namespace serialization
00310 {
00311
00312 template<class ContainerAllocator> struct Serializer< ::iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> >
00313 {
00314 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00315 {
00316 stream.next(m.grasp_point);
00317 }
00318
00319 ROS_DECLARE_ALLINONE_SERIALIZER;
00320 };
00321 }
00322 }
00323
00324 namespace ros
00325 {
00326 namespace service_traits
00327 {
00328 template<>
00329 struct MD5Sum<iri_bow_object_detector::RefineGraspPoint> {
00330 static const char* value()
00331 {
00332 return "4df81184ea52bef77e8b614f35924fb4";
00333 }
00334
00335 static const char* value(const iri_bow_object_detector::RefineGraspPoint&) { return value(); }
00336 };
00337
00338 template<>
00339 struct DataType<iri_bow_object_detector::RefineGraspPoint> {
00340 static const char* value()
00341 {
00342 return "iri_bow_object_detector/RefineGraspPoint";
00343 }
00344
00345 static const char* value(const iri_bow_object_detector::RefineGraspPoint&) { return value(); }
00346 };
00347
00348 template<class ContainerAllocator>
00349 struct MD5Sum<iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > {
00350 static const char* value()
00351 {
00352 return "4df81184ea52bef77e8b614f35924fb4";
00353 }
00354
00355 static const char* value(const iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> &) { return value(); }
00356 };
00357
00358 template<class ContainerAllocator>
00359 struct DataType<iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> > {
00360 static const char* value()
00361 {
00362 return "iri_bow_object_detector/RefineGraspPoint";
00363 }
00364
00365 static const char* value(const iri_bow_object_detector::RefineGraspPointRequest_<ContainerAllocator> &) { return value(); }
00366 };
00367
00368 template<class ContainerAllocator>
00369 struct MD5Sum<iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > {
00370 static const char* value()
00371 {
00372 return "4df81184ea52bef77e8b614f35924fb4";
00373 }
00374
00375 static const char* value(const iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> &) { return value(); }
00376 };
00377
00378 template<class ContainerAllocator>
00379 struct DataType<iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> > {
00380 static const char* value()
00381 {
00382 return "iri_bow_object_detector/RefineGraspPoint";
00383 }
00384
00385 static const char* value(const iri_bow_object_detector::RefineGraspPointResponse_<ContainerAllocator> &) { return value(); }
00386 };
00387
00388 }
00389 }
00390
00391 #endif // IRI_BOW_OBJECT_DETECTOR_SERVICE_REFINEGRASPPOINT_H
00392