00001 """autogenerated by genpy from ias_table_msgs/TableObject.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 geometry_msgs.msg
00009 import sensor_msgs.msg
00010
00011 class TableObject(genpy.Message):
00012 _md5sum = "3ce72124397384b196976e00d07c3482"
00013 _type = "ias_table_msgs/TableObject"
00014 _has_header = False
00015 _full_text = """geometry_msgs/Point32 center
00016 geometry_msgs/Point32 min_bound
00017 geometry_msgs/Point32 max_bound
00018
00019 uint64 object_cop_id
00020 uint64 lo_id
00021
00022 sensor_msgs/PointCloud points
00023 sensor_msgs/Image roi
00024
00025 string perception_method
00026 string sensor_type
00027 string object_type
00028 string object_color
00029 string object_geometric_type
00030 uint64 table_id
00031
00032 ================================================================================
00033 MSG: geometry_msgs/Point32
00034 # This contains the position of a point in free space(with 32 bits of precision).
00035 # It is recommeded to use Point wherever possible instead of Point32.
00036 #
00037 # This recommendation is to promote interoperability.
00038 #
00039 # This message is designed to take up less space when sending
00040 # lots of points at once, as in the case of a PointCloud.
00041
00042 float32 x
00043 float32 y
00044 float32 z
00045 ================================================================================
00046 MSG: sensor_msgs/PointCloud
00047 # This message holds a collection of 3d points, plus optional additional
00048 # information about each point.
00049
00050 # Time of sensor data acquisition, coordinate frame ID.
00051 Header header
00052
00053 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00054 # in the frame given in the header.
00055 geometry_msgs/Point32[] points
00056
00057 # Each channel should have the same number of elements as points array,
00058 # and the data in each channel should correspond 1:1 with each point.
00059 # Channel names in common practice are listed in ChannelFloat32.msg.
00060 ChannelFloat32[] channels
00061
00062 ================================================================================
00063 MSG: std_msgs/Header
00064 # Standard metadata for higher-level stamped data types.
00065 # This is generally used to communicate timestamped data
00066 # in a particular coordinate frame.
00067 #
00068 # sequence ID: consecutively increasing ID
00069 uint32 seq
00070 #Two-integer timestamp that is expressed as:
00071 # * stamp.secs: seconds (stamp_secs) since epoch
00072 # * stamp.nsecs: nanoseconds since stamp_secs
00073 # time-handling sugar is provided by the client library
00074 time stamp
00075 #Frame this data is associated with
00076 # 0: no frame
00077 # 1: global frame
00078 string frame_id
00079
00080 ================================================================================
00081 MSG: sensor_msgs/ChannelFloat32
00082 # This message is used by the PointCloud message to hold optional data
00083 # associated with each point in the cloud. The length of the values
00084 # array should be the same as the length of the points array in the
00085 # PointCloud, and each value should be associated with the corresponding
00086 # point.
00087
00088 # Channel names in existing practice include:
00089 # "u", "v" - row and column (respectively) in the left stereo image.
00090 # This is opposite to usual conventions but remains for
00091 # historical reasons. The newer PointCloud2 message has no
00092 # such problem.
00093 # "rgb" - For point clouds produced by color stereo cameras. uint8
00094 # (R,G,B) values packed into the least significant 24 bits,
00095 # in order.
00096 # "intensity" - laser or pixel intensity.
00097 # "distance"
00098
00099 # The channel name should give semantics of the channel (e.g.
00100 # "intensity" instead of "value").
00101 string name
00102
00103 # The values array should be 1-1 with the elements of the associated
00104 # PointCloud.
00105 float32[] values
00106
00107 ================================================================================
00108 MSG: sensor_msgs/Image
00109 # This message contains an uncompressed image
00110 # (0, 0) is at top-left corner of image
00111 #
00112
00113 Header header # Header timestamp should be acquisition time of image
00114 # Header frame_id should be optical frame of camera
00115 # origin of frame should be optical center of cameara
00116 # +x should point to the right in the image
00117 # +y should point down in the image
00118 # +z should point into to plane of the image
00119 # If the frame_id here and the frame_id of the CameraInfo
00120 # message associated with the image conflict
00121 # the behavior is undefined
00122
00123 uint32 height # image height, that is, number of rows
00124 uint32 width # image width, that is, number of columns
00125
00126 # The legal values for encoding are in file src/image_encodings.cpp
00127 # If you want to standardize a new string format, join
00128 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00129
00130 string encoding # Encoding of pixels -- channel meaning, ordering, size
00131 # taken from the list of strings in src/image_encodings.cpp
00132
00133 uint8 is_bigendian # is this data bigendian?
00134 uint32 step # Full row length in bytes
00135 uint8[] data # actual matrix data, size is (step * rows)
00136
00137 """
00138 __slots__ = ['center','min_bound','max_bound','object_cop_id','lo_id','points','roi','perception_method','sensor_type','object_type','object_color','object_geometric_type','table_id']
00139 _slot_types = ['geometry_msgs/Point32','geometry_msgs/Point32','geometry_msgs/Point32','uint64','uint64','sensor_msgs/PointCloud','sensor_msgs/Image','string','string','string','string','string','uint64']
00140
00141 def __init__(self, *args, **kwds):
00142 """
00143 Constructor. Any message fields that are implicitly/explicitly
00144 set to None will be assigned a default value. The recommend
00145 use is keyword arguments as this is more robust to future message
00146 changes. You cannot mix in-order arguments and keyword arguments.
00147
00148 The available fields are:
00149 center,min_bound,max_bound,object_cop_id,lo_id,points,roi,perception_method,sensor_type,object_type,object_color,object_geometric_type,table_id
00150
00151 :param args: complete set of field values, in .msg order
00152 :param kwds: use keyword arguments corresponding to message field names
00153 to set specific fields.
00154 """
00155 if args or kwds:
00156 super(TableObject, self).__init__(*args, **kwds)
00157 #message fields cannot be None, assign default values for those that are
00158 if self.center is None:
00159 self.center = geometry_msgs.msg.Point32()
00160 if self.min_bound is None:
00161 self.min_bound = geometry_msgs.msg.Point32()
00162 if self.max_bound is None:
00163 self.max_bound = geometry_msgs.msg.Point32()
00164 if self.object_cop_id is None:
00165 self.object_cop_id = 0
00166 if self.lo_id is None:
00167 self.lo_id = 0
00168 if self.points is None:
00169 self.points = sensor_msgs.msg.PointCloud()
00170 if self.roi is None:
00171 self.roi = sensor_msgs.msg.Image()
00172 if self.perception_method is None:
00173 self.perception_method = ''
00174 if self.sensor_type is None:
00175 self.sensor_type = ''
00176 if self.object_type is None:
00177 self.object_type = ''
00178 if self.object_color is None:
00179 self.object_color = ''
00180 if self.object_geometric_type is None:
00181 self.object_geometric_type = ''
00182 if self.table_id is None:
00183 self.table_id = 0
00184 else:
00185 self.center = geometry_msgs.msg.Point32()
00186 self.min_bound = geometry_msgs.msg.Point32()
00187 self.max_bound = geometry_msgs.msg.Point32()
00188 self.object_cop_id = 0
00189 self.lo_id = 0
00190 self.points = sensor_msgs.msg.PointCloud()
00191 self.roi = sensor_msgs.msg.Image()
00192 self.perception_method = ''
00193 self.sensor_type = ''
00194 self.object_type = ''
00195 self.object_color = ''
00196 self.object_geometric_type = ''
00197 self.table_id = 0
00198
00199 def _get_types(self):
00200 """
00201 internal API method
00202 """
00203 return self._slot_types
00204
00205 def serialize(self, buff):
00206 """
00207 serialize message into buffer
00208 :param buff: buffer, ``StringIO``
00209 """
00210 try:
00211 _x = self
00212 buff.write(_struct_9f2Q3I.pack(_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs))
00213 _x = self.points.header.frame_id
00214 length = len(_x)
00215 if python3 or type(_x) == unicode:
00216 _x = _x.encode('utf-8')
00217 length = len(_x)
00218 buff.write(struct.pack('<I%ss'%length, length, _x))
00219 length = len(self.points.points)
00220 buff.write(_struct_I.pack(length))
00221 for val1 in self.points.points:
00222 _x = val1
00223 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00224 length = len(self.points.channels)
00225 buff.write(_struct_I.pack(length))
00226 for val1 in self.points.channels:
00227 _x = val1.name
00228 length = len(_x)
00229 if python3 or type(_x) == unicode:
00230 _x = _x.encode('utf-8')
00231 length = len(_x)
00232 buff.write(struct.pack('<I%ss'%length, length, _x))
00233 length = len(val1.values)
00234 buff.write(_struct_I.pack(length))
00235 pattern = '<%sf'%length
00236 buff.write(struct.pack(pattern, *val1.values))
00237 _x = self
00238 buff.write(_struct_3I.pack(_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs))
00239 _x = self.roi.header.frame_id
00240 length = len(_x)
00241 if python3 or type(_x) == unicode:
00242 _x = _x.encode('utf-8')
00243 length = len(_x)
00244 buff.write(struct.pack('<I%ss'%length, length, _x))
00245 _x = self
00246 buff.write(_struct_2I.pack(_x.roi.height, _x.roi.width))
00247 _x = self.roi.encoding
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_BI.pack(_x.roi.is_bigendian, _x.roi.step))
00255 _x = self.roi.data
00256 length = len(_x)
00257 # - if encoded as a list instead, serialize as bytes instead of string
00258 if type(_x) in [list, tuple]:
00259 buff.write(struct.pack('<I%sB'%length, length, *_x))
00260 else:
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 _x = self.perception_method
00263 length = len(_x)
00264 if python3 or type(_x) == unicode:
00265 _x = _x.encode('utf-8')
00266 length = len(_x)
00267 buff.write(struct.pack('<I%ss'%length, length, _x))
00268 _x = self.sensor_type
00269 length = len(_x)
00270 if python3 or type(_x) == unicode:
00271 _x = _x.encode('utf-8')
00272 length = len(_x)
00273 buff.write(struct.pack('<I%ss'%length, length, _x))
00274 _x = self.object_type
00275 length = len(_x)
00276 if python3 or type(_x) == unicode:
00277 _x = _x.encode('utf-8')
00278 length = len(_x)
00279 buff.write(struct.pack('<I%ss'%length, length, _x))
00280 _x = self.object_color
00281 length = len(_x)
00282 if python3 or type(_x) == unicode:
00283 _x = _x.encode('utf-8')
00284 length = len(_x)
00285 buff.write(struct.pack('<I%ss'%length, length, _x))
00286 _x = self.object_geometric_type
00287 length = len(_x)
00288 if python3 or type(_x) == unicode:
00289 _x = _x.encode('utf-8')
00290 length = len(_x)
00291 buff.write(struct.pack('<I%ss'%length, length, _x))
00292 buff.write(_struct_Q.pack(self.table_id))
00293 except struct.error as se: self._check_types(se)
00294 except TypeError as te: self._check_types(te)
00295
00296 def deserialize(self, str):
00297 """
00298 unpack serialized message in str into this message instance
00299 :param str: byte array of serialized message, ``str``
00300 """
00301 try:
00302 if self.center is None:
00303 self.center = geometry_msgs.msg.Point32()
00304 if self.min_bound is None:
00305 self.min_bound = geometry_msgs.msg.Point32()
00306 if self.max_bound is None:
00307 self.max_bound = geometry_msgs.msg.Point32()
00308 if self.points is None:
00309 self.points = sensor_msgs.msg.PointCloud()
00310 if self.roi is None:
00311 self.roi = sensor_msgs.msg.Image()
00312 end = 0
00313 _x = self
00314 start = end
00315 end += 64
00316 (_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs,) = _struct_9f2Q3I.unpack(str[start:end])
00317 start = end
00318 end += 4
00319 (length,) = _struct_I.unpack(str[start:end])
00320 start = end
00321 end += length
00322 if python3:
00323 self.points.header.frame_id = str[start:end].decode('utf-8')
00324 else:
00325 self.points.header.frame_id = str[start:end]
00326 start = end
00327 end += 4
00328 (length,) = _struct_I.unpack(str[start:end])
00329 self.points.points = []
00330 for i in range(0, length):
00331 val1 = geometry_msgs.msg.Point32()
00332 _x = val1
00333 start = end
00334 end += 12
00335 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00336 self.points.points.append(val1)
00337 start = end
00338 end += 4
00339 (length,) = _struct_I.unpack(str[start:end])
00340 self.points.channels = []
00341 for i in range(0, length):
00342 val1 = sensor_msgs.msg.ChannelFloat32()
00343 start = end
00344 end += 4
00345 (length,) = _struct_I.unpack(str[start:end])
00346 start = end
00347 end += length
00348 if python3:
00349 val1.name = str[start:end].decode('utf-8')
00350 else:
00351 val1.name = str[start:end]
00352 start = end
00353 end += 4
00354 (length,) = _struct_I.unpack(str[start:end])
00355 pattern = '<%sf'%length
00356 start = end
00357 end += struct.calcsize(pattern)
00358 val1.values = struct.unpack(pattern, str[start:end])
00359 self.points.channels.append(val1)
00360 _x = self
00361 start = end
00362 end += 12
00363 (_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00364 start = end
00365 end += 4
00366 (length,) = _struct_I.unpack(str[start:end])
00367 start = end
00368 end += length
00369 if python3:
00370 self.roi.header.frame_id = str[start:end].decode('utf-8')
00371 else:
00372 self.roi.header.frame_id = str[start:end]
00373 _x = self
00374 start = end
00375 end += 8
00376 (_x.roi.height, _x.roi.width,) = _struct_2I.unpack(str[start:end])
00377 start = end
00378 end += 4
00379 (length,) = _struct_I.unpack(str[start:end])
00380 start = end
00381 end += length
00382 if python3:
00383 self.roi.encoding = str[start:end].decode('utf-8')
00384 else:
00385 self.roi.encoding = str[start:end]
00386 _x = self
00387 start = end
00388 end += 5
00389 (_x.roi.is_bigendian, _x.roi.step,) = _struct_BI.unpack(str[start:end])
00390 start = end
00391 end += 4
00392 (length,) = _struct_I.unpack(str[start:end])
00393 start = end
00394 end += length
00395 if python3:
00396 self.roi.data = str[start:end].decode('utf-8')
00397 else:
00398 self.roi.data = str[start:end]
00399 start = end
00400 end += 4
00401 (length,) = _struct_I.unpack(str[start:end])
00402 start = end
00403 end += length
00404 if python3:
00405 self.perception_method = str[start:end].decode('utf-8')
00406 else:
00407 self.perception_method = str[start:end]
00408 start = end
00409 end += 4
00410 (length,) = _struct_I.unpack(str[start:end])
00411 start = end
00412 end += length
00413 if python3:
00414 self.sensor_type = str[start:end].decode('utf-8')
00415 else:
00416 self.sensor_type = str[start:end]
00417 start = end
00418 end += 4
00419 (length,) = _struct_I.unpack(str[start:end])
00420 start = end
00421 end += length
00422 if python3:
00423 self.object_type = str[start:end].decode('utf-8')
00424 else:
00425 self.object_type = str[start:end]
00426 start = end
00427 end += 4
00428 (length,) = _struct_I.unpack(str[start:end])
00429 start = end
00430 end += length
00431 if python3:
00432 self.object_color = str[start:end].decode('utf-8')
00433 else:
00434 self.object_color = str[start:end]
00435 start = end
00436 end += 4
00437 (length,) = _struct_I.unpack(str[start:end])
00438 start = end
00439 end += length
00440 if python3:
00441 self.object_geometric_type = str[start:end].decode('utf-8')
00442 else:
00443 self.object_geometric_type = str[start:end]
00444 start = end
00445 end += 8
00446 (self.table_id,) = _struct_Q.unpack(str[start:end])
00447 return self
00448 except struct.error as e:
00449 raise genpy.DeserializationError(e) #most likely buffer underfill
00450
00451
00452 def serialize_numpy(self, buff, numpy):
00453 """
00454 serialize message with numpy array types into buffer
00455 :param buff: buffer, ``StringIO``
00456 :param numpy: numpy python module
00457 """
00458 try:
00459 _x = self
00460 buff.write(_struct_9f2Q3I.pack(_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs))
00461 _x = self.points.header.frame_id
00462 length = len(_x)
00463 if python3 or type(_x) == unicode:
00464 _x = _x.encode('utf-8')
00465 length = len(_x)
00466 buff.write(struct.pack('<I%ss'%length, length, _x))
00467 length = len(self.points.points)
00468 buff.write(_struct_I.pack(length))
00469 for val1 in self.points.points:
00470 _x = val1
00471 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00472 length = len(self.points.channels)
00473 buff.write(_struct_I.pack(length))
00474 for val1 in self.points.channels:
00475 _x = val1.name
00476 length = len(_x)
00477 if python3 or type(_x) == unicode:
00478 _x = _x.encode('utf-8')
00479 length = len(_x)
00480 buff.write(struct.pack('<I%ss'%length, length, _x))
00481 length = len(val1.values)
00482 buff.write(_struct_I.pack(length))
00483 pattern = '<%sf'%length
00484 buff.write(val1.values.tostring())
00485 _x = self
00486 buff.write(_struct_3I.pack(_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs))
00487 _x = self.roi.header.frame_id
00488 length = len(_x)
00489 if python3 or type(_x) == unicode:
00490 _x = _x.encode('utf-8')
00491 length = len(_x)
00492 buff.write(struct.pack('<I%ss'%length, length, _x))
00493 _x = self
00494 buff.write(_struct_2I.pack(_x.roi.height, _x.roi.width))
00495 _x = self.roi.encoding
00496 length = len(_x)
00497 if python3 or type(_x) == unicode:
00498 _x = _x.encode('utf-8')
00499 length = len(_x)
00500 buff.write(struct.pack('<I%ss'%length, length, _x))
00501 _x = self
00502 buff.write(_struct_BI.pack(_x.roi.is_bigendian, _x.roi.step))
00503 _x = self.roi.data
00504 length = len(_x)
00505 # - if encoded as a list instead, serialize as bytes instead of string
00506 if type(_x) in [list, tuple]:
00507 buff.write(struct.pack('<I%sB'%length, length, *_x))
00508 else:
00509 buff.write(struct.pack('<I%ss'%length, length, _x))
00510 _x = self.perception_method
00511 length = len(_x)
00512 if python3 or type(_x) == unicode:
00513 _x = _x.encode('utf-8')
00514 length = len(_x)
00515 buff.write(struct.pack('<I%ss'%length, length, _x))
00516 _x = self.sensor_type
00517 length = len(_x)
00518 if python3 or type(_x) == unicode:
00519 _x = _x.encode('utf-8')
00520 length = len(_x)
00521 buff.write(struct.pack('<I%ss'%length, length, _x))
00522 _x = self.object_type
00523 length = len(_x)
00524 if python3 or type(_x) == unicode:
00525 _x = _x.encode('utf-8')
00526 length = len(_x)
00527 buff.write(struct.pack('<I%ss'%length, length, _x))
00528 _x = self.object_color
00529 length = len(_x)
00530 if python3 or type(_x) == unicode:
00531 _x = _x.encode('utf-8')
00532 length = len(_x)
00533 buff.write(struct.pack('<I%ss'%length, length, _x))
00534 _x = self.object_geometric_type
00535 length = len(_x)
00536 if python3 or type(_x) == unicode:
00537 _x = _x.encode('utf-8')
00538 length = len(_x)
00539 buff.write(struct.pack('<I%ss'%length, length, _x))
00540 buff.write(_struct_Q.pack(self.table_id))
00541 except struct.error as se: self._check_types(se)
00542 except TypeError as te: self._check_types(te)
00543
00544 def deserialize_numpy(self, str, numpy):
00545 """
00546 unpack serialized message in str into this message instance using numpy for array types
00547 :param str: byte array of serialized message, ``str``
00548 :param numpy: numpy python module
00549 """
00550 try:
00551 if self.center is None:
00552 self.center = geometry_msgs.msg.Point32()
00553 if self.min_bound is None:
00554 self.min_bound = geometry_msgs.msg.Point32()
00555 if self.max_bound is None:
00556 self.max_bound = geometry_msgs.msg.Point32()
00557 if self.points is None:
00558 self.points = sensor_msgs.msg.PointCloud()
00559 if self.roi is None:
00560 self.roi = sensor_msgs.msg.Image()
00561 end = 0
00562 _x = self
00563 start = end
00564 end += 64
00565 (_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs,) = _struct_9f2Q3I.unpack(str[start:end])
00566 start = end
00567 end += 4
00568 (length,) = _struct_I.unpack(str[start:end])
00569 start = end
00570 end += length
00571 if python3:
00572 self.points.header.frame_id = str[start:end].decode('utf-8')
00573 else:
00574 self.points.header.frame_id = str[start:end]
00575 start = end
00576 end += 4
00577 (length,) = _struct_I.unpack(str[start:end])
00578 self.points.points = []
00579 for i in range(0, length):
00580 val1 = geometry_msgs.msg.Point32()
00581 _x = val1
00582 start = end
00583 end += 12
00584 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00585 self.points.points.append(val1)
00586 start = end
00587 end += 4
00588 (length,) = _struct_I.unpack(str[start:end])
00589 self.points.channels = []
00590 for i in range(0, length):
00591 val1 = sensor_msgs.msg.ChannelFloat32()
00592 start = end
00593 end += 4
00594 (length,) = _struct_I.unpack(str[start:end])
00595 start = end
00596 end += length
00597 if python3:
00598 val1.name = str[start:end].decode('utf-8')
00599 else:
00600 val1.name = str[start:end]
00601 start = end
00602 end += 4
00603 (length,) = _struct_I.unpack(str[start:end])
00604 pattern = '<%sf'%length
00605 start = end
00606 end += struct.calcsize(pattern)
00607 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00608 self.points.channels.append(val1)
00609 _x = self
00610 start = end
00611 end += 12
00612 (_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00613 start = end
00614 end += 4
00615 (length,) = _struct_I.unpack(str[start:end])
00616 start = end
00617 end += length
00618 if python3:
00619 self.roi.header.frame_id = str[start:end].decode('utf-8')
00620 else:
00621 self.roi.header.frame_id = str[start:end]
00622 _x = self
00623 start = end
00624 end += 8
00625 (_x.roi.height, _x.roi.width,) = _struct_2I.unpack(str[start:end])
00626 start = end
00627 end += 4
00628 (length,) = _struct_I.unpack(str[start:end])
00629 start = end
00630 end += length
00631 if python3:
00632 self.roi.encoding = str[start:end].decode('utf-8')
00633 else:
00634 self.roi.encoding = str[start:end]
00635 _x = self
00636 start = end
00637 end += 5
00638 (_x.roi.is_bigendian, _x.roi.step,) = _struct_BI.unpack(str[start:end])
00639 start = end
00640 end += 4
00641 (length,) = _struct_I.unpack(str[start:end])
00642 start = end
00643 end += length
00644 if python3:
00645 self.roi.data = str[start:end].decode('utf-8')
00646 else:
00647 self.roi.data = str[start:end]
00648 start = end
00649 end += 4
00650 (length,) = _struct_I.unpack(str[start:end])
00651 start = end
00652 end += length
00653 if python3:
00654 self.perception_method = str[start:end].decode('utf-8')
00655 else:
00656 self.perception_method = str[start:end]
00657 start = end
00658 end += 4
00659 (length,) = _struct_I.unpack(str[start:end])
00660 start = end
00661 end += length
00662 if python3:
00663 self.sensor_type = str[start:end].decode('utf-8')
00664 else:
00665 self.sensor_type = str[start:end]
00666 start = end
00667 end += 4
00668 (length,) = _struct_I.unpack(str[start:end])
00669 start = end
00670 end += length
00671 if python3:
00672 self.object_type = str[start:end].decode('utf-8')
00673 else:
00674 self.object_type = str[start:end]
00675 start = end
00676 end += 4
00677 (length,) = _struct_I.unpack(str[start:end])
00678 start = end
00679 end += length
00680 if python3:
00681 self.object_color = str[start:end].decode('utf-8')
00682 else:
00683 self.object_color = str[start:end]
00684 start = end
00685 end += 4
00686 (length,) = _struct_I.unpack(str[start:end])
00687 start = end
00688 end += length
00689 if python3:
00690 self.object_geometric_type = str[start:end].decode('utf-8')
00691 else:
00692 self.object_geometric_type = str[start:end]
00693 start = end
00694 end += 8
00695 (self.table_id,) = _struct_Q.unpack(str[start:end])
00696 return self
00697 except struct.error as e:
00698 raise genpy.DeserializationError(e) #most likely buffer underfill
00699
00700 _struct_I = genpy.struct_I
00701 _struct_9f2Q3I = struct.Struct("<9f2Q3I")
00702 _struct_BI = struct.Struct("<BI")
00703 _struct_2I = struct.Struct("<2I")
00704 _struct_Q = struct.Struct("<Q")
00705 _struct_3I = struct.Struct("<3I")
00706 _struct_3f = struct.Struct("<3f")