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