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