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