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