$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/GetModelState.srv */ 00002 #ifndef GAZEBO_SERVICE_GETMODELSTATE_H 00003 #define GAZEBO_SERVICE_GETMODELSTATE_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 #include "geometry_msgs/Twist.h" 00023 00024 namespace gazebo 00025 { 00026 template <class ContainerAllocator> 00027 struct GetModelStateRequest_ { 00028 typedef GetModelStateRequest_<ContainerAllocator> Type; 00029 00030 GetModelStateRequest_() 00031 : model_name() 00032 , relative_entity_name() 00033 { 00034 } 00035 00036 GetModelStateRequest_(const ContainerAllocator& _alloc) 00037 : model_name(_alloc) 00038 , relative_entity_name(_alloc) 00039 { 00040 } 00041 00042 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_name_type; 00043 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_name; 00044 00045 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _relative_entity_name_type; 00046 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > relative_entity_name; 00047 00048 00049 private: 00050 static const char* __s_getDataType_() { return "gazebo/GetModelStateRequest"; } 00051 public: 00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00053 00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00055 00056 private: 00057 static const char* __s_getMD5Sum_() { return "19d412713cefe4a67437e17a951e759e"; } 00058 public: 00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00060 00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00062 00063 private: 00064 static const char* __s_getServerMD5Sum_() { return "af0f702011820738976b120226dc9d96"; } 00065 public: 00066 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00067 00068 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00069 00070 private: 00071 static const char* __s_getMessageDefinition_() { return "\n\ 00072 \n\ 00073 string model_name\n\ 00074 string relative_entity_name\n\ 00075 \n\ 00076 \n\ 00077 \n\ 00078 \n\ 00079 "; } 00080 public: 00081 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00082 00083 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00084 00085 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00086 { 00087 ros::serialization::OStream stream(write_ptr, 1000000000); 00088 ros::serialization::serialize(stream, model_name); 00089 ros::serialization::serialize(stream, relative_entity_name); 00090 return stream.getData(); 00091 } 00092 00093 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00094 { 00095 ros::serialization::IStream stream(read_ptr, 1000000000); 00096 ros::serialization::deserialize(stream, model_name); 00097 ros::serialization::deserialize(stream, relative_entity_name); 00098 return stream.getData(); 00099 } 00100 00101 ROS_DEPRECATED virtual uint32_t serializationLength() const 00102 { 00103 uint32_t size = 0; 00104 size += ros::serialization::serializationLength(model_name); 00105 size += ros::serialization::serializationLength(relative_entity_name); 00106 return size; 00107 } 00108 00109 typedef boost::shared_ptr< ::gazebo::GetModelStateRequest_<ContainerAllocator> > Ptr; 00110 typedef boost::shared_ptr< ::gazebo::GetModelStateRequest_<ContainerAllocator> const> ConstPtr; 00111 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00112 }; // struct GetModelStateRequest 00113 typedef ::gazebo::GetModelStateRequest_<std::allocator<void> > GetModelStateRequest; 00114 00115 typedef boost::shared_ptr< ::gazebo::GetModelStateRequest> GetModelStateRequestPtr; 00116 typedef boost::shared_ptr< ::gazebo::GetModelStateRequest const> GetModelStateRequestConstPtr; 00117 00118 00119 template <class ContainerAllocator> 00120 struct GetModelStateResponse_ { 00121 typedef GetModelStateResponse_<ContainerAllocator> Type; 00122 00123 GetModelStateResponse_() 00124 : pose() 00125 , twist() 00126 , success(false) 00127 , status_message() 00128 { 00129 } 00130 00131 GetModelStateResponse_(const ContainerAllocator& _alloc) 00132 : pose(_alloc) 00133 , twist(_alloc) 00134 , success(false) 00135 , status_message(_alloc) 00136 { 00137 } 00138 00139 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type; 00140 ::geometry_msgs::Pose_<ContainerAllocator> pose; 00141 00142 typedef ::geometry_msgs::Twist_<ContainerAllocator> _twist_type; 00143 ::geometry_msgs::Twist_<ContainerAllocator> twist; 00144 00145 typedef uint8_t _success_type; 00146 uint8_t success; 00147 00148 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _status_message_type; 00149 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > status_message; 00150 00151 00152 private: 00153 static const char* __s_getDataType_() { return "gazebo/GetModelStateResponse"; } 00154 public: 00155 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00156 00157 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00158 00159 private: 00160 static const char* __s_getMD5Sum_() { return "1f8f991dc94e0cb27fe61383e0f576bb"; } 00161 public: 00162 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00163 00164 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00165 00166 private: 00167 static const char* __s_getServerMD5Sum_() { return "af0f702011820738976b120226dc9d96"; } 00168 public: 00169 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00170 00171 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00172 00173 private: 00174 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Pose pose\n\ 00175 geometry_msgs/Twist twist\n\ 00176 bool success\n\ 00177 string status_message\n\ 00178 \n\ 00179 \n\ 00180 ================================================================================\n\ 00181 MSG: geometry_msgs/Pose\n\ 00182 # A representation of pose in free space, composed of postion and orientation. \n\ 00183 Point position\n\ 00184 Quaternion orientation\n\ 00185 \n\ 00186 ================================================================================\n\ 00187 MSG: geometry_msgs/Point\n\ 00188 # This contains the position of a point in free space\n\ 00189 float64 x\n\ 00190 float64 y\n\ 00191 float64 z\n\ 00192 \n\ 00193 ================================================================================\n\ 00194 MSG: geometry_msgs/Quaternion\n\ 00195 # This represents an orientation in free space in quaternion form.\n\ 00196 \n\ 00197 float64 x\n\ 00198 float64 y\n\ 00199 float64 z\n\ 00200 float64 w\n\ 00201 \n\ 00202 ================================================================================\n\ 00203 MSG: geometry_msgs/Twist\n\ 00204 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00205 Vector3 linear\n\ 00206 Vector3 angular\n\ 00207 \n\ 00208 ================================================================================\n\ 00209 MSG: geometry_msgs/Vector3\n\ 00210 # This represents a vector in free space. \n\ 00211 \n\ 00212 float64 x\n\ 00213 float64 y\n\ 00214 float64 z\n\ 00215 "; } 00216 public: 00217 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00218 00219 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00220 00221 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00222 { 00223 ros::serialization::OStream stream(write_ptr, 1000000000); 00224 ros::serialization::serialize(stream, pose); 00225 ros::serialization::serialize(stream, twist); 00226 ros::serialization::serialize(stream, success); 00227 ros::serialization::serialize(stream, status_message); 00228 return stream.getData(); 00229 } 00230 00231 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00232 { 00233 ros::serialization::IStream stream(read_ptr, 1000000000); 00234 ros::serialization::deserialize(stream, pose); 00235 ros::serialization::deserialize(stream, twist); 00236 ros::serialization::deserialize(stream, success); 00237 ros::serialization::deserialize(stream, status_message); 00238 return stream.getData(); 00239 } 00240 00241 ROS_DEPRECATED virtual uint32_t serializationLength() const 00242 { 00243 uint32_t size = 0; 00244 size += ros::serialization::serializationLength(pose); 00245 size += ros::serialization::serializationLength(twist); 00246 size += ros::serialization::serializationLength(success); 00247 size += ros::serialization::serializationLength(status_message); 00248 return size; 00249 } 00250 00251 typedef boost::shared_ptr< ::gazebo::GetModelStateResponse_<ContainerAllocator> > Ptr; 00252 typedef boost::shared_ptr< ::gazebo::GetModelStateResponse_<ContainerAllocator> const> ConstPtr; 00253 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00254 }; // struct GetModelStateResponse 00255 typedef ::gazebo::GetModelStateResponse_<std::allocator<void> > GetModelStateResponse; 00256 00257 typedef boost::shared_ptr< ::gazebo::GetModelStateResponse> GetModelStateResponsePtr; 00258 typedef boost::shared_ptr< ::gazebo::GetModelStateResponse const> GetModelStateResponseConstPtr; 00259 00260 struct GetModelState 00261 { 00262 00263 typedef GetModelStateRequest Request; 00264 typedef GetModelStateResponse Response; 00265 Request request; 00266 Response response; 00267 00268 typedef Request RequestType; 00269 typedef Response ResponseType; 00270 }; // struct GetModelState 00271 } // namespace gazebo 00272 00273 namespace ros 00274 { 00275 namespace message_traits 00276 { 00277 template<class ContainerAllocator> struct IsMessage< ::gazebo::GetModelStateRequest_<ContainerAllocator> > : public TrueType {}; 00278 template<class ContainerAllocator> struct IsMessage< ::gazebo::GetModelStateRequest_<ContainerAllocator> const> : public TrueType {}; 00279 template<class ContainerAllocator> 00280 struct MD5Sum< ::gazebo::GetModelStateRequest_<ContainerAllocator> > { 00281 static const char* value() 00282 { 00283 return "19d412713cefe4a67437e17a951e759e"; 00284 } 00285 00286 static const char* value(const ::gazebo::GetModelStateRequest_<ContainerAllocator> &) { return value(); } 00287 static const uint64_t static_value1 = 0x19d412713cefe4a6ULL; 00288 static const uint64_t static_value2 = 0x7437e17a951e759eULL; 00289 }; 00290 00291 template<class ContainerAllocator> 00292 struct DataType< ::gazebo::GetModelStateRequest_<ContainerAllocator> > { 00293 static const char* value() 00294 { 00295 return "gazebo/GetModelStateRequest"; 00296 } 00297 00298 static const char* value(const ::gazebo::GetModelStateRequest_<ContainerAllocator> &) { return value(); } 00299 }; 00300 00301 template<class ContainerAllocator> 00302 struct Definition< ::gazebo::GetModelStateRequest_<ContainerAllocator> > { 00303 static const char* value() 00304 { 00305 return "\n\ 00306 \n\ 00307 string model_name\n\ 00308 string relative_entity_name\n\ 00309 \n\ 00310 \n\ 00311 \n\ 00312 \n\ 00313 "; 00314 } 00315 00316 static const char* value(const ::gazebo::GetModelStateRequest_<ContainerAllocator> &) { return value(); } 00317 }; 00318 00319 } // namespace message_traits 00320 } // namespace ros 00321 00322 00323 namespace ros 00324 { 00325 namespace message_traits 00326 { 00327 template<class ContainerAllocator> struct IsMessage< ::gazebo::GetModelStateResponse_<ContainerAllocator> > : public TrueType {}; 00328 template<class ContainerAllocator> struct IsMessage< ::gazebo::GetModelStateResponse_<ContainerAllocator> const> : public TrueType {}; 00329 template<class ContainerAllocator> 00330 struct MD5Sum< ::gazebo::GetModelStateResponse_<ContainerAllocator> > { 00331 static const char* value() 00332 { 00333 return "1f8f991dc94e0cb27fe61383e0f576bb"; 00334 } 00335 00336 static const char* value(const ::gazebo::GetModelStateResponse_<ContainerAllocator> &) { return value(); } 00337 static const uint64_t static_value1 = 0x1f8f991dc94e0cb2ULL; 00338 static const uint64_t static_value2 = 0x7fe61383e0f576bbULL; 00339 }; 00340 00341 template<class ContainerAllocator> 00342 struct DataType< ::gazebo::GetModelStateResponse_<ContainerAllocator> > { 00343 static const char* value() 00344 { 00345 return "gazebo/GetModelStateResponse"; 00346 } 00347 00348 static const char* value(const ::gazebo::GetModelStateResponse_<ContainerAllocator> &) { return value(); } 00349 }; 00350 00351 template<class ContainerAllocator> 00352 struct Definition< ::gazebo::GetModelStateResponse_<ContainerAllocator> > { 00353 static const char* value() 00354 { 00355 return "geometry_msgs/Pose pose\n\ 00356 geometry_msgs/Twist twist\n\ 00357 bool success\n\ 00358 string status_message\n\ 00359 \n\ 00360 \n\ 00361 ================================================================================\n\ 00362 MSG: geometry_msgs/Pose\n\ 00363 # A representation of pose in free space, composed of postion and orientation. \n\ 00364 Point position\n\ 00365 Quaternion orientation\n\ 00366 \n\ 00367 ================================================================================\n\ 00368 MSG: geometry_msgs/Point\n\ 00369 # This contains the position of a point in free space\n\ 00370 float64 x\n\ 00371 float64 y\n\ 00372 float64 z\n\ 00373 \n\ 00374 ================================================================================\n\ 00375 MSG: geometry_msgs/Quaternion\n\ 00376 # This represents an orientation in free space in quaternion form.\n\ 00377 \n\ 00378 float64 x\n\ 00379 float64 y\n\ 00380 float64 z\n\ 00381 float64 w\n\ 00382 \n\ 00383 ================================================================================\n\ 00384 MSG: geometry_msgs/Twist\n\ 00385 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00386 Vector3 linear\n\ 00387 Vector3 angular\n\ 00388 \n\ 00389 ================================================================================\n\ 00390 MSG: geometry_msgs/Vector3\n\ 00391 # This represents a vector in free space. \n\ 00392 \n\ 00393 float64 x\n\ 00394 float64 y\n\ 00395 float64 z\n\ 00396 "; 00397 } 00398 00399 static const char* value(const ::gazebo::GetModelStateResponse_<ContainerAllocator> &) { return value(); } 00400 }; 00401 00402 } // namespace message_traits 00403 } // namespace ros 00404 00405 namespace ros 00406 { 00407 namespace serialization 00408 { 00409 00410 template<class ContainerAllocator> struct Serializer< ::gazebo::GetModelStateRequest_<ContainerAllocator> > 00411 { 00412 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00413 { 00414 stream.next(m.model_name); 00415 stream.next(m.relative_entity_name); 00416 } 00417 00418 ROS_DECLARE_ALLINONE_SERIALIZER; 00419 }; // struct GetModelStateRequest_ 00420 } // namespace serialization 00421 } // namespace ros 00422 00423 00424 namespace ros 00425 { 00426 namespace serialization 00427 { 00428 00429 template<class ContainerAllocator> struct Serializer< ::gazebo::GetModelStateResponse_<ContainerAllocator> > 00430 { 00431 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00432 { 00433 stream.next(m.pose); 00434 stream.next(m.twist); 00435 stream.next(m.success); 00436 stream.next(m.status_message); 00437 } 00438 00439 ROS_DECLARE_ALLINONE_SERIALIZER; 00440 }; // struct GetModelStateResponse_ 00441 } // namespace serialization 00442 } // namespace ros 00443 00444 namespace ros 00445 { 00446 namespace service_traits 00447 { 00448 template<> 00449 struct MD5Sum<gazebo::GetModelState> { 00450 static const char* value() 00451 { 00452 return "af0f702011820738976b120226dc9d96"; 00453 } 00454 00455 static const char* value(const gazebo::GetModelState&) { return value(); } 00456 }; 00457 00458 template<> 00459 struct DataType<gazebo::GetModelState> { 00460 static const char* value() 00461 { 00462 return "gazebo/GetModelState"; 00463 } 00464 00465 static const char* value(const gazebo::GetModelState&) { return value(); } 00466 }; 00467 00468 template<class ContainerAllocator> 00469 struct MD5Sum<gazebo::GetModelStateRequest_<ContainerAllocator> > { 00470 static const char* value() 00471 { 00472 return "af0f702011820738976b120226dc9d96"; 00473 } 00474 00475 static const char* value(const gazebo::GetModelStateRequest_<ContainerAllocator> &) { return value(); } 00476 }; 00477 00478 template<class ContainerAllocator> 00479 struct DataType<gazebo::GetModelStateRequest_<ContainerAllocator> > { 00480 static const char* value() 00481 { 00482 return "gazebo/GetModelState"; 00483 } 00484 00485 static const char* value(const gazebo::GetModelStateRequest_<ContainerAllocator> &) { return value(); } 00486 }; 00487 00488 template<class ContainerAllocator> 00489 struct MD5Sum<gazebo::GetModelStateResponse_<ContainerAllocator> > { 00490 static const char* value() 00491 { 00492 return "af0f702011820738976b120226dc9d96"; 00493 } 00494 00495 static const char* value(const gazebo::GetModelStateResponse_<ContainerAllocator> &) { return value(); } 00496 }; 00497 00498 template<class ContainerAllocator> 00499 struct DataType<gazebo::GetModelStateResponse_<ContainerAllocator> > { 00500 static const char* value() 00501 { 00502 return "gazebo/GetModelState"; 00503 } 00504 00505 static const char* value(const gazebo::GetModelStateResponse_<ContainerAllocator> &) { return value(); } 00506 }; 00507 00508 } // namespace service_traits 00509 } // namespace ros 00510 00511 #endif // GAZEBO_SERVICE_GETMODELSTATE_H 00512