00001 """autogenerated by genpy from gazebo_msgs/SpawnModelRequest.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import geometry_msgs.msg
00008
00009 class SpawnModelRequest(genpy.Message):
00010 _md5sum = "6d0eba5753761cd57e6263a056b79930"
00011 _type = "gazebo_msgs/SpawnModelRequest"
00012 _has_header = False
00013 _full_text = """string model_name
00014 string model_xml
00015 string robot_namespace
00016 geometry_msgs/Pose initial_pose
00017 string reference_frame
00018
00019
00020
00021
00022 ================================================================================
00023 MSG: geometry_msgs/Pose
00024 # A representation of pose in free space, composed of postion and orientation.
00025 Point position
00026 Quaternion orientation
00027
00028 ================================================================================
00029 MSG: geometry_msgs/Point
00030 # This contains the position of a point in free space
00031 float64 x
00032 float64 y
00033 float64 z
00034
00035 ================================================================================
00036 MSG: geometry_msgs/Quaternion
00037 # This represents an orientation in free space in quaternion form.
00038
00039 float64 x
00040 float64 y
00041 float64 z
00042 float64 w
00043
00044 """
00045 __slots__ = ['model_name','model_xml','robot_namespace','initial_pose','reference_frame']
00046 _slot_types = ['string','string','string','geometry_msgs/Pose','string']
00047
00048 def __init__(self, *args, **kwds):
00049 """
00050 Constructor. Any message fields that are implicitly/explicitly
00051 set to None will be assigned a default value. The recommend
00052 use is keyword arguments as this is more robust to future message
00053 changes. You cannot mix in-order arguments and keyword arguments.
00054
00055 The available fields are:
00056 model_name,model_xml,robot_namespace,initial_pose,reference_frame
00057
00058 :param args: complete set of field values, in .msg order
00059 :param kwds: use keyword arguments corresponding to message field names
00060 to set specific fields.
00061 """
00062 if args or kwds:
00063 super(SpawnModelRequest, self).__init__(*args, **kwds)
00064
00065 if self.model_name is None:
00066 self.model_name = ''
00067 if self.model_xml is None:
00068 self.model_xml = ''
00069 if self.robot_namespace is None:
00070 self.robot_namespace = ''
00071 if self.initial_pose is None:
00072 self.initial_pose = geometry_msgs.msg.Pose()
00073 if self.reference_frame is None:
00074 self.reference_frame = ''
00075 else:
00076 self.model_name = ''
00077 self.model_xml = ''
00078 self.robot_namespace = ''
00079 self.initial_pose = geometry_msgs.msg.Pose()
00080 self.reference_frame = ''
00081
00082 def _get_types(self):
00083 """
00084 internal API method
00085 """
00086 return self._slot_types
00087
00088 def serialize(self, buff):
00089 """
00090 serialize message into buffer
00091 :param buff: buffer, ``StringIO``
00092 """
00093 try:
00094 _x = self.model_name
00095 length = len(_x)
00096 if python3 or type(_x) == unicode:
00097 _x = _x.encode('utf-8')
00098 length = len(_x)
00099 buff.write(struct.pack('<I%ss'%length, length, _x))
00100 _x = self.model_xml
00101 length = len(_x)
00102 if python3 or type(_x) == unicode:
00103 _x = _x.encode('utf-8')
00104 length = len(_x)
00105 buff.write(struct.pack('<I%ss'%length, length, _x))
00106 _x = self.robot_namespace
00107 length = len(_x)
00108 if python3 or type(_x) == unicode:
00109 _x = _x.encode('utf-8')
00110 length = len(_x)
00111 buff.write(struct.pack('<I%ss'%length, length, _x))
00112 _x = self
00113 buff.write(_struct_7d.pack(_x.initial_pose.position.x, _x.initial_pose.position.y, _x.initial_pose.position.z, _x.initial_pose.orientation.x, _x.initial_pose.orientation.y, _x.initial_pose.orientation.z, _x.initial_pose.orientation.w))
00114 _x = self.reference_frame
00115 length = len(_x)
00116 if python3 or type(_x) == unicode:
00117 _x = _x.encode('utf-8')
00118 length = len(_x)
00119 buff.write(struct.pack('<I%ss'%length, length, _x))
00120 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00121 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00122
00123 def deserialize(self, str):
00124 """
00125 unpack serialized message in str into this message instance
00126 :param str: byte array of serialized message, ``str``
00127 """
00128 try:
00129 if self.initial_pose is None:
00130 self.initial_pose = geometry_msgs.msg.Pose()
00131 end = 0
00132 start = end
00133 end += 4
00134 (length,) = _struct_I.unpack(str[start:end])
00135 start = end
00136 end += length
00137 if python3:
00138 self.model_name = str[start:end].decode('utf-8')
00139 else:
00140 self.model_name = str[start:end]
00141 start = end
00142 end += 4
00143 (length,) = _struct_I.unpack(str[start:end])
00144 start = end
00145 end += length
00146 if python3:
00147 self.model_xml = str[start:end].decode('utf-8')
00148 else:
00149 self.model_xml = str[start:end]
00150 start = end
00151 end += 4
00152 (length,) = _struct_I.unpack(str[start:end])
00153 start = end
00154 end += length
00155 if python3:
00156 self.robot_namespace = str[start:end].decode('utf-8')
00157 else:
00158 self.robot_namespace = str[start:end]
00159 _x = self
00160 start = end
00161 end += 56
00162 (_x.initial_pose.position.x, _x.initial_pose.position.y, _x.initial_pose.position.z, _x.initial_pose.orientation.x, _x.initial_pose.orientation.y, _x.initial_pose.orientation.z, _x.initial_pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00163 start = end
00164 end += 4
00165 (length,) = _struct_I.unpack(str[start:end])
00166 start = end
00167 end += length
00168 if python3:
00169 self.reference_frame = str[start:end].decode('utf-8')
00170 else:
00171 self.reference_frame = str[start:end]
00172 return self
00173 except struct.error as e:
00174 raise genpy.DeserializationError(e)
00175
00176
00177 def serialize_numpy(self, buff, numpy):
00178 """
00179 serialize message with numpy array types into buffer
00180 :param buff: buffer, ``StringIO``
00181 :param numpy: numpy python module
00182 """
00183 try:
00184 _x = self.model_name
00185 length = len(_x)
00186 if python3 or type(_x) == unicode:
00187 _x = _x.encode('utf-8')
00188 length = len(_x)
00189 buff.write(struct.pack('<I%ss'%length, length, _x))
00190 _x = self.model_xml
00191 length = len(_x)
00192 if python3 or type(_x) == unicode:
00193 _x = _x.encode('utf-8')
00194 length = len(_x)
00195 buff.write(struct.pack('<I%ss'%length, length, _x))
00196 _x = self.robot_namespace
00197 length = len(_x)
00198 if python3 or type(_x) == unicode:
00199 _x = _x.encode('utf-8')
00200 length = len(_x)
00201 buff.write(struct.pack('<I%ss'%length, length, _x))
00202 _x = self
00203 buff.write(_struct_7d.pack(_x.initial_pose.position.x, _x.initial_pose.position.y, _x.initial_pose.position.z, _x.initial_pose.orientation.x, _x.initial_pose.orientation.y, _x.initial_pose.orientation.z, _x.initial_pose.orientation.w))
00204 _x = self.reference_frame
00205 length = len(_x)
00206 if python3 or type(_x) == unicode:
00207 _x = _x.encode('utf-8')
00208 length = len(_x)
00209 buff.write(struct.pack('<I%ss'%length, length, _x))
00210 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00211 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00212
00213 def deserialize_numpy(self, str, numpy):
00214 """
00215 unpack serialized message in str into this message instance using numpy for array types
00216 :param str: byte array of serialized message, ``str``
00217 :param numpy: numpy python module
00218 """
00219 try:
00220 if self.initial_pose is None:
00221 self.initial_pose = geometry_msgs.msg.Pose()
00222 end = 0
00223 start = end
00224 end += 4
00225 (length,) = _struct_I.unpack(str[start:end])
00226 start = end
00227 end += length
00228 if python3:
00229 self.model_name = str[start:end].decode('utf-8')
00230 else:
00231 self.model_name = str[start:end]
00232 start = end
00233 end += 4
00234 (length,) = _struct_I.unpack(str[start:end])
00235 start = end
00236 end += length
00237 if python3:
00238 self.model_xml = str[start:end].decode('utf-8')
00239 else:
00240 self.model_xml = str[start:end]
00241 start = end
00242 end += 4
00243 (length,) = _struct_I.unpack(str[start:end])
00244 start = end
00245 end += length
00246 if python3:
00247 self.robot_namespace = str[start:end].decode('utf-8')
00248 else:
00249 self.robot_namespace = str[start:end]
00250 _x = self
00251 start = end
00252 end += 56
00253 (_x.initial_pose.position.x, _x.initial_pose.position.y, _x.initial_pose.position.z, _x.initial_pose.orientation.x, _x.initial_pose.orientation.y, _x.initial_pose.orientation.z, _x.initial_pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00254 start = end
00255 end += 4
00256 (length,) = _struct_I.unpack(str[start:end])
00257 start = end
00258 end += length
00259 if python3:
00260 self.reference_frame = str[start:end].decode('utf-8')
00261 else:
00262 self.reference_frame = str[start:end]
00263 return self
00264 except struct.error as e:
00265 raise genpy.DeserializationError(e)
00266
00267 _struct_I = genpy.struct_I
00268 _struct_7d = struct.Struct("<7d")
00269 """autogenerated by genpy from gazebo_msgs/SpawnModelResponse.msg. Do not edit."""
00270 import sys
00271 python3 = True if sys.hexversion > 0x03000000 else False
00272 import genpy
00273 import struct
00274
00275
00276 class SpawnModelResponse(genpy.Message):
00277 _md5sum = "2ec6f3eff0161f4257b808b12bc830c2"
00278 _type = "gazebo_msgs/SpawnModelResponse"
00279 _has_header = False
00280 _full_text = """bool success
00281 string status_message
00282
00283
00284 """
00285 __slots__ = ['success','status_message']
00286 _slot_types = ['bool','string']
00287
00288 def __init__(self, *args, **kwds):
00289 """
00290 Constructor. Any message fields that are implicitly/explicitly
00291 set to None will be assigned a default value. The recommend
00292 use is keyword arguments as this is more robust to future message
00293 changes. You cannot mix in-order arguments and keyword arguments.
00294
00295 The available fields are:
00296 success,status_message
00297
00298 :param args: complete set of field values, in .msg order
00299 :param kwds: use keyword arguments corresponding to message field names
00300 to set specific fields.
00301 """
00302 if args or kwds:
00303 super(SpawnModelResponse, self).__init__(*args, **kwds)
00304
00305 if self.success is None:
00306 self.success = False
00307 if self.status_message is None:
00308 self.status_message = ''
00309 else:
00310 self.success = False
00311 self.status_message = ''
00312
00313 def _get_types(self):
00314 """
00315 internal API method
00316 """
00317 return self._slot_types
00318
00319 def serialize(self, buff):
00320 """
00321 serialize message into buffer
00322 :param buff: buffer, ``StringIO``
00323 """
00324 try:
00325 buff.write(_struct_B.pack(self.success))
00326 _x = self.status_message
00327 length = len(_x)
00328 if python3 or type(_x) == unicode:
00329 _x = _x.encode('utf-8')
00330 length = len(_x)
00331 buff.write(struct.pack('<I%ss'%length, length, _x))
00332 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00333 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00334
00335 def deserialize(self, str):
00336 """
00337 unpack serialized message in str into this message instance
00338 :param str: byte array of serialized message, ``str``
00339 """
00340 try:
00341 end = 0
00342 start = end
00343 end += 1
00344 (self.success,) = _struct_B.unpack(str[start:end])
00345 self.success = bool(self.success)
00346 start = end
00347 end += 4
00348 (length,) = _struct_I.unpack(str[start:end])
00349 start = end
00350 end += length
00351 if python3:
00352 self.status_message = str[start:end].decode('utf-8')
00353 else:
00354 self.status_message = str[start:end]
00355 return self
00356 except struct.error as e:
00357 raise genpy.DeserializationError(e)
00358
00359
00360 def serialize_numpy(self, buff, numpy):
00361 """
00362 serialize message with numpy array types into buffer
00363 :param buff: buffer, ``StringIO``
00364 :param numpy: numpy python module
00365 """
00366 try:
00367 buff.write(_struct_B.pack(self.success))
00368 _x = self.status_message
00369 length = len(_x)
00370 if python3 or type(_x) == unicode:
00371 _x = _x.encode('utf-8')
00372 length = len(_x)
00373 buff.write(struct.pack('<I%ss'%length, length, _x))
00374 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00375 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00376
00377 def deserialize_numpy(self, str, numpy):
00378 """
00379 unpack serialized message in str into this message instance using numpy for array types
00380 :param str: byte array of serialized message, ``str``
00381 :param numpy: numpy python module
00382 """
00383 try:
00384 end = 0
00385 start = end
00386 end += 1
00387 (self.success,) = _struct_B.unpack(str[start:end])
00388 self.success = bool(self.success)
00389 start = end
00390 end += 4
00391 (length,) = _struct_I.unpack(str[start:end])
00392 start = end
00393 end += length
00394 if python3:
00395 self.status_message = str[start:end].decode('utf-8')
00396 else:
00397 self.status_message = str[start:end]
00398 return self
00399 except struct.error as e:
00400 raise genpy.DeserializationError(e)
00401
00402 _struct_I = genpy.struct_I
00403 _struct_B = struct.Struct("<B")
00404 class SpawnModel(object):
00405 _type = 'gazebo_msgs/SpawnModel'
00406 _md5sum = '9ed9c82c96abe1a00c3e8cdaeee24413'
00407 _request_class = SpawnModelRequest
00408 _response_class = SpawnModelResponse