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