00001
00002 #ifndef POLLED_CAMERA_SERVICE_GETPOLLEDIMAGE_H
00003 #define POLLED_CAMERA_SERVICE_GETPOLLEDIMAGE_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015 #include "sensor_msgs/RegionOfInterest.h"
00016
00017
00018
00019 namespace polled_camera
00020 {
00021 template <class ContainerAllocator>
00022 struct GetPolledImageRequest_ : public ros::Message
00023 {
00024 typedef GetPolledImageRequest_<ContainerAllocator> Type;
00025
00026 GetPolledImageRequest_()
00027 : response_namespace()
00028 , timeout()
00029 , binning_x(0)
00030 , binning_y(0)
00031 , roi()
00032 {
00033 }
00034
00035 GetPolledImageRequest_(const ContainerAllocator& _alloc)
00036 : response_namespace(_alloc)
00037 , timeout()
00038 , binning_x(0)
00039 , binning_y(0)
00040 , roi(_alloc)
00041 {
00042 }
00043
00044 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _response_namespace_type;
00045 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > response_namespace;
00046
00047 typedef ros::Duration _timeout_type;
00048 ros::Duration timeout;
00049
00050 typedef uint32_t _binning_x_type;
00051 uint32_t binning_x;
00052
00053 typedef uint32_t _binning_y_type;
00054 uint32_t binning_y;
00055
00056 typedef ::sensor_msgs::RegionOfInterest_<ContainerAllocator> _roi_type;
00057 ::sensor_msgs::RegionOfInterest_<ContainerAllocator> roi;
00058
00059
00060 private:
00061 static const char* __s_getDataType_() { return "polled_camera/GetPolledImageRequest"; }
00062 public:
00063 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00064
00065 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00066
00067 private:
00068 static const char* __s_getMD5Sum_() { return "c77ed43e530fd48e9e7a2a93845e154c"; }
00069 public:
00070 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00071
00072 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00073
00074 private:
00075 static const char* __s_getServerMD5Sum_() { return "1f3fb0d09d6e1c72d4a7eeb9822d9030"; }
00076 public:
00077 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00078
00079 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00080
00081 private:
00082 static const char* __s_getMessageDefinition_() { return "\n\
00083 \n\
00084 \n\
00085 \n\
00086 string response_namespace\n\
00087 \n\
00088 \n\
00089 \n\
00090 \n\
00091 duration timeout\n\
00092 \n\
00093 \n\
00094 uint32 binning_x\n\
00095 uint32 binning_y\n\
00096 \n\
00097 \n\
00098 sensor_msgs/RegionOfInterest roi\n\
00099 \n\
00100 ================================================================================\n\
00101 MSG: sensor_msgs/RegionOfInterest\n\
00102 # This message is used to specify a region of interest within an image.\n\
00103 #\n\
00104 # When used to specify the ROI setting of the camera when the image was\n\
00105 # taken, the height and width fields should either match the height and\n\
00106 # width fields for the associated image; or height = width = 0\n\
00107 # indicates that the full resolution image was captured.\n\
00108 \n\
00109 uint32 x_offset # Leftmost pixel of the ROI\n\
00110 # (0 if the ROI includes the left edge of the image)\n\
00111 uint32 y_offset # Topmost pixel of the ROI\n\
00112 # (0 if the ROI includes the top edge of the image)\n\
00113 uint32 height # Height of ROI\n\
00114 uint32 width # Width of ROI\n\
00115 \n\
00116 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
00117 # ROI in this message. Typically this should be False if the full image\n\
00118 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
00119 # used).\n\
00120 bool do_rectify\n\
00121 \n\
00122 "; }
00123 public:
00124 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00125
00126 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00127
00128 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00129 {
00130 ros::serialization::OStream stream(write_ptr, 1000000000);
00131 ros::serialization::serialize(stream, response_namespace);
00132 ros::serialization::serialize(stream, timeout);
00133 ros::serialization::serialize(stream, binning_x);
00134 ros::serialization::serialize(stream, binning_y);
00135 ros::serialization::serialize(stream, roi);
00136 return stream.getData();
00137 }
00138
00139 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00140 {
00141 ros::serialization::IStream stream(read_ptr, 1000000000);
00142 ros::serialization::deserialize(stream, response_namespace);
00143 ros::serialization::deserialize(stream, timeout);
00144 ros::serialization::deserialize(stream, binning_x);
00145 ros::serialization::deserialize(stream, binning_y);
00146 ros::serialization::deserialize(stream, roi);
00147 return stream.getData();
00148 }
00149
00150 ROS_DEPRECATED virtual uint32_t serializationLength() const
00151 {
00152 uint32_t size = 0;
00153 size += ros::serialization::serializationLength(response_namespace);
00154 size += ros::serialization::serializationLength(timeout);
00155 size += ros::serialization::serializationLength(binning_x);
00156 size += ros::serialization::serializationLength(binning_y);
00157 size += ros::serialization::serializationLength(roi);
00158 return size;
00159 }
00160
00161 typedef boost::shared_ptr< ::polled_camera::GetPolledImageRequest_<ContainerAllocator> > Ptr;
00162 typedef boost::shared_ptr< ::polled_camera::GetPolledImageRequest_<ContainerAllocator> const> ConstPtr;
00163 };
00164 typedef ::polled_camera::GetPolledImageRequest_<std::allocator<void> > GetPolledImageRequest;
00165
00166 typedef boost::shared_ptr< ::polled_camera::GetPolledImageRequest> GetPolledImageRequestPtr;
00167 typedef boost::shared_ptr< ::polled_camera::GetPolledImageRequest const> GetPolledImageRequestConstPtr;
00168
00169
00170 template <class ContainerAllocator>
00171 struct GetPolledImageResponse_ : public ros::Message
00172 {
00173 typedef GetPolledImageResponse_<ContainerAllocator> Type;
00174
00175 GetPolledImageResponse_()
00176 : success(false)
00177 , status_message()
00178 , stamp()
00179 {
00180 }
00181
00182 GetPolledImageResponse_(const ContainerAllocator& _alloc)
00183 : success(false)
00184 , status_message(_alloc)
00185 , stamp()
00186 {
00187 }
00188
00189 typedef uint8_t _success_type;
00190 uint8_t success;
00191
00192 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _status_message_type;
00193 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > status_message;
00194
00195 typedef ros::Time _stamp_type;
00196 ros::Time stamp;
00197
00198
00199 private:
00200 static const char* __s_getDataType_() { return "polled_camera/GetPolledImageResponse"; }
00201 public:
00202 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00203
00204 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00205
00206 private:
00207 static const char* __s_getMD5Sum_() { return "dbf1f851bc511800e6129ccd5a3542ab"; }
00208 public:
00209 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00210
00211 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00212
00213 private:
00214 static const char* __s_getServerMD5Sum_() { return "1f3fb0d09d6e1c72d4a7eeb9822d9030"; }
00215 public:
00216 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00217
00218 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00219
00220 private:
00221 static const char* __s_getMessageDefinition_() { return "bool success\n\
00222 string status_message\n\
00223 time stamp\n\
00224 \n\
00225 \n\
00226 \n\
00227 "; }
00228 public:
00229 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00230
00231 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00232
00233 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00234 {
00235 ros::serialization::OStream stream(write_ptr, 1000000000);
00236 ros::serialization::serialize(stream, success);
00237 ros::serialization::serialize(stream, status_message);
00238 ros::serialization::serialize(stream, stamp);
00239 return stream.getData();
00240 }
00241
00242 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00243 {
00244 ros::serialization::IStream stream(read_ptr, 1000000000);
00245 ros::serialization::deserialize(stream, success);
00246 ros::serialization::deserialize(stream, status_message);
00247 ros::serialization::deserialize(stream, stamp);
00248 return stream.getData();
00249 }
00250
00251 ROS_DEPRECATED virtual uint32_t serializationLength() const
00252 {
00253 uint32_t size = 0;
00254 size += ros::serialization::serializationLength(success);
00255 size += ros::serialization::serializationLength(status_message);
00256 size += ros::serialization::serializationLength(stamp);
00257 return size;
00258 }
00259
00260 typedef boost::shared_ptr< ::polled_camera::GetPolledImageResponse_<ContainerAllocator> > Ptr;
00261 typedef boost::shared_ptr< ::polled_camera::GetPolledImageResponse_<ContainerAllocator> const> ConstPtr;
00262 };
00263 typedef ::polled_camera::GetPolledImageResponse_<std::allocator<void> > GetPolledImageResponse;
00264
00265 typedef boost::shared_ptr< ::polled_camera::GetPolledImageResponse> GetPolledImageResponsePtr;
00266 typedef boost::shared_ptr< ::polled_camera::GetPolledImageResponse const> GetPolledImageResponseConstPtr;
00267
00268 struct GetPolledImage
00269 {
00270
00271 typedef GetPolledImageRequest Request;
00272 typedef GetPolledImageResponse Response;
00273 Request request;
00274 Response response;
00275
00276 typedef Request RequestType;
00277 typedef Response ResponseType;
00278 };
00279 }
00280
00281 namespace ros
00282 {
00283 namespace message_traits
00284 {
00285 template<class ContainerAllocator>
00286 struct MD5Sum< ::polled_camera::GetPolledImageRequest_<ContainerAllocator> > {
00287 static const char* value()
00288 {
00289 return "c77ed43e530fd48e9e7a2a93845e154c";
00290 }
00291
00292 static const char* value(const ::polled_camera::GetPolledImageRequest_<ContainerAllocator> &) { return value(); }
00293 static const uint64_t static_value1 = 0xc77ed43e530fd48eULL;
00294 static const uint64_t static_value2 = 0x9e7a2a93845e154cULL;
00295 };
00296
00297 template<class ContainerAllocator>
00298 struct DataType< ::polled_camera::GetPolledImageRequest_<ContainerAllocator> > {
00299 static const char* value()
00300 {
00301 return "polled_camera/GetPolledImageRequest";
00302 }
00303
00304 static const char* value(const ::polled_camera::GetPolledImageRequest_<ContainerAllocator> &) { return value(); }
00305 };
00306
00307 template<class ContainerAllocator>
00308 struct Definition< ::polled_camera::GetPolledImageRequest_<ContainerAllocator> > {
00309 static const char* value()
00310 {
00311 return "\n\
00312 \n\
00313 \n\
00314 \n\
00315 string response_namespace\n\
00316 \n\
00317 \n\
00318 \n\
00319 \n\
00320 duration timeout\n\
00321 \n\
00322 \n\
00323 uint32 binning_x\n\
00324 uint32 binning_y\n\
00325 \n\
00326 \n\
00327 sensor_msgs/RegionOfInterest roi\n\
00328 \n\
00329 ================================================================================\n\
00330 MSG: sensor_msgs/RegionOfInterest\n\
00331 # This message is used to specify a region of interest within an image.\n\
00332 #\n\
00333 # When used to specify the ROI setting of the camera when the image was\n\
00334 # taken, the height and width fields should either match the height and\n\
00335 # width fields for the associated image; or height = width = 0\n\
00336 # indicates that the full resolution image was captured.\n\
00337 \n\
00338 uint32 x_offset # Leftmost pixel of the ROI\n\
00339 # (0 if the ROI includes the left edge of the image)\n\
00340 uint32 y_offset # Topmost pixel of the ROI\n\
00341 # (0 if the ROI includes the top edge of the image)\n\
00342 uint32 height # Height of ROI\n\
00343 uint32 width # Width of ROI\n\
00344 \n\
00345 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
00346 # ROI in this message. Typically this should be False if the full image\n\
00347 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
00348 # used).\n\
00349 bool do_rectify\n\
00350 \n\
00351 ";
00352 }
00353
00354 static const char* value(const ::polled_camera::GetPolledImageRequest_<ContainerAllocator> &) { return value(); }
00355 };
00356
00357 }
00358 }
00359
00360
00361 namespace ros
00362 {
00363 namespace message_traits
00364 {
00365 template<class ContainerAllocator>
00366 struct MD5Sum< ::polled_camera::GetPolledImageResponse_<ContainerAllocator> > {
00367 static const char* value()
00368 {
00369 return "dbf1f851bc511800e6129ccd5a3542ab";
00370 }
00371
00372 static const char* value(const ::polled_camera::GetPolledImageResponse_<ContainerAllocator> &) { return value(); }
00373 static const uint64_t static_value1 = 0xdbf1f851bc511800ULL;
00374 static const uint64_t static_value2 = 0xe6129ccd5a3542abULL;
00375 };
00376
00377 template<class ContainerAllocator>
00378 struct DataType< ::polled_camera::GetPolledImageResponse_<ContainerAllocator> > {
00379 static const char* value()
00380 {
00381 return "polled_camera/GetPolledImageResponse";
00382 }
00383
00384 static const char* value(const ::polled_camera::GetPolledImageResponse_<ContainerAllocator> &) { return value(); }
00385 };
00386
00387 template<class ContainerAllocator>
00388 struct Definition< ::polled_camera::GetPolledImageResponse_<ContainerAllocator> > {
00389 static const char* value()
00390 {
00391 return "bool success\n\
00392 string status_message\n\
00393 time stamp\n\
00394 \n\
00395 \n\
00396 \n\
00397 ";
00398 }
00399
00400 static const char* value(const ::polled_camera::GetPolledImageResponse_<ContainerAllocator> &) { return value(); }
00401 };
00402
00403 }
00404 }
00405
00406 namespace ros
00407 {
00408 namespace serialization
00409 {
00410
00411 template<class ContainerAllocator> struct Serializer< ::polled_camera::GetPolledImageRequest_<ContainerAllocator> >
00412 {
00413 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00414 {
00415 stream.next(m.response_namespace);
00416 stream.next(m.timeout);
00417 stream.next(m.binning_x);
00418 stream.next(m.binning_y);
00419 stream.next(m.roi);
00420 }
00421
00422 ROS_DECLARE_ALLINONE_SERIALIZER;
00423 };
00424 }
00425 }
00426
00427
00428 namespace ros
00429 {
00430 namespace serialization
00431 {
00432
00433 template<class ContainerAllocator> struct Serializer< ::polled_camera::GetPolledImageResponse_<ContainerAllocator> >
00434 {
00435 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00436 {
00437 stream.next(m.success);
00438 stream.next(m.status_message);
00439 stream.next(m.stamp);
00440 }
00441
00442 ROS_DECLARE_ALLINONE_SERIALIZER;
00443 };
00444 }
00445 }
00446
00447 namespace ros
00448 {
00449 namespace service_traits
00450 {
00451 template<>
00452 struct MD5Sum<polled_camera::GetPolledImage> {
00453 static const char* value()
00454 {
00455 return "1f3fb0d09d6e1c72d4a7eeb9822d9030";
00456 }
00457
00458 static const char* value(const polled_camera::GetPolledImage&) { return value(); }
00459 };
00460
00461 template<>
00462 struct DataType<polled_camera::GetPolledImage> {
00463 static const char* value()
00464 {
00465 return "polled_camera/GetPolledImage";
00466 }
00467
00468 static const char* value(const polled_camera::GetPolledImage&) { return value(); }
00469 };
00470
00471 template<class ContainerAllocator>
00472 struct MD5Sum<polled_camera::GetPolledImageRequest_<ContainerAllocator> > {
00473 static const char* value()
00474 {
00475 return "1f3fb0d09d6e1c72d4a7eeb9822d9030";
00476 }
00477
00478 static const char* value(const polled_camera::GetPolledImageRequest_<ContainerAllocator> &) { return value(); }
00479 };
00480
00481 template<class ContainerAllocator>
00482 struct DataType<polled_camera::GetPolledImageRequest_<ContainerAllocator> > {
00483 static const char* value()
00484 {
00485 return "polled_camera/GetPolledImage";
00486 }
00487
00488 static const char* value(const polled_camera::GetPolledImageRequest_<ContainerAllocator> &) { return value(); }
00489 };
00490
00491 template<class ContainerAllocator>
00492 struct MD5Sum<polled_camera::GetPolledImageResponse_<ContainerAllocator> > {
00493 static const char* value()
00494 {
00495 return "1f3fb0d09d6e1c72d4a7eeb9822d9030";
00496 }
00497
00498 static const char* value(const polled_camera::GetPolledImageResponse_<ContainerAllocator> &) { return value(); }
00499 };
00500
00501 template<class ContainerAllocator>
00502 struct DataType<polled_camera::GetPolledImageResponse_<ContainerAllocator> > {
00503 static const char* value()
00504 {
00505 return "polled_camera/GetPolledImage";
00506 }
00507
00508 static const char* value(const polled_camera::GetPolledImageResponse_<ContainerAllocator> &) { return value(); }
00509 };
00510
00511 }
00512 }
00513
00514 #endif // POLLED_CAMERA_SERVICE_GETPOLLEDIMAGE_H
00515