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