Go to the documentation of this file.00001
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 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> > Ptr;
00050 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> const> ConstPtr;
00051 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00052 };
00053 typedef ::gazebo_msgs::GetModelStateRequest_<std::allocator<void> > GetModelStateRequest;
00054
00055 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateRequest> GetModelStateRequestPtr;
00056 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateRequest const> GetModelStateRequestConstPtr;
00057
00058
00059
00060 template <class ContainerAllocator>
00061 struct GetModelStateResponse_ {
00062 typedef GetModelStateResponse_<ContainerAllocator> Type;
00063
00064 GetModelStateResponse_()
00065 : pose()
00066 , twist()
00067 , success(false)
00068 , status_message()
00069 {
00070 }
00071
00072 GetModelStateResponse_(const ContainerAllocator& _alloc)
00073 : pose(_alloc)
00074 , twist(_alloc)
00075 , success(false)
00076 , status_message(_alloc)
00077 {
00078 }
00079
00080 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type;
00081 ::geometry_msgs::Pose_<ContainerAllocator> pose;
00082
00083 typedef ::geometry_msgs::Twist_<ContainerAllocator> _twist_type;
00084 ::geometry_msgs::Twist_<ContainerAllocator> twist;
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::GetModelStateResponse_<ContainerAllocator> > Ptr;
00094 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> const> ConstPtr;
00095 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00096 };
00097 typedef ::gazebo_msgs::GetModelStateResponse_<std::allocator<void> > GetModelStateResponse;
00098
00099 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateResponse> GetModelStateResponsePtr;
00100 typedef boost::shared_ptr< ::gazebo_msgs::GetModelStateResponse const> GetModelStateResponseConstPtr;
00101
00102
00103 struct GetModelState
00104 {
00105
00106 typedef GetModelStateRequest Request;
00107 typedef GetModelStateResponse 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::GetModelStateRequest_<ContainerAllocator> > : public TrueType {};
00121 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> const> : public TrueType {};
00122 template<class ContainerAllocator>
00123 struct MD5Sum< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> > {
00124 static const char* value()
00125 {
00126 return "19d412713cefe4a67437e17a951e759e";
00127 }
00128
00129 static const char* value(const ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> &) { return value(); }
00130 static const uint64_t static_value1 = 0x19d412713cefe4a6ULL;
00131 static const uint64_t static_value2 = 0x7437e17a951e759eULL;
00132 };
00133
00134 template<class ContainerAllocator>
00135 struct DataType< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> > {
00136 static const char* value()
00137 {
00138 return "gazebo_msgs/GetModelStateRequest";
00139 }
00140
00141 static const char* value(const ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> &) { return value(); }
00142 };
00143
00144 template<class ContainerAllocator>
00145 struct Definition< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> > {
00146 static const char* value()
00147 {
00148 return "string model_name\n\
00149 string relative_entity_name\n\
00150 \n\
00151 \n\
00152 \n\
00153 \n\
00154 ";
00155 }
00156
00157 static const char* value(const ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> &) { return value(); }
00158 };
00159
00160 }
00161 }
00162
00163
00164 namespace ros
00165 {
00166 namespace message_traits
00167 {
00168 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> > : public TrueType {};
00169 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> const> : public TrueType {};
00170 template<class ContainerAllocator>
00171 struct MD5Sum< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> > {
00172 static const char* value()
00173 {
00174 return "1f8f991dc94e0cb27fe61383e0f576bb";
00175 }
00176
00177 static const char* value(const ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> &) { return value(); }
00178 static const uint64_t static_value1 = 0x1f8f991dc94e0cb2ULL;
00179 static const uint64_t static_value2 = 0x7fe61383e0f576bbULL;
00180 };
00181
00182 template<class ContainerAllocator>
00183 struct DataType< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> > {
00184 static const char* value()
00185 {
00186 return "gazebo_msgs/GetModelStateResponse";
00187 }
00188
00189 static const char* value(const ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> &) { return value(); }
00190 };
00191
00192 template<class ContainerAllocator>
00193 struct Definition< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> > {
00194 static const char* value()
00195 {
00196 return "geometry_msgs/Pose pose\n\
00197 geometry_msgs/Twist twist\n\
00198 bool success\n\
00199 string status_message\n\
00200 \n\
00201 \n\
00202 ================================================================================\n\
00203 MSG: geometry_msgs/Pose\n\
00204 # A representation of pose in free space, composed of postion and orientation. \n\
00205 Point position\n\
00206 Quaternion orientation\n\
00207 \n\
00208 ================================================================================\n\
00209 MSG: geometry_msgs/Point\n\
00210 # This contains the position of a point in free space\n\
00211 float64 x\n\
00212 float64 y\n\
00213 float64 z\n\
00214 \n\
00215 ================================================================================\n\
00216 MSG: geometry_msgs/Quaternion\n\
00217 # This represents an orientation in free space in quaternion form.\n\
00218 \n\
00219 float64 x\n\
00220 float64 y\n\
00221 float64 z\n\
00222 float64 w\n\
00223 \n\
00224 ================================================================================\n\
00225 MSG: geometry_msgs/Twist\n\
00226 # This expresses velocity in free space broken into its linear and angular parts.\n\
00227 Vector3 linear\n\
00228 Vector3 angular\n\
00229 \n\
00230 ================================================================================\n\
00231 MSG: geometry_msgs/Vector3\n\
00232 # This represents a vector in free space. \n\
00233 \n\
00234 float64 x\n\
00235 float64 y\n\
00236 float64 z\n\
00237 ";
00238 }
00239
00240 static const char* value(const ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> &) { return value(); }
00241 };
00242
00243 }
00244 }
00245
00246 namespace ros
00247 {
00248 namespace serialization
00249 {
00250
00251 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetModelStateRequest_<ContainerAllocator> >
00252 {
00253 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00254 {
00255 stream.next(m.model_name);
00256 stream.next(m.relative_entity_name);
00257 }
00258
00259 ROS_DECLARE_ALLINONE_SERIALIZER;
00260 };
00261 }
00262 }
00263
00264
00265 namespace ros
00266 {
00267 namespace serialization
00268 {
00269
00270 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::GetModelStateResponse_<ContainerAllocator> >
00271 {
00272 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00273 {
00274 stream.next(m.pose);
00275 stream.next(m.twist);
00276 stream.next(m.success);
00277 stream.next(m.status_message);
00278 }
00279
00280 ROS_DECLARE_ALLINONE_SERIALIZER;
00281 };
00282 }
00283 }
00284
00285 namespace ros
00286 {
00287 namespace service_traits
00288 {
00289 template<>
00290 struct MD5Sum<gazebo_msgs::GetModelState> {
00291 static const char* value()
00292 {
00293 return "af0f702011820738976b120226dc9d96";
00294 }
00295
00296 static const char* value(const gazebo_msgs::GetModelState&) { return value(); }
00297 };
00298
00299 template<>
00300 struct DataType<gazebo_msgs::GetModelState> {
00301 static const char* value()
00302 {
00303 return "gazebo_msgs/GetModelState";
00304 }
00305
00306 static const char* value(const gazebo_msgs::GetModelState&) { return value(); }
00307 };
00308
00309 template<class ContainerAllocator>
00310 struct MD5Sum<gazebo_msgs::GetModelStateRequest_<ContainerAllocator> > {
00311 static const char* value()
00312 {
00313 return "af0f702011820738976b120226dc9d96";
00314 }
00315
00316 static const char* value(const gazebo_msgs::GetModelStateRequest_<ContainerAllocator> &) { return value(); }
00317 };
00318
00319 template<class ContainerAllocator>
00320 struct DataType<gazebo_msgs::GetModelStateRequest_<ContainerAllocator> > {
00321 static const char* value()
00322 {
00323 return "gazebo_msgs/GetModelState";
00324 }
00325
00326 static const char* value(const gazebo_msgs::GetModelStateRequest_<ContainerAllocator> &) { return value(); }
00327 };
00328
00329 template<class ContainerAllocator>
00330 struct MD5Sum<gazebo_msgs::GetModelStateResponse_<ContainerAllocator> > {
00331 static const char* value()
00332 {
00333 return "af0f702011820738976b120226dc9d96";
00334 }
00335
00336 static const char* value(const gazebo_msgs::GetModelStateResponse_<ContainerAllocator> &) { return value(); }
00337 };
00338
00339 template<class ContainerAllocator>
00340 struct DataType<gazebo_msgs::GetModelStateResponse_<ContainerAllocator> > {
00341 static const char* value()
00342 {
00343 return "gazebo_msgs/GetModelState";
00344 }
00345
00346 static const char* value(const gazebo_msgs::GetModelStateResponse_<ContainerAllocator> &) { return value(); }
00347 };
00348
00349 }
00350 }
00351
00352 #endif // GAZEBO_MSGS_SERVICE_GETMODELSTATE_H
00353