$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-simulator_gazebo/doc_stacks/2013-03-02_13-33-37.038309/simulator_gazebo/gazebo_msgs/srv/GetLinkProperties.srv */ 00002 #ifndef GAZEBO_MSGS_SERVICE_GETLINKPROPERTIES_H 00003 #define GAZEBO_MSGS_SERVICE_GETLINKPROPERTIES_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 00023 namespace gazebo_msgs 00024 { 00025 template <class ContainerAllocator> 00026 struct GetLinkPropertiesRequest_ { 00027 typedef GetLinkPropertiesRequest_<ContainerAllocator> Type; 00028 00029 GetLinkPropertiesRequest_() 00030 : link_name() 00031 { 00032 } 00033 00034 GetLinkPropertiesRequest_(const ContainerAllocator& _alloc) 00035 : link_name(_alloc) 00036 { 00037 } 00038 00039 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _link_name_type; 00040 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > link_name; 00041 00042 00043 private: 00044 static const char* __s_getDataType_() { return "gazebo_msgs/GetLinkPropertiesRequest"; } 00045 public: 00046 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00047 00048 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00049 00050 private: 00051 static const char* __s_getMD5Sum_() { return "7d82d60381f1b66a30f2157f60884345"; } 00052 public: 00053 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00054 00055 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00056 00057 private: 00058 static const char* __s_getServerMD5Sum_() { return "0e06a70386d0ee3fb880c02f23fcd821"; } 00059 public: 00060 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00061 00062 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00063 00064 private: 00065 static const char* __s_getMessageDefinition_() { return "string link_name\n\ 00066 \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, link_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, link_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(link_name); 00092 return size; 00093 } 00094 00095 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > Ptr; 00096 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> const> ConstPtr; 00097 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00098 }; // struct GetLinkPropertiesRequest 00099 typedef ::gazebo_msgs::GetLinkPropertiesRequest_<std::allocator<void> > GetLinkPropertiesRequest; 00100 00101 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest> GetLinkPropertiesRequestPtr; 00102 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest const> GetLinkPropertiesRequestConstPtr; 00103 00104 00105 template <class ContainerAllocator> 00106 struct GetLinkPropertiesResponse_ { 00107 typedef GetLinkPropertiesResponse_<ContainerAllocator> Type; 00108 00109 GetLinkPropertiesResponse_() 00110 : com() 00111 , gravity_mode(false) 00112 , mass(0.0) 00113 , ixx(0.0) 00114 , ixy(0.0) 00115 , ixz(0.0) 00116 , iyy(0.0) 00117 , iyz(0.0) 00118 , izz(0.0) 00119 , success(false) 00120 , status_message() 00121 { 00122 } 00123 00124 GetLinkPropertiesResponse_(const ContainerAllocator& _alloc) 00125 : com(_alloc) 00126 , gravity_mode(false) 00127 , mass(0.0) 00128 , ixx(0.0) 00129 , ixy(0.0) 00130 , ixz(0.0) 00131 , iyy(0.0) 00132 , iyz(0.0) 00133 , izz(0.0) 00134 , success(false) 00135 , status_message(_alloc) 00136 { 00137 } 00138 00139 typedef ::geometry_msgs::Pose_<ContainerAllocator> _com_type; 00140 ::geometry_msgs::Pose_<ContainerAllocator> com; 00141 00142 typedef uint8_t _gravity_mode_type; 00143 uint8_t gravity_mode; 00144 00145 typedef double _mass_type; 00146 double mass; 00147 00148 typedef double _ixx_type; 00149 double ixx; 00150 00151 typedef double _ixy_type; 00152 double ixy; 00153 00154 typedef double _ixz_type; 00155 double ixz; 00156 00157 typedef double _iyy_type; 00158 double iyy; 00159 00160 typedef double _iyz_type; 00161 double iyz; 00162 00163 typedef double _izz_type; 00164 double izz; 00165 00166 typedef uint8_t _success_type; 00167 uint8_t success; 00168 00169 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _status_message_type; 00170 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > status_message; 00171 00172 00173 private: 00174 static const char* __s_getDataType_() { return "gazebo_msgs/GetLinkPropertiesResponse"; } 00175 public: 00176 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00177 00178 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00179 00180 private: 00181 static const char* __s_getMD5Sum_() { return "a8619f92d17cfcc3958c0fd13299443d"; } 00182 public: 00183 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00184 00185 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00186 00187 private: 00188 static const char* __s_getServerMD5Sum_() { return "0e06a70386d0ee3fb880c02f23fcd821"; } 00189 public: 00190 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00191 00192 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00193 00194 private: 00195 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Pose com\n\ 00196 \n\ 00197 \n\ 00198 bool gravity_mode\n\ 00199 float64 mass\n\ 00200 float64 ixx\n\ 00201 float64 ixy\n\ 00202 float64 ixz\n\ 00203 float64 iyy\n\ 00204 float64 iyz\n\ 00205 float64 izz\n\ 00206 bool success\n\ 00207 string status_message\n\ 00208 \n\ 00209 \n\ 00210 ================================================================================\n\ 00211 MSG: geometry_msgs/Pose\n\ 00212 # A representation of pose in free space, composed of postion and orientation. \n\ 00213 Point position\n\ 00214 Quaternion orientation\n\ 00215 \n\ 00216 ================================================================================\n\ 00217 MSG: geometry_msgs/Point\n\ 00218 # This contains the position of a point in free space\n\ 00219 float64 x\n\ 00220 float64 y\n\ 00221 float64 z\n\ 00222 \n\ 00223 ================================================================================\n\ 00224 MSG: geometry_msgs/Quaternion\n\ 00225 # This represents an orientation in free space in quaternion form.\n\ 00226 \n\ 00227 float64 x\n\ 00228 float64 y\n\ 00229 float64 z\n\ 00230 float64 w\n\ 00231 \n\ 00232 "; } 00233 public: 00234 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00235 00236 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00237 00238 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00239 { 00240 ros::serialization::OStream stream(write_ptr, 1000000000); 00241 ros::serialization::serialize(stream, com); 00242 ros::serialization::serialize(stream, gravity_mode); 00243 ros::serialization::serialize(stream, mass); 00244 ros::serialization::serialize(stream, ixx); 00245 ros::serialization::serialize(stream, ixy); 00246 ros::serialization::serialize(stream, ixz); 00247 ros::serialization::serialize(stream, iyy); 00248 ros::serialization::serialize(stream, iyz); 00249 ros::serialization::serialize(stream, izz); 00250 ros::serialization::serialize(stream, success); 00251 ros::serialization::serialize(stream, status_message); 00252 return stream.getData(); 00253 } 00254 00255 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00256 { 00257 ros::serialization::IStream stream(read_ptr, 1000000000); 00258 ros::serialization::deserialize(stream, com); 00259 ros::serialization::deserialize(stream, gravity_mode); 00260 ros::serialization::deserialize(stream, mass); 00261 ros::serialization::deserialize(stream, ixx); 00262 ros::serialization::deserialize(stream, ixy); 00263 ros::serialization::deserialize(stream, ixz); 00264 ros::serialization::deserialize(stream, iyy); 00265 ros::serialization::deserialize(stream, iyz); 00266 ros::serialization::deserialize(stream, izz); 00267 ros::serialization::deserialize(stream, success); 00268 ros::serialization::deserialize(stream, status_message); 00269 return stream.getData(); 00270 } 00271 00272 ROS_DEPRECATED virtual uint32_t serializationLength() const 00273 { 00274 uint32_t size = 0; 00275 size += ros::serialization::serializationLength(com); 00276 size += ros::serialization::serializationLength(gravity_mode); 00277 size += ros::serialization::serializationLength(mass); 00278 size += ros::serialization::serializationLength(ixx); 00279 size += ros::serialization::serializationLength(ixy); 00280 size += ros::serialization::serializationLength(ixz); 00281 size += ros::serialization::serializationLength(iyy); 00282 size += ros::serialization::serializationLength(iyz); 00283 size += ros::serialization::serializationLength(izz); 00284 size += ros::serialization::serializationLength(success); 00285 size += ros::serialization::serializationLength(status_message); 00286 return size; 00287 } 00288 00289 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > Ptr; 00290 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> const> ConstPtr; 00291 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00292 }; // struct GetLinkPropertiesResponse 00293 typedef ::gazebo_msgs::GetLinkPropertiesResponse_<std::allocator<void> > GetLinkPropertiesResponse; 00294 00295 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse> GetLinkPropertiesResponsePtr; 00296 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse const> GetLinkPropertiesResponseConstPtr; 00297 00298 struct GetLinkProperties 00299 { 00300 00301 typedef GetLinkPropertiesRequest Request; 00302 typedef GetLinkPropertiesResponse Response; 00303 Request request; 00304 Response response; 00305 00306 typedef Request RequestType; 00307 typedef Response ResponseType; 00308 }; // struct GetLinkProperties 00309 } // namespace gazebo_msgs 00310 00311 namespace ros 00312 { 00313 namespace message_traits 00314 { 00315 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > : public TrueType {}; 00316 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> const> : public TrueType {}; 00317 template<class ContainerAllocator> 00318 struct MD5Sum< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > { 00319 static const char* value() 00320 { 00321 return "7d82d60381f1b66a30f2157f60884345"; 00322 } 00323 00324 static const char* value(const ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 00325 static const uint64_t static_value1 = 0x7d82d60381f1b66aULL; 00326 static const uint64_t static_value2 = 0x30f2157f60884345ULL; 00327 }; 00328 00329 template<class ContainerAllocator> 00330 struct DataType< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > { 00331 static const char* value() 00332 { 00333 return "gazebo_msgs/GetLinkPropertiesRequest"; 00334 } 00335 00336 static const char* value(const ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 00337 }; 00338 00339 template<class ContainerAllocator> 00340 struct Definition< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > { 00341 static const char* value() 00342 { 00343 return "string link_name\n\ 00344 \n\ 00345 \n\ 00346 "; 00347 } 00348 00349 static const char* value(const ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 00350 }; 00351 00352 } // namespace message_traits 00353 } // namespace ros 00354 00355 00356 namespace ros 00357 { 00358 namespace message_traits 00359 { 00360 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > : public TrueType {}; 00361 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> const> : public TrueType {}; 00362 template<class ContainerAllocator> 00363 struct MD5Sum< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > { 00364 static const char* value() 00365 { 00366 return "a8619f92d17cfcc3958c0fd13299443d"; 00367 } 00368 00369 static const char* value(const ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 00370 static const uint64_t static_value1 = 0xa8619f92d17cfcc3ULL; 00371 static const uint64_t static_value2 = 0x958c0fd13299443dULL; 00372 }; 00373 00374 template<class ContainerAllocator> 00375 struct DataType< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > { 00376 static const char* value() 00377 { 00378 return "gazebo_msgs/GetLinkPropertiesResponse"; 00379 } 00380 00381 static const char* value(const ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 00382 }; 00383 00384 template<class ContainerAllocator> 00385 struct Definition< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > { 00386 static const char* value() 00387 { 00388 return "geometry_msgs/Pose com\n\ 00389 \n\ 00390 \n\ 00391 bool gravity_mode\n\ 00392 float64 mass\n\ 00393 float64 ixx\n\ 00394 float64 ixy\n\ 00395 float64 ixz\n\ 00396 float64 iyy\n\ 00397 float64 iyz\n\ 00398 float64 izz\n\ 00399 bool success\n\ 00400 string status_message\n\ 00401 \n\ 00402 \n\ 00403 ================================================================================\n\ 00404 MSG: geometry_msgs/Pose\n\ 00405 # A representation of pose in free space, composed of postion and orientation. \n\ 00406 Point position\n\ 00407 Quaternion orientation\n\ 00408 \n\ 00409 ================================================================================\n\ 00410 MSG: geometry_msgs/Point\n\ 00411 # This contains the position of a point in free space\n\ 00412 float64 x\n\ 00413 float64 y\n\ 00414 float64 z\n\ 00415 \n\ 00416 ================================================================================\n\ 00417 MSG: geometry_msgs/Quaternion\n\ 00418 # This represents an orientation in free space in quaternion form.\n\ 00419 \n\ 00420 float64 x\n\ 00421 float64 y\n\ 00422 float64 z\n\ 00423 float64 w\n\ 00424 \n\ 00425 "; 00426 } 00427 00428 static const char* value(const ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 00429 }; 00430 00431 } // namespace message_traits 00432 } // namespace ros 00433 00434 namespace ros 00435 { 00436 namespace serialization 00437 { 00438 00439 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > 00440 { 00441 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00442 { 00443 stream.next(m.link_name); 00444 } 00445 00446 ROS_DECLARE_ALLINONE_SERIALIZER; 00447 }; // struct GetLinkPropertiesRequest_ 00448 } // namespace serialization 00449 } // namespace ros 00450 00451 00452 namespace ros 00453 { 00454 namespace serialization 00455 { 00456 00457 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > 00458 { 00459 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00460 { 00461 stream.next(m.com); 00462 stream.next(m.gravity_mode); 00463 stream.next(m.mass); 00464 stream.next(m.ixx); 00465 stream.next(m.ixy); 00466 stream.next(m.ixz); 00467 stream.next(m.iyy); 00468 stream.next(m.iyz); 00469 stream.next(m.izz); 00470 stream.next(m.success); 00471 stream.next(m.status_message); 00472 } 00473 00474 ROS_DECLARE_ALLINONE_SERIALIZER; 00475 }; // struct GetLinkPropertiesResponse_ 00476 } // namespace serialization 00477 } // namespace ros 00478 00479 namespace ros 00480 { 00481 namespace service_traits 00482 { 00483 template<> 00484 struct MD5Sum<gazebo_msgs::GetLinkProperties> { 00485 static const char* value() 00486 { 00487 return "0e06a70386d0ee3fb880c02f23fcd821"; 00488 } 00489 00490 static const char* value(const gazebo_msgs::GetLinkProperties&) { return value(); } 00491 }; 00492 00493 template<> 00494 struct DataType<gazebo_msgs::GetLinkProperties> { 00495 static const char* value() 00496 { 00497 return "gazebo_msgs/GetLinkProperties"; 00498 } 00499 00500 static const char* value(const gazebo_msgs::GetLinkProperties&) { return value(); } 00501 }; 00502 00503 template<class ContainerAllocator> 00504 struct MD5Sum<gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > { 00505 static const char* value() 00506 { 00507 return "0e06a70386d0ee3fb880c02f23fcd821"; 00508 } 00509 00510 static const char* value(const gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 00511 }; 00512 00513 template<class ContainerAllocator> 00514 struct DataType<gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > { 00515 static const char* value() 00516 { 00517 return "gazebo_msgs/GetLinkProperties"; 00518 } 00519 00520 static const char* value(const gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 00521 }; 00522 00523 template<class ContainerAllocator> 00524 struct MD5Sum<gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > { 00525 static const char* value() 00526 { 00527 return "0e06a70386d0ee3fb880c02f23fcd821"; 00528 } 00529 00530 static const char* value(const gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 00531 }; 00532 00533 template<class ContainerAllocator> 00534 struct DataType<gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > { 00535 static const char* value() 00536 { 00537 return "gazebo_msgs/GetLinkProperties"; 00538 } 00539 00540 static const char* value(const gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 00541 }; 00542 00543 } // namespace service_traits 00544 } // namespace ros 00545 00546 #endif // GAZEBO_MSGS_SERVICE_GETLINKPROPERTIES_H 00547