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


gazebo_msgs
Author(s): John Hsu
autogenerated on Sun Jan 5 2014 11:34:32