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