$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_driver/doc_stacks/2013-03-01_14-39-27.991733/cob_driver/cob_camera_sensors/srv/GetTOFImages.srv */ 00002 #ifndef COB_CAMERA_SENSORS_SERVICE_GETTOFIMAGES_H 00003 #define COB_CAMERA_SENSORS_SERVICE_GETTOFIMAGES_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 00020 00021 #include "sensor_msgs/Image.h" 00022 #include "sensor_msgs/Image.h" 00023 00024 namespace cob_camera_sensors 00025 { 00026 template <class ContainerAllocator> 00027 struct GetTOFImagesRequest_ { 00028 typedef GetTOFImagesRequest_<ContainerAllocator> Type; 00029 00030 GetTOFImagesRequest_() 00031 { 00032 } 00033 00034 GetTOFImagesRequest_(const ContainerAllocator& _alloc) 00035 { 00036 } 00037 00038 00039 private: 00040 static const char* __s_getDataType_() { return "cob_camera_sensors/GetTOFImagesRequest"; } 00041 public: 00042 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00043 00044 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00045 00046 private: 00047 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00048 public: 00049 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00050 00051 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00052 00053 private: 00054 static const char* __s_getServerMD5Sum_() { return "245ce4e6dd0ec61a5c674c8191a91877"; } 00055 public: 00056 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00057 00058 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00059 00060 private: 00061 static const char* __s_getMessageDefinition_() { return "\n\ 00062 "; } 00063 public: 00064 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00065 00066 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00067 00068 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00069 { 00070 ros::serialization::OStream stream(write_ptr, 1000000000); 00071 return stream.getData(); 00072 } 00073 00074 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00075 { 00076 ros::serialization::IStream stream(read_ptr, 1000000000); 00077 return stream.getData(); 00078 } 00079 00080 ROS_DEPRECATED virtual uint32_t serializationLength() const 00081 { 00082 uint32_t size = 0; 00083 return size; 00084 } 00085 00086 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > Ptr; 00087 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> const> ConstPtr; 00088 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00089 }; // struct GetTOFImagesRequest 00090 typedef ::cob_camera_sensors::GetTOFImagesRequest_<std::allocator<void> > GetTOFImagesRequest; 00091 00092 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesRequest> GetTOFImagesRequestPtr; 00093 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesRequest const> GetTOFImagesRequestConstPtr; 00094 00095 00096 template <class ContainerAllocator> 00097 struct GetTOFImagesResponse_ { 00098 typedef GetTOFImagesResponse_<ContainerAllocator> Type; 00099 00100 GetTOFImagesResponse_() 00101 : greyImage() 00102 , xyzImage() 00103 { 00104 } 00105 00106 GetTOFImagesResponse_(const ContainerAllocator& _alloc) 00107 : greyImage(_alloc) 00108 , xyzImage(_alloc) 00109 { 00110 } 00111 00112 typedef ::sensor_msgs::Image_<ContainerAllocator> _greyImage_type; 00113 ::sensor_msgs::Image_<ContainerAllocator> greyImage; 00114 00115 typedef ::sensor_msgs::Image_<ContainerAllocator> _xyzImage_type; 00116 ::sensor_msgs::Image_<ContainerAllocator> xyzImage; 00117 00118 00119 private: 00120 static const char* __s_getDataType_() { return "cob_camera_sensors/GetTOFImagesResponse"; } 00121 public: 00122 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00123 00124 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00125 00126 private: 00127 static const char* __s_getMD5Sum_() { return "245ce4e6dd0ec61a5c674c8191a91877"; } 00128 public: 00129 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00130 00131 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00132 00133 private: 00134 static const char* __s_getServerMD5Sum_() { return "245ce4e6dd0ec61a5c674c8191a91877"; } 00135 public: 00136 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00137 00138 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00139 00140 private: 00141 static const char* __s_getMessageDefinition_() { return "sensor_msgs/Image greyImage\n\ 00142 sensor_msgs/Image xyzImage\n\ 00143 \n\ 00144 \n\ 00145 ================================================================================\n\ 00146 MSG: sensor_msgs/Image\n\ 00147 # This message contains an uncompressed image\n\ 00148 # (0, 0) is at top-left corner of image\n\ 00149 #\n\ 00150 \n\ 00151 Header header # Header timestamp should be acquisition time of image\n\ 00152 # Header frame_id should be optical frame of camera\n\ 00153 # origin of frame should be optical center of cameara\n\ 00154 # +x should point to the right in the image\n\ 00155 # +y should point down in the image\n\ 00156 # +z should point into to plane of the image\n\ 00157 # If the frame_id here and the frame_id of the CameraInfo\n\ 00158 # message associated with the image conflict\n\ 00159 # the behavior is undefined\n\ 00160 \n\ 00161 uint32 height # image height, that is, number of rows\n\ 00162 uint32 width # image width, that is, number of columns\n\ 00163 \n\ 00164 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00165 # If you want to standardize a new string format, join\n\ 00166 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00167 \n\ 00168 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00169 # taken from the list of strings in src/image_encodings.cpp\n\ 00170 \n\ 00171 uint8 is_bigendian # is this data bigendian?\n\ 00172 uint32 step # Full row length in bytes\n\ 00173 uint8[] data # actual matrix data, size is (step * rows)\n\ 00174 \n\ 00175 ================================================================================\n\ 00176 MSG: std_msgs/Header\n\ 00177 # Standard metadata for higher-level stamped data types.\n\ 00178 # This is generally used to communicate timestamped data \n\ 00179 # in a particular coordinate frame.\n\ 00180 # \n\ 00181 # sequence ID: consecutively increasing ID \n\ 00182 uint32 seq\n\ 00183 #Two-integer timestamp that is expressed as:\n\ 00184 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00185 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00186 # time-handling sugar is provided by the client library\n\ 00187 time stamp\n\ 00188 #Frame this data is associated with\n\ 00189 # 0: no frame\n\ 00190 # 1: global frame\n\ 00191 string frame_id\n\ 00192 \n\ 00193 "; } 00194 public: 00195 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00196 00197 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00198 00199 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00200 { 00201 ros::serialization::OStream stream(write_ptr, 1000000000); 00202 ros::serialization::serialize(stream, greyImage); 00203 ros::serialization::serialize(stream, xyzImage); 00204 return stream.getData(); 00205 } 00206 00207 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00208 { 00209 ros::serialization::IStream stream(read_ptr, 1000000000); 00210 ros::serialization::deserialize(stream, greyImage); 00211 ros::serialization::deserialize(stream, xyzImage); 00212 return stream.getData(); 00213 } 00214 00215 ROS_DEPRECATED virtual uint32_t serializationLength() const 00216 { 00217 uint32_t size = 0; 00218 size += ros::serialization::serializationLength(greyImage); 00219 size += ros::serialization::serializationLength(xyzImage); 00220 return size; 00221 } 00222 00223 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > Ptr; 00224 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> const> ConstPtr; 00225 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00226 }; // struct GetTOFImagesResponse 00227 typedef ::cob_camera_sensors::GetTOFImagesResponse_<std::allocator<void> > GetTOFImagesResponse; 00228 00229 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesResponse> GetTOFImagesResponsePtr; 00230 typedef boost::shared_ptr< ::cob_camera_sensors::GetTOFImagesResponse const> GetTOFImagesResponseConstPtr; 00231 00232 struct GetTOFImages 00233 { 00234 00235 typedef GetTOFImagesRequest Request; 00236 typedef GetTOFImagesResponse Response; 00237 Request request; 00238 Response response; 00239 00240 typedef Request RequestType; 00241 typedef Response ResponseType; 00242 }; // struct GetTOFImages 00243 } // namespace cob_camera_sensors 00244 00245 namespace ros 00246 { 00247 namespace message_traits 00248 { 00249 template<class ContainerAllocator> struct IsMessage< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > : public TrueType {}; 00250 template<class ContainerAllocator> struct IsMessage< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> const> : public TrueType {}; 00251 template<class ContainerAllocator> 00252 struct MD5Sum< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > { 00253 static const char* value() 00254 { 00255 return "d41d8cd98f00b204e9800998ecf8427e"; 00256 } 00257 00258 static const char* value(const ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> &) { return value(); } 00259 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00260 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00261 }; 00262 00263 template<class ContainerAllocator> 00264 struct DataType< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > { 00265 static const char* value() 00266 { 00267 return "cob_camera_sensors/GetTOFImagesRequest"; 00268 } 00269 00270 static const char* value(const ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> &) { return value(); } 00271 }; 00272 00273 template<class ContainerAllocator> 00274 struct Definition< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > { 00275 static const char* value() 00276 { 00277 return "\n\ 00278 "; 00279 } 00280 00281 static const char* value(const ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> &) { return value(); } 00282 }; 00283 00284 template<class ContainerAllocator> struct IsFixedSize< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > : public TrueType {}; 00285 } // namespace message_traits 00286 } // namespace ros 00287 00288 00289 namespace ros 00290 { 00291 namespace message_traits 00292 { 00293 template<class ContainerAllocator> struct IsMessage< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > : public TrueType {}; 00294 template<class ContainerAllocator> struct IsMessage< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> const> : public TrueType {}; 00295 template<class ContainerAllocator> 00296 struct MD5Sum< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > { 00297 static const char* value() 00298 { 00299 return "245ce4e6dd0ec61a5c674c8191a91877"; 00300 } 00301 00302 static const char* value(const ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> &) { return value(); } 00303 static const uint64_t static_value1 = 0x245ce4e6dd0ec61aULL; 00304 static const uint64_t static_value2 = 0x5c674c8191a91877ULL; 00305 }; 00306 00307 template<class ContainerAllocator> 00308 struct DataType< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > { 00309 static const char* value() 00310 { 00311 return "cob_camera_sensors/GetTOFImagesResponse"; 00312 } 00313 00314 static const char* value(const ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> &) { return value(); } 00315 }; 00316 00317 template<class ContainerAllocator> 00318 struct Definition< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > { 00319 static const char* value() 00320 { 00321 return "sensor_msgs/Image greyImage\n\ 00322 sensor_msgs/Image xyzImage\n\ 00323 \n\ 00324 \n\ 00325 ================================================================================\n\ 00326 MSG: sensor_msgs/Image\n\ 00327 # This message contains an uncompressed image\n\ 00328 # (0, 0) is at top-left corner of image\n\ 00329 #\n\ 00330 \n\ 00331 Header header # Header timestamp should be acquisition time of image\n\ 00332 # Header frame_id should be optical frame of camera\n\ 00333 # origin of frame should be optical center of cameara\n\ 00334 # +x should point to the right in the image\n\ 00335 # +y should point down in the image\n\ 00336 # +z should point into to plane of the image\n\ 00337 # If the frame_id here and the frame_id of the CameraInfo\n\ 00338 # message associated with the image conflict\n\ 00339 # the behavior is undefined\n\ 00340 \n\ 00341 uint32 height # image height, that is, number of rows\n\ 00342 uint32 width # image width, that is, number of columns\n\ 00343 \n\ 00344 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00345 # If you want to standardize a new string format, join\n\ 00346 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00347 \n\ 00348 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00349 # taken from the list of strings in src/image_encodings.cpp\n\ 00350 \n\ 00351 uint8 is_bigendian # is this data bigendian?\n\ 00352 uint32 step # Full row length in bytes\n\ 00353 uint8[] data # actual matrix data, size is (step * rows)\n\ 00354 \n\ 00355 ================================================================================\n\ 00356 MSG: std_msgs/Header\n\ 00357 # Standard metadata for higher-level stamped data types.\n\ 00358 # This is generally used to communicate timestamped data \n\ 00359 # in a particular coordinate frame.\n\ 00360 # \n\ 00361 # sequence ID: consecutively increasing ID \n\ 00362 uint32 seq\n\ 00363 #Two-integer timestamp that is expressed as:\n\ 00364 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00365 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00366 # time-handling sugar is provided by the client library\n\ 00367 time stamp\n\ 00368 #Frame this data is associated with\n\ 00369 # 0: no frame\n\ 00370 # 1: global frame\n\ 00371 string frame_id\n\ 00372 \n\ 00373 "; 00374 } 00375 00376 static const char* value(const ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> &) { return value(); } 00377 }; 00378 00379 } // namespace message_traits 00380 } // namespace ros 00381 00382 namespace ros 00383 { 00384 namespace serialization 00385 { 00386 00387 template<class ContainerAllocator> struct Serializer< ::cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > 00388 { 00389 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00390 { 00391 } 00392 00393 ROS_DECLARE_ALLINONE_SERIALIZER; 00394 }; // struct GetTOFImagesRequest_ 00395 } // namespace serialization 00396 } // namespace ros 00397 00398 00399 namespace ros 00400 { 00401 namespace serialization 00402 { 00403 00404 template<class ContainerAllocator> struct Serializer< ::cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > 00405 { 00406 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00407 { 00408 stream.next(m.greyImage); 00409 stream.next(m.xyzImage); 00410 } 00411 00412 ROS_DECLARE_ALLINONE_SERIALIZER; 00413 }; // struct GetTOFImagesResponse_ 00414 } // namespace serialization 00415 } // namespace ros 00416 00417 namespace ros 00418 { 00419 namespace service_traits 00420 { 00421 template<> 00422 struct MD5Sum<cob_camera_sensors::GetTOFImages> { 00423 static const char* value() 00424 { 00425 return "245ce4e6dd0ec61a5c674c8191a91877"; 00426 } 00427 00428 static const char* value(const cob_camera_sensors::GetTOFImages&) { return value(); } 00429 }; 00430 00431 template<> 00432 struct DataType<cob_camera_sensors::GetTOFImages> { 00433 static const char* value() 00434 { 00435 return "cob_camera_sensors/GetTOFImages"; 00436 } 00437 00438 static const char* value(const cob_camera_sensors::GetTOFImages&) { return value(); } 00439 }; 00440 00441 template<class ContainerAllocator> 00442 struct MD5Sum<cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > { 00443 static const char* value() 00444 { 00445 return "245ce4e6dd0ec61a5c674c8191a91877"; 00446 } 00447 00448 static const char* value(const cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> &) { return value(); } 00449 }; 00450 00451 template<class ContainerAllocator> 00452 struct DataType<cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> > { 00453 static const char* value() 00454 { 00455 return "cob_camera_sensors/GetTOFImages"; 00456 } 00457 00458 static const char* value(const cob_camera_sensors::GetTOFImagesRequest_<ContainerAllocator> &) { return value(); } 00459 }; 00460 00461 template<class ContainerAllocator> 00462 struct MD5Sum<cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > { 00463 static const char* value() 00464 { 00465 return "245ce4e6dd0ec61a5c674c8191a91877"; 00466 } 00467 00468 static const char* value(const cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> &) { return value(); } 00469 }; 00470 00471 template<class ContainerAllocator> 00472 struct DataType<cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> > { 00473 static const char* value() 00474 { 00475 return "cob_camera_sensors/GetTOFImages"; 00476 } 00477 00478 static const char* value(const cob_camera_sensors::GetTOFImagesResponse_<ContainerAllocator> &) { return value(); } 00479 }; 00480 00481 } // namespace service_traits 00482 } // namespace ros 00483 00484 #endif // COB_CAMERA_SENSORS_SERVICE_GETTOFIMAGES_H 00485