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