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(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00284 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
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 self.contents.data = str[start:end]
00364 _x = self
00365 start = end
00366 end += 13
00367 (_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00368 self.contents.is_dense = bool(self.contents.is_dense)
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 start = end
00373 end += length
00374 if python3:
00375 self.container.header.frame_id = str[start:end].decode('utf-8')
00376 else:
00377 self.container.header.frame_id = str[start:end]
00378 _x = self
00379 start = end
00380 end += 8
00381 (_x.container.height, _x.container.width,) = _struct_2I.unpack(str[start:end])
00382 start = end
00383 end += 4
00384 (length,) = _struct_I.unpack(str[start:end])
00385 self.container.fields = []
00386 for i in range(0, length):
00387 val1 = sensor_msgs.msg.PointField()
00388 start = end
00389 end += 4
00390 (length,) = _struct_I.unpack(str[start:end])
00391 start = end
00392 end += length
00393 if python3:
00394 val1.name = str[start:end].decode('utf-8')
00395 else:
00396 val1.name = str[start:end]
00397 _x = val1
00398 start = end
00399 end += 9
00400 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00401 self.container.fields.append(val1)
00402 _x = self
00403 start = end
00404 end += 9
00405 (_x.container.is_bigendian, _x.container.point_step, _x.container.row_step,) = _struct_B2I.unpack(str[start:end])
00406 self.container.is_bigendian = bool(self.container.is_bigendian)
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 start = end
00411 end += length
00412 self.container.data = str[start:end]
00413 start = end
00414 end += 1
00415 (self.container.is_dense,) = _struct_B.unpack(str[start:end])
00416 self.container.is_dense = bool(self.container.is_dense)
00417 start = end
00418 end += 4
00419 (length,) = _struct_I.unpack(str[start:end])
00420 self.clusters = []
00421 for i in range(0, length):
00422 val1 = sensor_msgs.msg.PointCloud2()
00423 _v3 = val1.header
00424 start = end
00425 end += 4
00426 (_v3.seq,) = _struct_I.unpack(str[start:end])
00427 _v4 = _v3.stamp
00428 _x = _v4
00429 start = end
00430 end += 8
00431 (_x.secs, _x.nsecs,) = _struct_2I.unpack(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 _v3.frame_id = str[start:end].decode('utf-8')
00439 else:
00440 _v3.frame_id = str[start:end]
00441 _x = val1
00442 start = end
00443 end += 8
00444 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00445 start = end
00446 end += 4
00447 (length,) = _struct_I.unpack(str[start:end])
00448 val1.fields = []
00449 for i in range(0, length):
00450 val2 = sensor_msgs.msg.PointField()
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 start = end
00455 end += length
00456 if python3:
00457 val2.name = str[start:end].decode('utf-8')
00458 else:
00459 val2.name = str[start:end]
00460 _x = val2
00461 start = end
00462 end += 9
00463 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00464 val1.fields.append(val2)
00465 _x = val1
00466 start = end
00467 end += 9
00468 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00469 val1.is_bigendian = bool(val1.is_bigendian)
00470 start = end
00471 end += 4
00472 (length,) = _struct_I.unpack(str[start:end])
00473 start = end
00474 end += length
00475 val1.data = str[start:end]
00476 start = end
00477 end += 1
00478 (val1.is_dense,) = _struct_B.unpack(str[start:end])
00479 val1.is_dense = bool(val1.is_dense)
00480 self.clusters.append(val1)
00481 return self
00482 except struct.error as e:
00483 raise genpy.DeserializationError(e)
00484
00485
00486 def serialize_numpy(self, buff, numpy):
00487 """
00488 serialize message with numpy array types into buffer
00489 :param buff: buffer, ``StringIO``
00490 :param numpy: numpy python module
00491 """
00492 try:
00493 _x = self
00494 buff.write(_struct_3I.pack(_x.box_pose.header.seq, _x.box_pose.header.stamp.secs, _x.box_pose.header.stamp.nsecs))
00495 _x = self.box_pose.header.frame_id
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_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))
00503 _x = self.contents.header.frame_id
00504 length = len(_x)
00505 if python3 or type(_x) == unicode:
00506 _x = _x.encode('utf-8')
00507 length = len(_x)
00508 buff.write(struct.pack('<I%ss'%length, length, _x))
00509 _x = self
00510 buff.write(_struct_2I.pack(_x.contents.height, _x.contents.width))
00511 length = len(self.contents.fields)
00512 buff.write(_struct_I.pack(length))
00513 for val1 in self.contents.fields:
00514 _x = val1.name
00515 length = len(_x)
00516 if python3 or type(_x) == unicode:
00517 _x = _x.encode('utf-8')
00518 length = len(_x)
00519 buff.write(struct.pack('<I%ss'%length, length, _x))
00520 _x = val1
00521 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00522 _x = self
00523 buff.write(_struct_B2I.pack(_x.contents.is_bigendian, _x.contents.point_step, _x.contents.row_step))
00524 _x = self.contents.data
00525 length = len(_x)
00526
00527 if type(_x) in [list, tuple]:
00528 buff.write(struct.pack('<I%sB'%length, length, *_x))
00529 else:
00530 buff.write(struct.pack('<I%ss'%length, length, _x))
00531 _x = self
00532 buff.write(_struct_B3I.pack(_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs))
00533 _x = self.container.header.frame_id
00534 length = len(_x)
00535 if python3 or type(_x) == unicode:
00536 _x = _x.encode('utf-8')
00537 length = len(_x)
00538 buff.write(struct.pack('<I%ss'%length, length, _x))
00539 _x = self
00540 buff.write(_struct_2I.pack(_x.container.height, _x.container.width))
00541 length = len(self.container.fields)
00542 buff.write(_struct_I.pack(length))
00543 for val1 in self.container.fields:
00544 _x = val1.name
00545 length = len(_x)
00546 if python3 or type(_x) == unicode:
00547 _x = _x.encode('utf-8')
00548 length = len(_x)
00549 buff.write(struct.pack('<I%ss'%length, length, _x))
00550 _x = val1
00551 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00552 _x = self
00553 buff.write(_struct_B2I.pack(_x.container.is_bigendian, _x.container.point_step, _x.container.row_step))
00554 _x = self.container.data
00555 length = len(_x)
00556
00557 if type(_x) in [list, tuple]:
00558 buff.write(struct.pack('<I%sB'%length, length, *_x))
00559 else:
00560 buff.write(struct.pack('<I%ss'%length, length, _x))
00561 buff.write(_struct_B.pack(self.container.is_dense))
00562 length = len(self.clusters)
00563 buff.write(_struct_I.pack(length))
00564 for val1 in self.clusters:
00565 _v5 = val1.header
00566 buff.write(_struct_I.pack(_v5.seq))
00567 _v6 = _v5.stamp
00568 _x = _v6
00569 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00570 _x = _v5.frame_id
00571 length = len(_x)
00572 if python3 or type(_x) == unicode:
00573 _x = _x.encode('utf-8')
00574 length = len(_x)
00575 buff.write(struct.pack('<I%ss'%length, length, _x))
00576 _x = val1
00577 buff.write(_struct_2I.pack(_x.height, _x.width))
00578 length = len(val1.fields)
00579 buff.write(_struct_I.pack(length))
00580 for val2 in val1.fields:
00581 _x = val2.name
00582 length = len(_x)
00583 if python3 or type(_x) == unicode:
00584 _x = _x.encode('utf-8')
00585 length = len(_x)
00586 buff.write(struct.pack('<I%ss'%length, length, _x))
00587 _x = val2
00588 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00589 _x = val1
00590 buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00591 _x = val1.data
00592 length = len(_x)
00593
00594 if type(_x) in [list, tuple]:
00595 buff.write(struct.pack('<I%sB'%length, length, *_x))
00596 else:
00597 buff.write(struct.pack('<I%ss'%length, length, _x))
00598 buff.write(_struct_B.pack(val1.is_dense))
00599 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00600 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00601
00602 def deserialize_numpy(self, str, numpy):
00603 """
00604 unpack serialized message in str into this message instance using numpy for array types
00605 :param str: byte array of serialized message, ``str``
00606 :param numpy: numpy python module
00607 """
00608 try:
00609 if self.box_pose is None:
00610 self.box_pose = geometry_msgs.msg.PoseStamped()
00611 if self.box_dims is None:
00612 self.box_dims = geometry_msgs.msg.Vector3()
00613 if self.contents is None:
00614 self.contents = sensor_msgs.msg.PointCloud2()
00615 if self.container is None:
00616 self.container = sensor_msgs.msg.PointCloud2()
00617 if self.clusters is None:
00618 self.clusters = None
00619 end = 0
00620 _x = self
00621 start = end
00622 end += 12
00623 (_x.box_pose.header.seq, _x.box_pose.header.stamp.secs, _x.box_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00624 start = end
00625 end += 4
00626 (length,) = _struct_I.unpack(str[start:end])
00627 start = end
00628 end += length
00629 if python3:
00630 self.box_pose.header.frame_id = str[start:end].decode('utf-8')
00631 else:
00632 self.box_pose.header.frame_id = str[start:end]
00633 _x = self
00634 start = end
00635 end += 92
00636 (_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])
00637 start = end
00638 end += 4
00639 (length,) = _struct_I.unpack(str[start:end])
00640 start = end
00641 end += length
00642 if python3:
00643 self.contents.header.frame_id = str[start:end].decode('utf-8')
00644 else:
00645 self.contents.header.frame_id = str[start:end]
00646 _x = self
00647 start = end
00648 end += 8
00649 (_x.contents.height, _x.contents.width,) = _struct_2I.unpack(str[start:end])
00650 start = end
00651 end += 4
00652 (length,) = _struct_I.unpack(str[start:end])
00653 self.contents.fields = []
00654 for i in range(0, length):
00655 val1 = sensor_msgs.msg.PointField()
00656 start = end
00657 end += 4
00658 (length,) = _struct_I.unpack(str[start:end])
00659 start = end
00660 end += length
00661 if python3:
00662 val1.name = str[start:end].decode('utf-8')
00663 else:
00664 val1.name = str[start:end]
00665 _x = val1
00666 start = end
00667 end += 9
00668 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00669 self.contents.fields.append(val1)
00670 _x = self
00671 start = end
00672 end += 9
00673 (_x.contents.is_bigendian, _x.contents.point_step, _x.contents.row_step,) = _struct_B2I.unpack(str[start:end])
00674 self.contents.is_bigendian = bool(self.contents.is_bigendian)
00675 start = end
00676 end += 4
00677 (length,) = _struct_I.unpack(str[start:end])
00678 start = end
00679 end += length
00680 self.contents.data = str[start:end]
00681 _x = self
00682 start = end
00683 end += 13
00684 (_x.contents.is_dense, _x.container.header.seq, _x.container.header.stamp.secs, _x.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00685 self.contents.is_dense = bool(self.contents.is_dense)
00686 start = end
00687 end += 4
00688 (length,) = _struct_I.unpack(str[start:end])
00689 start = end
00690 end += length
00691 if python3:
00692 self.container.header.frame_id = str[start:end].decode('utf-8')
00693 else:
00694 self.container.header.frame_id = str[start:end]
00695 _x = self
00696 start = end
00697 end += 8
00698 (_x.container.height, _x.container.width,) = _struct_2I.unpack(str[start:end])
00699 start = end
00700 end += 4
00701 (length,) = _struct_I.unpack(str[start:end])
00702 self.container.fields = []
00703 for i in range(0, length):
00704 val1 = sensor_msgs.msg.PointField()
00705 start = end
00706 end += 4
00707 (length,) = _struct_I.unpack(str[start:end])
00708 start = end
00709 end += length
00710 if python3:
00711 val1.name = str[start:end].decode('utf-8')
00712 else:
00713 val1.name = str[start:end]
00714 _x = val1
00715 start = end
00716 end += 9
00717 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00718 self.container.fields.append(val1)
00719 _x = self
00720 start = end
00721 end += 9
00722 (_x.container.is_bigendian, _x.container.point_step, _x.container.row_step,) = _struct_B2I.unpack(str[start:end])
00723 self.container.is_bigendian = bool(self.container.is_bigendian)
00724 start = end
00725 end += 4
00726 (length,) = _struct_I.unpack(str[start:end])
00727 start = end
00728 end += length
00729 self.container.data = str[start:end]
00730 start = end
00731 end += 1
00732 (self.container.is_dense,) = _struct_B.unpack(str[start:end])
00733 self.container.is_dense = bool(self.container.is_dense)
00734 start = end
00735 end += 4
00736 (length,) = _struct_I.unpack(str[start:end])
00737 self.clusters = []
00738 for i in range(0, length):
00739 val1 = sensor_msgs.msg.PointCloud2()
00740 _v7 = val1.header
00741 start = end
00742 end += 4
00743 (_v7.seq,) = _struct_I.unpack(str[start:end])
00744 _v8 = _v7.stamp
00745 _x = _v8
00746 start = end
00747 end += 8
00748 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00749 start = end
00750 end += 4
00751 (length,) = _struct_I.unpack(str[start:end])
00752 start = end
00753 end += length
00754 if python3:
00755 _v7.frame_id = str[start:end].decode('utf-8')
00756 else:
00757 _v7.frame_id = str[start:end]
00758 _x = val1
00759 start = end
00760 end += 8
00761 (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00762 start = end
00763 end += 4
00764 (length,) = _struct_I.unpack(str[start:end])
00765 val1.fields = []
00766 for i in range(0, length):
00767 val2 = sensor_msgs.msg.PointField()
00768 start = end
00769 end += 4
00770 (length,) = _struct_I.unpack(str[start:end])
00771 start = end
00772 end += length
00773 if python3:
00774 val2.name = str[start:end].decode('utf-8')
00775 else:
00776 val2.name = str[start:end]
00777 _x = val2
00778 start = end
00779 end += 9
00780 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00781 val1.fields.append(val2)
00782 _x = val1
00783 start = end
00784 end += 9
00785 (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00786 val1.is_bigendian = bool(val1.is_bigendian)
00787 start = end
00788 end += 4
00789 (length,) = _struct_I.unpack(str[start:end])
00790 start = end
00791 end += length
00792 val1.data = str[start:end]
00793 start = end
00794 end += 1
00795 (val1.is_dense,) = _struct_B.unpack(str[start:end])
00796 val1.is_dense = bool(val1.is_dense)
00797 self.clusters.append(val1)
00798 return self
00799 except struct.error as e:
00800 raise genpy.DeserializationError(e)
00801
00802 _struct_I = genpy.struct_I
00803 _struct_IBI = struct.Struct("<IBI")
00804 _struct_B = struct.Struct("<B")
00805 _struct_10d3I = struct.Struct("<10d3I")
00806 _struct_3I = struct.Struct("<3I")
00807 _struct_B3I = struct.Struct("<B3I")
00808 _struct_B2I = struct.Struct("<B2I")
00809 _struct_2I = struct.Struct("<2I")