00001 """autogenerated by genpy from object_manipulation_msgs/FindContainerResult.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 std_msgs.msg
00010
00011 class FindContainerResult(genpy.Message):
00012 _md5sum = "9f205f80410192b4ceee2889befe1096"
00013 _type = "object_manipulation_msgs/FindContainerResult"
00014 _has_header = False
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016 # refined pose and dimensions of bounding box for container
00017 geometry_msgs/PoseStamped box_pose
00018 geometry_msgs/Vector3 box_dims
00019
00020 # cloud chunks of stuff in container, and container
00021 sensor_msgs/PointCloud2 contents
00022 sensor_msgs/PointCloud2 container
00023 sensor_msgs/PointCloud2[] clusters
00024
00025
00026 ================================================================================
00027 MSG: geometry_msgs/PoseStamped
00028 # A Pose with reference coordinate frame and timestamp
00029 Header header
00030 Pose pose
00031
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data
00036 # in a particular coordinate frame.
00037 #
00038 # sequence ID: consecutively increasing ID
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049
00050 ================================================================================
00051 MSG: geometry_msgs/Pose
00052 # A representation of pose in free space, composed of postion and orientation.
00053 Point position
00054 Quaternion orientation
00055
00056 ================================================================================
00057 MSG: geometry_msgs/Point
00058 # This contains the position of a point in free space
00059 float64 x
00060 float64 y
00061 float64 z
00062
00063 ================================================================================
00064 MSG: geometry_msgs/Quaternion
00065 # This represents an orientation in free space in quaternion form.
00066
00067 float64 x
00068 float64 y
00069 float64 z
00070 float64 w
00071
00072 ================================================================================
00073 MSG: geometry_msgs/Vector3
00074 # This represents a vector in free space.
00075
00076 float64 x
00077 float64 y
00078 float64 z
00079 ================================================================================
00080 MSG: sensor_msgs/PointCloud2
00081 # This message holds a collection of N-dimensional points, which may
00082 # contain additional information such as normals, intensity, etc. The
00083 # point data is stored as a binary blob, its layout described by the
00084 # contents of the "fields" array.
00085
00086 # The point cloud data may be organized 2d (image-like) or 1d
00087 # (unordered). Point clouds organized as 2d images may be produced by
00088 # camera depth sensors such as stereo or time-of-flight.
00089
00090 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00091 # points).
00092 Header header
00093
00094 # 2D structure of the point cloud. If the cloud is unordered, height is
00095 # 1 and width is the length of the point cloud.
00096 uint32 height
00097 uint32 width
00098
00099 # Describes the channels and their layout in the binary data blob.
00100 PointField[] fields
00101
00102 bool is_bigendian # Is this data bigendian?
00103 uint32 point_step # Length of a point in bytes
00104 uint32 row_step # Length of a row in bytes
00105 uint8[] data # Actual point data, size is (row_step*height)
00106
00107 bool is_dense # True if there are no invalid points
00108
00109 ================================================================================
00110 MSG: sensor_msgs/PointField
00111 # This message holds the description of one point entry in the
00112 # PointCloud2 message format.
00113 uint8 INT8 = 1
00114 uint8 UINT8 = 2
00115 uint8 INT16 = 3
00116 uint8 UINT16 = 4
00117 uint8 INT32 = 5
00118 uint8 UINT32 = 6
00119 uint8 FLOAT32 = 7
00120 uint8 FLOAT64 = 8
00121
00122 string name # Name of field
00123 uint32 offset # Offset from start of point struct
00124 uint8 datatype # Datatype enumeration, see above
00125 uint32 count # How many elements in the field
00126
00127 """
00128 __slots__ = ['box_pose','box_dims','contents','container','clusters']
00129 _slot_types = ['geometry_msgs/PoseStamped','geometry_msgs/Vector3','sensor_msgs/PointCloud2','sensor_msgs/PointCloud2','sensor_msgs/PointCloud2[]']
00130
00131 def __init__(self, *args, **kwds):
00132 """
00133 Constructor. Any message fields that are implicitly/explicitly
00134 set to None will be assigned a default value. The recommend
00135 use is keyword arguments as this is more robust to future message
00136 changes. You cannot mix in-order arguments and keyword arguments.
00137
00138 The available fields are:
00139 box_pose,box_dims,contents,container,clusters
00140
00141 :param args: complete set of field values, in .msg order
00142 :param kwds: use keyword arguments corresponding to message field names
00143 to set specific fields.
00144 """
00145 if args or kwds:
00146 super(FindContainerResult, self).__init__(*args, **kwds)
00147
00148 if self.box_pose is None:
00149 self.box_pose = geometry_msgs.msg.PoseStamped()
00150 if self.box_dims is None:
00151 self.box_dims = geometry_msgs.msg.Vector3()
00152 if self.contents is None:
00153 self.contents = sensor_msgs.msg.PointCloud2()
00154 if self.container is None:
00155 self.container = sensor_msgs.msg.PointCloud2()
00156 if self.clusters is None:
00157 self.clusters = []
00158 else:
00159 self.box_pose = geometry_msgs.msg.PoseStamped()
00160 self.box_dims = geometry_msgs.msg.Vector3()
00161 self.contents = sensor_msgs.msg.PointCloud2()
00162 self.container = sensor_msgs.msg.PointCloud2()
00163 self.clusters = []
00164
00165 def _get_types(self):
00166 """
00167 internal API method
00168 """
00169 return self._slot_types
00170
00171 def serialize(self, buff):
00172 """
00173 serialize message into buffer
00174 :param buff: buffer, ``StringIO``
00175 """
00176 try:
00177 _x = self
00178 buff.write(_struct_3I.pack(_x.box_pose.header.seq, _x.box_pose.header.stamp.secs, _x.box_pose.header.stamp.nsecs))
00179 _x = self.box_pose.header.frame_id
00180 length = len(_x)
00181 if python3 or type(_x) == unicode:
00182 _x = _x.encode('utf-8')
00183 length = len(_x)
00184 buff.write(struct.pack('<I%ss'%length, length, _x))
00185 _x = self
00186 buff.write(_struct_10d3I.pack(_x.box_pose.pose.position.x, _x.box_pose.pose.position.y, _x.box_pose.pose.position.z, _x.box_pose.pose.orientation.x, _x.box_pose.pose.orientation.y, _x.box_pose.pose.orientation.z, _x.box_pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.contents.header.seq, _x.contents.header.stamp.secs, _x.contents.header.stamp.nsecs))
00187 _x = self.contents.header.frame_id
00188 length = len(_x)
00189 if python3 or type(_x) == unicode:
00190 _x = _x.encode('utf-8')
00191 length = len(_x)
00192 buff.write(struct.pack('<I%ss'%length, length, _x))
00193 _x = self
00194 buff.write(_struct_2I.pack(_x.contents.height, _x.contents.width))
00195 length = len(self.contents.fields)
00196 buff.write(_struct_I.pack(length))
00197 for val1 in self.contents.fields:
00198 _x = val1.name
00199 length = len(_x)
00200 if python3 or type(_x) == unicode:
00201 _x = _x.encode('utf-8')
00202 length = len(_x)
00203 buff.write(struct.pack('<I%ss'%length, length, _x))
00204 _x = val1
00205 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00206 _x = self
00207 buff.write(_struct_B2I.pack(_x.contents.is_bigendian, _x.contents.point_step, _x.contents.row_step))
00208 _x = self.contents.data
00209 length = len(_x)
00210
00211 if type(_x) in [list, tuple]:
00212 buff.write(struct.pack('<I%sB'%length, length, *_x))
00213 else:
00214 buff.write(struct.pack('<I%ss'%length, length, _x))
00215 _x = self
00216 buff.write(_struct_B3I.pack(_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs))
00217 _x = self.container.header.frame_id
00218 length = len(_x)
00219 if python3 or type(_x) == unicode:
00220 _x = _x.encode('utf-8')
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 _x = self
00224 buff.write(_struct_2I.pack(_x.container.height, _x.container.width))
00225 length = len(self.container.fields)
00226 buff.write(_struct_I.pack(length))
00227 for val1 in self.container.fields:
00228 _x = val1.name
00229 length = len(_x)
00230 if python3 or type(_x) == unicode:
00231 _x = _x.encode('utf-8')
00232 length = len(_x)
00233 buff.write(struct.pack('<I%ss'%length, length, _x))
00234 _x = val1
00235 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00236 _x = self
00237 buff.write(_struct_B2I.pack(_x.container.is_bigendian, _x.container.point_step, _x.container.row_step))
00238 _x = self.container.data
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 buff.write(_struct_B.pack(self.container.is_dense))
00246 length = len(self.clusters)
00247 buff.write(_struct_I.pack(length))
00248 for val1 in self.clusters:
00249 _v1 = val1.header
00250 buff.write(_struct_I.pack(_v1.seq))
00251 _v2 = _v1.stamp
00252 _x = _v2
00253 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00254 _x = _v1.frame_id
00255 length = len(_x)
00256 if python3 or type(_x) == unicode:
00257 _x = _x.encode('utf-8')
00258 length = len(_x)
00259 buff.write(struct.pack('<I%ss'%length, length, _x))
00260 _x = val1
00261 buff.write(_struct_2I.pack(_x.height, _x.width))
00262 length = len(val1.fields)
00263 buff.write(_struct_I.pack(length))
00264 for val2 in val1.fields:
00265 _x = val2.name
00266 length = len(_x)
00267 if python3 or type(_x) == unicode:
00268 _x = _x.encode('utf-8')
00269 length = len(_x)
00270 buff.write(struct.pack('<I%ss'%length, length, _x))
00271 _x = val2
00272 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00273 _x = val1
00274 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00275 _x = val1.data
00276 length = len(_x)
00277
00278 if type(_x) in [list, tuple]:
00279 buff.write(struct.pack('<I%sB'%length, length, *_x))
00280 else:
00281 buff.write(struct.pack('<I%ss'%length, length, _x))
00282 buff.write(_struct_B.pack(val1.is_dense))
00283 except struct.error as se: self._check_types(se)
00284 except TypeError as te: self._check_types(te)
00285
00286 def deserialize(self, str):
00287 """
00288 unpack serialized message in str into this message instance
00289 :param str: byte array of serialized message, ``str``
00290 """
00291 try:
00292 if self.box_pose is None:
00293 self.box_pose = geometry_msgs.msg.PoseStamped()
00294 if self.box_dims is None:
00295 self.box_dims = geometry_msgs.msg.Vector3()
00296 if self.contents is None:
00297 self.contents = sensor_msgs.msg.PointCloud2()
00298 if self.container is None:
00299 self.container = sensor_msgs.msg.PointCloud2()
00300 if self.clusters is None:
00301 self.clusters = None
00302 end = 0
00303 _x = self
00304 start = end
00305 end += 12
00306 (_x.box_pose.header.seq, _x.box_pose.header.stamp.secs, _x.box_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00307 start = end
00308 end += 4
00309 (length,) = _struct_I.unpack(str[start:end])
00310 start = end
00311 end += length
00312 if python3:
00313 self.box_pose.header.frame_id = str[start:end].decode('utf-8')
00314 else:
00315 self.box_pose.header.frame_id = str[start:end]
00316 _x = self
00317 start = end
00318 end += 92
00319 (_x.box_pose.pose.position.x, _x.box_pose.pose.position.y, _x.box_pose.pose.position.z, _x.box_pose.pose.orientation.x, _x.box_pose.pose.orientation.y, _x.box_pose.pose.orientation.z, _x.box_pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.contents.header.seq, _x.contents.header.stamp.secs, _x.contents.header.stamp.nsecs,) = _struct_10d3I.unpack(str[start:end])
00320 start = end
00321 end += 4
00322 (length,) = _struct_I.unpack(str[start:end])
00323 start = end
00324 end += length
00325 if python3:
00326 self.contents.header.frame_id = str[start:end].decode('utf-8')
00327 else:
00328 self.contents.header.frame_id = str[start:end]
00329 _x = self
00330 start = end
00331 end += 8
00332 (_x.contents.height, _x.contents.width,) = _struct_2I.unpack(str[start:end])
00333 start = end
00334 end += 4
00335 (length,) = _struct_I.unpack(str[start:end])
00336 self.contents.fields = []
00337 for i in range(0, length):
00338 val1 = sensor_msgs.msg.PointField()
00339 start = end
00340 end += 4
00341 (length,) = _struct_I.unpack(str[start:end])
00342 start = end
00343 end += length
00344 if python3:
00345 val1.name = str[start:end].decode('utf-8')
00346 else:
00347 val1.name = str[start:end]
00348 _x = val1
00349 start = end
00350 end += 9
00351 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00352 self.contents.fields.append(val1)
00353 _x = self
00354 start = end
00355 end += 9
00356 (_x.contents.is_bigendian, _x.contents.point_step, _x.contents.row_step,) = _struct_B2I.unpack(str[start:end])
00357 self.contents.is_bigendian = bool(self.contents.is_bigendian)
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.contents.data = str[start:end].decode('utf-8')
00365 else:
00366 self.contents.data = str[start:end]
00367 _x = self
00368 start = end
00369 end += 13
00370 (_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00371 self.contents.is_dense = bool(self.contents.is_dense)
00372 start = end
00373 end += 4
00374 (length,) = _struct_I.unpack(str[start:end])
00375 start = end
00376 end += length
00377 if python3:
00378 self.container.header.frame_id = str[start:end].decode('utf-8')
00379 else:
00380 self.container.header.frame_id = str[start:end]
00381 _x = self
00382 start = end
00383 end += 8
00384 (_x.container.height, _x.container.width,) = _struct_2I.unpack(str[start:end])
00385 start = end
00386 end += 4
00387 (length,) = _struct_I.unpack(str[start:end])
00388 self.container.fields = []
00389 for i in range(0, length):
00390 val1 = sensor_msgs.msg.PointField()
00391 start = end
00392 end += 4
00393 (length,) = _struct_I.unpack(str[start:end])
00394 start = end
00395 end += length
00396 if python3:
00397 val1.name = str[start:end].decode('utf-8')
00398 else:
00399 val1.name = str[start:end]
00400 _x = val1
00401 start = end
00402 end += 9
00403 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00404 self.container.fields.append(val1)
00405 _x = self
00406 start = end
00407 end += 9
00408 (_x.container.is_bigendian, _x.container.point_step, _x.container.row_step,) = _struct_B2I.unpack(str[start:end])
00409 self.container.is_bigendian = bool(self.container.is_bigendian)
00410 start = end
00411 end += 4
00412 (length,) = _struct_I.unpack(str[start:end])
00413 start = end
00414 end += length
00415 if python3:
00416 self.container.data = str[start:end].decode('utf-8')
00417 else:
00418 self.container.data = str[start:end]
00419 start = end
00420 end += 1
00421 (self.container.is_dense,) = _struct_B.unpack(str[start:end])
00422 self.container.is_dense = bool(self.container.is_dense)
00423 start = end
00424 end += 4
00425 (length,) = _struct_I.unpack(str[start:end])
00426 self.clusters = []
00427 for i in range(0, length):
00428 val1 = sensor_msgs.msg.PointCloud2()
00429 _v3 = val1.header
00430 start = end
00431 end += 4
00432 (_v3.seq,) = _struct_I.unpack(str[start:end])
00433 _v4 = _v3.stamp
00434 _x = _v4
00435 start = end
00436 end += 8
00437 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00438 start = end
00439 end += 4
00440 (length,) = _struct_I.unpack(str[start:end])
00441 start = end
00442 end += length
00443 if python3:
00444 _v3.frame_id = str[start:end].decode('utf-8')
00445 else:
00446 _v3.frame_id = str[start:end]
00447 _x = val1
00448 start = end
00449 end += 8
00450 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 val1.fields = []
00455 for i in range(0, length):
00456 val2 = sensor_msgs.msg.PointField()
00457 start = end
00458 end += 4
00459 (length,) = _struct_I.unpack(str[start:end])
00460 start = end
00461 end += length
00462 if python3:
00463 val2.name = str[start:end].decode('utf-8')
00464 else:
00465 val2.name = str[start:end]
00466 _x = val2
00467 start = end
00468 end += 9
00469 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00470 val1.fields.append(val2)
00471 _x = val1
00472 start = end
00473 end += 9
00474 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00475 val1.is_bigendian = bool(val1.is_bigendian)
00476 start = end
00477 end += 4
00478 (length,) = _struct_I.unpack(str[start:end])
00479 start = end
00480 end += length
00481 if python3:
00482 val1.data = str[start:end].decode('utf-8')
00483 else:
00484 val1.data = str[start:end]
00485 start = end
00486 end += 1
00487 (val1.is_dense,) = _struct_B.unpack(str[start:end])
00488 val1.is_dense = bool(val1.is_dense)
00489 self.clusters.append(val1)
00490 return self
00491 except struct.error as e:
00492 raise genpy.DeserializationError(e)
00493
00494
00495 def serialize_numpy(self, buff, numpy):
00496 """
00497 serialize message with numpy array types into buffer
00498 :param buff: buffer, ``StringIO``
00499 :param numpy: numpy python module
00500 """
00501 try:
00502 _x = self
00503 buff.write(_struct_3I.pack(_x.box_pose.header.seq, _x.box_pose.header.stamp.secs, _x.box_pose.header.stamp.nsecs))
00504 _x = self.box_pose.header.frame_id
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_10d3I.pack(_x.box_pose.pose.position.x, _x.box_pose.pose.position.y, _x.box_pose.pose.position.z, _x.box_pose.pose.orientation.x, _x.box_pose.pose.orientation.y, _x.box_pose.pose.orientation.z, _x.box_pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.contents.header.seq, _x.contents.header.stamp.secs, _x.contents.header.stamp.nsecs))
00512 _x = self.contents.header.frame_id
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 _x = self
00519 buff.write(_struct_2I.pack(_x.contents.height, _x.contents.width))
00520 length = len(self.contents.fields)
00521 buff.write(_struct_I.pack(length))
00522 for val1 in self.contents.fields:
00523 _x = val1.name
00524 length = len(_x)
00525 if python3 or type(_x) == unicode:
00526 _x = _x.encode('utf-8')
00527 length = len(_x)
00528 buff.write(struct.pack('<I%ss'%length, length, _x))
00529 _x = val1
00530 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00531 _x = self
00532 buff.write(_struct_B2I.pack(_x.contents.is_bigendian, _x.contents.point_step, _x.contents.row_step))
00533 _x = self.contents.data
00534 length = len(_x)
00535
00536 if type(_x) in [list, tuple]:
00537 buff.write(struct.pack('<I%sB'%length, length, *_x))
00538 else:
00539 buff.write(struct.pack('<I%ss'%length, length, _x))
00540 _x = self
00541 buff.write(_struct_B3I.pack(_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs))
00542 _x = self.container.header.frame_id
00543 length = len(_x)
00544 if python3 or type(_x) == unicode:
00545 _x = _x.encode('utf-8')
00546 length = len(_x)
00547 buff.write(struct.pack('<I%ss'%length, length, _x))
00548 _x = self
00549 buff.write(_struct_2I.pack(_x.container.height, _x.container.width))
00550 length = len(self.container.fields)
00551 buff.write(_struct_I.pack(length))
00552 for val1 in self.container.fields:
00553 _x = val1.name
00554 length = len(_x)
00555 if python3 or type(_x) == unicode:
00556 _x = _x.encode('utf-8')
00557 length = len(_x)
00558 buff.write(struct.pack('<I%ss'%length, length, _x))
00559 _x = val1
00560 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00561 _x = self
00562 buff.write(_struct_B2I.pack(_x.container.is_bigendian, _x.container.point_step, _x.container.row_step))
00563 _x = self.container.data
00564 length = len(_x)
00565
00566 if type(_x) in [list, tuple]:
00567 buff.write(struct.pack('<I%sB'%length, length, *_x))
00568 else:
00569 buff.write(struct.pack('<I%ss'%length, length, _x))
00570 buff.write(_struct_B.pack(self.container.is_dense))
00571 length = len(self.clusters)
00572 buff.write(_struct_I.pack(length))
00573 for val1 in self.clusters:
00574 _v5 = val1.header
00575 buff.write(_struct_I.pack(_v5.seq))
00576 _v6 = _v5.stamp
00577 _x = _v6
00578 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00579 _x = _v5.frame_id
00580 length = len(_x)
00581 if python3 or type(_x) == unicode:
00582 _x = _x.encode('utf-8')
00583 length = len(_x)
00584 buff.write(struct.pack('<I%ss'%length, length, _x))
00585 _x = val1
00586 buff.write(_struct_2I.pack(_x.height, _x.width))
00587 length = len(val1.fields)
00588 buff.write(_struct_I.pack(length))
00589 for val2 in val1.fields:
00590 _x = val2.name
00591 length = len(_x)
00592 if python3 or type(_x) == unicode:
00593 _x = _x.encode('utf-8')
00594 length = len(_x)
00595 buff.write(struct.pack('<I%ss'%length, length, _x))
00596 _x = val2
00597 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00598 _x = val1
00599 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00600 _x = val1.data
00601 length = len(_x)
00602
00603 if type(_x) in [list, tuple]:
00604 buff.write(struct.pack('<I%sB'%length, length, *_x))
00605 else:
00606 buff.write(struct.pack('<I%ss'%length, length, _x))
00607 buff.write(_struct_B.pack(val1.is_dense))
00608 except struct.error as se: self._check_types(se)
00609 except TypeError as te: self._check_types(te)
00610
00611 def deserialize_numpy(self, str, numpy):
00612 """
00613 unpack serialized message in str into this message instance using numpy for array types
00614 :param str: byte array of serialized message, ``str``
00615 :param numpy: numpy python module
00616 """
00617 try:
00618 if self.box_pose is None:
00619 self.box_pose = geometry_msgs.msg.PoseStamped()
00620 if self.box_dims is None:
00621 self.box_dims = geometry_msgs.msg.Vector3()
00622 if self.contents is None:
00623 self.contents = sensor_msgs.msg.PointCloud2()
00624 if self.container is None:
00625 self.container = sensor_msgs.msg.PointCloud2()
00626 if self.clusters is None:
00627 self.clusters = None
00628 end = 0
00629 _x = self
00630 start = end
00631 end += 12
00632 (_x.box_pose.header.seq, _x.box_pose.header.stamp.secs, _x.box_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00633 start = end
00634 end += 4
00635 (length,) = _struct_I.unpack(str[start:end])
00636 start = end
00637 end += length
00638 if python3:
00639 self.box_pose.header.frame_id = str[start:end].decode('utf-8')
00640 else:
00641 self.box_pose.header.frame_id = str[start:end]
00642 _x = self
00643 start = end
00644 end += 92
00645 (_x.box_pose.pose.position.x, _x.box_pose.pose.position.y, _x.box_pose.pose.position.z, _x.box_pose.pose.orientation.x, _x.box_pose.pose.orientation.y, _x.box_pose.pose.orientation.z, _x.box_pose.pose.orientation.w, _x.box_dims.x, _x.box_dims.y, _x.box_dims.z, _x.contents.header.seq, _x.contents.header.stamp.secs, _x.contents.header.stamp.nsecs,) = _struct_10d3I.unpack(str[start:end])
00646 start = end
00647 end += 4
00648 (length,) = _struct_I.unpack(str[start:end])
00649 start = end
00650 end += length
00651 if python3:
00652 self.contents.header.frame_id = str[start:end].decode('utf-8')
00653 else:
00654 self.contents.header.frame_id = str[start:end]
00655 _x = self
00656 start = end
00657 end += 8
00658 (_x.contents.height, _x.contents.width,) = _struct_2I.unpack(str[start:end])
00659 start = end
00660 end += 4
00661 (length,) = _struct_I.unpack(str[start:end])
00662 self.contents.fields = []
00663 for i in range(0, length):
00664 val1 = sensor_msgs.msg.PointField()
00665 start = end
00666 end += 4
00667 (length,) = _struct_I.unpack(str[start:end])
00668 start = end
00669 end += length
00670 if python3:
00671 val1.name = str[start:end].decode('utf-8')
00672 else:
00673 val1.name = str[start:end]
00674 _x = val1
00675 start = end
00676 end += 9
00677 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00678 self.contents.fields.append(val1)
00679 _x = self
00680 start = end
00681 end += 9
00682 (_x.contents.is_bigendian, _x.contents.point_step, _x.contents.row_step,) = _struct_B2I.unpack(str[start:end])
00683 self.contents.is_bigendian = bool(self.contents.is_bigendian)
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.contents.data = str[start:end].decode('utf-8')
00691 else:
00692 self.contents.data = str[start:end]
00693 _x = self
00694 start = end
00695 end += 13
00696 (_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00697 self.contents.is_dense = bool(self.contents.is_dense)
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.container.header.frame_id = str[start:end].decode('utf-8')
00705 else:
00706 self.container.header.frame_id = str[start:end]
00707 _x = self
00708 start = end
00709 end += 8
00710 (_x.container.height, _x.container.width,) = _struct_2I.unpack(str[start:end])
00711 start = end
00712 end += 4
00713 (length,) = _struct_I.unpack(str[start:end])
00714 self.container.fields = []
00715 for i in range(0, length):
00716 val1 = sensor_msgs.msg.PointField()
00717 start = end
00718 end += 4
00719 (length,) = _struct_I.unpack(str[start:end])
00720 start = end
00721 end += length
00722 if python3:
00723 val1.name = str[start:end].decode('utf-8')
00724 else:
00725 val1.name = str[start:end]
00726 _x = val1
00727 start = end
00728 end += 9
00729 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00730 self.container.fields.append(val1)
00731 _x = self
00732 start = end
00733 end += 9
00734 (_x.container.is_bigendian, _x.container.point_step, _x.container.row_step,) = _struct_B2I.unpack(str[start:end])
00735 self.container.is_bigendian = bool(self.container.is_bigendian)
00736 start = end
00737 end += 4
00738 (length,) = _struct_I.unpack(str[start:end])
00739 start = end
00740 end += length
00741 if python3:
00742 self.container.data = str[start:end].decode('utf-8')
00743 else:
00744 self.container.data = str[start:end]
00745 start = end
00746 end += 1
00747 (self.container.is_dense,) = _struct_B.unpack(str[start:end])
00748 self.container.is_dense = bool(self.container.is_dense)
00749 start = end
00750 end += 4
00751 (length,) = _struct_I.unpack(str[start:end])
00752 self.clusters = []
00753 for i in range(0, length):
00754 val1 = sensor_msgs.msg.PointCloud2()
00755 _v7 = val1.header
00756 start = end
00757 end += 4
00758 (_v7.seq,) = _struct_I.unpack(str[start:end])
00759 _v8 = _v7.stamp
00760 _x = _v8
00761 start = end
00762 end += 8
00763 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00764 start = end
00765 end += 4
00766 (length,) = _struct_I.unpack(str[start:end])
00767 start = end
00768 end += length
00769 if python3:
00770 _v7.frame_id = str[start:end].decode('utf-8')
00771 else:
00772 _v7.frame_id = str[start:end]
00773 _x = val1
00774 start = end
00775 end += 8
00776 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00777 start = end
00778 end += 4
00779 (length,) = _struct_I.unpack(str[start:end])
00780 val1.fields = []
00781 for i in range(0, length):
00782 val2 = sensor_msgs.msg.PointField()
00783 start = end
00784 end += 4
00785 (length,) = _struct_I.unpack(str[start:end])
00786 start = end
00787 end += length
00788 if python3:
00789 val2.name = str[start:end].decode('utf-8')
00790 else:
00791 val2.name = str[start:end]
00792 _x = val2
00793 start = end
00794 end += 9
00795 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00796 val1.fields.append(val2)
00797 _x = val1
00798 start = end
00799 end += 9
00800 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00801 val1.is_bigendian = bool(val1.is_bigendian)
00802 start = end
00803 end += 4
00804 (length,) = _struct_I.unpack(str[start:end])
00805 start = end
00806 end += length
00807 if python3:
00808 val1.data = str[start:end].decode('utf-8')
00809 else:
00810 val1.data = str[start:end]
00811 start = end
00812 end += 1
00813 (val1.is_dense,) = _struct_B.unpack(str[start:end])
00814 val1.is_dense = bool(val1.is_dense)
00815 self.clusters.append(val1)
00816 return self
00817 except struct.error as e:
00818 raise genpy.DeserializationError(e)
00819
00820 _struct_I = genpy.struct_I
00821 _struct_IBI = struct.Struct("<IBI")
00822 _struct_B = struct.Struct("<B")
00823 _struct_10d3I = struct.Struct("<10d3I")
00824 _struct_3I = struct.Struct("<3I")
00825 _struct_B3I = struct.Struct("<B3I")
00826 _struct_B2I = struct.Struct("<B2I")
00827 _struct_2I = struct.Struct("<2I")