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 src/image_encodings.cpp
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 if python3:
00377 self.pcl = str[start:end].decode('utf-8')
00378 else:
00379 self.pcl = str[start:end]
00380 start = end
00381 end += 4
00382 (length,) = _struct_I.unpack(str[start:end])
00383 start = end
00384 end += length
00385 if python3:
00386 self.fpt = str[start:end].decode('utf-8')
00387 else:
00388 self.fpt = str[start:end]
00389 _x = self
00390 start = end
00391 end += 12
00392 (_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00393 start = end
00394 end += 4
00395 (length,) = _struct_I.unpack(str[start:end])
00396 start = end
00397 end += length
00398 if python3:
00399 self.img.header.frame_id = str[start:end].decode('utf-8')
00400 else:
00401 self.img.header.frame_id = str[start:end]
00402 _x = self
00403 start = end
00404 end += 8
00405 (_x.img.height, _x.img.width,) = _struct_2I.unpack(str[start:end])
00406 start = end
00407 end += 4
00408 (length,) = _struct_I.unpack(str[start:end])
00409 start = end
00410 end += length
00411 if python3:
00412 self.img.encoding = str[start:end].decode('utf-8')
00413 else:
00414 self.img.encoding = str[start:end]
00415 _x = self
00416 start = end
00417 end += 5
00418 (_x.img.is_bigendian, _x.img.step,) = _struct_BI.unpack(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.img.data = str[start:end].decode('utf-8')
00426 else:
00427 self.img.data = str[start:end]
00428 start = end
00429 end += 4
00430 (length,) = _struct_I.unpack(str[start:end])
00431 start = end
00432 end += length
00433 if python3:
00434 self.image_type = str[start:end].decode('utf-8')
00435 else:
00436 self.image_type = str[start:end]
00437 start = end
00438 end += 4
00439 (length,) = _struct_I.unpack(str[start:end])
00440 start = end
00441 end += length
00442 if python3:
00443 self.data_grasp = str[start:end].decode('utf-8')
00444 else:
00445 self.data_grasp = str[start:end]
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 start = end
00450 end += length
00451 if python3:
00452 self.data_mesh = str[start:end].decode('utf-8')
00453 else:
00454 self.data_mesh = str[start:end]
00455 start = end
00456 end += 4
00457 (length,) = _struct_I.unpack(str[start:end])
00458 start = end
00459 end += length
00460 if python3:
00461 self.meshType = str[start:end].decode('utf-8')
00462 else:
00463 self.meshType = str[start:end]
00464 start = end
00465 end += 4
00466 (length,) = _struct_I.unpack(str[start:end])
00467 start = end
00468 end += length
00469 if python3:
00470 self.urdf = str[start:end].decode('utf-8')
00471 else:
00472 self.urdf = str[start:end]
00473 return self
00474 except struct.error as e:
00475 raise genpy.DeserializationError(e)
00476
00477
00478 def serialize_numpy(self, buff, numpy):
00479 """
00480 serialize message with numpy array types into buffer
00481 :param buff: buffer, ``StringIO``
00482 :param numpy: numpy python module
00483 """
00484 try:
00485 _x = self.function
00486 length = len(_x)
00487 if python3 or type(_x) == unicode:
00488 _x = _x.encode('utf-8')
00489 length = len(_x)
00490 buff.write(struct.pack('<I%ss'%length, length, _x))
00491 buff.write(_struct_i.pack(self.model_id))
00492 _x = self.model_name
00493 length = len(_x)
00494 if python3 or type(_x) == unicode:
00495 _x = _x.encode('utf-8')
00496 length = len(_x)
00497 buff.write(struct.pack('<I%ss'%length, length, _x))
00498 _x = self.model_desc
00499 length = len(_x)
00500 if python3 or type(_x) == unicode:
00501 _x = _x.encode('utf-8')
00502 length = len(_x)
00503 buff.write(struct.pack('<I%ss'%length, length, _x))
00504 _x = self.model_category
00505 length = len(_x)
00506 if python3 or type(_x) == unicode:
00507 _x = _x.encode('utf-8')
00508 length = len(_x)
00509 buff.write(struct.pack('<I%ss'%length, length, _x))
00510 _x = self
00511 buff.write(_struct_3f.pack(_x.model_x_size, _x.model_y_size, _x.model_z_size))
00512 _x = self.model_basic_shape
00513 length = len(_x)
00514 if python3 or type(_x) == unicode:
00515 _x = _x.encode('utf-8')
00516 length = len(_x)
00517 buff.write(struct.pack('<I%ss'%length, length, _x))
00518 buff.write(_struct_B.pack(self.graspable))
00519 _x = self.pcl
00520 length = len(_x)
00521
00522 if type(_x) in [list, tuple]:
00523 buff.write(struct.pack('<I%sB'%length, length, *_x))
00524 else:
00525 buff.write(struct.pack('<I%ss'%length, length, _x))
00526 _x = self.fpt
00527 length = len(_x)
00528
00529 if type(_x) in [list, tuple]:
00530 buff.write(struct.pack('<I%sB'%length, length, *_x))
00531 else:
00532 buff.write(struct.pack('<I%ss'%length, length, _x))
00533 _x = self
00534 buff.write(_struct_3I.pack(_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs))
00535 _x = self.img.header.frame_id
00536 length = len(_x)
00537 if python3 or type(_x) == unicode:
00538 _x = _x.encode('utf-8')
00539 length = len(_x)
00540 buff.write(struct.pack('<I%ss'%length, length, _x))
00541 _x = self
00542 buff.write(_struct_2I.pack(_x.img.height, _x.img.width))
00543 _x = self.img.encoding
00544 length = len(_x)
00545 if python3 or type(_x) == unicode:
00546 _x = _x.encode('utf-8')
00547 length = len(_x)
00548 buff.write(struct.pack('<I%ss'%length, length, _x))
00549 _x = self
00550 buff.write(_struct_BI.pack(_x.img.is_bigendian, _x.img.step))
00551 _x = self.img.data
00552 length = len(_x)
00553
00554 if type(_x) in [list, tuple]:
00555 buff.write(struct.pack('<I%sB'%length, length, *_x))
00556 else:
00557 buff.write(struct.pack('<I%ss'%length, length, _x))
00558 _x = self.image_type
00559 length = len(_x)
00560 if python3 or type(_x) == unicode:
00561 _x = _x.encode('utf-8')
00562 length = len(_x)
00563 buff.write(struct.pack('<I%ss'%length, length, _x))
00564 _x = self.data_grasp
00565 length = len(_x)
00566
00567 if type(_x) in [list, tuple]:
00568 buff.write(struct.pack('<I%sB'%length, length, *_x))
00569 else:
00570 buff.write(struct.pack('<I%ss'%length, length, _x))
00571 _x = self.data_mesh
00572 length = len(_x)
00573
00574 if type(_x) in [list, tuple]:
00575 buff.write(struct.pack('<I%sB'%length, length, *_x))
00576 else:
00577 buff.write(struct.pack('<I%ss'%length, length, _x))
00578 _x = self.meshType
00579 length = len(_x)
00580 if python3 or type(_x) == unicode:
00581 _x = _x.encode('utf-8')
00582 length = len(_x)
00583 buff.write(struct.pack('<I%ss'%length, length, _x))
00584 _x = self.urdf
00585 length = len(_x)
00586
00587 if type(_x) in [list, tuple]:
00588 buff.write(struct.pack('<I%sB'%length, length, *_x))
00589 else:
00590 buff.write(struct.pack('<I%ss'%length, length, _x))
00591 except struct.error as se: self._check_types(se)
00592 except TypeError as te: self._check_types(te)
00593
00594 def deserialize_numpy(self, str, numpy):
00595 """
00596 unpack serialized message in str into this message instance using numpy for array types
00597 :param str: byte array of serialized message, ``str``
00598 :param numpy: numpy python module
00599 """
00600 try:
00601 if self.img is None:
00602 self.img = sensor_msgs.msg.Image()
00603 end = 0
00604 start = end
00605 end += 4
00606 (length,) = _struct_I.unpack(str[start:end])
00607 start = end
00608 end += length
00609 if python3:
00610 self.function = str[start:end].decode('utf-8')
00611 else:
00612 self.function = str[start:end]
00613 start = end
00614 end += 4
00615 (self.model_id,) = _struct_i.unpack(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_name = str[start:end].decode('utf-8')
00623 else:
00624 self.model_name = str[start:end]
00625 start = end
00626 end += 4
00627 (length,) = _struct_I.unpack(str[start:end])
00628 start = end
00629 end += length
00630 if python3:
00631 self.model_desc = str[start:end].decode('utf-8')
00632 else:
00633 self.model_desc = str[start:end]
00634 start = end
00635 end += 4
00636 (length,) = _struct_I.unpack(str[start:end])
00637 start = end
00638 end += length
00639 if python3:
00640 self.model_category = str[start:end].decode('utf-8')
00641 else:
00642 self.model_category = str[start:end]
00643 _x = self
00644 start = end
00645 end += 12
00646 (_x.model_x_size, _x.model_y_size, _x.model_z_size,) = _struct_3f.unpack(str[start:end])
00647 start = end
00648 end += 4
00649 (length,) = _struct_I.unpack(str[start:end])
00650 start = end
00651 end += length
00652 if python3:
00653 self.model_basic_shape = str[start:end].decode('utf-8')
00654 else:
00655 self.model_basic_shape = str[start:end]
00656 start = end
00657 end += 1
00658 (self.graspable,) = _struct_B.unpack(str[start:end])
00659 self.graspable = bool(self.graspable)
00660 start = end
00661 end += 4
00662 (length,) = _struct_I.unpack(str[start:end])
00663 start = end
00664 end += length
00665 if python3:
00666 self.pcl = str[start:end].decode('utf-8')
00667 else:
00668 self.pcl = str[start:end]
00669 start = end
00670 end += 4
00671 (length,) = _struct_I.unpack(str[start:end])
00672 start = end
00673 end += length
00674 if python3:
00675 self.fpt = str[start:end].decode('utf-8')
00676 else:
00677 self.fpt = str[start:end]
00678 _x = self
00679 start = end
00680 end += 12
00681 (_x.img.header.seq, _x.img.header.stamp.secs, _x.img.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00682 start = end
00683 end += 4
00684 (length,) = _struct_I.unpack(str[start:end])
00685 start = end
00686 end += length
00687 if python3:
00688 self.img.header.frame_id = str[start:end].decode('utf-8')
00689 else:
00690 self.img.header.frame_id = str[start:end]
00691 _x = self
00692 start = end
00693 end += 8
00694 (_x.img.height, _x.img.width,) = _struct_2I.unpack(str[start:end])
00695 start = end
00696 end += 4
00697 (length,) = _struct_I.unpack(str[start:end])
00698 start = end
00699 end += length
00700 if python3:
00701 self.img.encoding = str[start:end].decode('utf-8')
00702 else:
00703 self.img.encoding = str[start:end]
00704 _x = self
00705 start = end
00706 end += 5
00707 (_x.img.is_bigendian, _x.img.step,) = _struct_BI.unpack(str[start:end])
00708 start = end
00709 end += 4
00710 (length,) = _struct_I.unpack(str[start:end])
00711 start = end
00712 end += length
00713 if python3:
00714 self.img.data = str[start:end].decode('utf-8')
00715 else:
00716 self.img.data = str[start:end]
00717 start = end
00718 end += 4
00719 (length,) = _struct_I.unpack(str[start:end])
00720 start = end
00721 end += length
00722 if python3:
00723 self.image_type = str[start:end].decode('utf-8')
00724 else:
00725 self.image_type = str[start:end]
00726 start = end
00727 end += 4
00728 (length,) = _struct_I.unpack(str[start:end])
00729 start = end
00730 end += length
00731 if python3:
00732 self.data_grasp = str[start:end].decode('utf-8')
00733 else:
00734 self.data_grasp = str[start:end]
00735 start = end
00736 end += 4
00737 (length,) = _struct_I.unpack(str[start:end])
00738 start = end
00739 end += length
00740 if python3:
00741 self.data_mesh = str[start:end].decode('utf-8')
00742 else:
00743 self.data_mesh = str[start:end]
00744 start = end
00745 end += 4
00746 (length,) = _struct_I.unpack(str[start:end])
00747 start = end
00748 end += length
00749 if python3:
00750 self.meshType = str[start:end].decode('utf-8')
00751 else:
00752 self.meshType = str[start:end]
00753 start = end
00754 end += 4
00755 (length,) = _struct_I.unpack(str[start:end])
00756 start = end
00757 end += length
00758 if python3:
00759 self.urdf = str[start:end].decode('utf-8')
00760 else:
00761 self.urdf = str[start:end]
00762 return self
00763 except struct.error as e:
00764 raise genpy.DeserializationError(e)
00765
00766 _struct_I = genpy.struct_I
00767 _struct_B = struct.Struct("<B")
00768 _struct_i = struct.Struct("<i")
00769 _struct_BI = struct.Struct("<BI")
00770 _struct_2I = struct.Struct("<2I")
00771 _struct_3I = struct.Struct("<3I")
00772 _struct_3f = struct.Struct("<3f")
00773 """autogenerated by genpy from srs_object_database_msgs/InsertObjectResponse.msg. Do not edit."""
00774 import sys
00775 python3 = True if sys.hexversion > 0x03000000 else False
00776 import genpy
00777 import struct
00778
00779
00780 class InsertObjectResponse(genpy.Message):
00781 _md5sum = "bcd4a8cb19bdcae33e0a74fc2d3b2e46"
00782 _type = "srs_object_database_msgs/InsertObjectResponse"
00783 _has_header = False
00784 _full_text = """
00785
00786 string return_response
00787
00788 int32 model_id
00789
00790
00791
00792 """
00793 __slots__ = ['return_response','model_id']
00794 _slot_types = ['string','int32']
00795
00796 def __init__(self, *args, **kwds):
00797 """
00798 Constructor. Any message fields that are implicitly/explicitly
00799 set to None will be assigned a default value. The recommend
00800 use is keyword arguments as this is more robust to future message
00801 changes. You cannot mix in-order arguments and keyword arguments.
00802
00803 The available fields are:
00804 return_response,model_id
00805
00806 :param args: complete set of field values, in .msg order
00807 :param kwds: use keyword arguments corresponding to message field names
00808 to set specific fields.
00809 """
00810 if args or kwds:
00811 super(InsertObjectResponse, self).__init__(*args, **kwds)
00812
00813 if self.return_response is None:
00814 self.return_response = ''
00815 if self.model_id is None:
00816 self.model_id = 0
00817 else:
00818 self.return_response = ''
00819 self.model_id = 0
00820
00821 def _get_types(self):
00822 """
00823 internal API method
00824 """
00825 return self._slot_types
00826
00827 def serialize(self, buff):
00828 """
00829 serialize message into buffer
00830 :param buff: buffer, ``StringIO``
00831 """
00832 try:
00833 _x = self.return_response
00834 length = len(_x)
00835 if python3 or type(_x) == unicode:
00836 _x = _x.encode('utf-8')
00837 length = len(_x)
00838 buff.write(struct.pack('<I%ss'%length, length, _x))
00839 buff.write(_struct_i.pack(self.model_id))
00840 except struct.error as se: self._check_types(se)
00841 except TypeError as te: self._check_types(te)
00842
00843 def deserialize(self, str):
00844 """
00845 unpack serialized message in str into this message instance
00846 :param str: byte array of serialized message, ``str``
00847 """
00848 try:
00849 end = 0
00850 start = end
00851 end += 4
00852 (length,) = _struct_I.unpack(str[start:end])
00853 start = end
00854 end += length
00855 if python3:
00856 self.return_response = str[start:end].decode('utf-8')
00857 else:
00858 self.return_response = str[start:end]
00859 start = end
00860 end += 4
00861 (self.model_id,) = _struct_i.unpack(str[start:end])
00862 return self
00863 except struct.error as e:
00864 raise genpy.DeserializationError(e)
00865
00866
00867 def serialize_numpy(self, buff, numpy):
00868 """
00869 serialize message with numpy array types into buffer
00870 :param buff: buffer, ``StringIO``
00871 :param numpy: numpy python module
00872 """
00873 try:
00874 _x = self.return_response
00875 length = len(_x)
00876 if python3 or type(_x) == unicode:
00877 _x = _x.encode('utf-8')
00878 length = len(_x)
00879 buff.write(struct.pack('<I%ss'%length, length, _x))
00880 buff.write(_struct_i.pack(self.model_id))
00881 except struct.error as se: self._check_types(se)
00882 except TypeError as te: self._check_types(te)
00883
00884 def deserialize_numpy(self, str, numpy):
00885 """
00886 unpack serialized message in str into this message instance using numpy for array types
00887 :param str: byte array of serialized message, ``str``
00888 :param numpy: numpy python module
00889 """
00890 try:
00891 end = 0
00892 start = end
00893 end += 4
00894 (length,) = _struct_I.unpack(str[start:end])
00895 start = end
00896 end += length
00897 if python3:
00898 self.return_response = str[start:end].decode('utf-8')
00899 else:
00900 self.return_response = str[start:end]
00901 start = end
00902 end += 4
00903 (self.model_id,) = _struct_i.unpack(str[start:end])
00904 return self
00905 except struct.error as e:
00906 raise genpy.DeserializationError(e)
00907
00908 _struct_I = genpy.struct_I
00909 _struct_i = struct.Struct("<i")
00910 class InsertObject(object):
00911 _type = 'srs_object_database_msgs/InsertObject'
00912 _md5sum = '665c5bed07e3c52611345e1782e947e1'
00913 _request_class = InsertObjectRequest
00914 _response_class = InsertObjectResponse