$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-srs_public/doc_stacks/2013-03-05_12-22-34.333426/srs_public/srs_interaction_primitives/srv/GetUnknownObject.srv */ 00002 #ifndef SRS_INTERACTION_PRIMITIVES_SERVICE_GETUNKNOWNOBJECT_H 00003 #define SRS_INTERACTION_PRIMITIVES_SERVICE_GETUNKNOWNOBJECT_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 "geometry_msgs/Pose.h" 00022 #include "geometry_msgs/Vector3.h" 00023 00024 namespace srs_interaction_primitives 00025 { 00026 template <class ContainerAllocator> 00027 struct GetUnknownObjectRequest_ { 00028 typedef GetUnknownObjectRequest_<ContainerAllocator> Type; 00029 00030 GetUnknownObjectRequest_() 00031 : name() 00032 { 00033 } 00034 00035 GetUnknownObjectRequest_(const ContainerAllocator& _alloc) 00036 : name(_alloc) 00037 { 00038 } 00039 00040 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type; 00041 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name; 00042 00043 00044 private: 00045 static const char* __s_getDataType_() { return "srs_interaction_primitives/GetUnknownObjectRequest"; } 00046 public: 00047 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00048 00049 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00050 00051 private: 00052 static const char* __s_getMD5Sum_() { return "c1f3d28f1b044c871e6eff2e9fc3c667"; } 00053 public: 00054 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00055 00056 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00057 00058 private: 00059 static const char* __s_getServerMD5Sum_() { return "ee9aa16c34388cc30eaf9eea1330d475"; } 00060 public: 00061 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00062 00063 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00064 00065 private: 00066 static const char* __s_getMessageDefinition_() { return "string name\n\ 00067 \n\ 00068 "; } 00069 public: 00070 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00071 00072 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00073 00074 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00075 { 00076 ros::serialization::OStream stream(write_ptr, 1000000000); 00077 ros::serialization::serialize(stream, name); 00078 return stream.getData(); 00079 } 00080 00081 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00082 { 00083 ros::serialization::IStream stream(read_ptr, 1000000000); 00084 ros::serialization::deserialize(stream, name); 00085 return stream.getData(); 00086 } 00087 00088 ROS_DEPRECATED virtual uint32_t serializationLength() const 00089 { 00090 uint32_t size = 0; 00091 size += ros::serialization::serializationLength(name); 00092 return size; 00093 } 00094 00095 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > Ptr; 00096 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> const> ConstPtr; 00097 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00098 }; // struct GetUnknownObjectRequest 00099 typedef ::srs_interaction_primitives::GetUnknownObjectRequest_<std::allocator<void> > GetUnknownObjectRequest; 00100 00101 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectRequest> GetUnknownObjectRequestPtr; 00102 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectRequest const> GetUnknownObjectRequestConstPtr; 00103 00104 00105 template <class ContainerAllocator> 00106 struct GetUnknownObjectResponse_ { 00107 typedef GetUnknownObjectResponse_<ContainerAllocator> Type; 00108 00109 GetUnknownObjectResponse_() 00110 : frame_id() 00111 , name() 00112 , description() 00113 , pose_type(0) 00114 , pose() 00115 , scale() 00116 { 00117 } 00118 00119 GetUnknownObjectResponse_(const ContainerAllocator& _alloc) 00120 : frame_id(_alloc) 00121 , name(_alloc) 00122 , description(_alloc) 00123 , pose_type(0) 00124 , pose(_alloc) 00125 , scale(_alloc) 00126 { 00127 } 00128 00129 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _frame_id_type; 00130 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > frame_id; 00131 00132 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type; 00133 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name; 00134 00135 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _description_type; 00136 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > description; 00137 00138 typedef uint8_t _pose_type_type; 00139 uint8_t pose_type; 00140 00141 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type; 00142 ::geometry_msgs::Pose_<ContainerAllocator> pose; 00143 00144 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _scale_type; 00145 ::geometry_msgs::Vector3_<ContainerAllocator> scale; 00146 00147 00148 private: 00149 static const char* __s_getDataType_() { return "srs_interaction_primitives/GetUnknownObjectResponse"; } 00150 public: 00151 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00152 00153 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00154 00155 private: 00156 static const char* __s_getMD5Sum_() { return "fa05deb26932a5fd6c9c6ad37fe3565a"; } 00157 public: 00158 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00159 00160 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00161 00162 private: 00163 static const char* __s_getServerMD5Sum_() { return "ee9aa16c34388cc30eaf9eea1330d475"; } 00164 public: 00165 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00166 00167 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00168 00169 private: 00170 static const char* __s_getMessageDefinition_() { return "string frame_id\n\ 00171 string name\n\ 00172 string description\n\ 00173 uint8 pose_type\n\ 00174 geometry_msgs/Pose pose\n\ 00175 geometry_msgs/Vector3 scale\n\ 00176 \n\ 00177 \n\ 00178 ================================================================================\n\ 00179 MSG: geometry_msgs/Pose\n\ 00180 # A representation of pose in free space, composed of postion and orientation. \n\ 00181 Point position\n\ 00182 Quaternion orientation\n\ 00183 \n\ 00184 ================================================================================\n\ 00185 MSG: geometry_msgs/Point\n\ 00186 # This contains the position of a point in free space\n\ 00187 float64 x\n\ 00188 float64 y\n\ 00189 float64 z\n\ 00190 \n\ 00191 ================================================================================\n\ 00192 MSG: geometry_msgs/Quaternion\n\ 00193 # This represents an orientation in free space in quaternion form.\n\ 00194 \n\ 00195 float64 x\n\ 00196 float64 y\n\ 00197 float64 z\n\ 00198 float64 w\n\ 00199 \n\ 00200 ================================================================================\n\ 00201 MSG: geometry_msgs/Vector3\n\ 00202 # This represents a vector in free space. \n\ 00203 \n\ 00204 float64 x\n\ 00205 float64 y\n\ 00206 float64 z\n\ 00207 "; } 00208 public: 00209 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00210 00211 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00212 00213 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00214 { 00215 ros::serialization::OStream stream(write_ptr, 1000000000); 00216 ros::serialization::serialize(stream, frame_id); 00217 ros::serialization::serialize(stream, name); 00218 ros::serialization::serialize(stream, description); 00219 ros::serialization::serialize(stream, pose_type); 00220 ros::serialization::serialize(stream, pose); 00221 ros::serialization::serialize(stream, scale); 00222 return stream.getData(); 00223 } 00224 00225 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00226 { 00227 ros::serialization::IStream stream(read_ptr, 1000000000); 00228 ros::serialization::deserialize(stream, frame_id); 00229 ros::serialization::deserialize(stream, name); 00230 ros::serialization::deserialize(stream, description); 00231 ros::serialization::deserialize(stream, pose_type); 00232 ros::serialization::deserialize(stream, pose); 00233 ros::serialization::deserialize(stream, scale); 00234 return stream.getData(); 00235 } 00236 00237 ROS_DEPRECATED virtual uint32_t serializationLength() const 00238 { 00239 uint32_t size = 0; 00240 size += ros::serialization::serializationLength(frame_id); 00241 size += ros::serialization::serializationLength(name); 00242 size += ros::serialization::serializationLength(description); 00243 size += ros::serialization::serializationLength(pose_type); 00244 size += ros::serialization::serializationLength(pose); 00245 size += ros::serialization::serializationLength(scale); 00246 return size; 00247 } 00248 00249 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > Ptr; 00250 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> const> ConstPtr; 00251 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00252 }; // struct GetUnknownObjectResponse 00253 typedef ::srs_interaction_primitives::GetUnknownObjectResponse_<std::allocator<void> > GetUnknownObjectResponse; 00254 00255 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectResponse> GetUnknownObjectResponsePtr; 00256 typedef boost::shared_ptr< ::srs_interaction_primitives::GetUnknownObjectResponse const> GetUnknownObjectResponseConstPtr; 00257 00258 struct GetUnknownObject 00259 { 00260 00261 typedef GetUnknownObjectRequest Request; 00262 typedef GetUnknownObjectResponse Response; 00263 Request request; 00264 Response response; 00265 00266 typedef Request RequestType; 00267 typedef Response ResponseType; 00268 }; // struct GetUnknownObject 00269 } // namespace srs_interaction_primitives 00270 00271 namespace ros 00272 { 00273 namespace message_traits 00274 { 00275 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > : public TrueType {}; 00276 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> const> : public TrueType {}; 00277 template<class ContainerAllocator> 00278 struct MD5Sum< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > { 00279 static const char* value() 00280 { 00281 return "c1f3d28f1b044c871e6eff2e9fc3c667"; 00282 } 00283 00284 static const char* value(const ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> &) { return value(); } 00285 static const uint64_t static_value1 = 0xc1f3d28f1b044c87ULL; 00286 static const uint64_t static_value2 = 0x1e6eff2e9fc3c667ULL; 00287 }; 00288 00289 template<class ContainerAllocator> 00290 struct DataType< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > { 00291 static const char* value() 00292 { 00293 return "srs_interaction_primitives/GetUnknownObjectRequest"; 00294 } 00295 00296 static const char* value(const ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> &) { return value(); } 00297 }; 00298 00299 template<class ContainerAllocator> 00300 struct Definition< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > { 00301 static const char* value() 00302 { 00303 return "string name\n\ 00304 \n\ 00305 "; 00306 } 00307 00308 static const char* value(const ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> &) { return value(); } 00309 }; 00310 00311 } // namespace message_traits 00312 } // namespace ros 00313 00314 00315 namespace ros 00316 { 00317 namespace message_traits 00318 { 00319 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > : public TrueType {}; 00320 template<class ContainerAllocator> struct IsMessage< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> const> : public TrueType {}; 00321 template<class ContainerAllocator> 00322 struct MD5Sum< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > { 00323 static const char* value() 00324 { 00325 return "fa05deb26932a5fd6c9c6ad37fe3565a"; 00326 } 00327 00328 static const char* value(const ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> &) { return value(); } 00329 static const uint64_t static_value1 = 0xfa05deb26932a5fdULL; 00330 static const uint64_t static_value2 = 0x6c9c6ad37fe3565aULL; 00331 }; 00332 00333 template<class ContainerAllocator> 00334 struct DataType< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > { 00335 static const char* value() 00336 { 00337 return "srs_interaction_primitives/GetUnknownObjectResponse"; 00338 } 00339 00340 static const char* value(const ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> &) { return value(); } 00341 }; 00342 00343 template<class ContainerAllocator> 00344 struct Definition< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > { 00345 static const char* value() 00346 { 00347 return "string frame_id\n\ 00348 string name\n\ 00349 string description\n\ 00350 uint8 pose_type\n\ 00351 geometry_msgs/Pose pose\n\ 00352 geometry_msgs/Vector3 scale\n\ 00353 \n\ 00354 \n\ 00355 ================================================================================\n\ 00356 MSG: geometry_msgs/Pose\n\ 00357 # A representation of pose in free space, composed of postion and orientation. \n\ 00358 Point position\n\ 00359 Quaternion orientation\n\ 00360 \n\ 00361 ================================================================================\n\ 00362 MSG: geometry_msgs/Point\n\ 00363 # This contains the position of a point in free space\n\ 00364 float64 x\n\ 00365 float64 y\n\ 00366 float64 z\n\ 00367 \n\ 00368 ================================================================================\n\ 00369 MSG: geometry_msgs/Quaternion\n\ 00370 # This represents an orientation in free space in quaternion form.\n\ 00371 \n\ 00372 float64 x\n\ 00373 float64 y\n\ 00374 float64 z\n\ 00375 float64 w\n\ 00376 \n\ 00377 ================================================================================\n\ 00378 MSG: geometry_msgs/Vector3\n\ 00379 # This represents a vector in free space. \n\ 00380 \n\ 00381 float64 x\n\ 00382 float64 y\n\ 00383 float64 z\n\ 00384 "; 00385 } 00386 00387 static const char* value(const ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> &) { return value(); } 00388 }; 00389 00390 } // namespace message_traits 00391 } // namespace ros 00392 00393 namespace ros 00394 { 00395 namespace serialization 00396 { 00397 00398 template<class ContainerAllocator> struct Serializer< ::srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > 00399 { 00400 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00401 { 00402 stream.next(m.name); 00403 } 00404 00405 ROS_DECLARE_ALLINONE_SERIALIZER; 00406 }; // struct GetUnknownObjectRequest_ 00407 } // namespace serialization 00408 } // namespace ros 00409 00410 00411 namespace ros 00412 { 00413 namespace serialization 00414 { 00415 00416 template<class ContainerAllocator> struct Serializer< ::srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > 00417 { 00418 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00419 { 00420 stream.next(m.frame_id); 00421 stream.next(m.name); 00422 stream.next(m.description); 00423 stream.next(m.pose_type); 00424 stream.next(m.pose); 00425 stream.next(m.scale); 00426 } 00427 00428 ROS_DECLARE_ALLINONE_SERIALIZER; 00429 }; // struct GetUnknownObjectResponse_ 00430 } // namespace serialization 00431 } // namespace ros 00432 00433 namespace ros 00434 { 00435 namespace service_traits 00436 { 00437 template<> 00438 struct MD5Sum<srs_interaction_primitives::GetUnknownObject> { 00439 static const char* value() 00440 { 00441 return "ee9aa16c34388cc30eaf9eea1330d475"; 00442 } 00443 00444 static const char* value(const srs_interaction_primitives::GetUnknownObject&) { return value(); } 00445 }; 00446 00447 template<> 00448 struct DataType<srs_interaction_primitives::GetUnknownObject> { 00449 static const char* value() 00450 { 00451 return "srs_interaction_primitives/GetUnknownObject"; 00452 } 00453 00454 static const char* value(const srs_interaction_primitives::GetUnknownObject&) { return value(); } 00455 }; 00456 00457 template<class ContainerAllocator> 00458 struct MD5Sum<srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > { 00459 static const char* value() 00460 { 00461 return "ee9aa16c34388cc30eaf9eea1330d475"; 00462 } 00463 00464 static const char* value(const srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> &) { return value(); } 00465 }; 00466 00467 template<class ContainerAllocator> 00468 struct DataType<srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> > { 00469 static const char* value() 00470 { 00471 return "srs_interaction_primitives/GetUnknownObject"; 00472 } 00473 00474 static const char* value(const srs_interaction_primitives::GetUnknownObjectRequest_<ContainerAllocator> &) { return value(); } 00475 }; 00476 00477 template<class ContainerAllocator> 00478 struct MD5Sum<srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > { 00479 static const char* value() 00480 { 00481 return "ee9aa16c34388cc30eaf9eea1330d475"; 00482 } 00483 00484 static const char* value(const srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> &) { return value(); } 00485 }; 00486 00487 template<class ContainerAllocator> 00488 struct DataType<srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> > { 00489 static const char* value() 00490 { 00491 return "srs_interaction_primitives/GetUnknownObject"; 00492 } 00493 00494 static const char* value(const srs_interaction_primitives::GetUnknownObjectResponse_<ContainerAllocator> &) { return value(); } 00495 }; 00496 00497 } // namespace service_traits 00498 } // namespace ros 00499 00500 #endif // SRS_INTERACTION_PRIMITIVES_SERVICE_GETUNKNOWNOBJECT_H 00501