$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/GetPhysicsProperties.srv */ 00002 #ifndef GAZEBO_MSGS_SERVICE_GETPHYSICSPROPERTIES_H 00003 #define GAZEBO_MSGS_SERVICE_GETPHYSICSPROPERTIES_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/Vector3.h" 00022 #include "gazebo_msgs/ODEPhysics.h" 00023 00024 namespace gazebo_msgs 00025 { 00026 template <class ContainerAllocator> 00027 struct GetPhysicsPropertiesRequest_ { 00028 typedef GetPhysicsPropertiesRequest_<ContainerAllocator> Type; 00029 00030 GetPhysicsPropertiesRequest_() 00031 { 00032 } 00033 00034 GetPhysicsPropertiesRequest_(const ContainerAllocator& _alloc) 00035 { 00036 } 00037 00038 00039 private: 00040 static const char* __s_getDataType_() { return "gazebo_msgs/GetPhysicsPropertiesRequest"; } 00041 public: 00042 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00043 00044 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00045 00046 private: 00047 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00048 public: 00049 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00050 00051 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00052 00053 private: 00054 static const char* __s_getServerMD5Sum_() { return "575a5e74786981b7df2e3afc567693a6"; } 00055 public: 00056 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00057 00058 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00059 00060 private: 00061 static const char* __s_getMessageDefinition_() { return "\n\ 00062 "; } 00063 public: 00064 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00065 00066 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00067 00068 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00069 { 00070 ros::serialization::OStream stream(write_ptr, 1000000000); 00071 return stream.getData(); 00072 } 00073 00074 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00075 { 00076 ros::serialization::IStream stream(read_ptr, 1000000000); 00077 return stream.getData(); 00078 } 00079 00080 ROS_DEPRECATED virtual uint32_t serializationLength() const 00081 { 00082 uint32_t size = 0; 00083 return size; 00084 } 00085 00086 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > Ptr; 00087 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> const> ConstPtr; 00088 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00089 }; // struct GetPhysicsPropertiesRequest 00090 typedef ::gazebo_msgs::GetPhysicsPropertiesRequest_<std::allocator<void> > GetPhysicsPropertiesRequest; 00091 00092 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesRequest> GetPhysicsPropertiesRequestPtr; 00093 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesRequest const> GetPhysicsPropertiesRequestConstPtr; 00094 00095 00096 template <class ContainerAllocator> 00097 struct GetPhysicsPropertiesResponse_ { 00098 typedef GetPhysicsPropertiesResponse_<ContainerAllocator> Type; 00099 00100 GetPhysicsPropertiesResponse_() 00101 : time_step(0.0) 00102 , pause(false) 00103 , max_update_rate(0.0) 00104 , gravity() 00105 , ode_config() 00106 , success(false) 00107 , status_message() 00108 { 00109 } 00110 00111 GetPhysicsPropertiesResponse_(const ContainerAllocator& _alloc) 00112 : time_step(0.0) 00113 , pause(false) 00114 , max_update_rate(0.0) 00115 , gravity(_alloc) 00116 , ode_config(_alloc) 00117 , success(false) 00118 , status_message(_alloc) 00119 { 00120 } 00121 00122 typedef double _time_step_type; 00123 double time_step; 00124 00125 typedef uint8_t _pause_type; 00126 uint8_t pause; 00127 00128 typedef double _max_update_rate_type; 00129 double max_update_rate; 00130 00131 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _gravity_type; 00132 ::geometry_msgs::Vector3_<ContainerAllocator> gravity; 00133 00134 typedef ::gazebo_msgs::ODEPhysics_<ContainerAllocator> _ode_config_type; 00135 ::gazebo_msgs::ODEPhysics_<ContainerAllocator> ode_config; 00136 00137 typedef uint8_t _success_type; 00138 uint8_t success; 00139 00140 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _status_message_type; 00141 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > status_message; 00142 00143 00144 private: 00145 static const char* __s_getDataType_() { return "gazebo_msgs/GetPhysicsPropertiesResponse"; } 00146 public: 00147 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00148 00149 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00150 00151 private: 00152 static const char* __s_getMD5Sum_() { return "575a5e74786981b7df2e3afc567693a6"; } 00153 public: 00154 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00155 00156 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00157 00158 private: 00159 static const char* __s_getServerMD5Sum_() { return "575a5e74786981b7df2e3afc567693a6"; } 00160 public: 00161 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00162 00163 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00164 00165 private: 00166 static const char* __s_getMessageDefinition_() { return "\n\ 00167 float64 time_step\n\ 00168 bool pause\n\ 00169 float64 max_update_rate\n\ 00170 geometry_msgs/Vector3 gravity\n\ 00171 gazebo_msgs/ODEPhysics ode_config\n\ 00172 bool success\n\ 00173 string status_message\n\ 00174 \n\ 00175 \n\ 00176 ================================================================================\n\ 00177 MSG: geometry_msgs/Vector3\n\ 00178 # This represents a vector in free space. \n\ 00179 \n\ 00180 float64 x\n\ 00181 float64 y\n\ 00182 float64 z\n\ 00183 ================================================================================\n\ 00184 MSG: gazebo_msgs/ODEPhysics\n\ 00185 bool auto_disable_bodies # enable auto disabling of bodies, default false\n\ 00186 uint32 sor_pgs_precon_iters # preconditioning inner iterations when uisng projected Gauss Seidel\n\ 00187 uint32 sor_pgs_iters # inner iterations when uisng projected Gauss Seidel\n\ 00188 float64 sor_pgs_w # relaxation parameter when using projected Gauss Seidel, 1 = no relaxation\n\ 00189 float64 sor_pgs_rms_error_tol # rms error tolerance before stopping inner iterations\n\ 00190 float64 contact_surface_layer # contact \"dead-band\" width\n\ 00191 float64 contact_max_correcting_vel # contact maximum correction velocity\n\ 00192 float64 cfm # global constraint force mixing\n\ 00193 float64 erp # global error reduction parameter\n\ 00194 uint32 max_contacts # maximum contact joints between two geoms\n\ 00195 \n\ 00196 "; } 00197 public: 00198 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00199 00200 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00201 00202 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00203 { 00204 ros::serialization::OStream stream(write_ptr, 1000000000); 00205 ros::serialization::serialize(stream, time_step); 00206 ros::serialization::serialize(stream, pause); 00207 ros::serialization::serialize(stream, max_update_rate); 00208 ros::serialization::serialize(stream, gravity); 00209 ros::serialization::serialize(stream, ode_config); 00210 ros::serialization::serialize(stream, success); 00211 ros::serialization::serialize(stream, status_message); 00212 return stream.getData(); 00213 } 00214 00215 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00216 { 00217 ros::serialization::IStream stream(read_ptr, 1000000000); 00218 ros::serialization::deserialize(stream, time_step); 00219 ros::serialization::deserialize(stream, pause); 00220 ros::serialization::deserialize(stream, max_update_rate); 00221 ros::serialization::deserialize(stream, gravity); 00222 ros::serialization::deserialize(stream, ode_config); 00223 ros::serialization::deserialize(stream, success); 00224 ros::serialization::deserialize(stream, status_message); 00225 return stream.getData(); 00226 } 00227 00228 ROS_DEPRECATED virtual uint32_t serializationLength() const 00229 { 00230 uint32_t size = 0; 00231 size += ros::serialization::serializationLength(time_step); 00232 size += ros::serialization::serializationLength(pause); 00233 size += ros::serialization::serializationLength(max_update_rate); 00234 size += ros::serialization::serializationLength(gravity); 00235 size += ros::serialization::serializationLength(ode_config); 00236 size += ros::serialization::serializationLength(success); 00237 size += ros::serialization::serializationLength(status_message); 00238 return size; 00239 } 00240 00241 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > Ptr; 00242 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> const> ConstPtr; 00243 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00244 }; // struct GetPhysicsPropertiesResponse 00245 typedef ::gazebo_msgs::GetPhysicsPropertiesResponse_<std::allocator<void> > GetPhysicsPropertiesResponse; 00246 00247 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesResponse> GetPhysicsPropertiesResponsePtr; 00248 typedef boost::shared_ptr< ::gazebo_msgs::GetPhysicsPropertiesResponse const> GetPhysicsPropertiesResponseConstPtr; 00249 00250 struct GetPhysicsProperties 00251 { 00252 00253 typedef GetPhysicsPropertiesRequest Request; 00254 typedef GetPhysicsPropertiesResponse Response; 00255 Request request; 00256 Response response; 00257 00258 typedef Request RequestType; 00259 typedef Response ResponseType; 00260 }; // struct GetPhysicsProperties 00261 } // namespace gazebo_msgs 00262 00263 namespace ros 00264 { 00265 namespace message_traits 00266 { 00267 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > : public TrueType {}; 00268 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> const> : public TrueType {}; 00269 template<class ContainerAllocator> 00270 struct MD5Sum< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > { 00271 static const char* value() 00272 { 00273 return "d41d8cd98f00b204e9800998ecf8427e"; 00274 } 00275 00276 static const char* value(const ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); } 00277 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00278 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00279 }; 00280 00281 template<class ContainerAllocator> 00282 struct DataType< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > { 00283 static const char* value() 00284 { 00285 return "gazebo_msgs/GetPhysicsPropertiesRequest"; 00286 } 00287 00288 static const char* value(const ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); } 00289 }; 00290 00291 template<class ContainerAllocator> 00292 struct Definition< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > { 00293 static const char* value() 00294 { 00295 return "\n\ 00296 "; 00297 } 00298 00299 static const char* value(const ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); } 00300 }; 00301 00302 template<class ContainerAllocator> struct IsFixedSize< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > : public TrueType {}; 00303 } // namespace message_traits 00304 } // namespace ros 00305 00306 00307 namespace ros 00308 { 00309 namespace message_traits 00310 { 00311 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > : public TrueType {}; 00312 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> const> : public TrueType {}; 00313 template<class ContainerAllocator> 00314 struct MD5Sum< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > { 00315 static const char* value() 00316 { 00317 return "575a5e74786981b7df2e3afc567693a6"; 00318 } 00319 00320 static const char* value(const ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); } 00321 static const uint64_t static_value1 = 0x575a5e74786981b7ULL; 00322 static const uint64_t static_value2 = 0xdf2e3afc567693a6ULL; 00323 }; 00324 00325 template<class ContainerAllocator> 00326 struct DataType< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > { 00327 static const char* value() 00328 { 00329 return "gazebo_msgs/GetPhysicsPropertiesResponse"; 00330 } 00331 00332 static const char* value(const ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); } 00333 }; 00334 00335 template<class ContainerAllocator> 00336 struct Definition< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > { 00337 static const char* value() 00338 { 00339 return "\n\ 00340 float64 time_step\n\ 00341 bool pause\n\ 00342 float64 max_update_rate\n\ 00343 geometry_msgs/Vector3 gravity\n\ 00344 gazebo_msgs/ODEPhysics ode_config\n\ 00345 bool success\n\ 00346 string status_message\n\ 00347 \n\ 00348 \n\ 00349 ================================================================================\n\ 00350 MSG: geometry_msgs/Vector3\n\ 00351 # This represents a vector in free space. \n\ 00352 \n\ 00353 float64 x\n\ 00354 float64 y\n\ 00355 float64 z\n\ 00356 ================================================================================\n\ 00357 MSG: gazebo_msgs/ODEPhysics\n\ 00358 bool auto_disable_bodies # enable auto disabling of bodies, default false\n\ 00359 uint32 sor_pgs_precon_iters # preconditioning inner iterations when uisng projected Gauss Seidel\n\ 00360 uint32 sor_pgs_iters # inner iterations when uisng projected Gauss Seidel\n\ 00361 float64 sor_pgs_w # relaxation parameter when using projected Gauss Seidel, 1 = no relaxation\n\ 00362 float64 sor_pgs_rms_error_tol # rms error tolerance before stopping inner iterations\n\ 00363 float64 contact_surface_layer # contact \"dead-band\" width\n\ 00364 float64 contact_max_correcting_vel # contact maximum correction velocity\n\ 00365 float64 cfm # global constraint force mixing\n\ 00366 float64 erp # global error reduction parameter\n\ 00367 uint32 max_contacts # maximum contact joints between two geoms\n\ 00368 \n\ 00369 "; 00370 } 00371 00372 static const char* value(const ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); } 00373 }; 00374 00375 } // namespace message_traits 00376 } // namespace ros 00377 00378 namespace ros 00379 { 00380 namespace serialization 00381 { 00382 00383 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > 00384 { 00385 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00386 { 00387 } 00388 00389 ROS_DECLARE_ALLINONE_SERIALIZER; 00390 }; // struct GetPhysicsPropertiesRequest_ 00391 } // namespace serialization 00392 } // namespace ros 00393 00394 00395 namespace ros 00396 { 00397 namespace serialization 00398 { 00399 00400 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > 00401 { 00402 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00403 { 00404 stream.next(m.time_step); 00405 stream.next(m.pause); 00406 stream.next(m.max_update_rate); 00407 stream.next(m.gravity); 00408 stream.next(m.ode_config); 00409 stream.next(m.success); 00410 stream.next(m.status_message); 00411 } 00412 00413 ROS_DECLARE_ALLINONE_SERIALIZER; 00414 }; // struct GetPhysicsPropertiesResponse_ 00415 } // namespace serialization 00416 } // namespace ros 00417 00418 namespace ros 00419 { 00420 namespace service_traits 00421 { 00422 template<> 00423 struct MD5Sum<gazebo_msgs::GetPhysicsProperties> { 00424 static const char* value() 00425 { 00426 return "575a5e74786981b7df2e3afc567693a6"; 00427 } 00428 00429 static const char* value(const gazebo_msgs::GetPhysicsProperties&) { return value(); } 00430 }; 00431 00432 template<> 00433 struct DataType<gazebo_msgs::GetPhysicsProperties> { 00434 static const char* value() 00435 { 00436 return "gazebo_msgs/GetPhysicsProperties"; 00437 } 00438 00439 static const char* value(const gazebo_msgs::GetPhysicsProperties&) { return value(); } 00440 }; 00441 00442 template<class ContainerAllocator> 00443 struct MD5Sum<gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > { 00444 static const char* value() 00445 { 00446 return "575a5e74786981b7df2e3afc567693a6"; 00447 } 00448 00449 static const char* value(const gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); } 00450 }; 00451 00452 template<class ContainerAllocator> 00453 struct DataType<gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> > { 00454 static const char* value() 00455 { 00456 return "gazebo_msgs/GetPhysicsProperties"; 00457 } 00458 00459 static const char* value(const gazebo_msgs::GetPhysicsPropertiesRequest_<ContainerAllocator> &) { return value(); } 00460 }; 00461 00462 template<class ContainerAllocator> 00463 struct MD5Sum<gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > { 00464 static const char* value() 00465 { 00466 return "575a5e74786981b7df2e3afc567693a6"; 00467 } 00468 00469 static const char* value(const gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); } 00470 }; 00471 00472 template<class ContainerAllocator> 00473 struct DataType<gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> > { 00474 static const char* value() 00475 { 00476 return "gazebo_msgs/GetPhysicsProperties"; 00477 } 00478 00479 static const char* value(const gazebo_msgs::GetPhysicsPropertiesResponse_<ContainerAllocator> &) { return value(); } 00480 }; 00481 00482 } // namespace service_traits 00483 } // namespace ros 00484 00485 #endif // GAZEBO_MSGS_SERVICE_GETPHYSICSPROPERTIES_H 00486