GetLinkProperties.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-simulator_gazebo/doc_stacks/2014-10-06_12-11-14.842894/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   typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > Ptr;
00044   typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator>  const> ConstPtr;
00045   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00046 }; // struct GetLinkPropertiesRequest
00047 typedef  ::gazebo_msgs::GetLinkPropertiesRequest_<std::allocator<void> > GetLinkPropertiesRequest;
00048 
00049 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest> GetLinkPropertiesRequestPtr;
00050 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesRequest const> GetLinkPropertiesRequestConstPtr;
00051 
00052 
00053 
00054 template <class ContainerAllocator>
00055 struct GetLinkPropertiesResponse_ {
00056   typedef GetLinkPropertiesResponse_<ContainerAllocator> Type;
00057 
00058   GetLinkPropertiesResponse_()
00059   : com()
00060   , gravity_mode(false)
00061   , mass(0.0)
00062   , ixx(0.0)
00063   , ixy(0.0)
00064   , ixz(0.0)
00065   , iyy(0.0)
00066   , iyz(0.0)
00067   , izz(0.0)
00068   , success(false)
00069   , status_message()
00070   {
00071   }
00072 
00073   GetLinkPropertiesResponse_(const ContainerAllocator& _alloc)
00074   : com(_alloc)
00075   , gravity_mode(false)
00076   , mass(0.0)
00077   , ixx(0.0)
00078   , ixy(0.0)
00079   , ixz(0.0)
00080   , iyy(0.0)
00081   , iyz(0.0)
00082   , izz(0.0)
00083   , success(false)
00084   , status_message(_alloc)
00085   {
00086   }
00087 
00088   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _com_type;
00089    ::geometry_msgs::Pose_<ContainerAllocator>  com;
00090 
00091   typedef uint8_t _gravity_mode_type;
00092   uint8_t gravity_mode;
00093 
00094   typedef double _mass_type;
00095   double mass;
00096 
00097   typedef double _ixx_type;
00098   double ixx;
00099 
00100   typedef double _ixy_type;
00101   double ixy;
00102 
00103   typedef double _ixz_type;
00104   double ixz;
00105 
00106   typedef double _iyy_type;
00107   double iyy;
00108 
00109   typedef double _iyz_type;
00110   double iyz;
00111 
00112   typedef double _izz_type;
00113   double izz;
00114 
00115   typedef uint8_t _success_type;
00116   uint8_t success;
00117 
00118   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _status_message_type;
00119   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  status_message;
00120 
00121 
00122   typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > Ptr;
00123   typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator>  const> ConstPtr;
00124   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00125 }; // struct GetLinkPropertiesResponse
00126 typedef  ::gazebo_msgs::GetLinkPropertiesResponse_<std::allocator<void> > GetLinkPropertiesResponse;
00127 
00128 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse> GetLinkPropertiesResponsePtr;
00129 typedef boost::shared_ptr< ::gazebo_msgs::GetLinkPropertiesResponse const> GetLinkPropertiesResponseConstPtr;
00130 
00131 
00132 struct GetLinkProperties
00133 {
00134 
00135 typedef GetLinkPropertiesRequest Request;
00136 typedef GetLinkPropertiesResponse Response;
00137 Request request;
00138 Response response;
00139 
00140 typedef Request RequestType;
00141 typedef Response ResponseType;
00142 }; // struct GetLinkProperties
00143 } // namespace gazebo_msgs
00144 
00145 namespace ros
00146 {
00147 namespace message_traits
00148 {
00149 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > : public TrueType {};
00150 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator>  const> : public TrueType {};
00151 template<class ContainerAllocator>
00152 struct MD5Sum< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > {
00153   static const char* value() 
00154   {
00155     return "7d82d60381f1b66a30f2157f60884345";
00156   }
00157 
00158   static const char* value(const  ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 
00159   static const uint64_t static_value1 = 0x7d82d60381f1b66aULL;
00160   static const uint64_t static_value2 = 0x30f2157f60884345ULL;
00161 };
00162 
00163 template<class ContainerAllocator>
00164 struct DataType< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > {
00165   static const char* value() 
00166   {
00167     return "gazebo_msgs/GetLinkPropertiesRequest";
00168   }
00169 
00170   static const char* value(const  ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 
00171 };
00172 
00173 template<class ContainerAllocator>
00174 struct Definition< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > {
00175   static const char* value() 
00176   {
00177     return "string link_name\n\
00178 \n\
00179 \n\
00180 ";
00181   }
00182 
00183   static const char* value(const  ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 
00184 };
00185 
00186 } // namespace message_traits
00187 } // namespace ros
00188 
00189 
00190 namespace ros
00191 {
00192 namespace message_traits
00193 {
00194 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > : public TrueType {};
00195 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator>  const> : public TrueType {};
00196 template<class ContainerAllocator>
00197 struct MD5Sum< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > {
00198   static const char* value() 
00199   {
00200     return "a8619f92d17cfcc3958c0fd13299443d";
00201   }
00202 
00203   static const char* value(const  ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 
00204   static const uint64_t static_value1 = 0xa8619f92d17cfcc3ULL;
00205   static const uint64_t static_value2 = 0x958c0fd13299443dULL;
00206 };
00207 
00208 template<class ContainerAllocator>
00209 struct DataType< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > {
00210   static const char* value() 
00211   {
00212     return "gazebo_msgs/GetLinkPropertiesResponse";
00213   }
00214 
00215   static const char* value(const  ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 
00216 };
00217 
00218 template<class ContainerAllocator>
00219 struct Definition< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > {
00220   static const char* value() 
00221   {
00222     return "geometry_msgs/Pose com\n\
00223 \n\
00224 \n\
00225 bool gravity_mode\n\
00226 float64 mass\n\
00227 float64 ixx\n\
00228 float64 ixy\n\
00229 float64 ixz\n\
00230 float64 iyy\n\
00231 float64 iyz\n\
00232 float64 izz\n\
00233 bool success\n\
00234 string status_message\n\
00235 \n\
00236 \n\
00237 ================================================================================\n\
00238 MSG: geometry_msgs/Pose\n\
00239 # A representation of pose in free space, composed of postion and orientation. \n\
00240 Point position\n\
00241 Quaternion orientation\n\
00242 \n\
00243 ================================================================================\n\
00244 MSG: geometry_msgs/Point\n\
00245 # This contains the position of a point in free space\n\
00246 float64 x\n\
00247 float64 y\n\
00248 float64 z\n\
00249 \n\
00250 ================================================================================\n\
00251 MSG: geometry_msgs/Quaternion\n\
00252 # This represents an orientation in free space in quaternion form.\n\
00253 \n\
00254 float64 x\n\
00255 float64 y\n\
00256 float64 z\n\
00257 float64 w\n\
00258 \n\
00259 ";
00260   }
00261 
00262   static const char* value(const  ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 
00263 };
00264 
00265 } // namespace message_traits
00266 } // namespace ros
00267 
00268 namespace ros
00269 {
00270 namespace serialization
00271 {
00272 
00273 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> >
00274 {
00275   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00276   {
00277     stream.next(m.link_name);
00278   }
00279 
00280   ROS_DECLARE_ALLINONE_SERIALIZER;
00281 }; // struct GetLinkPropertiesRequest_
00282 } // namespace serialization
00283 } // namespace ros
00284 
00285 
00286 namespace ros
00287 {
00288 namespace serialization
00289 {
00290 
00291 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> >
00292 {
00293   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00294   {
00295     stream.next(m.com);
00296     stream.next(m.gravity_mode);
00297     stream.next(m.mass);
00298     stream.next(m.ixx);
00299     stream.next(m.ixy);
00300     stream.next(m.ixz);
00301     stream.next(m.iyy);
00302     stream.next(m.iyz);
00303     stream.next(m.izz);
00304     stream.next(m.success);
00305     stream.next(m.status_message);
00306   }
00307 
00308   ROS_DECLARE_ALLINONE_SERIALIZER;
00309 }; // struct GetLinkPropertiesResponse_
00310 } // namespace serialization
00311 } // namespace ros
00312 
00313 namespace ros
00314 {
00315 namespace service_traits
00316 {
00317 template<>
00318 struct MD5Sum<gazebo_msgs::GetLinkProperties> {
00319   static const char* value() 
00320   {
00321     return "0e06a70386d0ee3fb880c02f23fcd821";
00322   }
00323 
00324   static const char* value(const gazebo_msgs::GetLinkProperties&) { return value(); } 
00325 };
00326 
00327 template<>
00328 struct DataType<gazebo_msgs::GetLinkProperties> {
00329   static const char* value() 
00330   {
00331     return "gazebo_msgs/GetLinkProperties";
00332   }
00333 
00334   static const char* value(const gazebo_msgs::GetLinkProperties&) { return value(); } 
00335 };
00336 
00337 template<class ContainerAllocator>
00338 struct MD5Sum<gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > {
00339   static const char* value() 
00340   {
00341     return "0e06a70386d0ee3fb880c02f23fcd821";
00342   }
00343 
00344   static const char* value(const gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 
00345 };
00346 
00347 template<class ContainerAllocator>
00348 struct DataType<gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> > {
00349   static const char* value() 
00350   {
00351     return "gazebo_msgs/GetLinkProperties";
00352   }
00353 
00354   static const char* value(const gazebo_msgs::GetLinkPropertiesRequest_<ContainerAllocator> &) { return value(); } 
00355 };
00356 
00357 template<class ContainerAllocator>
00358 struct MD5Sum<gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > {
00359   static const char* value() 
00360   {
00361     return "0e06a70386d0ee3fb880c02f23fcd821";
00362   }
00363 
00364   static const char* value(const gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 
00365 };
00366 
00367 template<class ContainerAllocator>
00368 struct DataType<gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> > {
00369   static const char* value() 
00370   {
00371     return "gazebo_msgs/GetLinkProperties";
00372   }
00373 
00374   static const char* value(const gazebo_msgs::GetLinkPropertiesResponse_<ContainerAllocator> &) { return value(); } 
00375 };
00376 
00377 } // namespace service_traits
00378 } // namespace ros
00379 
00380 #endif // GAZEBO_MSGS_SERVICE_GETLINKPROPERTIES_H
00381 


gazebo_msgs
Author(s): John Hsu
autogenerated on Mon Oct 6 2014 12:14:34