AcquireObjectImage.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-cob_perception_common/doc_stacks/2013-03-08_15-00-12.727680/cob_perception_common/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   typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > Ptr;
00060   typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator>  const> ConstPtr;
00061   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00062 }; // struct AcquireObjectImageRequest
00063 typedef  ::cob_object_detection_msgs::AcquireObjectImageRequest_<std::allocator<void> > AcquireObjectImageRequest;
00064 
00065 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest> AcquireObjectImageRequestPtr;
00066 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageRequest const> AcquireObjectImageRequestConstPtr;
00067 
00068 
00069 template <class ContainerAllocator>
00070 struct AcquireObjectImageResponse_ {
00071   typedef AcquireObjectImageResponse_<ContainerAllocator> Type;
00072 
00073   AcquireObjectImageResponse_()
00074   {
00075   }
00076 
00077   AcquireObjectImageResponse_(const ContainerAllocator& _alloc)
00078   {
00079   }
00080 
00081 
00082   typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > Ptr;
00083   typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator>  const> ConstPtr;
00084   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00085 }; // struct AcquireObjectImageResponse
00086 typedef  ::cob_object_detection_msgs::AcquireObjectImageResponse_<std::allocator<void> > AcquireObjectImageResponse;
00087 
00088 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse> AcquireObjectImageResponsePtr;
00089 typedef boost::shared_ptr< ::cob_object_detection_msgs::AcquireObjectImageResponse const> AcquireObjectImageResponseConstPtr;
00090 
00091 struct AcquireObjectImage
00092 {
00093 
00094 typedef AcquireObjectImageRequest Request;
00095 typedef AcquireObjectImageResponse Response;
00096 Request request;
00097 Response response;
00098 
00099 typedef Request RequestType;
00100 typedef Response ResponseType;
00101 }; // struct AcquireObjectImage
00102 } // namespace cob_object_detection_msgs
00103 
00104 namespace ros
00105 {
00106 namespace message_traits
00107 {
00108 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > : public TrueType {};
00109 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator>  const> : public TrueType {};
00110 template<class ContainerAllocator>
00111 struct MD5Sum< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > {
00112   static const char* value() 
00113   {
00114     return "a834da64b488488418ecf10d2737befd";
00115   }
00116 
00117   static const char* value(const  ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 
00118   static const uint64_t static_value1 = 0xa834da64b4884884ULL;
00119   static const uint64_t static_value2 = 0x18ecf10d2737befdULL;
00120 };
00121 
00122 template<class ContainerAllocator>
00123 struct DataType< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > {
00124   static const char* value() 
00125   {
00126     return "cob_object_detection_msgs/AcquireObjectImageRequest";
00127   }
00128 
00129   static const char* value(const  ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 
00130 };
00131 
00132 template<class ContainerAllocator>
00133 struct Definition< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > {
00134   static const char* value() 
00135   {
00136     return "string object_name\n\
00137 bool reset_image_counter\n\
00138 geometry_msgs/PoseStamped pose\n\
00139 geometry_msgs/PoseStamped[] sdh_joints\n\
00140 \n\
00141 ================================================================================\n\
00142 MSG: geometry_msgs/PoseStamped\n\
00143 # A Pose with reference coordinate frame and timestamp\n\
00144 Header header\n\
00145 Pose pose\n\
00146 \n\
00147 ================================================================================\n\
00148 MSG: std_msgs/Header\n\
00149 # Standard metadata for higher-level stamped data types.\n\
00150 # This is generally used to communicate timestamped data \n\
00151 # in a particular coordinate frame.\n\
00152 # \n\
00153 # sequence ID: consecutively increasing ID \n\
00154 uint32 seq\n\
00155 #Two-integer timestamp that is expressed as:\n\
00156 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00157 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00158 # time-handling sugar is provided by the client library\n\
00159 time stamp\n\
00160 #Frame this data is associated with\n\
00161 # 0: no frame\n\
00162 # 1: global frame\n\
00163 string frame_id\n\
00164 \n\
00165 ================================================================================\n\
00166 MSG: geometry_msgs/Pose\n\
00167 # A representation of pose in free space, composed of postion and orientation. \n\
00168 Point position\n\
00169 Quaternion orientation\n\
00170 \n\
00171 ================================================================================\n\
00172 MSG: geometry_msgs/Point\n\
00173 # This contains the position of a point in free space\n\
00174 float64 x\n\
00175 float64 y\n\
00176 float64 z\n\
00177 \n\
00178 ================================================================================\n\
00179 MSG: geometry_msgs/Quaternion\n\
00180 # This represents an orientation in free space in quaternion form.\n\
00181 \n\
00182 float64 x\n\
00183 float64 y\n\
00184 float64 z\n\
00185 float64 w\n\
00186 \n\
00187 ";
00188   }
00189 
00190   static const char* value(const  ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 
00191 };
00192 
00193 } // namespace message_traits
00194 } // namespace ros
00195 
00196 
00197 namespace ros
00198 {
00199 namespace message_traits
00200 {
00201 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > : public TrueType {};
00202 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator>  const> : public TrueType {};
00203 template<class ContainerAllocator>
00204 struct MD5Sum< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > {
00205   static const char* value() 
00206   {
00207     return "d41d8cd98f00b204e9800998ecf8427e";
00208   }
00209 
00210   static const char* value(const  ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 
00211   static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL;
00212   static const uint64_t static_value2 = 0xe9800998ecf8427eULL;
00213 };
00214 
00215 template<class ContainerAllocator>
00216 struct DataType< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > {
00217   static const char* value() 
00218   {
00219     return "cob_object_detection_msgs/AcquireObjectImageResponse";
00220   }
00221 
00222   static const char* value(const  ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 
00223 };
00224 
00225 template<class ContainerAllocator>
00226 struct Definition< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > {
00227   static const char* value() 
00228   {
00229     return "\n\
00230 \n\
00231 \n\
00232 ";
00233   }
00234 
00235   static const char* value(const  ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 
00236 };
00237 
00238 template<class ContainerAllocator> struct IsFixedSize< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > : public TrueType {};
00239 } // namespace message_traits
00240 } // namespace ros
00241 
00242 namespace ros
00243 {
00244 namespace serialization
00245 {
00246 
00247 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> >
00248 {
00249   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00250   {
00251     stream.next(m.object_name);
00252     stream.next(m.reset_image_counter);
00253     stream.next(m.pose);
00254     stream.next(m.sdh_joints);
00255   }
00256 
00257   ROS_DECLARE_ALLINONE_SERIALIZER;
00258 }; // struct AcquireObjectImageRequest_
00259 } // namespace serialization
00260 } // namespace ros
00261 
00262 
00263 namespace ros
00264 {
00265 namespace serialization
00266 {
00267 
00268 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> >
00269 {
00270   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00271   {
00272   }
00273 
00274   ROS_DECLARE_ALLINONE_SERIALIZER;
00275 }; // struct AcquireObjectImageResponse_
00276 } // namespace serialization
00277 } // namespace ros
00278 
00279 namespace ros
00280 {
00281 namespace service_traits
00282 {
00283 template<>
00284 struct MD5Sum<cob_object_detection_msgs::AcquireObjectImage> {
00285   static const char* value() 
00286   {
00287     return "a834da64b488488418ecf10d2737befd";
00288   }
00289 
00290   static const char* value(const cob_object_detection_msgs::AcquireObjectImage&) { return value(); } 
00291 };
00292 
00293 template<>
00294 struct DataType<cob_object_detection_msgs::AcquireObjectImage> {
00295   static const char* value() 
00296   {
00297     return "cob_object_detection_msgs/AcquireObjectImage";
00298   }
00299 
00300   static const char* value(const cob_object_detection_msgs::AcquireObjectImage&) { return value(); } 
00301 };
00302 
00303 template<class ContainerAllocator>
00304 struct MD5Sum<cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > {
00305   static const char* value() 
00306   {
00307     return "a834da64b488488418ecf10d2737befd";
00308   }
00309 
00310   static const char* value(const cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 
00311 };
00312 
00313 template<class ContainerAllocator>
00314 struct DataType<cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> > {
00315   static const char* value() 
00316   {
00317     return "cob_object_detection_msgs/AcquireObjectImage";
00318   }
00319 
00320   static const char* value(const cob_object_detection_msgs::AcquireObjectImageRequest_<ContainerAllocator> &) { return value(); } 
00321 };
00322 
00323 template<class ContainerAllocator>
00324 struct MD5Sum<cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > {
00325   static const char* value() 
00326   {
00327     return "a834da64b488488418ecf10d2737befd";
00328   }
00329 
00330   static const char* value(const cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 
00331 };
00332 
00333 template<class ContainerAllocator>
00334 struct DataType<cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> > {
00335   static const char* value() 
00336   {
00337     return "cob_object_detection_msgs/AcquireObjectImage";
00338   }
00339 
00340   static const char* value(const cob_object_detection_msgs::AcquireObjectImageResponse_<ContainerAllocator> &) { return value(); } 
00341 };
00342 
00343 } // namespace service_traits
00344 } // namespace ros
00345 
00346 #endif // COB_OBJECT_DETECTION_MSGS_SERVICE_ACQUIREOBJECTIMAGE_H
00347 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


cob_object_detection_msgs
Author(s): Florian Weisshardt
autogenerated on Fri Mar 8 2013 15:04:09