00001 """autogenerated by genmsg_py from SpawnModelRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import gazebo_plugins.msg
00006 import geometry_msgs.msg
00007
00008 class SpawnModelRequest(roslib.message.Message):
00009 _md5sum = "8915810c16a568ad2934526b89348967"
00010 _type = "gazebo_plugins/SpawnModelRequest"
00011 _has_header = False
00012 _full_text = """gazebo_plugins/GazeboModel model
00013
00014 ================================================================================
00015 MSG: gazebo_plugins/GazeboModel
00016 # This is a message that hold the data necessary to spawn a model in Gazebo
00017 # this message is used by SpawnModel service calls to RosFactory plugin.
00018
00019 string model_name # name of the model to be spawned in Gazebo
00020 string robot_model # contains either URDF or Gazebo XML robot model
00021 uint32 xml_type # specifies what the content of robot_model is
00022 string robot_namespace # ros namespace for all the ros interface of the model
00023 geometry_msgs/Pose initial_pose # initial pose in the gazebo world frame
00024 uint32 disable_urdf_joint_limits = 0 # special flag to disable URDF joint limits
00025 uint32 URDF = 0 # enum: robot_model contains XML string for an URDF model
00026 uint32 GAZEBO_XML = 1 # enum: robot_model contains XML string for an URDF model
00027 uint32 URDF_PARAM_NAME = 2 # enum: robot_model contains parameter name containing URDF XML
00028 uint32 GAZEBO_XML_PARAM_NAME = 3 # enum: robot_model contains parameter name containing Gazebo Model XML
00029 uint32 URDF_FILE_NAME = 4 # enum: robot_model contains file name containing URDF XML
00030 uint32 GAZEBO_XML_FILE_NAME = 5 # enum: robot_model contains file name containing Gazebo Model XML
00031
00032
00033 ================================================================================
00034 MSG: geometry_msgs/Pose
00035 # A representation of pose in free space, composed of postion and orientation.
00036 Point position
00037 Quaternion orientation
00038
00039 ================================================================================
00040 MSG: geometry_msgs/Point
00041 # This contains the position of a point in free space
00042 float64 x
00043 float64 y
00044 float64 z
00045
00046 ================================================================================
00047 MSG: geometry_msgs/Quaternion
00048 # This represents an orientation in free space in quaternion form.
00049
00050 float64 x
00051 float64 y
00052 float64 z
00053 float64 w
00054
00055 """
00056 __slots__ = ['model']
00057 _slot_types = ['gazebo_plugins/GazeboModel']
00058
00059 def __init__(self, *args, **kwds):
00060 """
00061 Constructor. Any message fields that are implicitly/explicitly
00062 set to None will be assigned a default value. The recommend
00063 use is keyword arguments as this is more robust to future message
00064 changes. You cannot mix in-order arguments and keyword arguments.
00065
00066 The available fields are:
00067 model
00068
00069 @param args: complete set of field values, in .msg order
00070 @param kwds: use keyword arguments corresponding to message field names
00071 to set specific fields.
00072 """
00073 if args or kwds:
00074 super(SpawnModelRequest, self).__init__(*args, **kwds)
00075
00076 if self.model is None:
00077 self.model = gazebo_plugins.msg.GazeboModel()
00078 else:
00079 self.model = gazebo_plugins.msg.GazeboModel()
00080
00081 def _get_types(self):
00082 """
00083 internal API method
00084 """
00085 return self._slot_types
00086
00087 def serialize(self, buff):
00088 """
00089 serialize message into buffer
00090 @param buff: buffer
00091 @type buff: StringIO
00092 """
00093 try:
00094 _x = self.model.model_name
00095 length = len(_x)
00096 buff.write(struct.pack('<I%ss'%length, length, _x))
00097 _x = self.model.robot_model
00098 length = len(_x)
00099 buff.write(struct.pack('<I%ss'%length, length, _x))
00100 buff.write(_struct_I.pack(self.model.xml_type))
00101 _x = self.model.robot_namespace
00102 length = len(_x)
00103 buff.write(struct.pack('<I%ss'%length, length, _x))
00104 _x = self
00105 buff.write(_struct_7d.pack(_x.model.initial_pose.position.x, _x.model.initial_pose.position.y, _x.model.initial_pose.position.z, _x.model.initial_pose.orientation.x, _x.model.initial_pose.orientation.y, _x.model.initial_pose.orientation.z, _x.model.initial_pose.orientation.w))
00106 except struct.error, se: self._check_types(se)
00107 except TypeError, te: self._check_types(te)
00108
00109 def deserialize(self, str):
00110 """
00111 unpack serialized message in str into this message instance
00112 @param str: byte array of serialized message
00113 @type str: str
00114 """
00115 try:
00116 if self.model is None:
00117 self.model = gazebo_plugins.msg.GazeboModel()
00118 end = 0
00119 start = end
00120 end += 4
00121 (length,) = _struct_I.unpack(str[start:end])
00122 start = end
00123 end += length
00124 self.model.model_name = str[start:end]
00125 start = end
00126 end += 4
00127 (length,) = _struct_I.unpack(str[start:end])
00128 start = end
00129 end += length
00130 self.model.robot_model = str[start:end]
00131 start = end
00132 end += 4
00133 (self.model.xml_type,) = _struct_I.unpack(str[start:end])
00134 start = end
00135 end += 4
00136 (length,) = _struct_I.unpack(str[start:end])
00137 start = end
00138 end += length
00139 self.model.robot_namespace = str[start:end]
00140 _x = self
00141 start = end
00142 end += 56
00143 (_x.model.initial_pose.position.x, _x.model.initial_pose.position.y, _x.model.initial_pose.position.z, _x.model.initial_pose.orientation.x, _x.model.initial_pose.orientation.y, _x.model.initial_pose.orientation.z, _x.model.initial_pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00144 return self
00145 except struct.error, e:
00146 raise roslib.message.DeserializationError(e)
00147
00148
00149 def serialize_numpy(self, buff, numpy):
00150 """
00151 serialize message with numpy array types into buffer
00152 @param buff: buffer
00153 @type buff: StringIO
00154 @param numpy: numpy python module
00155 @type numpy module
00156 """
00157 try:
00158 _x = self.model.model_name
00159 length = len(_x)
00160 buff.write(struct.pack('<I%ss'%length, length, _x))
00161 _x = self.model.robot_model
00162 length = len(_x)
00163 buff.write(struct.pack('<I%ss'%length, length, _x))
00164 buff.write(_struct_I.pack(self.model.xml_type))
00165 _x = self.model.robot_namespace
00166 length = len(_x)
00167 buff.write(struct.pack('<I%ss'%length, length, _x))
00168 _x = self
00169 buff.write(_struct_7d.pack(_x.model.initial_pose.position.x, _x.model.initial_pose.position.y, _x.model.initial_pose.position.z, _x.model.initial_pose.orientation.x, _x.model.initial_pose.orientation.y, _x.model.initial_pose.orientation.z, _x.model.initial_pose.orientation.w))
00170 except struct.error, se: self._check_types(se)
00171 except TypeError, te: self._check_types(te)
00172
00173 def deserialize_numpy(self, str, numpy):
00174 """
00175 unpack serialized message in str into this message instance using numpy for array types
00176 @param str: byte array of serialized message
00177 @type str: str
00178 @param numpy: numpy python module
00179 @type numpy: module
00180 """
00181 try:
00182 if self.model is None:
00183 self.model = gazebo_plugins.msg.GazeboModel()
00184 end = 0
00185 start = end
00186 end += 4
00187 (length,) = _struct_I.unpack(str[start:end])
00188 start = end
00189 end += length
00190 self.model.model_name = str[start:end]
00191 start = end
00192 end += 4
00193 (length,) = _struct_I.unpack(str[start:end])
00194 start = end
00195 end += length
00196 self.model.robot_model = str[start:end]
00197 start = end
00198 end += 4
00199 (self.model.xml_type,) = _struct_I.unpack(str[start:end])
00200 start = end
00201 end += 4
00202 (length,) = _struct_I.unpack(str[start:end])
00203 start = end
00204 end += length
00205 self.model.robot_namespace = str[start:end]
00206 _x = self
00207 start = end
00208 end += 56
00209 (_x.model.initial_pose.position.x, _x.model.initial_pose.position.y, _x.model.initial_pose.position.z, _x.model.initial_pose.orientation.x, _x.model.initial_pose.orientation.y, _x.model.initial_pose.orientation.z, _x.model.initial_pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00210 return self
00211 except struct.error, e:
00212 raise roslib.message.DeserializationError(e)
00213
00214 _struct_I = roslib.message.struct_I
00215 _struct_7d = struct.Struct("<7d")
00216 """autogenerated by genmsg_py from SpawnModelResponse.msg. Do not edit."""
00217 import roslib.message
00218 import struct
00219
00220
00221 class SpawnModelResponse(roslib.message.Message):
00222 _md5sum = "2ec6f3eff0161f4257b808b12bc830c2"
00223 _type = "gazebo_plugins/SpawnModelResponse"
00224 _has_header = False
00225 _full_text = """bool success
00226 string status_message
00227
00228
00229 """
00230 __slots__ = ['success','status_message']
00231 _slot_types = ['bool','string']
00232
00233 def __init__(self, *args, **kwds):
00234 """
00235 Constructor. Any message fields that are implicitly/explicitly
00236 set to None will be assigned a default value. The recommend
00237 use is keyword arguments as this is more robust to future message
00238 changes. You cannot mix in-order arguments and keyword arguments.
00239
00240 The available fields are:
00241 success,status_message
00242
00243 @param args: complete set of field values, in .msg order
00244 @param kwds: use keyword arguments corresponding to message field names
00245 to set specific fields.
00246 """
00247 if args or kwds:
00248 super(SpawnModelResponse, self).__init__(*args, **kwds)
00249
00250 if self.success is None:
00251 self.success = False
00252 if self.status_message is None:
00253 self.status_message = ''
00254 else:
00255 self.success = False
00256 self.status_message = ''
00257
00258 def _get_types(self):
00259 """
00260 internal API method
00261 """
00262 return self._slot_types
00263
00264 def serialize(self, buff):
00265 """
00266 serialize message into buffer
00267 @param buff: buffer
00268 @type buff: StringIO
00269 """
00270 try:
00271 buff.write(_struct_B.pack(self.success))
00272 _x = self.status_message
00273 length = len(_x)
00274 buff.write(struct.pack('<I%ss'%length, length, _x))
00275 except struct.error, se: self._check_types(se)
00276 except TypeError, te: self._check_types(te)
00277
00278 def deserialize(self, str):
00279 """
00280 unpack serialized message in str into this message instance
00281 @param str: byte array of serialized message
00282 @type str: str
00283 """
00284 try:
00285 end = 0
00286 start = end
00287 end += 1
00288 (self.success,) = _struct_B.unpack(str[start:end])
00289 self.success = bool(self.success)
00290 start = end
00291 end += 4
00292 (length,) = _struct_I.unpack(str[start:end])
00293 start = end
00294 end += length
00295 self.status_message = str[start:end]
00296 return self
00297 except struct.error, e:
00298 raise roslib.message.DeserializationError(e)
00299
00300
00301 def serialize_numpy(self, buff, numpy):
00302 """
00303 serialize message with numpy array types into buffer
00304 @param buff: buffer
00305 @type buff: StringIO
00306 @param numpy: numpy python module
00307 @type numpy module
00308 """
00309 try:
00310 buff.write(_struct_B.pack(self.success))
00311 _x = self.status_message
00312 length = len(_x)
00313 buff.write(struct.pack('<I%ss'%length, length, _x))
00314 except struct.error, se: self._check_types(se)
00315 except TypeError, te: self._check_types(te)
00316
00317 def deserialize_numpy(self, str, numpy):
00318 """
00319 unpack serialized message in str into this message instance using numpy for array types
00320 @param str: byte array of serialized message
00321 @type str: str
00322 @param numpy: numpy python module
00323 @type numpy: module
00324 """
00325 try:
00326 end = 0
00327 start = end
00328 end += 1
00329 (self.success,) = _struct_B.unpack(str[start:end])
00330 self.success = bool(self.success)
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 self.status_message = str[start:end]
00337 return self
00338 except struct.error, e:
00339 raise roslib.message.DeserializationError(e)
00340
00341 _struct_I = roslib.message.struct_I
00342 _struct_B = struct.Struct("<B")
00343 class SpawnModel(roslib.message.ServiceDefinition):
00344 _type = 'gazebo_plugins/SpawnModel'
00345 _md5sum = 'ce64f81e9bc82e2fce98de7d4eea3e13'
00346 _request_class = SpawnModelRequest
00347 _response_class = SpawnModelResponse