Go to the documentation of this file.00001
00002 #ifndef GAZEBO_MSGS_SERVICE_SETPHYSICSPROPERTIES_H
00003 #define GAZEBO_MSGS_SERVICE_SETPHYSICSPROPERTIES_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/Vector3.h"
00020 #include "gazebo_msgs/ODEPhysics.h"
00021
00022
00023
00024 namespace gazebo_msgs
00025 {
00026 template <class ContainerAllocator>
00027 struct SetPhysicsPropertiesRequest_ {
00028 typedef SetPhysicsPropertiesRequest_<ContainerAllocator> Type;
00029
00030 SetPhysicsPropertiesRequest_()
00031 : time_step(0.0)
00032 , max_update_rate(0.0)
00033 , gravity()
00034 , ode_config()
00035 {
00036 }
00037
00038 SetPhysicsPropertiesRequest_(const ContainerAllocator& _alloc)
00039 : time_step(0.0)
00040 , max_update_rate(0.0)
00041 , gravity(_alloc)
00042 , ode_config(_alloc)
00043 {
00044 }
00045
00046 typedef double _time_step_type;
00047 double time_step;
00048
00049 typedef double _max_update_rate_type;
00050 double max_update_rate;
00051
00052 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _gravity_type;
00053 ::geometry_msgs::Vector3_<ContainerAllocator> gravity;
00054
00055 typedef ::gazebo_msgs::ODEPhysics_<ContainerAllocator> _ode_config_type;
00056 ::gazebo_msgs::ODEPhysics_<ContainerAllocator> ode_config;
00057
00058
00059 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > Ptr;
00060 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> const> ConstPtr;
00061 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00062 };
00063 typedef ::gazebo_msgs::SetPhysicsPropertiesRequest_<std::allocator<void> > SetPhysicsPropertiesRequest;
00064
00065 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesRequest> SetPhysicsPropertiesRequestPtr;
00066 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesRequest const> SetPhysicsPropertiesRequestConstPtr;
00067
00068
00069
00070 template <class ContainerAllocator>
00071 struct SetPhysicsPropertiesResponse_ {
00072 typedef SetPhysicsPropertiesResponse_<ContainerAllocator> Type;
00073
00074 SetPhysicsPropertiesResponse_()
00075 : success(false)
00076 , status_message()
00077 {
00078 }
00079
00080 SetPhysicsPropertiesResponse_(const ContainerAllocator& _alloc)
00081 : success(false)
00082 , status_message(_alloc)
00083 {
00084 }
00085
00086 typedef uint8_t _success_type;
00087 uint8_t success;
00088
00089 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _status_message_type;
00090 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > status_message;
00091
00092
00093 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > Ptr;
00094 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> const> ConstPtr;
00095 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00096 };
00097 typedef ::gazebo_msgs::SetPhysicsPropertiesResponse_<std::allocator<void> > SetPhysicsPropertiesResponse;
00098
00099 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesResponse> SetPhysicsPropertiesResponsePtr;
00100 typedef boost::shared_ptr< ::gazebo_msgs::SetPhysicsPropertiesResponse const> SetPhysicsPropertiesResponseConstPtr;
00101
00102
00103 struct SetPhysicsProperties
00104 {
00105
00106 typedef SetPhysicsPropertiesRequest Request;
00107 typedef SetPhysicsPropertiesResponse Response;
00108 Request request;
00109 Response response;
00110
00111 typedef Request RequestType;
00112 typedef Response ResponseType;
00113 };
00114 }
00115
00116 namespace ros
00117 {
00118 namespace message_traits
00119 {
00120 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > : public TrueType {};
00121 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> const> : public TrueType {};
00122 template<class ContainerAllocator>
00123 struct MD5Sum< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > {
00124 static const char* value()
00125 {
00126 return "abd9f82732b52b92e9d6bb36e6a82452";
00127 }
00128
00129 static const char* value(const ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); }
00130 static const uint64_t static_value1 = 0xabd9f82732b52b92ULL;
00131 static const uint64_t static_value2 = 0xe9d6bb36e6a82452ULL;
00132 };
00133
00134 template<class ContainerAllocator>
00135 struct DataType< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > {
00136 static const char* value()
00137 {
00138 return "gazebo_msgs/SetPhysicsPropertiesRequest";
00139 }
00140
00141 static const char* value(const ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); }
00142 };
00143
00144 template<class ContainerAllocator>
00145 struct Definition< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > {
00146 static const char* value()
00147 {
00148 return "\n\
00149 float64 time_step\n\
00150 float64 max_update_rate\n\
00151 geometry_msgs/Vector3 gravity\n\
00152 gazebo_msgs/ODEPhysics ode_config\n\
00153 \n\
00154 ================================================================================\n\
00155 MSG: geometry_msgs/Vector3\n\
00156 # This represents a vector in free space. \n\
00157 \n\
00158 float64 x\n\
00159 float64 y\n\
00160 float64 z\n\
00161 ================================================================================\n\
00162 MSG: gazebo_msgs/ODEPhysics\n\
00163 bool auto_disable_bodies # enable auto disabling of bodies, default false\n\
00164 uint32 sor_pgs_precon_iters # preconditioning inner iterations when uisng projected Gauss Seidel\n\
00165 uint32 sor_pgs_iters # inner iterations when uisng projected Gauss Seidel\n\
00166 float64 sor_pgs_w # relaxation parameter when using projected Gauss Seidel, 1 = no relaxation\n\
00167 float64 sor_pgs_rms_error_tol # rms error tolerance before stopping inner iterations\n\
00168 float64 contact_surface_layer # contact \"dead-band\" width\n\
00169 float64 contact_max_correcting_vel # contact maximum correction velocity\n\
00170 float64 cfm # global constraint force mixing\n\
00171 float64 erp # global error reduction parameter\n\
00172 uint32 max_contacts # maximum contact joints between two geoms\n\
00173 \n\
00174 ";
00175 }
00176
00177 static const char* value(const ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); }
00178 };
00179
00180 template<class ContainerAllocator> struct IsFixedSize< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > : public TrueType {};
00181 }
00182 }
00183
00184
00185 namespace ros
00186 {
00187 namespace message_traits
00188 {
00189 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > : public TrueType {};
00190 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> const> : public TrueType {};
00191 template<class ContainerAllocator>
00192 struct MD5Sum< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > {
00193 static const char* value()
00194 {
00195 return "2ec6f3eff0161f4257b808b12bc830c2";
00196 }
00197
00198 static const char* value(const ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); }
00199 static const uint64_t static_value1 = 0x2ec6f3eff0161f42ULL;
00200 static const uint64_t static_value2 = 0x57b808b12bc830c2ULL;
00201 };
00202
00203 template<class ContainerAllocator>
00204 struct DataType< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > {
00205 static const char* value()
00206 {
00207 return "gazebo_msgs/SetPhysicsPropertiesResponse";
00208 }
00209
00210 static const char* value(const ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); }
00211 };
00212
00213 template<class ContainerAllocator>
00214 struct Definition< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > {
00215 static const char* value()
00216 {
00217 return "bool success\n\
00218 string status_message\n\
00219 \n\
00220 \n\
00221 ";
00222 }
00223
00224 static const char* value(const ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); }
00225 };
00226
00227 }
00228 }
00229
00230 namespace ros
00231 {
00232 namespace serialization
00233 {
00234
00235 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> >
00236 {
00237 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00238 {
00239 stream.next(m.time_step);
00240 stream.next(m.max_update_rate);
00241 stream.next(m.gravity);
00242 stream.next(m.ode_config);
00243 }
00244
00245 ROS_DECLARE_ALLINONE_SERIALIZER;
00246 };
00247 }
00248 }
00249
00250
00251 namespace ros
00252 {
00253 namespace serialization
00254 {
00255
00256 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> >
00257 {
00258 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00259 {
00260 stream.next(m.success);
00261 stream.next(m.status_message);
00262 }
00263
00264 ROS_DECLARE_ALLINONE_SERIALIZER;
00265 };
00266 }
00267 }
00268
00269 namespace ros
00270 {
00271 namespace service_traits
00272 {
00273 template<>
00274 struct MD5Sum<gazebo_msgs::SetPhysicsProperties> {
00275 static const char* value()
00276 {
00277 return "97e2057080558ce4730434b5fae75c91";
00278 }
00279
00280 static const char* value(const gazebo_msgs::SetPhysicsProperties&) { return value(); }
00281 };
00282
00283 template<>
00284 struct DataType<gazebo_msgs::SetPhysicsProperties> {
00285 static const char* value()
00286 {
00287 return "gazebo_msgs/SetPhysicsProperties";
00288 }
00289
00290 static const char* value(const gazebo_msgs::SetPhysicsProperties&) { return value(); }
00291 };
00292
00293 template<class ContainerAllocator>
00294 struct MD5Sum<gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > {
00295 static const char* value()
00296 {
00297 return "97e2057080558ce4730434b5fae75c91";
00298 }
00299
00300 static const char* value(const gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); }
00301 };
00302
00303 template<class ContainerAllocator>
00304 struct DataType<gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> > {
00305 static const char* value()
00306 {
00307 return "gazebo_msgs/SetPhysicsProperties";
00308 }
00309
00310 static const char* value(const gazebo_msgs::SetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); }
00311 };
00312
00313 template<class ContainerAllocator>
00314 struct MD5Sum<gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > {
00315 static const char* value()
00316 {
00317 return "97e2057080558ce4730434b5fae75c91";
00318 }
00319
00320 static const char* value(const gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); }
00321 };
00322
00323 template<class ContainerAllocator>
00324 struct DataType<gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> > {
00325 static const char* value()
00326 {
00327 return "gazebo_msgs/SetPhysicsProperties";
00328 }
00329
00330 static const char* value(const gazebo_msgs::SetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); }
00331 };
00332
00333 }
00334 }
00335
00336 #endif // GAZEBO_MSGS_SERVICE_SETPHYSICSPROPERTIES_H
00337