$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_object_perception/doc_stacks/2013-03-01_14-45-40.878742/cob_object_perception/cob_object_detection_msgs/srv/AcquireObjectImage.srv */ 00002 #ifndef COB_OBJECT_DETECTION_MSGS_SERVICE_ACQUIREOBJECTIMAGE_H 00003 #define COB_OBJECT_DETECTION_MSGS_SERVICE_ACQUIREOBJECTIMAGE_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 "geometry_msgs/PoseStamped.h" 00020 #include "geometry_msgs/PoseStamped.h" 00021 00022 00023 00024 namespace cob_object_detection_msgs 00025 { 00026 template <class ContainerAllocator> 00027 struct AcquireObjectImageRequest_ { 00028 typedef AcquireObjectImageRequest_<ContainerAllocator> Type; 00029 00030 AcquireObjectImageRequest_() 00031 : object_name() 00032 , reset_image_counter(false) 00033 , pose() 00034 , sdh_joints() 00035 { 00036 } 00037 00038 AcquireObjectImageRequest_(const ContainerAllocator& _alloc) 00039 : object_name(_alloc) 00040 , reset_image_counter(false) 00041 , pose(_alloc) 00042 , sdh_joints(_alloc) 00043 { 00044 } 00045 00046 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_name_type; 00047 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_name; 00048 00049 typedef uint8_t _reset_image_counter_type; 00050 uint8_t reset_image_counter; 00051 00052 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_type; 00053 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose; 00054 00055 typedef std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > _sdh_joints_type; 00056 std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > sdh_joints; 00057 00058 00059 ROS_DEPRECATED uint32_t get_sdh_joints_size() const { return (uint32_t)sdh_joints.size(); } 00060 ROS_DEPRECATED void set_sdh_joints_size(uint32_t size) { sdh_joints.resize((size_t)size); } 00061 ROS_DEPRECATED void get_sdh_joints_vec(std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > & vec) const { vec = this->sdh_joints; } 00062 ROS_DEPRECATED void set_sdh_joints_vec(const std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > & vec) { this->sdh_joints = vec; } 00063 private: 00064 static const char* __s_getDataType_() { return "cob_object_detection_msgs/AcquireObjectImageRequest"; } 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 "a834da64b488488418ecf10d2737befd"; } 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 "a834da64b488488418ecf10d2737befd"; } 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 "string object_name\n\ 00086 bool reset_image_counter\n\ 00087 geometry_msgs/PoseStamped pose\n\ 00088 geometry_msgs/PoseStamped[] sdh_joints\n\ 00089 \n\ 00090 ================================================================================\n\ 00091 MSG: geometry_msgs/PoseStamped\n\ 00092 # A Pose with reference coordinate frame and timestamp\n\ 00093 Header header\n\ 00094 Pose pose\n\ 00095 \n\ 00096 ================================================================================\n\ 00097 MSG: std_msgs/Header\n\ 00098 # Standard metadata for higher-level stamped data types.\n\ 00099 # This is generally used to communicate timestamped data \n\ 00100 # in a particular coordinate frame.\n\ 00101 # \n\ 00102 # sequence ID: consecutively increasing ID \n\ 00103 uint32 seq\n\ 00104 #Two-integer timestamp that is expressed as:\n\ 00105 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00106 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00107 # time-handling sugar is provided by the client library\n\ 00108 time stamp\n\ 00109 #Frame this data is associated with\n\ 00110 # 0: no frame\n\ 00111 # 1: global frame\n\ 00112 string frame_id\n\ 00113 \n\ 00114 ================================================================================\n\ 00115 MSG: geometry_msgs/Pose\n\ 00116 # A representation of pose in free space, composed of postion and orientation. \n\ 00117 Point position\n\ 00118 Quaternion orientation\n\ 00119 \n\ 00120 ================================================================================\n\ 00121 MSG: geometry_msgs/Point\n\ 00122 # This contains the position of a point in free space\n\ 00123 float64 x\n\ 00124 float64 y\n\ 00125 float64 z\n\ 00126 \n\ 00127 ================================================================================\n\ 00128 MSG: geometry_msgs/Quaternion\n\ 00129 # This represents an orientation in free space in quaternion form.\n\ 00130 \n\ 00131 float64 x\n\ 00132 float64 y\n\ 00133 float64 z\n\ 00134 float64 w\n\ 00135 \n\ 00136 "; } 00137 public: 00138 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00139 00140 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00141 00142 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00143 { 00144 ros::serialization::OStream stream(write_ptr, 1000000000); 00145 ros::serialization::serialize(stream, object_name); 00146 ros::serialization::serialize(stream, reset_image_counter); 00147 ros::serialization::serialize(stream, pose); 00148 ros::serialization::serialize(stream, sdh_joints); 00149 return stream.getData(); 00150 } 00151 00152 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00153 { 00154 ros::serialization::IStream stream(read_ptr, 1000000000); 00155 ros::serialization::deserialize(stream, object_name); 00156 ros::serialization::deserialize(stream, reset_image_counter); 00157 ros::serialization::deserialize(stream, pose); 00158 ros::serialization::deserialize(stream, sdh_joints); 00159 return stream.getData(); 00160 } 00161 00162 ROS_DEPRECATED virtual uint32_t serializationLength() const 00163 { 00164 uint32_t size = 0; 00165 size += ros::serialization::serializationLength(object_name); 00166 size += ros::serialization::serializationLength(reset_image_counter); 00167 size += ros::serialization::serializationLength(pose); 00168 size += ros::serialization::serializationLength(sdh_joints); 00169 return size; 00170 } 00171 00172 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > Ptr; 00173 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> const> ConstPtr; 00174 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00175 }; // struct AcquireObjectImageRequest 00176 typedef ::cob_object_detection_msgs::AcquireObjectImageRequest_<std::allocator<void> > AcquireObjectImageRequest; 00177 00178 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest> AcquireObjectImageRequestPtr; 00179 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest const> AcquireObjectImageRequestConstPtr; 00180 00181 00182 template <class ContainerAllocator> 00183 struct AcquireObjectImageResponse_ { 00184 typedef AcquireObjectImageResponse_<ContainerAllocator> Type; 00185 00186 AcquireObjectImageResponse_() 00187 { 00188 } 00189 00190 AcquireObjectImageResponse_(const ContainerAllocator& _alloc) 00191 { 00192 } 00193 00194 00195 private: 00196 static const char* __s_getDataType_() { return "cob_object_detection_msgs/AcquireObjectImageResponse"; } 00197 public: 00198 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00199 00200 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00201 00202 private: 00203 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00204 public: 00205 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00206 00207 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00208 00209 private: 00210 static const char* __s_getServerMD5Sum_() { return "a834da64b488488418ecf10d2737befd"; } 00211 public: 00212 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00213 00214 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00215 00216 private: 00217 static const char* __s_getMessageDefinition_() { return "\n\ 00218 \n\ 00219 \n\ 00220 "; } 00221 public: 00222 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00223 00224 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00225 00226 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00227 { 00228 ros::serialization::OStream stream(write_ptr, 1000000000); 00229 return stream.getData(); 00230 } 00231 00232 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00233 { 00234 ros::serialization::IStream stream(read_ptr, 1000000000); 00235 return stream.getData(); 00236 } 00237 00238 ROS_DEPRECATED virtual uint32_t serializationLength() const 00239 { 00240 uint32_t size = 0; 00241 return size; 00242 } 00243 00244 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > Ptr; 00245 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> const> ConstPtr; 00246 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00247 }; // struct AcquireObjectImageResponse 00248 typedef ::cob_object_detection_msgs::AcquireObjectImageResponse_<std::allocator<void> > AcquireObjectImageResponse; 00249 00250 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse> AcquireObjectImageResponsePtr; 00251 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse const> AcquireObjectImageResponseConstPtr; 00252 00253 struct AcquireObjectImage 00254 { 00255 00256 typedef AcquireObjectImageRequest Request; 00257 typedef AcquireObjectImageResponse Response; 00258 Request request; 00259 Response response; 00260 00261 typedef Request RequestType; 00262 typedef Response ResponseType; 00263 }; // struct AcquireObjectImage 00264 } // namespace cob_object_detection_msgs 00265 00266 namespace ros 00267 { 00268 namespace message_traits 00269 { 00270 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > : public TrueType {}; 00271 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> const> : public TrueType {}; 00272 template<class ContainerAllocator> 00273 struct MD5Sum< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > { 00274 static const char* value() 00275 { 00276 return "a834da64b488488418ecf10d2737befd"; 00277 } 00278 00279 static const char* value(const ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 00280 static const uint64_t static_value1 = 0xa834da64b4884884ULL; 00281 static const uint64_t static_value2 = 0x18ecf10d2737befdULL; 00282 }; 00283 00284 template<class ContainerAllocator> 00285 struct DataType< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > { 00286 static const char* value() 00287 { 00288 return "cob_object_detection_msgs/AcquireObjectImageRequest"; 00289 } 00290 00291 static const char* value(const ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 00292 }; 00293 00294 template<class ContainerAllocator> 00295 struct Definition< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > { 00296 static const char* value() 00297 { 00298 return "string object_name\n\ 00299 bool reset_image_counter\n\ 00300 geometry_msgs/PoseStamped pose\n\ 00301 geometry_msgs/PoseStamped[] sdh_joints\n\ 00302 \n\ 00303 ================================================================================\n\ 00304 MSG: geometry_msgs/PoseStamped\n\ 00305 # A Pose with reference coordinate frame and timestamp\n\ 00306 Header header\n\ 00307 Pose pose\n\ 00308 \n\ 00309 ================================================================================\n\ 00310 MSG: std_msgs/Header\n\ 00311 # Standard metadata for higher-level stamped data types.\n\ 00312 # This is generally used to communicate timestamped data \n\ 00313 # in a particular coordinate frame.\n\ 00314 # \n\ 00315 # sequence ID: consecutively increasing ID \n\ 00316 uint32 seq\n\ 00317 #Two-integer timestamp that is expressed as:\n\ 00318 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00319 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00320 # time-handling sugar is provided by the client library\n\ 00321 time stamp\n\ 00322 #Frame this data is associated with\n\ 00323 # 0: no frame\n\ 00324 # 1: global frame\n\ 00325 string frame_id\n\ 00326 \n\ 00327 ================================================================================\n\ 00328 MSG: geometry_msgs/Pose\n\ 00329 # A representation of pose in free space, composed of postion and orientation. \n\ 00330 Point position\n\ 00331 Quaternion orientation\n\ 00332 \n\ 00333 ================================================================================\n\ 00334 MSG: geometry_msgs/Point\n\ 00335 # This contains the position of a point in free space\n\ 00336 float64 x\n\ 00337 float64 y\n\ 00338 float64 z\n\ 00339 \n\ 00340 ================================================================================\n\ 00341 MSG: geometry_msgs/Quaternion\n\ 00342 # This represents an orientation in free space in quaternion form.\n\ 00343 \n\ 00344 float64 x\n\ 00345 float64 y\n\ 00346 float64 z\n\ 00347 float64 w\n\ 00348 \n\ 00349 "; 00350 } 00351 00352 static const char* value(const ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 00353 }; 00354 00355 } // namespace message_traits 00356 } // namespace ros 00357 00358 00359 namespace ros 00360 { 00361 namespace message_traits 00362 { 00363 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > : public TrueType {}; 00364 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> const> : public TrueType {}; 00365 template<class ContainerAllocator> 00366 struct MD5Sum< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > { 00367 static const char* value() 00368 { 00369 return "d41d8cd98f00b204e9800998ecf8427e"; 00370 } 00371 00372 static const char* value(const ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 00373 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00374 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00375 }; 00376 00377 template<class ContainerAllocator> 00378 struct DataType< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > { 00379 static const char* value() 00380 { 00381 return "cob_object_detection_msgs/AcquireObjectImageResponse"; 00382 } 00383 00384 static const char* value(const ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 00385 }; 00386 00387 template<class ContainerAllocator> 00388 struct Definition< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > { 00389 static const char* value() 00390 { 00391 return "\n\ 00392 \n\ 00393 \n\ 00394 "; 00395 } 00396 00397 static const char* value(const ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 00398 }; 00399 00400 template<class ContainerAllocator> struct IsFixedSize< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > : public TrueType {}; 00401 } // namespace message_traits 00402 } // namespace ros 00403 00404 namespace ros 00405 { 00406 namespace serialization 00407 { 00408 00409 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > 00410 { 00411 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00412 { 00413 stream.next(m.object_name); 00414 stream.next(m.reset_image_counter); 00415 stream.next(m.pose); 00416 stream.next(m.sdh_joints); 00417 } 00418 00419 ROS_DECLARE_ALLINONE_SERIALIZER; 00420 }; // struct AcquireObjectImageRequest_ 00421 } // namespace serialization 00422 } // namespace ros 00423 00424 00425 namespace ros 00426 { 00427 namespace serialization 00428 { 00429 00430 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > 00431 { 00432 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00433 { 00434 } 00435 00436 ROS_DECLARE_ALLINONE_SERIALIZER; 00437 }; // struct AcquireObjectImageResponse_ 00438 } // namespace serialization 00439 } // namespace ros 00440 00441 namespace ros 00442 { 00443 namespace service_traits 00444 { 00445 template<> 00446 struct MD5Sum<cob_object_detection_msgs::AcquireObjectImage> { 00447 static const char* value() 00448 { 00449 return "a834da64b488488418ecf10d2737befd"; 00450 } 00451 00452 static const char* value(const cob_object_detection_msgs::AcquireObjectImage&) { return value(); } 00453 }; 00454 00455 template<> 00456 struct DataType<cob_object_detection_msgs::AcquireObjectImage> { 00457 static const char* value() 00458 { 00459 return "cob_object_detection_msgs/AcquireObjectImage"; 00460 } 00461 00462 static const char* value(const cob_object_detection_msgs::AcquireObjectImage&) { return value(); } 00463 }; 00464 00465 template<class ContainerAllocator> 00466 struct MD5Sum<cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > { 00467 static const char* value() 00468 { 00469 return "a834da64b488488418ecf10d2737befd"; 00470 } 00471 00472 static const char* value(const cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 00473 }; 00474 00475 template<class ContainerAllocator> 00476 struct DataType<cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > { 00477 static const char* value() 00478 { 00479 return "cob_object_detection_msgs/AcquireObjectImage"; 00480 } 00481 00482 static const char* value(const cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 00483 }; 00484 00485 template<class ContainerAllocator> 00486 struct MD5Sum<cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > { 00487 static const char* value() 00488 { 00489 return "a834da64b488488418ecf10d2737befd"; 00490 } 00491 00492 static const char* value(const cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 00493 }; 00494 00495 template<class ContainerAllocator> 00496 struct DataType<cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > { 00497 static const char* value() 00498 { 00499 return "cob_object_detection_msgs/AcquireObjectImage"; 00500 } 00501 00502 static const char* value(const cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 00503 }; 00504 00505 } // namespace service_traits 00506 } // namespace ros 00507 00508 #endif // COB_OBJECT_DETECTION_MSGS_SERVICE_ACQUIREOBJECTIMAGE_H 00509