00001 """autogenerated by genpy from srs_object_database_msgs/InsertObjectRequest.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 std_msgs.msg
00008 import sensor_msgs.msg
00009
00010 class InsertObjectRequest(genpy.Message):
00011 _md5sum = "4045f8a3a36be31cf6b0274a21ca2bb4"
00012 _type = "srs_object_database_msgs/InsertObjectRequest"
00013 _has_header = False
00014 _full_text = """
00015
00016
00017
00018 string function
00019
00020
00021 int32 model_id
00022
00023
00024 string model_name
00025
00026
00027 string model_desc
00028
00029
00030 string model_category
00031
00032
00033 float32 model_x_size
00034
00035
00036 float32 model_y_size
00037
00038
00039 float32 model_z_size
00040
00041
00042 string model_basic_shape
00043
00044
00045 bool graspable
00046
00047
00048
00049 uint8[] pcl
00050 uint8[] fpt
00051 sensor_msgs/Image img
00052 string image_type
00053 uint8[] data_grasp
00054
00055 uint8[] data_mesh
00056 string meshType
00057 uint8[] urdf
00058
00059
00060 ================================================================================
00061 MSG: sensor_msgs/Image
00062 # This message contains an uncompressed image
00063 # (0, 0) is at top-left corner of image
00064 #
00065
00066 Header header # Header timestamp should be acquisition time of image
00067 # Header frame_id should be optical frame of camera
00068 # origin of frame should be optical center of cameara
00069 # +x should point to the right in the image
00070 # +y should point down in the image
00071 # +z should point into to plane of the image
00072 # If the frame_id here and the frame_id of the CameraInfo
00073 # message associated with the image conflict
00074 # the behavior is undefined
00075
00076 uint32 height # image height, that is, number of rows
00077 uint32 width # image width, that is, number of columns
00078
00079 # The legal values for encoding are in file src/image_encodings.cpp
00080 # If you want to standardize a new string format, join
00081 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00082
00083 string encoding # Encoding of pixels -- channel meaning, ordering, size
00084 # taken from the list of strings in include/sensor_msgs/image_encodings.h
00085
00086 uint8 is_bigendian # is this data bigendian?
00087 uint32 step # Full row length in bytes
00088 uint8[] data # actual matrix data, size is (step * rows)
00089
00090 ================================================================================
00091 MSG: std_msgs/Header
00092 # Standard metadata for higher-level stamped data types.
00093 # This is generally used to communicate timestamped data
00094 # in a particular coordinate frame.
00095 #
00096 # sequence ID: consecutively increasing ID
00097 uint32 seq
00098 #Two-integer timestamp that is expressed as:
00099 # * stamp.secs: seconds (stamp_secs) since epoch
00100 # * stamp.nsecs: nanoseconds since stamp_secs
00101 # time-handling sugar is provided by the client library
00102 time stamp
00103 #Frame this data is associated with
00104 # 0: no frame
00105 # 1: global frame
00106 string frame_id
00107
00108 """
00109 __slots__ = ['function','model_id','model_name','model_desc','model_category','model_x_size','model_y_size','model_z_size','model_basic_shape','graspable','pcl','fpt','img','image_type','data_grasp','data_mesh','meshType','urdf']
00110 _slot_types = ['string','int32','string','string','string','float32','float32','float32','string','bool','uint8[]','uint8[]','sensor_msgs/Image','string','uint8[]','uint8[]','string','uint8[]']
00111
00112 def __init__(self, *args, **kwds):
00113 """
00114 Constructor. Any message fields that are implicitly/explicitly
00115 set to None will be assigned a default value. The recommend
00116 use is keyword arguments as this is more robust to future message
00117 changes. You cannot mix in-order arguments and keyword arguments.
00118
00119 The available fields are:
00120 function,model_id,model_name,model_desc,model_category,model_x_size,model_y_size,model_z_size,model_basic_shape,graspable,pcl,fpt,img,image_type,data_grasp,data_mesh,meshType,urdf
00121
00122 :param args: complete set of field values, in .msg order
00123 :param kwds: use keyword arguments corresponding to message field names
00124 to set specific fields.
00125 """
00126 if args or kwds:
00127 super(InsertObjectRequest, self).__init__(*args, **kwds)
00128
00129 if self.function is None:
00130 self.function = ''
00131 if self.model_id is None:
00132 self.model_id = 0
00133 if self.model_name is None:
00134 self.model_name = ''
00135 if self.model_desc is None:
00136 self.model_desc = ''
00137 if self.model_category is None:
00138 self.model_category = ''
00139 if self.model_x_size is None:
00140 self.model_x_size = 0.
00141 if self.model_y_size is None:
00142 self.model_y_size = 0.
00143 if self.model_z_size is None:
00144 self.model_z_size = 0.
00145 if self.model_basic_shape is None:
00146 self.model_basic_shape = ''
00147 if self.graspable is None:
00148 self.graspable = False
00149 if self.pcl is None:
00150 self.pcl = ''
00151 if self.fpt is None:
00152 self.fpt = ''
00153 if self.img is None:
00154 self.img = sensor_msgs.msg.Image()
00155 if self.image_type is None:
00156 self.image_type = ''
00157 if self.data_grasp is None:
00158 self.data_grasp = ''
00159 if self.data_mesh is None:
00160 self.data_mesh = ''
00161 if self.meshType is None:
00162 self.meshType = ''
00163 if self.urdf is None:
00164 self.urdf = ''
00165 else:
00166 self.function = ''
00167 self.model_id = 0
00168 self.model_name = ''
00169 self.model_desc = ''
00170 self.model_category = ''
00171 self.model_x_size = 0.
00172 self.model_y_size = 0.
00173 self.model_z_size = 0.
00174 self.model_basic_shape = ''
00175 self.graspable = False
00176 self.pcl = ''
00177 self.fpt = ''
00178 self.img = sensor_msgs.msg.Image()
00179 self.image_type = ''
00180 self.data_grasp = ''
00181 self.data_mesh = ''
00182 self.meshType = ''
00183 self.urdf = ''
00184
00185 def _get_types(self):
00186 """
00187 internal API method
00188 """
00189 return self._slot_types
00190
00191 def serialize(self, buff):
00192 """
00193 serialize message into buffer
00194 :param buff: buffer, ``StringIO``
00195 """
00196 try:
00197 _x = self.function
00198 length = len(_x)
00199 if python3 or type(_x) == unicode:
00200 _x = _x.encode('utf-8')
00201 length = len(_x)
00202 buff.write(struct.pack('<I%ss'%length, length, _x))
00203 buff.write(_struct_i.pack(self.model_id))
00204 _x = self.model_name
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 _x = self.model_desc
00211 length = len(_x)
00212 if python3 or type(_x) == unicode:
00213 _x = _x.encode('utf-8')
00214 length = len(_x)
00215 buff.write(struct.pack('<I%ss'%length, length, _x))
00216 _x = self.model_category
00217 length = len(_x)
00218 if python3 or type(_x) == unicode:
00219 _x = _x.encode('utf-8')
00220 length = len(_x)
00221 buff.write(struct.pack('<I%ss'%length, length, _x))
00222 _x = self
00223 buff.write(_struct_3f.pack(_x.model_x_size, _x.model_y_size, _x.model_z_size))
00224 _x = self.model_basic_shape
00225 length = len(_x)
00226 if python3 or type(_x) == unicode:
00227 _x = _x.encode('utf-8')
00228 length = len(_x)
00229 buff.write(struct.pack('<I%ss'%length, length, _x))
00230 buff.write(_struct_B.pack(self.graspable))
00231 _x = self.pcl
00232 length = len(_x)
00233
00234 if type(_x) in [list, tuple]:
00235 buff.write(struct.pack('<I%sB'%length, length, *_x))
00236 else:
00237 buff.write(struct.pack('<I%ss'%length, length, _x))
00238 _x = self.fpt
00239 length = len(_x)
00240
00241 if type(_x) in [list, tuple]:
00242 buff.write(struct.pack('<I%sB'%length, length, *_x))
00243 else:
00244 buff.write(struct.pack('<I%ss'%length, length, _x))
00245 _x = self
00246 buff.write(_struct_3I.pack(_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs))
00247 _x = self.img.header.frame_id
00248 length = len(_x)
00249 if python3 or type(_x) == unicode:
00250 _x = _x.encode('utf-8')
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _x = self
00254 buff.write(_struct_2I.pack(_x.img.height, _x.img.width))
00255 _x = self.img.encoding
00256 length = len(_x)
00257 if python3 or type(_x) == unicode:
00258 _x = _x.encode('utf-8')
00259 length = len(_x)
00260 buff.write(struct.pack('<I%ss'%length, length, _x))
00261 _x = self
00262 buff.write(_struct_BI.pack(_x.img.is_bigendian, _x.img.step))
00263 _x = self.img.data
00264 length = len(_x)
00265
00266 if type(_x) in [list, tuple]:
00267 buff.write(struct.pack('<I%sB'%length, length, *_x))
00268 else:
00269 buff.write(struct.pack('<I%ss'%length, length, _x))
00270 _x = self.image_type
00271 length = len(_x)
00272 if python3 or type(_x) == unicode:
00273 _x = _x.encode('utf-8')
00274 length = len(_x)
00275 buff.write(struct.pack('<I%ss'%length, length, _x))
00276 _x = self.data_grasp
00277 length = len(_x)
00278
00279 if type(_x) in [list, tuple]:
00280 buff.write(struct.pack('<I%sB'%length, length, *_x))
00281 else:
00282 buff.write(struct.pack('<I%ss'%length, length, _x))
00283 _x = self.data_mesh
00284 length = len(_x)
00285
00286 if type(_x) in [list, tuple]:
00287 buff.write(struct.pack('<I%sB'%length, length, *_x))
00288 else:
00289 buff.write(struct.pack('<I%ss'%length, length, _x))
00290 _x = self.meshType
00291 length = len(_x)
00292 if python3 or type(_x) == unicode:
00293 _x = _x.encode('utf-8')
00294 length = len(_x)
00295 buff.write(struct.pack('<I%ss'%length, length, _x))
00296 _x = self.urdf
00297 length = len(_x)
00298
00299 if type(_x) in [list, tuple]:
00300 buff.write(struct.pack('<I%sB'%length, length, *_x))
00301 else:
00302 buff.write(struct.pack('<I%ss'%length, length, _x))
00303 except struct.error as se: self._check_types(se)
00304 except TypeError as te: self._check_types(te)
00305
00306 def deserialize(self, str):
00307 """
00308 unpack serialized message in str into this message instance
00309 :param str: byte array of serialized message, ``str``
00310 """
00311 try:
00312 if self.img is None:
00313 self.img = sensor_msgs.msg.Image()
00314 end = 0
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 start = end
00319 end += length
00320 if python3:
00321 self.function = str[start:end].decode('utf-8')
00322 else:
00323 self.function = str[start:end]
00324 start = end
00325 end += 4
00326 (self.model_id,) = _struct_i.unpack(str[start:end])
00327 start = end
00328 end += 4
00329 (length,) = _struct_I.unpack(str[start:end])
00330 start = end
00331 end += length
00332 if python3:
00333 self.model_name = str[start:end].decode('utf-8')
00334 else:
00335 self.model_name = str[start:end]
00336 start = end
00337 end += 4
00338 (length,) = _struct_I.unpack(str[start:end])
00339 start = end
00340 end += length
00341 if python3:
00342 self.model_desc = str[start:end].decode('utf-8')
00343 else:
00344 self.model_desc = str[start:end]
00345 start = end
00346 end += 4
00347 (length,) = _struct_I.unpack(str[start:end])
00348 start = end
00349 end += length
00350 if python3:
00351 self.model_category = str[start:end].decode('utf-8')
00352 else:
00353 self.model_category = str[start:end]
00354 _x = self
00355 start = end
00356 end += 12
00357 (_x.model_x_size, _x.model_y_size, _x.model_z_size,) = _struct_3f.unpack(str[start:end])
00358 start = end
00359 end += 4
00360 (length,) = _struct_I.unpack(str[start:end])
00361 start = end
00362 end += length
00363 if python3:
00364 self.model_basic_shape = str[start:end].decode('utf-8')
00365 else:
00366 self.model_basic_shape = str[start:end]
00367 start = end
00368 end += 1
00369 (self.graspable,) = _struct_B.unpack(str[start:end])
00370 self.graspable = bool(self.graspable)
00371 start = end
00372 end += 4
00373 (length,) = _struct_I.unpack(str[start:end])
00374 start = end
00375 end += length
00376 self.pcl = str[start:end]
00377 start = end
00378 end += 4
00379 (length,) = _struct_I.unpack(str[start:end])
00380 start = end
00381 end += length
00382 self.fpt = str[start:end]
00383 _x = self
00384 start = end
00385 end += 12
00386 (_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00387 start = end
00388 end += 4
00389 (length,) = _struct_I.unpack(str[start:end])
00390 start = end
00391 end += length
00392 if python3:
00393 self.img.header.frame_id = str[start:end].decode('utf-8')
00394 else:
00395 self.img.header.frame_id = str[start:end]
00396 _x = self
00397 start = end
00398 end += 8
00399 (_x.img.height, _x.img.width,) = _struct_2I.unpack(str[start:end])
00400 start = end
00401 end += 4
00402 (length,) = _struct_I.unpack(str[start:end])
00403 start = end
00404 end += length
00405 if python3:
00406 self.img.encoding = str[start:end].decode('utf-8')
00407 else:
00408 self.img.encoding = str[start:end]
00409 _x = self
00410 start = end
00411 end += 5
00412 (_x.img.is_bigendian, _x.img.step,) = _struct_BI.unpack(str[start:end])
00413 start = end
00414 end += 4
00415 (length,) = _struct_I.unpack(str[start:end])
00416 start = end
00417 end += length
00418 self.img.data = str[start:end]
00419 start = end
00420 end += 4
00421 (length,) = _struct_I.unpack(str[start:end])
00422 start = end
00423 end += length
00424 if python3:
00425 self.image_type = str[start:end].decode('utf-8')
00426 else:
00427 self.image_type = str[start:end]
00428 start = end
00429 end += 4
00430 (length,) = _struct_I.unpack(str[start:end])
00431 start = end
00432 end += length
00433 self.data_grasp = str[start:end]
00434 start = end
00435 end += 4
00436 (length,) = _struct_I.unpack(str[start:end])
00437 start = end
00438 end += length
00439 self.data_mesh = str[start:end]
00440 start = end
00441 end += 4
00442 (length,) = _struct_I.unpack(str[start:end])
00443 start = end
00444 end += length
00445 if python3:
00446 self.meshType = str[start:end].decode('utf-8')
00447 else:
00448 self.meshType = str[start:end]
00449 start = end
00450 end += 4
00451 (length,) = _struct_I.unpack(str[start:end])
00452 start = end
00453 end += length
00454 self.urdf = str[start:end]
00455 return self
00456 except struct.error as e:
00457 raise genpy.DeserializationError(e)
00458
00459
00460 def serialize_numpy(self, buff, numpy):
00461 """
00462 serialize message with numpy array types into buffer
00463 :param buff: buffer, ``StringIO``
00464 :param numpy: numpy python module
00465 """
00466 try:
00467 _x = self.function
00468 length = len(_x)
00469 if python3 or type(_x) == unicode:
00470 _x = _x.encode('utf-8')
00471 length = len(_x)
00472 buff.write(struct.pack('<I%ss'%length, length, _x))
00473 buff.write(_struct_i.pack(self.model_id))
00474 _x = self.model_name
00475 length = len(_x)
00476 if python3 or type(_x) == unicode:
00477 _x = _x.encode('utf-8')
00478 length = len(_x)
00479 buff.write(struct.pack('<I%ss'%length, length, _x))
00480 _x = self.model_desc
00481 length = len(_x)
00482 if python3 or type(_x) == unicode:
00483 _x = _x.encode('utf-8')
00484 length = len(_x)
00485 buff.write(struct.pack('<I%ss'%length, length, _x))
00486 _x = self.model_category
00487 length = len(_x)
00488 if python3 or type(_x) == unicode:
00489 _x = _x.encode('utf-8')
00490 length = len(_x)
00491 buff.write(struct.pack('<I%ss'%length, length, _x))
00492 _x = self
00493 buff.write(_struct_3f.pack(_x.model_x_size, _x.model_y_size, _x.model_z_size))
00494 _x = self.model_basic_shape
00495 length = len(_x)
00496 if python3 or type(_x) == unicode:
00497 _x = _x.encode('utf-8')
00498 length = len(_x)
00499 buff.write(struct.pack('<I%ss'%length, length, _x))
00500 buff.write(_struct_B.pack(self.graspable))
00501 _x = self.pcl
00502 length = len(_x)
00503
00504 if type(_x) in [list, tuple]:
00505 buff.write(struct.pack('<I%sB'%length, length, *_x))
00506 else:
00507 buff.write(struct.pack('<I%ss'%length, length, _x))
00508 _x = self.fpt
00509 length = len(_x)
00510
00511 if type(_x) in [list, tuple]:
00512 buff.write(struct.pack('<I%sB'%length, length, *_x))
00513 else:
00514 buff.write(struct.pack('<I%ss'%length, length, _x))
00515 _x = self
00516 buff.write(_struct_3I.pack(_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs))
00517 _x = self.img.header.frame_id
00518 length = len(_x)
00519 if python3 or type(_x) == unicode:
00520 _x = _x.encode('utf-8')
00521 length = len(_x)
00522 buff.write(struct.pack('<I%ss'%length, length, _x))
00523 _x = self
00524 buff.write(_struct_2I.pack(_x.img.height, _x.img.width))
00525 _x = self.img.encoding
00526 length = len(_x)
00527 if python3 or type(_x) == unicode:
00528 _x = _x.encode('utf-8')
00529 length = len(_x)
00530 buff.write(struct.pack('<I%ss'%length, length, _x))
00531 _x = self
00532 buff.write(_struct_BI.pack(_x.img.is_bigendian, _x.img.step))
00533 _x = self.img.data
00534 length = len(_x)
00535
00536 if type(_x) in [list, tuple]:
00537 buff.write(struct.pack('<I%sB'%length, length, *_x))
00538 else:
00539 buff.write(struct.pack('<I%ss'%length, length, _x))
00540 _x = self.image_type
00541 length = len(_x)
00542 if python3 or type(_x) == unicode:
00543 _x = _x.encode('utf-8')
00544 length = len(_x)
00545 buff.write(struct.pack('<I%ss'%length, length, _x))
00546 _x = self.data_grasp
00547 length = len(_x)
00548
00549 if type(_x) in [list, tuple]:
00550 buff.write(struct.pack('<I%sB'%length, length, *_x))
00551 else:
00552 buff.write(struct.pack('<I%ss'%length, length, _x))
00553 _x = self.data_mesh
00554 length = len(_x)
00555
00556 if type(_x) in [list, tuple]:
00557 buff.write(struct.pack('<I%sB'%length, length, *_x))
00558 else:
00559 buff.write(struct.pack('<I%ss'%length, length, _x))
00560 _x = self.meshType
00561 length = len(_x)
00562 if python3 or type(_x) == unicode:
00563 _x = _x.encode('utf-8')
00564 length = len(_x)
00565 buff.write(struct.pack('<I%ss'%length, length, _x))
00566 _x = self.urdf
00567 length = len(_x)
00568
00569 if type(_x) in [list, tuple]:
00570 buff.write(struct.pack('<I%sB'%length, length, *_x))
00571 else:
00572 buff.write(struct.pack('<I%ss'%length, length, _x))
00573 except struct.error as se: self._check_types(se)
00574 except TypeError as te: self._check_types(te)
00575
00576 def deserialize_numpy(self, str, numpy):
00577 """
00578 unpack serialized message in str into this message instance using numpy for array types
00579 :param str: byte array of serialized message, ``str``
00580 :param numpy: numpy python module
00581 """
00582 try:
00583 if self.img is None:
00584 self.img = sensor_msgs.msg.Image()
00585 end = 0
00586 start = end
00587 end += 4
00588 (length,) = _struct_I.unpack(str[start:end])
00589 start = end
00590 end += length
00591 if python3:
00592 self.function = str[start:end].decode('utf-8')
00593 else:
00594 self.function = str[start:end]
00595 start = end
00596 end += 4
00597 (self.model_id,) = _struct_i.unpack(str[start:end])
00598 start = end
00599 end += 4
00600 (length,) = _struct_I.unpack(str[start:end])
00601 start = end
00602 end += length
00603 if python3:
00604 self.model_name = str[start:end].decode('utf-8')
00605 else:
00606 self.model_name = str[start:end]
00607 start = end
00608 end += 4
00609 (length,) = _struct_I.unpack(str[start:end])
00610 start = end
00611 end += length
00612 if python3:
00613 self.model_desc = str[start:end].decode('utf-8')
00614 else:
00615 self.model_desc = str[start:end]
00616 start = end
00617 end += 4
00618 (length,) = _struct_I.unpack(str[start:end])
00619 start = end
00620 end += length
00621 if python3:
00622 self.model_category = str[start:end].decode('utf-8')
00623 else:
00624 self.model_category = str[start:end]
00625 _x = self
00626 start = end
00627 end += 12
00628 (_x.model_x_size, _x.model_y_size, _x.model_z_size,) = _struct_3f.unpack(str[start:end])
00629 start = end
00630 end += 4
00631 (length,) = _struct_I.unpack(str[start:end])
00632 start = end
00633 end += length
00634 if python3:
00635 self.model_basic_shape = str[start:end].decode('utf-8')
00636 else:
00637 self.model_basic_shape = str[start:end]
00638 start = end
00639 end += 1
00640 (self.graspable,) = _struct_B.unpack(str[start:end])
00641 self.graspable = bool(self.graspable)
00642 start = end
00643 end += 4
00644 (length,) = _struct_I.unpack(str[start:end])
00645 start = end
00646 end += length
00647 self.pcl = str[start:end]
00648 start = end
00649 end += 4
00650 (length,) = _struct_I.unpack(str[start:end])
00651 start = end
00652 end += length
00653 self.fpt = str[start:end]
00654 _x = self
00655 start = end
00656 end += 12
00657 (_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00658 start = end
00659 end += 4
00660 (length,) = _struct_I.unpack(str[start:end])
00661 start = end
00662 end += length
00663 if python3:
00664 self.img.header.frame_id = str[start:end].decode('utf-8')
00665 else:
00666 self.img.header.frame_id = str[start:end]
00667 _x = self
00668 start = end
00669 end += 8
00670 (_x.img.height, _x.img.width,) = _struct_2I.unpack(str[start:end])
00671 start = end
00672 end += 4
00673 (length,) = _struct_I.unpack(str[start:end])
00674 start = end
00675 end += length
00676 if python3:
00677 self.img.encoding = str[start:end].decode('utf-8')
00678 else:
00679 self.img.encoding = str[start:end]
00680 _x = self
00681 start = end
00682 end += 5
00683 (_x.img.is_bigendian, _x.img.step,) = _struct_BI.unpack(str[start:end])
00684 start = end
00685 end += 4
00686 (length,) = _struct_I.unpack(str[start:end])
00687 start = end
00688 end += length
00689 self.img.data = str[start:end]
00690 start = end
00691 end += 4
00692 (length,) = _struct_I.unpack(str[start:end])
00693 start = end
00694 end += length
00695 if python3:
00696 self.image_type = str[start:end].decode('utf-8')
00697 else:
00698 self.image_type = str[start:end]
00699 start = end
00700 end += 4
00701 (length,) = _struct_I.unpack(str[start:end])
00702 start = end
00703 end += length
00704 self.data_grasp = str[start:end]
00705 start = end
00706 end += 4
00707 (length,) = _struct_I.unpack(str[start:end])
00708 start = end
00709 end += length
00710 self.data_mesh = str[start:end]
00711 start = end
00712 end += 4
00713 (length,) = _struct_I.unpack(str[start:end])
00714 start = end
00715 end += length
00716 if python3:
00717 self.meshType = str[start:end].decode('utf-8')
00718 else:
00719 self.meshType = str[start:end]
00720 start = end
00721 end += 4
00722 (length,) = _struct_I.unpack(str[start:end])
00723 start = end
00724 end += length
00725 self.urdf = str[start:end]
00726 return self
00727 except struct.error as e:
00728 raise genpy.DeserializationError(e)
00729
00730 _struct_I = genpy.struct_I
00731 _struct_B = struct.Struct("<B")
00732 _struct_i = struct.Struct("<i")
00733 _struct_BI = struct.Struct("<BI")
00734 _struct_2I = struct.Struct("<2I")
00735 _struct_3I = struct.Struct("<3I")
00736 _struct_3f = struct.Struct("<3f")
00737 """autogenerated by genpy from srs_object_database_msgs/InsertObjectResponse.msg. Do not edit."""
00738 import sys
00739 python3 = True if sys.hexversion > 0x03000000 else False
00740 import genpy
00741 import struct
00742
00743
00744 class InsertObjectResponse(genpy.Message):
00745 _md5sum = "bcd4a8cb19bdcae33e0a74fc2d3b2e46"
00746 _type = "srs_object_database_msgs/InsertObjectResponse"
00747 _has_header = False
00748 _full_text = """
00749
00750 string return_response
00751
00752 int32 model_id
00753
00754
00755
00756 """
00757 __slots__ = ['return_response','model_id']
00758 _slot_types = ['string','int32']
00759
00760 def __init__(self, *args, **kwds):
00761 """
00762 Constructor. Any message fields that are implicitly/explicitly
00763 set to None will be assigned a default value. The recommend
00764 use is keyword arguments as this is more robust to future message
00765 changes. You cannot mix in-order arguments and keyword arguments.
00766
00767 The available fields are:
00768 return_response,model_id
00769
00770 :param args: complete set of field values, in .msg order
00771 :param kwds: use keyword arguments corresponding to message field names
00772 to set specific fields.
00773 """
00774 if args or kwds:
00775 super(InsertObjectResponse, self).__init__(*args, **kwds)
00776
00777 if self.return_response is None:
00778 self.return_response = ''
00779 if self.model_id is None:
00780 self.model_id = 0
00781 else:
00782 self.return_response = ''
00783 self.model_id = 0
00784
00785 def _get_types(self):
00786 """
00787 internal API method
00788 """
00789 return self._slot_types
00790
00791 def serialize(self, buff):
00792 """
00793 serialize message into buffer
00794 :param buff: buffer, ``StringIO``
00795 """
00796 try:
00797 _x = self.return_response
00798 length = len(_x)
00799 if python3 or type(_x) == unicode:
00800 _x = _x.encode('utf-8')
00801 length = len(_x)
00802 buff.write(struct.pack('<I%ss'%length, length, _x))
00803 buff.write(_struct_i.pack(self.model_id))
00804 except struct.error as se: self._check_types(se)
00805 except TypeError as te: self._check_types(te)
00806
00807 def deserialize(self, str):
00808 """
00809 unpack serialized message in str into this message instance
00810 :param str: byte array of serialized message, ``str``
00811 """
00812 try:
00813 end = 0
00814 start = end
00815 end += 4
00816 (length,) = _struct_I.unpack(str[start:end])
00817 start = end
00818 end += length
00819 if python3:
00820 self.return_response = str[start:end].decode('utf-8')
00821 else:
00822 self.return_response = str[start:end]
00823 start = end
00824 end += 4
00825 (self.model_id,) = _struct_i.unpack(str[start:end])
00826 return self
00827 except struct.error as e:
00828 raise genpy.DeserializationError(e)
00829
00830
00831 def serialize_numpy(self, buff, numpy):
00832 """
00833 serialize message with numpy array types into buffer
00834 :param buff: buffer, ``StringIO``
00835 :param numpy: numpy python module
00836 """
00837 try:
00838 _x = self.return_response
00839 length = len(_x)
00840 if python3 or type(_x) == unicode:
00841 _x = _x.encode('utf-8')
00842 length = len(_x)
00843 buff.write(struct.pack('<I%ss'%length, length, _x))
00844 buff.write(_struct_i.pack(self.model_id))
00845 except struct.error as se: self._check_types(se)
00846 except TypeError as te: self._check_types(te)
00847
00848 def deserialize_numpy(self, str, numpy):
00849 """
00850 unpack serialized message in str into this message instance using numpy for array types
00851 :param str: byte array of serialized message, ``str``
00852 :param numpy: numpy python module
00853 """
00854 try:
00855 end = 0
00856 start = end
00857 end += 4
00858 (length,) = _struct_I.unpack(str[start:end])
00859 start = end
00860 end += length
00861 if python3:
00862 self.return_response = str[start:end].decode('utf-8')
00863 else:
00864 self.return_response = str[start:end]
00865 start = end
00866 end += 4
00867 (self.model_id,) = _struct_i.unpack(str[start:end])
00868 return self
00869 except struct.error as e:
00870 raise genpy.DeserializationError(e)
00871
00872 _struct_I = genpy.struct_I
00873 _struct_i = struct.Struct("<i")
00874 class InsertObject(object):
00875 _type = 'srs_object_database_msgs/InsertObject'
00876 _md5sum = '665c5bed07e3c52611345e1782e947e1'
00877 _request_class = InsertObjectRequest
00878 _response_class = InsertObjectResponse