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