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 include/sensor_msgs/image_encodings.h
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(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00294 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
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 self.roi.data = str[start:end]
00396 start = end
00397 end += 4
00398 (length,) = _struct_I.unpack(str[start:end])
00399 start = end
00400 end += length
00401 if python3:
00402 self.perception_method = str[start:end].decode('utf-8')
00403 else:
00404 self.perception_method = str[start:end]
00405 start = end
00406 end += 4
00407 (length,) = _struct_I.unpack(str[start:end])
00408 start = end
00409 end += length
00410 if python3:
00411 self.sensor_type = str[start:end].decode('utf-8')
00412 else:
00413 self.sensor_type = str[start:end]
00414 start = end
00415 end += 4
00416 (length,) = _struct_I.unpack(str[start:end])
00417 start = end
00418 end += length
00419 if python3:
00420 self.object_type = str[start:end].decode('utf-8')
00421 else:
00422 self.object_type = str[start:end]
00423 start = end
00424 end += 4
00425 (length,) = _struct_I.unpack(str[start:end])
00426 start = end
00427 end += length
00428 if python3:
00429 self.object_color = str[start:end].decode('utf-8')
00430 else:
00431 self.object_color = str[start:end]
00432 start = end
00433 end += 4
00434 (length,) = _struct_I.unpack(str[start:end])
00435 start = end
00436 end += length
00437 if python3:
00438 self.object_geometric_type = str[start:end].decode('utf-8')
00439 else:
00440 self.object_geometric_type = str[start:end]
00441 start = end
00442 end += 8
00443 (self.table_id,) = _struct_Q.unpack(str[start:end])
00444 return self
00445 except struct.error as e:
00446 raise genpy.DeserializationError(e) #most likely buffer underfill
00447
00448
00449 def serialize_numpy(self, buff, numpy):
00450 """
00451 serialize message with numpy array types into buffer
00452 :param buff: buffer, ``StringIO``
00453 :param numpy: numpy python module
00454 """
00455 try:
00456 _x = self
00457 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))
00458 _x = self.points.header.frame_id
00459 length = len(_x)
00460 if python3 or type(_x) == unicode:
00461 _x = _x.encode('utf-8')
00462 length = len(_x)
00463 buff.write(struct.pack('<I%ss'%length, length, _x))
00464 length = len(self.points.points)
00465 buff.write(_struct_I.pack(length))
00466 for val1 in self.points.points:
00467 _x = val1
00468 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00469 length = len(self.points.channels)
00470 buff.write(_struct_I.pack(length))
00471 for val1 in self.points.channels:
00472 _x = val1.name
00473 length = len(_x)
00474 if python3 or type(_x) == unicode:
00475 _x = _x.encode('utf-8')
00476 length = len(_x)
00477 buff.write(struct.pack('<I%ss'%length, length, _x))
00478 length = len(val1.values)
00479 buff.write(_struct_I.pack(length))
00480 pattern = '<%sf'%length
00481 buff.write(val1.values.tostring())
00482 _x = self
00483 buff.write(_struct_3I.pack(_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs))
00484 _x = self.roi.header.frame_id
00485 length = len(_x)
00486 if python3 or type(_x) == unicode:
00487 _x = _x.encode('utf-8')
00488 length = len(_x)
00489 buff.write(struct.pack('<I%ss'%length, length, _x))
00490 _x = self
00491 buff.write(_struct_2I.pack(_x.roi.height, _x.roi.width))
00492 _x = self.roi.encoding
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
00499 buff.write(_struct_BI.pack(_x.roi.is_bigendian, _x.roi.step))
00500 _x = self.roi.data
00501 length = len(_x)
00502 # - if encoded as a list instead, serialize as bytes instead of string
00503 if type(_x) in [list, tuple]:
00504 buff.write(struct.pack('<I%sB'%length, length, *_x))
00505 else:
00506 buff.write(struct.pack('<I%ss'%length, length, _x))
00507 _x = self.perception_method
00508 length = len(_x)
00509 if python3 or type(_x) == unicode:
00510 _x = _x.encode('utf-8')
00511 length = len(_x)
00512 buff.write(struct.pack('<I%ss'%length, length, _x))
00513 _x = self.sensor_type
00514 length = len(_x)
00515 if python3 or type(_x) == unicode:
00516 _x = _x.encode('utf-8')
00517 length = len(_x)
00518 buff.write(struct.pack('<I%ss'%length, length, _x))
00519 _x = self.object_type
00520 length = len(_x)
00521 if python3 or type(_x) == unicode:
00522 _x = _x.encode('utf-8')
00523 length = len(_x)
00524 buff.write(struct.pack('<I%ss'%length, length, _x))
00525 _x = self.object_color
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.object_geometric_type
00532 length = len(_x)
00533 if python3 or type(_x) == unicode:
00534 _x = _x.encode('utf-8')
00535 length = len(_x)
00536 buff.write(struct.pack('<I%ss'%length, length, _x))
00537 buff.write(_struct_Q.pack(self.table_id))
00538 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00539 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00540
00541 def deserialize_numpy(self, str, numpy):
00542 """
00543 unpack serialized message in str into this message instance using numpy for array types
00544 :param str: byte array of serialized message, ``str``
00545 :param numpy: numpy python module
00546 """
00547 try:
00548 if self.center is None:
00549 self.center = geometry_msgs.msg.Point32()
00550 if self.min_bound is None:
00551 self.min_bound = geometry_msgs.msg.Point32()
00552 if self.max_bound is None:
00553 self.max_bound = geometry_msgs.msg.Point32()
00554 if self.points is None:
00555 self.points = sensor_msgs.msg.PointCloud()
00556 if self.roi is None:
00557 self.roi = sensor_msgs.msg.Image()
00558 end = 0
00559 _x = self
00560 start = end
00561 end += 64
00562 (_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])
00563 start = end
00564 end += 4
00565 (length,) = _struct_I.unpack(str[start:end])
00566 start = end
00567 end += length
00568 if python3:
00569 self.points.header.frame_id = str[start:end].decode('utf-8')
00570 else:
00571 self.points.header.frame_id = str[start:end]
00572 start = end
00573 end += 4
00574 (length,) = _struct_I.unpack(str[start:end])
00575 self.points.points = []
00576 for i in range(0, length):
00577 val1 = geometry_msgs.msg.Point32()
00578 _x = val1
00579 start = end
00580 end += 12
00581 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00582 self.points.points.append(val1)
00583 start = end
00584 end += 4
00585 (length,) = _struct_I.unpack(str[start:end])
00586 self.points.channels = []
00587 for i in range(0, length):
00588 val1 = sensor_msgs.msg.ChannelFloat32()
00589 start = end
00590 end += 4
00591 (length,) = _struct_I.unpack(str[start:end])
00592 start = end
00593 end += length
00594 if python3:
00595 val1.name = str[start:end].decode('utf-8')
00596 else:
00597 val1.name = str[start:end]
00598 start = end
00599 end += 4
00600 (length,) = _struct_I.unpack(str[start:end])
00601 pattern = '<%sf'%length
00602 start = end
00603 end += struct.calcsize(pattern)
00604 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00605 self.points.channels.append(val1)
00606 _x = self
00607 start = end
00608 end += 12
00609 (_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00610 start = end
00611 end += 4
00612 (length,) = _struct_I.unpack(str[start:end])
00613 start = end
00614 end += length
00615 if python3:
00616 self.roi.header.frame_id = str[start:end].decode('utf-8')
00617 else:
00618 self.roi.header.frame_id = str[start:end]
00619 _x = self
00620 start = end
00621 end += 8
00622 (_x.roi.height, _x.roi.width,) = _struct_2I.unpack(str[start:end])
00623 start = end
00624 end += 4
00625 (length,) = _struct_I.unpack(str[start:end])
00626 start = end
00627 end += length
00628 if python3:
00629 self.roi.encoding = str[start:end].decode('utf-8')
00630 else:
00631 self.roi.encoding = str[start:end]
00632 _x = self
00633 start = end
00634 end += 5
00635 (_x.roi.is_bigendian, _x.roi.step,) = _struct_BI.unpack(str[start:end])
00636 start = end
00637 end += 4
00638 (length,) = _struct_I.unpack(str[start:end])
00639 start = end
00640 end += length
00641 self.roi.data = str[start:end]
00642 start = end
00643 end += 4
00644 (length,) = _struct_I.unpack(str[start:end])
00645 start = end
00646 end += length
00647 if python3:
00648 self.perception_method = str[start:end].decode('utf-8')
00649 else:
00650 self.perception_method = str[start:end]
00651 start = end
00652 end += 4
00653 (length,) = _struct_I.unpack(str[start:end])
00654 start = end
00655 end += length
00656 if python3:
00657 self.sensor_type = str[start:end].decode('utf-8')
00658 else:
00659 self.sensor_type = str[start:end]
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.object_type = str[start:end].decode('utf-8')
00667 else:
00668 self.object_type = 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.object_color = str[start:end].decode('utf-8')
00676 else:
00677 self.object_color = str[start:end]
00678 start = end
00679 end += 4
00680 (length,) = _struct_I.unpack(str[start:end])
00681 start = end
00682 end += length
00683 if python3:
00684 self.object_geometric_type = str[start:end].decode('utf-8')
00685 else:
00686 self.object_geometric_type = str[start:end]
00687 start = end
00688 end += 8
00689 (self.table_id,) = _struct_Q.unpack(str[start:end])
00690 return self
00691 except struct.error as e:
00692 raise genpy.DeserializationError(e) #most likely buffer underfill
00693
00694 _struct_I = genpy.struct_I
00695 _struct_9f2Q3I = struct.Struct("<9f2Q3I")
00696 _struct_BI = struct.Struct("<BI")
00697 _struct_2I = struct.Struct("<2I")
00698 _struct_Q = struct.Struct("<Q")
00699 _struct_3I = struct.Struct("<3I")
00700 _struct_3f = struct.Struct("<3f")