00001 """autogenerated by genpy from cr_capture/RawCloudData.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 cr_capture.msg
00008 import sensor_msgs.msg
00009 import std_msgs.msg
00010
00011 class RawCloudData(genpy.Message):
00012 _md5sum = "576b69ba11e4225220315b3f3359d42e"
00013 _type = "cr_capture/RawCloudData"
00014 _has_header = True
00015 _full_text = """Header header
00016 # range sensor
00017 sensor_msgs/Image intensity
00018 sensor_msgs/Image confidence
00019 sensor_msgs/Image depth
00020 sensor_msgs/Image depth16
00021 # sensor_msgs/PointCloud point_cloud_raw
00022 sensor_msgs/CameraInfo range_info
00023
00024 # camera
00025 sensor_msgs/Image left_image
00026 sensor_msgs/Image right_image
00027 sensor_msgs/CameraInfo left_info
00028 sensor_msgs/CameraInfo right_info
00029
00030 # result
00031 cr_capture/PixelIndices pixel_indices
00032 sensor_msgs/PointCloud2 point_cloud
00033
00034 ================================================================================
00035 MSG: std_msgs/Header
00036 # Standard metadata for higher-level stamped data types.
00037 # This is generally used to communicate timestamped data
00038 # in a particular coordinate frame.
00039 #
00040 # sequence ID: consecutively increasing ID
00041 uint32 seq
00042 #Two-integer timestamp that is expressed as:
00043 # * stamp.secs: seconds (stamp_secs) since epoch
00044 # * stamp.nsecs: nanoseconds since stamp_secs
00045 # time-handling sugar is provided by the client library
00046 time stamp
00047 #Frame this data is associated with
00048 # 0: no frame
00049 # 1: global frame
00050 string frame_id
00051
00052 ================================================================================
00053 MSG: sensor_msgs/Image
00054 # This message contains an uncompressed image
00055 # (0, 0) is at top-left corner of image
00056 #
00057
00058 Header header # Header timestamp should be acquisition time of image
00059 # Header frame_id should be optical frame of camera
00060 # origin of frame should be optical center of cameara
00061 # +x should point to the right in the image
00062 # +y should point down in the image
00063 # +z should point into to plane of the image
00064 # If the frame_id here and the frame_id of the CameraInfo
00065 # message associated with the image conflict
00066 # the behavior is undefined
00067
00068 uint32 height # image height, that is, number of rows
00069 uint32 width # image width, that is, number of columns
00070
00071 # The legal values for encoding are in file src/image_encodings.cpp
00072 # If you want to standardize a new string format, join
00073 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00074
00075 string encoding # Encoding of pixels -- channel meaning, ordering, size
00076 # taken from the list of strings in include/sensor_msgs/image_encodings.h
00077
00078 uint8 is_bigendian # is this data bigendian?
00079 uint32 step # Full row length in bytes
00080 uint8[] data # actual matrix data, size is (step * rows)
00081
00082 ================================================================================
00083 MSG: sensor_msgs/CameraInfo
00084 # This message defines meta information for a camera. It should be in a
00085 # camera namespace on topic "camera_info" and accompanied by up to five
00086 # image topics named:
00087 #
00088 # image_raw - raw data from the camera driver, possibly Bayer encoded
00089 # image - monochrome, distorted
00090 # image_color - color, distorted
00091 # image_rect - monochrome, rectified
00092 # image_rect_color - color, rectified
00093 #
00094 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00095 # for producing the four processed image topics from image_raw and
00096 # camera_info. The meaning of the camera parameters are described in
00097 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00098 #
00099 # The image_geometry package provides a user-friendly interface to
00100 # common operations using this meta information. If you want to, e.g.,
00101 # project a 3d point into image coordinates, we strongly recommend
00102 # using image_geometry.
00103 #
00104 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00105 # zeroed out. In particular, clients may assume that K[0] == 0.0
00106 # indicates an uncalibrated camera.
00107
00108 #######################################################################
00109 # Image acquisition info #
00110 #######################################################################
00111
00112 # Time of image acquisition, camera coordinate frame ID
00113 Header header # Header timestamp should be acquisition time of image
00114 # Header frame_id should be optical frame of camera
00115 # origin of frame should be optical center of camera
00116 # +x should point to the right in the image
00117 # +y should point down in the image
00118 # +z should point into the plane of the image
00119
00120
00121 #######################################################################
00122 # Calibration Parameters #
00123 #######################################################################
00124 # These are fixed during camera calibration. Their values will be the #
00125 # same in all messages until the camera is recalibrated. Note that #
00126 # self-calibrating systems may "recalibrate" frequently. #
00127 # #
00128 # The internal parameters can be used to warp a raw (distorted) image #
00129 # to: #
00130 # 1. An undistorted image (requires D and K) #
00131 # 2. A rectified image (requires D, K, R) #
00132 # The projection matrix P projects 3D points into the rectified image.#
00133 #######################################################################
00134
00135 # The image dimensions with which the camera was calibrated. Normally
00136 # this will be the full camera resolution in pixels.
00137 uint32 height
00138 uint32 width
00139
00140 # The distortion model used. Supported models are listed in
00141 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00142 # simple model of radial and tangential distortion - is sufficent.
00143 string distortion_model
00144
00145 # The distortion parameters, size depending on the distortion model.
00146 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00147 float64[] D
00148
00149 # Intrinsic camera matrix for the raw (distorted) images.
00150 # [fx 0 cx]
00151 # K = [ 0 fy cy]
00152 # [ 0 0 1]
00153 # Projects 3D points in the camera coordinate frame to 2D pixel
00154 # coordinates using the focal lengths (fx, fy) and principal point
00155 # (cx, cy).
00156 float64[9] K # 3x3 row-major matrix
00157
00158 # Rectification matrix (stereo cameras only)
00159 # A rotation matrix aligning the camera coordinate system to the ideal
00160 # stereo image plane so that epipolar lines in both stereo images are
00161 # parallel.
00162 float64[9] R # 3x3 row-major matrix
00163
00164 # Projection/camera matrix
00165 # [fx' 0 cx' Tx]
00166 # P = [ 0 fy' cy' Ty]
00167 # [ 0 0 1 0]
00168 # By convention, this matrix specifies the intrinsic (camera) matrix
00169 # of the processed (rectified) image. That is, the left 3x3 portion
00170 # is the normal camera intrinsic matrix for the rectified image.
00171 # It projects 3D points in the camera coordinate frame to 2D pixel
00172 # coordinates using the focal lengths (fx', fy') and principal point
00173 # (cx', cy') - these may differ from the values in K.
00174 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00175 # also have R = the identity and P[1:3,1:3] = K.
00176 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00177 # position of the optical center of the second camera in the first
00178 # camera's frame. We assume Tz = 0 so both cameras are in the same
00179 # stereo image plane. The first camera always has Tx = Ty = 0. For
00180 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00181 # Tx = -fx' * B, where B is the baseline between the cameras.
00182 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00183 # the rectified image is given by:
00184 # [u v w]' = P * [X Y Z 1]'
00185 # x = u / w
00186 # y = v / w
00187 # This holds for both images of a stereo pair.
00188 float64[12] P # 3x4 row-major matrix
00189
00190
00191 #######################################################################
00192 # Operational Parameters #
00193 #######################################################################
00194 # These define the image region actually captured by the camera #
00195 # driver. Although they affect the geometry of the output image, they #
00196 # may be changed freely without recalibrating the camera. #
00197 #######################################################################
00198
00199 # Binning refers here to any camera setting which combines rectangular
00200 # neighborhoods of pixels into larger "super-pixels." It reduces the
00201 # resolution of the output image to
00202 # (width / binning_x) x (height / binning_y).
00203 # The default values binning_x = binning_y = 0 is considered the same
00204 # as binning_x = binning_y = 1 (no subsampling).
00205 uint32 binning_x
00206 uint32 binning_y
00207
00208 # Region of interest (subwindow of full camera resolution), given in
00209 # full resolution (unbinned) image coordinates. A particular ROI
00210 # always denotes the same window of pixels on the camera sensor,
00211 # regardless of binning settings.
00212 # The default setting of roi (all values 0) is considered the same as
00213 # full resolution (roi.width = width, roi.height = height).
00214 RegionOfInterest roi
00215
00216 ================================================================================
00217 MSG: sensor_msgs/RegionOfInterest
00218 # This message is used to specify a region of interest within an image.
00219 #
00220 # When used to specify the ROI setting of the camera when the image was
00221 # taken, the height and width fields should either match the height and
00222 # width fields for the associated image; or height = width = 0
00223 # indicates that the full resolution image was captured.
00224
00225 uint32 x_offset # Leftmost pixel of the ROI
00226 # (0 if the ROI includes the left edge of the image)
00227 uint32 y_offset # Topmost pixel of the ROI
00228 # (0 if the ROI includes the top edge of the image)
00229 uint32 height # Height of ROI
00230 uint32 width # Width of ROI
00231
00232 # True if a distinct rectified ROI should be calculated from the "raw"
00233 # ROI in this message. Typically this should be False if the full image
00234 # is captured (ROI not used), and True if a subwindow is captured (ROI
00235 # used).
00236 bool do_rectify
00237
00238 ================================================================================
00239 MSG: cr_capture/PixelIndices
00240 Header header
00241 int32[] indices # [[lu,ru,v],...]
00242
00243 ================================================================================
00244 MSG: sensor_msgs/PointCloud2
00245 # This message holds a collection of N-dimensional points, which may
00246 # contain additional information such as normals, intensity, etc. The
00247 # point data is stored as a binary blob, its layout described by the
00248 # contents of the "fields" array.
00249
00250 # The point cloud data may be organized 2d (image-like) or 1d
00251 # (unordered). Point clouds organized as 2d images may be produced by
00252 # camera depth sensors such as stereo or time-of-flight.
00253
00254 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00255 # points).
00256 Header header
00257
00258 # 2D structure of the point cloud. If the cloud is unordered, height is
00259 # 1 and width is the length of the point cloud.
00260 uint32 height
00261 uint32 width
00262
00263 # Describes the channels and their layout in the binary data blob.
00264 PointField[] fields
00265
00266 bool is_bigendian # Is this data bigendian?
00267 uint32 point_step # Length of a point in bytes
00268 uint32 row_step # Length of a row in bytes
00269 uint8[] data # Actual point data, size is (row_step*height)
00270
00271 bool is_dense # True if there are no invalid points
00272
00273 ================================================================================
00274 MSG: sensor_msgs/PointField
00275 # This message holds the description of one point entry in the
00276 # PointCloud2 message format.
00277 uint8 INT8 = 1
00278 uint8 UINT8 = 2
00279 uint8 INT16 = 3
00280 uint8 UINT16 = 4
00281 uint8 INT32 = 5
00282 uint8 UINT32 = 6
00283 uint8 FLOAT32 = 7
00284 uint8 FLOAT64 = 8
00285
00286 string name # Name of field
00287 uint32 offset # Offset from start of point struct
00288 uint8 datatype # Datatype enumeration, see above
00289 uint32 count # How many elements in the field
00290
00291 """
00292 __slots__ = ['header','intensity','confidence','depth','depth16','range_info','left_image','right_image','left_info','right_info','pixel_indices','point_cloud']
00293 _slot_types = ['std_msgs/Header','sensor_msgs/Image','sensor_msgs/Image','sensor_msgs/Image','sensor_msgs/Image','sensor_msgs/CameraInfo','sensor_msgs/Image','sensor_msgs/Image','sensor_msgs/CameraInfo','sensor_msgs/CameraInfo','cr_capture/PixelIndices','sensor_msgs/PointCloud2']
00294
00295 def __init__(self, *args, **kwds):
00296 """
00297 Constructor. Any message fields that are implicitly/explicitly
00298 set to None will be assigned a default value. The recommend
00299 use is keyword arguments as this is more robust to future message
00300 changes. You cannot mix in-order arguments and keyword arguments.
00301
00302 The available fields are:
00303 header,intensity,confidence,depth,depth16,range_info,left_image,right_image,left_info,right_info,pixel_indices,point_cloud
00304
00305 :param args: complete set of field values, in .msg order
00306 :param kwds: use keyword arguments corresponding to message field names
00307 to set specific fields.
00308 """
00309 if args or kwds:
00310 super(RawCloudData, self).__init__(*args, **kwds)
00311
00312 if self.header is None:
00313 self.header = std_msgs.msg.Header()
00314 if self.intensity is None:
00315 self.intensity = sensor_msgs.msg.Image()
00316 if self.confidence is None:
00317 self.confidence = sensor_msgs.msg.Image()
00318 if self.depth is None:
00319 self.depth = sensor_msgs.msg.Image()
00320 if self.depth16 is None:
00321 self.depth16 = sensor_msgs.msg.Image()
00322 if self.range_info is None:
00323 self.range_info = sensor_msgs.msg.CameraInfo()
00324 if self.left_image is None:
00325 self.left_image = sensor_msgs.msg.Image()
00326 if self.right_image is None:
00327 self.right_image = sensor_msgs.msg.Image()
00328 if self.left_info is None:
00329 self.left_info = sensor_msgs.msg.CameraInfo()
00330 if self.right_info is None:
00331 self.right_info = sensor_msgs.msg.CameraInfo()
00332 if self.pixel_indices is None:
00333 self.pixel_indices = cr_capture.msg.PixelIndices()
00334 if self.point_cloud is None:
00335 self.point_cloud = sensor_msgs.msg.PointCloud2()
00336 else:
00337 self.header = std_msgs.msg.Header()
00338 self.intensity = sensor_msgs.msg.Image()
00339 self.confidence = sensor_msgs.msg.Image()
00340 self.depth = sensor_msgs.msg.Image()
00341 self.depth16 = sensor_msgs.msg.Image()
00342 self.range_info = sensor_msgs.msg.CameraInfo()
00343 self.left_image = sensor_msgs.msg.Image()
00344 self.right_image = sensor_msgs.msg.Image()
00345 self.left_info = sensor_msgs.msg.CameraInfo()
00346 self.right_info = sensor_msgs.msg.CameraInfo()
00347 self.pixel_indices = cr_capture.msg.PixelIndices()
00348 self.point_cloud = sensor_msgs.msg.PointCloud2()
00349
00350 def _get_types(self):
00351 """
00352 internal API method
00353 """
00354 return self._slot_types
00355
00356 def serialize(self, buff):
00357 """
00358 serialize message into buffer
00359 :param buff: buffer, ``StringIO``
00360 """
00361 try:
00362 _x = self
00363 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00364 _x = self.header.frame_id
00365 length = len(_x)
00366 if python3 or type(_x) == unicode:
00367 _x = _x.encode('utf-8')
00368 length = len(_x)
00369 buff.write(struct.pack('<I%ss'%length, length, _x))
00370 _x = self
00371 buff.write(_struct_3I.pack(_x.intensity.header.seq, _x.intensity.header.stamp.secs, _x.intensity.header.stamp.nsecs))
00372 _x = self.intensity.header.frame_id
00373 length = len(_x)
00374 if python3 or type(_x) == unicode:
00375 _x = _x.encode('utf-8')
00376 length = len(_x)
00377 buff.write(struct.pack('<I%ss'%length, length, _x))
00378 _x = self
00379 buff.write(_struct_2I.pack(_x.intensity.height, _x.intensity.width))
00380 _x = self.intensity.encoding
00381 length = len(_x)
00382 if python3 or type(_x) == unicode:
00383 _x = _x.encode('utf-8')
00384 length = len(_x)
00385 buff.write(struct.pack('<I%ss'%length, length, _x))
00386 _x = self
00387 buff.write(_struct_BI.pack(_x.intensity.is_bigendian, _x.intensity.step))
00388 _x = self.intensity.data
00389 length = len(_x)
00390
00391 if type(_x) in [list, tuple]:
00392 buff.write(struct.pack('<I%sB'%length, length, *_x))
00393 else:
00394 buff.write(struct.pack('<I%ss'%length, length, _x))
00395 _x = self
00396 buff.write(_struct_3I.pack(_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs))
00397 _x = self.confidence.header.frame_id
00398 length = len(_x)
00399 if python3 or type(_x) == unicode:
00400 _x = _x.encode('utf-8')
00401 length = len(_x)
00402 buff.write(struct.pack('<I%ss'%length, length, _x))
00403 _x = self
00404 buff.write(_struct_2I.pack(_x.confidence.height, _x.confidence.width))
00405 _x = self.confidence.encoding
00406 length = len(_x)
00407 if python3 or type(_x) == unicode:
00408 _x = _x.encode('utf-8')
00409 length = len(_x)
00410 buff.write(struct.pack('<I%ss'%length, length, _x))
00411 _x = self
00412 buff.write(_struct_BI.pack(_x.confidence.is_bigendian, _x.confidence.step))
00413 _x = self.confidence.data
00414 length = len(_x)
00415
00416 if type(_x) in [list, tuple]:
00417 buff.write(struct.pack('<I%sB'%length, length, *_x))
00418 else:
00419 buff.write(struct.pack('<I%ss'%length, length, _x))
00420 _x = self
00421 buff.write(_struct_3I.pack(_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs))
00422 _x = self.depth.header.frame_id
00423 length = len(_x)
00424 if python3 or type(_x) == unicode:
00425 _x = _x.encode('utf-8')
00426 length = len(_x)
00427 buff.write(struct.pack('<I%ss'%length, length, _x))
00428 _x = self
00429 buff.write(_struct_2I.pack(_x.depth.height, _x.depth.width))
00430 _x = self.depth.encoding
00431 length = len(_x)
00432 if python3 or type(_x) == unicode:
00433 _x = _x.encode('utf-8')
00434 length = len(_x)
00435 buff.write(struct.pack('<I%ss'%length, length, _x))
00436 _x = self
00437 buff.write(_struct_BI.pack(_x.depth.is_bigendian, _x.depth.step))
00438 _x = self.depth.data
00439 length = len(_x)
00440
00441 if type(_x) in [list, tuple]:
00442 buff.write(struct.pack('<I%sB'%length, length, *_x))
00443 else:
00444 buff.write(struct.pack('<I%ss'%length, length, _x))
00445 _x = self
00446 buff.write(_struct_3I.pack(_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs))
00447 _x = self.depth16.header.frame_id
00448 length = len(_x)
00449 if python3 or type(_x) == unicode:
00450 _x = _x.encode('utf-8')
00451 length = len(_x)
00452 buff.write(struct.pack('<I%ss'%length, length, _x))
00453 _x = self
00454 buff.write(_struct_2I.pack(_x.depth16.height, _x.depth16.width))
00455 _x = self.depth16.encoding
00456 length = len(_x)
00457 if python3 or type(_x) == unicode:
00458 _x = _x.encode('utf-8')
00459 length = len(_x)
00460 buff.write(struct.pack('<I%ss'%length, length, _x))
00461 _x = self
00462 buff.write(_struct_BI.pack(_x.depth16.is_bigendian, _x.depth16.step))
00463 _x = self.depth16.data
00464 length = len(_x)
00465
00466 if type(_x) in [list, tuple]:
00467 buff.write(struct.pack('<I%sB'%length, length, *_x))
00468 else:
00469 buff.write(struct.pack('<I%ss'%length, length, _x))
00470 _x = self
00471 buff.write(_struct_3I.pack(_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs))
00472 _x = self.range_info.header.frame_id
00473 length = len(_x)
00474 if python3 or type(_x) == unicode:
00475 _x = _x.encode('utf-8')
00476 length = len(_x)
00477 buff.write(struct.pack('<I%ss'%length, length, _x))
00478 _x = self
00479 buff.write(_struct_2I.pack(_x.range_info.height, _x.range_info.width))
00480 _x = self.range_info.distortion_model
00481 length = len(_x)
00482 if python3 or type(_x) == unicode:
00483 _x = _x.encode('utf-8')
00484 length = len(_x)
00485 buff.write(struct.pack('<I%ss'%length, length, _x))
00486 length = len(self.range_info.D)
00487 buff.write(_struct_I.pack(length))
00488 pattern = '<%sd'%length
00489 buff.write(struct.pack(pattern, *self.range_info.D))
00490 buff.write(_struct_9d.pack(*self.range_info.K))
00491 buff.write(_struct_9d.pack(*self.range_info.R))
00492 buff.write(_struct_12d.pack(*self.range_info.P))
00493 _x = self
00494 buff.write(_struct_6IB3I.pack(_x.range_info.binning_x, _x.range_info.binning_y, _x.range_info.roi.x_offset, _x.range_info.roi.y_offset, _x.range_info.roi.height, _x.range_info.roi.width, _x.range_info.roi.do_rectify, _x.left_image.header.seq, _x.left_image.header.stamp.secs, _x.left_image.header.stamp.nsecs))
00495 _x = self.left_image.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_2I.pack(_x.left_image.height, _x.left_image.width))
00503 _x = self.left_image.encoding
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_BI.pack(_x.left_image.is_bigendian, _x.left_image.step))
00511 _x = self.left_image.data
00512 length = len(_x)
00513
00514 if type(_x) in [list, tuple]:
00515 buff.write(struct.pack('<I%sB'%length, length, *_x))
00516 else:
00517 buff.write(struct.pack('<I%ss'%length, length, _x))
00518 _x = self
00519 buff.write(_struct_3I.pack(_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.header.stamp.nsecs))
00520 _x = self.right_image.header.frame_id
00521 length = len(_x)
00522 if python3 or type(_x) == unicode:
00523 _x = _x.encode('utf-8')
00524 length = len(_x)
00525 buff.write(struct.pack('<I%ss'%length, length, _x))
00526 _x = self
00527 buff.write(_struct_2I.pack(_x.right_image.height, _x.right_image.width))
00528 _x = self.right_image.encoding
00529 length = len(_x)
00530 if python3 or type(_x) == unicode:
00531 _x = _x.encode('utf-8')
00532 length = len(_x)
00533 buff.write(struct.pack('<I%ss'%length, length, _x))
00534 _x = self
00535 buff.write(_struct_BI.pack(_x.right_image.is_bigendian, _x.right_image.step))
00536 _x = self.right_image.data
00537 length = len(_x)
00538
00539 if type(_x) in [list, tuple]:
00540 buff.write(struct.pack('<I%sB'%length, length, *_x))
00541 else:
00542 buff.write(struct.pack('<I%ss'%length, length, _x))
00543 _x = self
00544 buff.write(_struct_3I.pack(_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs))
00545 _x = self.left_info.header.frame_id
00546 length = len(_x)
00547 if python3 or type(_x) == unicode:
00548 _x = _x.encode('utf-8')
00549 length = len(_x)
00550 buff.write(struct.pack('<I%ss'%length, length, _x))
00551 _x = self
00552 buff.write(_struct_2I.pack(_x.left_info.height, _x.left_info.width))
00553 _x = self.left_info.distortion_model
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 length = len(self.left_info.D)
00560 buff.write(_struct_I.pack(length))
00561 pattern = '<%sd'%length
00562 buff.write(struct.pack(pattern, *self.left_info.D))
00563 buff.write(_struct_9d.pack(*self.left_info.K))
00564 buff.write(_struct_9d.pack(*self.left_info.R))
00565 buff.write(_struct_12d.pack(*self.left_info.P))
00566 _x = self
00567 buff.write(_struct_6IB3I.pack(_x.left_info.binning_x, _x.left_info.binning_y, _x.left_info.roi.x_offset, _x.left_info.roi.y_offset, _x.left_info.roi.height, _x.left_info.roi.width, _x.left_info.roi.do_rectify, _x.right_info.header.seq, _x.right_info.header.stamp.secs, _x.right_info.header.stamp.nsecs))
00568 _x = self.right_info.header.frame_id
00569 length = len(_x)
00570 if python3 or type(_x) == unicode:
00571 _x = _x.encode('utf-8')
00572 length = len(_x)
00573 buff.write(struct.pack('<I%ss'%length, length, _x))
00574 _x = self
00575 buff.write(_struct_2I.pack(_x.right_info.height, _x.right_info.width))
00576 _x = self.right_info.distortion_model
00577 length = len(_x)
00578 if python3 or type(_x) == unicode:
00579 _x = _x.encode('utf-8')
00580 length = len(_x)
00581 buff.write(struct.pack('<I%ss'%length, length, _x))
00582 length = len(self.right_info.D)
00583 buff.write(_struct_I.pack(length))
00584 pattern = '<%sd'%length
00585 buff.write(struct.pack(pattern, *self.right_info.D))
00586 buff.write(_struct_9d.pack(*self.right_info.K))
00587 buff.write(_struct_9d.pack(*self.right_info.R))
00588 buff.write(_struct_12d.pack(*self.right_info.P))
00589 _x = self
00590 buff.write(_struct_6IB3I.pack(_x.right_info.binning_x, _x.right_info.binning_y, _x.right_info.roi.x_offset, _x.right_info.roi.y_offset, _x.right_info.roi.height, _x.right_info.roi.width, _x.right_info.roi.do_rectify, _x.pixel_indices.header.seq, _x.pixel_indices.header.stamp.secs, _x.pixel_indices.header.stamp.nsecs))
00591 _x = self.pixel_indices.header.frame_id
00592 length = len(_x)
00593 if python3 or type(_x) == unicode:
00594 _x = _x.encode('utf-8')
00595 length = len(_x)
00596 buff.write(struct.pack('<I%ss'%length, length, _x))
00597 length = len(self.pixel_indices.indices)
00598 buff.write(_struct_I.pack(length))
00599 pattern = '<%si'%length
00600 buff.write(struct.pack(pattern, *self.pixel_indices.indices))
00601 _x = self
00602 buff.write(_struct_3I.pack(_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
00603 _x = self.point_cloud.header.frame_id
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 _x = self
00610 buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
00611 length = len(self.point_cloud.fields)
00612 buff.write(_struct_I.pack(length))
00613 for val1 in self.point_cloud.fields:
00614 _x = val1.name
00615 length = len(_x)
00616 if python3 or type(_x) == unicode:
00617 _x = _x.encode('utf-8')
00618 length = len(_x)
00619 buff.write(struct.pack('<I%ss'%length, length, _x))
00620 _x = val1
00621 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00622 _x = self
00623 buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
00624 _x = self.point_cloud.data
00625 length = len(_x)
00626
00627 if type(_x) in [list, tuple]:
00628 buff.write(struct.pack('<I%sB'%length, length, *_x))
00629 else:
00630 buff.write(struct.pack('<I%ss'%length, length, _x))
00631 buff.write(_struct_B.pack(self.point_cloud.is_dense))
00632 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00633 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00634
00635 def deserialize(self, str):
00636 """
00637 unpack serialized message in str into this message instance
00638 :param str: byte array of serialized message, ``str``
00639 """
00640 try:
00641 if self.header is None:
00642 self.header = std_msgs.msg.Header()
00643 if self.intensity is None:
00644 self.intensity = sensor_msgs.msg.Image()
00645 if self.confidence is None:
00646 self.confidence = sensor_msgs.msg.Image()
00647 if self.depth is None:
00648 self.depth = sensor_msgs.msg.Image()
00649 if self.depth16 is None:
00650 self.depth16 = sensor_msgs.msg.Image()
00651 if self.range_info is None:
00652 self.range_info = sensor_msgs.msg.CameraInfo()
00653 if self.left_image is None:
00654 self.left_image = sensor_msgs.msg.Image()
00655 if self.right_image is None:
00656 self.right_image = sensor_msgs.msg.Image()
00657 if self.left_info is None:
00658 self.left_info = sensor_msgs.msg.CameraInfo()
00659 if self.right_info is None:
00660 self.right_info = sensor_msgs.msg.CameraInfo()
00661 if self.pixel_indices is None:
00662 self.pixel_indices = cr_capture.msg.PixelIndices()
00663 if self.point_cloud is None:
00664 self.point_cloud = sensor_msgs.msg.PointCloud2()
00665 end = 0
00666 _x = self
00667 start = end
00668 end += 12
00669 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00670 start = end
00671 end += 4
00672 (length,) = _struct_I.unpack(str[start:end])
00673 start = end
00674 end += length
00675 if python3:
00676 self.header.frame_id = str[start:end].decode('utf-8')
00677 else:
00678 self.header.frame_id = str[start:end]
00679 _x = self
00680 start = end
00681 end += 12
00682 (_x.intensity.header.seq, _x.intensity.header.stamp.secs, _x.intensity.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00683 start = end
00684 end += 4
00685 (length,) = _struct_I.unpack(str[start:end])
00686 start = end
00687 end += length
00688 if python3:
00689 self.intensity.header.frame_id = str[start:end].decode('utf-8')
00690 else:
00691 self.intensity.header.frame_id = str[start:end]
00692 _x = self
00693 start = end
00694 end += 8
00695 (_x.intensity.height, _x.intensity.width,) = _struct_2I.unpack(str[start:end])
00696 start = end
00697 end += 4
00698 (length,) = _struct_I.unpack(str[start:end])
00699 start = end
00700 end += length
00701 if python3:
00702 self.intensity.encoding = str[start:end].decode('utf-8')
00703 else:
00704 self.intensity.encoding = str[start:end]
00705 _x = self
00706 start = end
00707 end += 5
00708 (_x.intensity.is_bigendian, _x.intensity.step,) = _struct_BI.unpack(str[start:end])
00709 start = end
00710 end += 4
00711 (length,) = _struct_I.unpack(str[start:end])
00712 start = end
00713 end += length
00714 self.intensity.data = str[start:end]
00715 _x = self
00716 start = end
00717 end += 12
00718 (_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00719 start = end
00720 end += 4
00721 (length,) = _struct_I.unpack(str[start:end])
00722 start = end
00723 end += length
00724 if python3:
00725 self.confidence.header.frame_id = str[start:end].decode('utf-8')
00726 else:
00727 self.confidence.header.frame_id = str[start:end]
00728 _x = self
00729 start = end
00730 end += 8
00731 (_x.confidence.height, _x.confidence.width,) = _struct_2I.unpack(str[start:end])
00732 start = end
00733 end += 4
00734 (length,) = _struct_I.unpack(str[start:end])
00735 start = end
00736 end += length
00737 if python3:
00738 self.confidence.encoding = str[start:end].decode('utf-8')
00739 else:
00740 self.confidence.encoding = str[start:end]
00741 _x = self
00742 start = end
00743 end += 5
00744 (_x.confidence.is_bigendian, _x.confidence.step,) = _struct_BI.unpack(str[start:end])
00745 start = end
00746 end += 4
00747 (length,) = _struct_I.unpack(str[start:end])
00748 start = end
00749 end += length
00750 self.confidence.data = str[start:end]
00751 _x = self
00752 start = end
00753 end += 12
00754 (_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 start = end
00759 end += length
00760 if python3:
00761 self.depth.header.frame_id = str[start:end].decode('utf-8')
00762 else:
00763 self.depth.header.frame_id = str[start:end]
00764 _x = self
00765 start = end
00766 end += 8
00767 (_x.depth.height, _x.depth.width,) = _struct_2I.unpack(str[start:end])
00768 start = end
00769 end += 4
00770 (length,) = _struct_I.unpack(str[start:end])
00771 start = end
00772 end += length
00773 if python3:
00774 self.depth.encoding = str[start:end].decode('utf-8')
00775 else:
00776 self.depth.encoding = str[start:end]
00777 _x = self
00778 start = end
00779 end += 5
00780 (_x.depth.is_bigendian, _x.depth.step,) = _struct_BI.unpack(str[start:end])
00781 start = end
00782 end += 4
00783 (length,) = _struct_I.unpack(str[start:end])
00784 start = end
00785 end += length
00786 self.depth.data = str[start:end]
00787 _x = self
00788 start = end
00789 end += 12
00790 (_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00791 start = end
00792 end += 4
00793 (length,) = _struct_I.unpack(str[start:end])
00794 start = end
00795 end += length
00796 if python3:
00797 self.depth16.header.frame_id = str[start:end].decode('utf-8')
00798 else:
00799 self.depth16.header.frame_id = str[start:end]
00800 _x = self
00801 start = end
00802 end += 8
00803 (_x.depth16.height, _x.depth16.width,) = _struct_2I.unpack(str[start:end])
00804 start = end
00805 end += 4
00806 (length,) = _struct_I.unpack(str[start:end])
00807 start = end
00808 end += length
00809 if python3:
00810 self.depth16.encoding = str[start:end].decode('utf-8')
00811 else:
00812 self.depth16.encoding = str[start:end]
00813 _x = self
00814 start = end
00815 end += 5
00816 (_x.depth16.is_bigendian, _x.depth16.step,) = _struct_BI.unpack(str[start:end])
00817 start = end
00818 end += 4
00819 (length,) = _struct_I.unpack(str[start:end])
00820 start = end
00821 end += length
00822 self.depth16.data = str[start:end]
00823 _x = self
00824 start = end
00825 end += 12
00826 (_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00827 start = end
00828 end += 4
00829 (length,) = _struct_I.unpack(str[start:end])
00830 start = end
00831 end += length
00832 if python3:
00833 self.range_info.header.frame_id = str[start:end].decode('utf-8')
00834 else:
00835 self.range_info.header.frame_id = str[start:end]
00836 _x = self
00837 start = end
00838 end += 8
00839 (_x.range_info.height, _x.range_info.width,) = _struct_2I.unpack(str[start:end])
00840 start = end
00841 end += 4
00842 (length,) = _struct_I.unpack(str[start:end])
00843 start = end
00844 end += length
00845 if python3:
00846 self.range_info.distortion_model = str[start:end].decode('utf-8')
00847 else:
00848 self.range_info.distortion_model = str[start:end]
00849 start = end
00850 end += 4
00851 (length,) = _struct_I.unpack(str[start:end])
00852 pattern = '<%sd'%length
00853 start = end
00854 end += struct.calcsize(pattern)
00855 self.range_info.D = struct.unpack(pattern, str[start:end])
00856 start = end
00857 end += 72
00858 self.range_info.K = _struct_9d.unpack(str[start:end])
00859 start = end
00860 end += 72
00861 self.range_info.R = _struct_9d.unpack(str[start:end])
00862 start = end
00863 end += 96
00864 self.range_info.P = _struct_12d.unpack(str[start:end])
00865 _x = self
00866 start = end
00867 end += 37
00868 (_x.range_info.binning_x, _x.range_info.binning_y, _x.range_info.roi.x_offset, _x.range_info.roi.y_offset, _x.range_info.roi.height, _x.range_info.roi.width, _x.range_info.roi.do_rectify, _x.left_image.header.seq, _x.left_image.header.stamp.secs, _x.left_image.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00869 self.range_info.roi.do_rectify = bool(self.range_info.roi.do_rectify)
00870 start = end
00871 end += 4
00872 (length,) = _struct_I.unpack(str[start:end])
00873 start = end
00874 end += length
00875 if python3:
00876 self.left_image.header.frame_id = str[start:end].decode('utf-8')
00877 else:
00878 self.left_image.header.frame_id = str[start:end]
00879 _x = self
00880 start = end
00881 end += 8
00882 (_x.left_image.height, _x.left_image.width,) = _struct_2I.unpack(str[start:end])
00883 start = end
00884 end += 4
00885 (length,) = _struct_I.unpack(str[start:end])
00886 start = end
00887 end += length
00888 if python3:
00889 self.left_image.encoding = str[start:end].decode('utf-8')
00890 else:
00891 self.left_image.encoding = str[start:end]
00892 _x = self
00893 start = end
00894 end += 5
00895 (_x.left_image.is_bigendian, _x.left_image.step,) = _struct_BI.unpack(str[start:end])
00896 start = end
00897 end += 4
00898 (length,) = _struct_I.unpack(str[start:end])
00899 start = end
00900 end += length
00901 self.left_image.data = str[start:end]
00902 _x = self
00903 start = end
00904 end += 12
00905 (_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00906 start = end
00907 end += 4
00908 (length,) = _struct_I.unpack(str[start:end])
00909 start = end
00910 end += length
00911 if python3:
00912 self.right_image.header.frame_id = str[start:end].decode('utf-8')
00913 else:
00914 self.right_image.header.frame_id = str[start:end]
00915 _x = self
00916 start = end
00917 end += 8
00918 (_x.right_image.height, _x.right_image.width,) = _struct_2I.unpack(str[start:end])
00919 start = end
00920 end += 4
00921 (length,) = _struct_I.unpack(str[start:end])
00922 start = end
00923 end += length
00924 if python3:
00925 self.right_image.encoding = str[start:end].decode('utf-8')
00926 else:
00927 self.right_image.encoding = str[start:end]
00928 _x = self
00929 start = end
00930 end += 5
00931 (_x.right_image.is_bigendian, _x.right_image.step,) = _struct_BI.unpack(str[start:end])
00932 start = end
00933 end += 4
00934 (length,) = _struct_I.unpack(str[start:end])
00935 start = end
00936 end += length
00937 self.right_image.data = str[start:end]
00938 _x = self
00939 start = end
00940 end += 12
00941 (_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00942 start = end
00943 end += 4
00944 (length,) = _struct_I.unpack(str[start:end])
00945 start = end
00946 end += length
00947 if python3:
00948 self.left_info.header.frame_id = str[start:end].decode('utf-8')
00949 else:
00950 self.left_info.header.frame_id = str[start:end]
00951 _x = self
00952 start = end
00953 end += 8
00954 (_x.left_info.height, _x.left_info.width,) = _struct_2I.unpack(str[start:end])
00955 start = end
00956 end += 4
00957 (length,) = _struct_I.unpack(str[start:end])
00958 start = end
00959 end += length
00960 if python3:
00961 self.left_info.distortion_model = str[start:end].decode('utf-8')
00962 else:
00963 self.left_info.distortion_model = str[start:end]
00964 start = end
00965 end += 4
00966 (length,) = _struct_I.unpack(str[start:end])
00967 pattern = '<%sd'%length
00968 start = end
00969 end += struct.calcsize(pattern)
00970 self.left_info.D = struct.unpack(pattern, str[start:end])
00971 start = end
00972 end += 72
00973 self.left_info.K = _struct_9d.unpack(str[start:end])
00974 start = end
00975 end += 72
00976 self.left_info.R = _struct_9d.unpack(str[start:end])
00977 start = end
00978 end += 96
00979 self.left_info.P = _struct_12d.unpack(str[start:end])
00980 _x = self
00981 start = end
00982 end += 37
00983 (_x.left_info.binning_x, _x.left_info.binning_y, _x.left_info.roi.x_offset, _x.left_info.roi.y_offset, _x.left_info.roi.height, _x.left_info.roi.width, _x.left_info.roi.do_rectify, _x.right_info.header.seq, _x.right_info.header.stamp.secs, _x.right_info.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00984 self.left_info.roi.do_rectify = bool(self.left_info.roi.do_rectify)
00985 start = end
00986 end += 4
00987 (length,) = _struct_I.unpack(str[start:end])
00988 start = end
00989 end += length
00990 if python3:
00991 self.right_info.header.frame_id = str[start:end].decode('utf-8')
00992 else:
00993 self.right_info.header.frame_id = str[start:end]
00994 _x = self
00995 start = end
00996 end += 8
00997 (_x.right_info.height, _x.right_info.width,) = _struct_2I.unpack(str[start:end])
00998 start = end
00999 end += 4
01000 (length,) = _struct_I.unpack(str[start:end])
01001 start = end
01002 end += length
01003 if python3:
01004 self.right_info.distortion_model = str[start:end].decode('utf-8')
01005 else:
01006 self.right_info.distortion_model = str[start:end]
01007 start = end
01008 end += 4
01009 (length,) = _struct_I.unpack(str[start:end])
01010 pattern = '<%sd'%length
01011 start = end
01012 end += struct.calcsize(pattern)
01013 self.right_info.D = struct.unpack(pattern, str[start:end])
01014 start = end
01015 end += 72
01016 self.right_info.K = _struct_9d.unpack(str[start:end])
01017 start = end
01018 end += 72
01019 self.right_info.R = _struct_9d.unpack(str[start:end])
01020 start = end
01021 end += 96
01022 self.right_info.P = _struct_12d.unpack(str[start:end])
01023 _x = self
01024 start = end
01025 end += 37
01026 (_x.right_info.binning_x, _x.right_info.binning_y, _x.right_info.roi.x_offset, _x.right_info.roi.y_offset, _x.right_info.roi.height, _x.right_info.roi.width, _x.right_info.roi.do_rectify, _x.pixel_indices.header.seq, _x.pixel_indices.header.stamp.secs, _x.pixel_indices.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01027 self.right_info.roi.do_rectify = bool(self.right_info.roi.do_rectify)
01028 start = end
01029 end += 4
01030 (length,) = _struct_I.unpack(str[start:end])
01031 start = end
01032 end += length
01033 if python3:
01034 self.pixel_indices.header.frame_id = str[start:end].decode('utf-8')
01035 else:
01036 self.pixel_indices.header.frame_id = str[start:end]
01037 start = end
01038 end += 4
01039 (length,) = _struct_I.unpack(str[start:end])
01040 pattern = '<%si'%length
01041 start = end
01042 end += struct.calcsize(pattern)
01043 self.pixel_indices.indices = struct.unpack(pattern, str[start:end])
01044 _x = self
01045 start = end
01046 end += 12
01047 (_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01048 start = end
01049 end += 4
01050 (length,) = _struct_I.unpack(str[start:end])
01051 start = end
01052 end += length
01053 if python3:
01054 self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01055 else:
01056 self.point_cloud.header.frame_id = str[start:end]
01057 _x = self
01058 start = end
01059 end += 8
01060 (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01061 start = end
01062 end += 4
01063 (length,) = _struct_I.unpack(str[start:end])
01064 self.point_cloud.fields = []
01065 for i in range(0, length):
01066 val1 = sensor_msgs.msg.PointField()
01067 start = end
01068 end += 4
01069 (length,) = _struct_I.unpack(str[start:end])
01070 start = end
01071 end += length
01072 if python3:
01073 val1.name = str[start:end].decode('utf-8')
01074 else:
01075 val1.name = str[start:end]
01076 _x = val1
01077 start = end
01078 end += 9
01079 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01080 self.point_cloud.fields.append(val1)
01081 _x = self
01082 start = end
01083 end += 9
01084 (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01085 self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
01086 start = end
01087 end += 4
01088 (length,) = _struct_I.unpack(str[start:end])
01089 start = end
01090 end += length
01091 self.point_cloud.data = str[start:end]
01092 start = end
01093 end += 1
01094 (self.point_cloud.is_dense,) = _struct_B.unpack(str[start:end])
01095 self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
01096 return self
01097 except struct.error as e:
01098 raise genpy.DeserializationError(e)
01099
01100
01101 def serialize_numpy(self, buff, numpy):
01102 """
01103 serialize message with numpy array types into buffer
01104 :param buff: buffer, ``StringIO``
01105 :param numpy: numpy python module
01106 """
01107 try:
01108 _x = self
01109 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
01110 _x = self.header.frame_id
01111 length = len(_x)
01112 if python3 or type(_x) == unicode:
01113 _x = _x.encode('utf-8')
01114 length = len(_x)
01115 buff.write(struct.pack('<I%ss'%length, length, _x))
01116 _x = self
01117 buff.write(_struct_3I.pack(_x.intensity.header.seq, _x.intensity.header.stamp.secs, _x.intensity.header.stamp.nsecs))
01118 _x = self.intensity.header.frame_id
01119 length = len(_x)
01120 if python3 or type(_x) == unicode:
01121 _x = _x.encode('utf-8')
01122 length = len(_x)
01123 buff.write(struct.pack('<I%ss'%length, length, _x))
01124 _x = self
01125 buff.write(_struct_2I.pack(_x.intensity.height, _x.intensity.width))
01126 _x = self.intensity.encoding
01127 length = len(_x)
01128 if python3 or type(_x) == unicode:
01129 _x = _x.encode('utf-8')
01130 length = len(_x)
01131 buff.write(struct.pack('<I%ss'%length, length, _x))
01132 _x = self
01133 buff.write(_struct_BI.pack(_x.intensity.is_bigendian, _x.intensity.step))
01134 _x = self.intensity.data
01135 length = len(_x)
01136
01137 if type(_x) in [list, tuple]:
01138 buff.write(struct.pack('<I%sB'%length, length, *_x))
01139 else:
01140 buff.write(struct.pack('<I%ss'%length, length, _x))
01141 _x = self
01142 buff.write(_struct_3I.pack(_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs))
01143 _x = self.confidence.header.frame_id
01144 length = len(_x)
01145 if python3 or type(_x) == unicode:
01146 _x = _x.encode('utf-8')
01147 length = len(_x)
01148 buff.write(struct.pack('<I%ss'%length, length, _x))
01149 _x = self
01150 buff.write(_struct_2I.pack(_x.confidence.height, _x.confidence.width))
01151 _x = self.confidence.encoding
01152 length = len(_x)
01153 if python3 or type(_x) == unicode:
01154 _x = _x.encode('utf-8')
01155 length = len(_x)
01156 buff.write(struct.pack('<I%ss'%length, length, _x))
01157 _x = self
01158 buff.write(_struct_BI.pack(_x.confidence.is_bigendian, _x.confidence.step))
01159 _x = self.confidence.data
01160 length = len(_x)
01161
01162 if type(_x) in [list, tuple]:
01163 buff.write(struct.pack('<I%sB'%length, length, *_x))
01164 else:
01165 buff.write(struct.pack('<I%ss'%length, length, _x))
01166 _x = self
01167 buff.write(_struct_3I.pack(_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs))
01168 _x = self.depth.header.frame_id
01169 length = len(_x)
01170 if python3 or type(_x) == unicode:
01171 _x = _x.encode('utf-8')
01172 length = len(_x)
01173 buff.write(struct.pack('<I%ss'%length, length, _x))
01174 _x = self
01175 buff.write(_struct_2I.pack(_x.depth.height, _x.depth.width))
01176 _x = self.depth.encoding
01177 length = len(_x)
01178 if python3 or type(_x) == unicode:
01179 _x = _x.encode('utf-8')
01180 length = len(_x)
01181 buff.write(struct.pack('<I%ss'%length, length, _x))
01182 _x = self
01183 buff.write(_struct_BI.pack(_x.depth.is_bigendian, _x.depth.step))
01184 _x = self.depth.data
01185 length = len(_x)
01186
01187 if type(_x) in [list, tuple]:
01188 buff.write(struct.pack('<I%sB'%length, length, *_x))
01189 else:
01190 buff.write(struct.pack('<I%ss'%length, length, _x))
01191 _x = self
01192 buff.write(_struct_3I.pack(_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs))
01193 _x = self.depth16.header.frame_id
01194 length = len(_x)
01195 if python3 or type(_x) == unicode:
01196 _x = _x.encode('utf-8')
01197 length = len(_x)
01198 buff.write(struct.pack('<I%ss'%length, length, _x))
01199 _x = self
01200 buff.write(_struct_2I.pack(_x.depth16.height, _x.depth16.width))
01201 _x = self.depth16.encoding
01202 length = len(_x)
01203 if python3 or type(_x) == unicode:
01204 _x = _x.encode('utf-8')
01205 length = len(_x)
01206 buff.write(struct.pack('<I%ss'%length, length, _x))
01207 _x = self
01208 buff.write(_struct_BI.pack(_x.depth16.is_bigendian, _x.depth16.step))
01209 _x = self.depth16.data
01210 length = len(_x)
01211
01212 if type(_x) in [list, tuple]:
01213 buff.write(struct.pack('<I%sB'%length, length, *_x))
01214 else:
01215 buff.write(struct.pack('<I%ss'%length, length, _x))
01216 _x = self
01217 buff.write(_struct_3I.pack(_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs))
01218 _x = self.range_info.header.frame_id
01219 length = len(_x)
01220 if python3 or type(_x) == unicode:
01221 _x = _x.encode('utf-8')
01222 length = len(_x)
01223 buff.write(struct.pack('<I%ss'%length, length, _x))
01224 _x = self
01225 buff.write(_struct_2I.pack(_x.range_info.height, _x.range_info.width))
01226 _x = self.range_info.distortion_model
01227 length = len(_x)
01228 if python3 or type(_x) == unicode:
01229 _x = _x.encode('utf-8')
01230 length = len(_x)
01231 buff.write(struct.pack('<I%ss'%length, length, _x))
01232 length = len(self.range_info.D)
01233 buff.write(_struct_I.pack(length))
01234 pattern = '<%sd'%length
01235 buff.write(self.range_info.D.tostring())
01236 buff.write(self.range_info.K.tostring())
01237 buff.write(self.range_info.R.tostring())
01238 buff.write(self.range_info.P.tostring())
01239 _x = self
01240 buff.write(_struct_6IB3I.pack(_x.range_info.binning_x, _x.range_info.binning_y, _x.range_info.roi.x_offset, _x.range_info.roi.y_offset, _x.range_info.roi.height, _x.range_info.roi.width, _x.range_info.roi.do_rectify, _x.left_image.header.seq, _x.left_image.header.stamp.secs, _x.left_image.header.stamp.nsecs))
01241 _x = self.left_image.header.frame_id
01242 length = len(_x)
01243 if python3 or type(_x) == unicode:
01244 _x = _x.encode('utf-8')
01245 length = len(_x)
01246 buff.write(struct.pack('<I%ss'%length, length, _x))
01247 _x = self
01248 buff.write(_struct_2I.pack(_x.left_image.height, _x.left_image.width))
01249 _x = self.left_image.encoding
01250 length = len(_x)
01251 if python3 or type(_x) == unicode:
01252 _x = _x.encode('utf-8')
01253 length = len(_x)
01254 buff.write(struct.pack('<I%ss'%length, length, _x))
01255 _x = self
01256 buff.write(_struct_BI.pack(_x.left_image.is_bigendian, _x.left_image.step))
01257 _x = self.left_image.data
01258 length = len(_x)
01259
01260 if type(_x) in [list, tuple]:
01261 buff.write(struct.pack('<I%sB'%length, length, *_x))
01262 else:
01263 buff.write(struct.pack('<I%ss'%length, length, _x))
01264 _x = self
01265 buff.write(_struct_3I.pack(_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.header.stamp.nsecs))
01266 _x = self.right_image.header.frame_id
01267 length = len(_x)
01268 if python3 or type(_x) == unicode:
01269 _x = _x.encode('utf-8')
01270 length = len(_x)
01271 buff.write(struct.pack('<I%ss'%length, length, _x))
01272 _x = self
01273 buff.write(_struct_2I.pack(_x.right_image.height, _x.right_image.width))
01274 _x = self.right_image.encoding
01275 length = len(_x)
01276 if python3 or type(_x) == unicode:
01277 _x = _x.encode('utf-8')
01278 length = len(_x)
01279 buff.write(struct.pack('<I%ss'%length, length, _x))
01280 _x = self
01281 buff.write(_struct_BI.pack(_x.right_image.is_bigendian, _x.right_image.step))
01282 _x = self.right_image.data
01283 length = len(_x)
01284
01285 if type(_x) in [list, tuple]:
01286 buff.write(struct.pack('<I%sB'%length, length, *_x))
01287 else:
01288 buff.write(struct.pack('<I%ss'%length, length, _x))
01289 _x = self
01290 buff.write(_struct_3I.pack(_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs))
01291 _x = self.left_info.header.frame_id
01292 length = len(_x)
01293 if python3 or type(_x) == unicode:
01294 _x = _x.encode('utf-8')
01295 length = len(_x)
01296 buff.write(struct.pack('<I%ss'%length, length, _x))
01297 _x = self
01298 buff.write(_struct_2I.pack(_x.left_info.height, _x.left_info.width))
01299 _x = self.left_info.distortion_model
01300 length = len(_x)
01301 if python3 or type(_x) == unicode:
01302 _x = _x.encode('utf-8')
01303 length = len(_x)
01304 buff.write(struct.pack('<I%ss'%length, length, _x))
01305 length = len(self.left_info.D)
01306 buff.write(_struct_I.pack(length))
01307 pattern = '<%sd'%length
01308 buff.write(self.left_info.D.tostring())
01309 buff.write(self.left_info.K.tostring())
01310 buff.write(self.left_info.R.tostring())
01311 buff.write(self.left_info.P.tostring())
01312 _x = self
01313 buff.write(_struct_6IB3I.pack(_x.left_info.binning_x, _x.left_info.binning_y, _x.left_info.roi.x_offset, _x.left_info.roi.y_offset, _x.left_info.roi.height, _x.left_info.roi.width, _x.left_info.roi.do_rectify, _x.right_info.header.seq, _x.right_info.header.stamp.secs, _x.right_info.header.stamp.nsecs))
01314 _x = self.right_info.header.frame_id
01315 length = len(_x)
01316 if python3 or type(_x) == unicode:
01317 _x = _x.encode('utf-8')
01318 length = len(_x)
01319 buff.write(struct.pack('<I%ss'%length, length, _x))
01320 _x = self
01321 buff.write(_struct_2I.pack(_x.right_info.height, _x.right_info.width))
01322 _x = self.right_info.distortion_model
01323 length = len(_x)
01324 if python3 or type(_x) == unicode:
01325 _x = _x.encode('utf-8')
01326 length = len(_x)
01327 buff.write(struct.pack('<I%ss'%length, length, _x))
01328 length = len(self.right_info.D)
01329 buff.write(_struct_I.pack(length))
01330 pattern = '<%sd'%length
01331 buff.write(self.right_info.D.tostring())
01332 buff.write(self.right_info.K.tostring())
01333 buff.write(self.right_info.R.tostring())
01334 buff.write(self.right_info.P.tostring())
01335 _x = self
01336 buff.write(_struct_6IB3I.pack(_x.right_info.binning_x, _x.right_info.binning_y, _x.right_info.roi.x_offset, _x.right_info.roi.y_offset, _x.right_info.roi.height, _x.right_info.roi.width, _x.right_info.roi.do_rectify, _x.pixel_indices.header.seq, _x.pixel_indices.header.stamp.secs, _x.pixel_indices.header.stamp.nsecs))
01337 _x = self.pixel_indices.header.frame_id
01338 length = len(_x)
01339 if python3 or type(_x) == unicode:
01340 _x = _x.encode('utf-8')
01341 length = len(_x)
01342 buff.write(struct.pack('<I%ss'%length, length, _x))
01343 length = len(self.pixel_indices.indices)
01344 buff.write(_struct_I.pack(length))
01345 pattern = '<%si'%length
01346 buff.write(self.pixel_indices.indices.tostring())
01347 _x = self
01348 buff.write(_struct_3I.pack(_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
01349 _x = self.point_cloud.header.frame_id
01350 length = len(_x)
01351 if python3 or type(_x) == unicode:
01352 _x = _x.encode('utf-8')
01353 length = len(_x)
01354 buff.write(struct.pack('<I%ss'%length, length, _x))
01355 _x = self
01356 buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
01357 length = len(self.point_cloud.fields)
01358 buff.write(_struct_I.pack(length))
01359 for val1 in self.point_cloud.fields:
01360 _x = val1.name
01361 length = len(_x)
01362 if python3 or type(_x) == unicode:
01363 _x = _x.encode('utf-8')
01364 length = len(_x)
01365 buff.write(struct.pack('<I%ss'%length, length, _x))
01366 _x = val1
01367 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01368 _x = self
01369 buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
01370 _x = self.point_cloud.data
01371 length = len(_x)
01372
01373 if type(_x) in [list, tuple]:
01374 buff.write(struct.pack('<I%sB'%length, length, *_x))
01375 else:
01376 buff.write(struct.pack('<I%ss'%length, length, _x))
01377 buff.write(_struct_B.pack(self.point_cloud.is_dense))
01378 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
01379 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
01380
01381 def deserialize_numpy(self, str, numpy):
01382 """
01383 unpack serialized message in str into this message instance using numpy for array types
01384 :param str: byte array of serialized message, ``str``
01385 :param numpy: numpy python module
01386 """
01387 try:
01388 if self.header is None:
01389 self.header = std_msgs.msg.Header()
01390 if self.intensity is None:
01391 self.intensity = sensor_msgs.msg.Image()
01392 if self.confidence is None:
01393 self.confidence = sensor_msgs.msg.Image()
01394 if self.depth is None:
01395 self.depth = sensor_msgs.msg.Image()
01396 if self.depth16 is None:
01397 self.depth16 = sensor_msgs.msg.Image()
01398 if self.range_info is None:
01399 self.range_info = sensor_msgs.msg.CameraInfo()
01400 if self.left_image is None:
01401 self.left_image = sensor_msgs.msg.Image()
01402 if self.right_image is None:
01403 self.right_image = sensor_msgs.msg.Image()
01404 if self.left_info is None:
01405 self.left_info = sensor_msgs.msg.CameraInfo()
01406 if self.right_info is None:
01407 self.right_info = sensor_msgs.msg.CameraInfo()
01408 if self.pixel_indices is None:
01409 self.pixel_indices = cr_capture.msg.PixelIndices()
01410 if self.point_cloud is None:
01411 self.point_cloud = sensor_msgs.msg.PointCloud2()
01412 end = 0
01413 _x = self
01414 start = end
01415 end += 12
01416 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01417 start = end
01418 end += 4
01419 (length,) = _struct_I.unpack(str[start:end])
01420 start = end
01421 end += length
01422 if python3:
01423 self.header.frame_id = str[start:end].decode('utf-8')
01424 else:
01425 self.header.frame_id = str[start:end]
01426 _x = self
01427 start = end
01428 end += 12
01429 (_x.intensity.header.seq, _x.intensity.header.stamp.secs, _x.intensity.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01430 start = end
01431 end += 4
01432 (length,) = _struct_I.unpack(str[start:end])
01433 start = end
01434 end += length
01435 if python3:
01436 self.intensity.header.frame_id = str[start:end].decode('utf-8')
01437 else:
01438 self.intensity.header.frame_id = str[start:end]
01439 _x = self
01440 start = end
01441 end += 8
01442 (_x.intensity.height, _x.intensity.width,) = _struct_2I.unpack(str[start:end])
01443 start = end
01444 end += 4
01445 (length,) = _struct_I.unpack(str[start:end])
01446 start = end
01447 end += length
01448 if python3:
01449 self.intensity.encoding = str[start:end].decode('utf-8')
01450 else:
01451 self.intensity.encoding = str[start:end]
01452 _x = self
01453 start = end
01454 end += 5
01455 (_x.intensity.is_bigendian, _x.intensity.step,) = _struct_BI.unpack(str[start:end])
01456 start = end
01457 end += 4
01458 (length,) = _struct_I.unpack(str[start:end])
01459 start = end
01460 end += length
01461 self.intensity.data = str[start:end]
01462 _x = self
01463 start = end
01464 end += 12
01465 (_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01466 start = end
01467 end += 4
01468 (length,) = _struct_I.unpack(str[start:end])
01469 start = end
01470 end += length
01471 if python3:
01472 self.confidence.header.frame_id = str[start:end].decode('utf-8')
01473 else:
01474 self.confidence.header.frame_id = str[start:end]
01475 _x = self
01476 start = end
01477 end += 8
01478 (_x.confidence.height, _x.confidence.width,) = _struct_2I.unpack(str[start:end])
01479 start = end
01480 end += 4
01481 (length,) = _struct_I.unpack(str[start:end])
01482 start = end
01483 end += length
01484 if python3:
01485 self.confidence.encoding = str[start:end].decode('utf-8')
01486 else:
01487 self.confidence.encoding = str[start:end]
01488 _x = self
01489 start = end
01490 end += 5
01491 (_x.confidence.is_bigendian, _x.confidence.step,) = _struct_BI.unpack(str[start:end])
01492 start = end
01493 end += 4
01494 (length,) = _struct_I.unpack(str[start:end])
01495 start = end
01496 end += length
01497 self.confidence.data = str[start:end]
01498 _x = self
01499 start = end
01500 end += 12
01501 (_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01502 start = end
01503 end += 4
01504 (length,) = _struct_I.unpack(str[start:end])
01505 start = end
01506 end += length
01507 if python3:
01508 self.depth.header.frame_id = str[start:end].decode('utf-8')
01509 else:
01510 self.depth.header.frame_id = str[start:end]
01511 _x = self
01512 start = end
01513 end += 8
01514 (_x.depth.height, _x.depth.width,) = _struct_2I.unpack(str[start:end])
01515 start = end
01516 end += 4
01517 (length,) = _struct_I.unpack(str[start:end])
01518 start = end
01519 end += length
01520 if python3:
01521 self.depth.encoding = str[start:end].decode('utf-8')
01522 else:
01523 self.depth.encoding = str[start:end]
01524 _x = self
01525 start = end
01526 end += 5
01527 (_x.depth.is_bigendian, _x.depth.step,) = _struct_BI.unpack(str[start:end])
01528 start = end
01529 end += 4
01530 (length,) = _struct_I.unpack(str[start:end])
01531 start = end
01532 end += length
01533 self.depth.data = str[start:end]
01534 _x = self
01535 start = end
01536 end += 12
01537 (_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01538 start = end
01539 end += 4
01540 (length,) = _struct_I.unpack(str[start:end])
01541 start = end
01542 end += length
01543 if python3:
01544 self.depth16.header.frame_id = str[start:end].decode('utf-8')
01545 else:
01546 self.depth16.header.frame_id = str[start:end]
01547 _x = self
01548 start = end
01549 end += 8
01550 (_x.depth16.height, _x.depth16.width,) = _struct_2I.unpack(str[start:end])
01551 start = end
01552 end += 4
01553 (length,) = _struct_I.unpack(str[start:end])
01554 start = end
01555 end += length
01556 if python3:
01557 self.depth16.encoding = str[start:end].decode('utf-8')
01558 else:
01559 self.depth16.encoding = str[start:end]
01560 _x = self
01561 start = end
01562 end += 5
01563 (_x.depth16.is_bigendian, _x.depth16.step,) = _struct_BI.unpack(str[start:end])
01564 start = end
01565 end += 4
01566 (length,) = _struct_I.unpack(str[start:end])
01567 start = end
01568 end += length
01569 self.depth16.data = str[start:end]
01570 _x = self
01571 start = end
01572 end += 12
01573 (_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01574 start = end
01575 end += 4
01576 (length,) = _struct_I.unpack(str[start:end])
01577 start = end
01578 end += length
01579 if python3:
01580 self.range_info.header.frame_id = str[start:end].decode('utf-8')
01581 else:
01582 self.range_info.header.frame_id = str[start:end]
01583 _x = self
01584 start = end
01585 end += 8
01586 (_x.range_info.height, _x.range_info.width,) = _struct_2I.unpack(str[start:end])
01587 start = end
01588 end += 4
01589 (length,) = _struct_I.unpack(str[start:end])
01590 start = end
01591 end += length
01592 if python3:
01593 self.range_info.distortion_model = str[start:end].decode('utf-8')
01594 else:
01595 self.range_info.distortion_model = str[start:end]
01596 start = end
01597 end += 4
01598 (length,) = _struct_I.unpack(str[start:end])
01599 pattern = '<%sd'%length
01600 start = end
01601 end += struct.calcsize(pattern)
01602 self.range_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01603 start = end
01604 end += 72
01605 self.range_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01606 start = end
01607 end += 72
01608 self.range_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01609 start = end
01610 end += 96
01611 self.range_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01612 _x = self
01613 start = end
01614 end += 37
01615 (_x.range_info.binning_x, _x.range_info.binning_y, _x.range_info.roi.x_offset, _x.range_info.roi.y_offset, _x.range_info.roi.height, _x.range_info.roi.width, _x.range_info.roi.do_rectify, _x.left_image.header.seq, _x.left_image.header.stamp.secs, _x.left_image.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01616 self.range_info.roi.do_rectify = bool(self.range_info.roi.do_rectify)
01617 start = end
01618 end += 4
01619 (length,) = _struct_I.unpack(str[start:end])
01620 start = end
01621 end += length
01622 if python3:
01623 self.left_image.header.frame_id = str[start:end].decode('utf-8')
01624 else:
01625 self.left_image.header.frame_id = str[start:end]
01626 _x = self
01627 start = end
01628 end += 8
01629 (_x.left_image.height, _x.left_image.width,) = _struct_2I.unpack(str[start:end])
01630 start = end
01631 end += 4
01632 (length,) = _struct_I.unpack(str[start:end])
01633 start = end
01634 end += length
01635 if python3:
01636 self.left_image.encoding = str[start:end].decode('utf-8')
01637 else:
01638 self.left_image.encoding = str[start:end]
01639 _x = self
01640 start = end
01641 end += 5
01642 (_x.left_image.is_bigendian, _x.left_image.step,) = _struct_BI.unpack(str[start:end])
01643 start = end
01644 end += 4
01645 (length,) = _struct_I.unpack(str[start:end])
01646 start = end
01647 end += length
01648 self.left_image.data = str[start:end]
01649 _x = self
01650 start = end
01651 end += 12
01652 (_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01653 start = end
01654 end += 4
01655 (length,) = _struct_I.unpack(str[start:end])
01656 start = end
01657 end += length
01658 if python3:
01659 self.right_image.header.frame_id = str[start:end].decode('utf-8')
01660 else:
01661 self.right_image.header.frame_id = str[start:end]
01662 _x = self
01663 start = end
01664 end += 8
01665 (_x.right_image.height, _x.right_image.width,) = _struct_2I.unpack(str[start:end])
01666 start = end
01667 end += 4
01668 (length,) = _struct_I.unpack(str[start:end])
01669 start = end
01670 end += length
01671 if python3:
01672 self.right_image.encoding = str[start:end].decode('utf-8')
01673 else:
01674 self.right_image.encoding = str[start:end]
01675 _x = self
01676 start = end
01677 end += 5
01678 (_x.right_image.is_bigendian, _x.right_image.step,) = _struct_BI.unpack(str[start:end])
01679 start = end
01680 end += 4
01681 (length,) = _struct_I.unpack(str[start:end])
01682 start = end
01683 end += length
01684 self.right_image.data = str[start:end]
01685 _x = self
01686 start = end
01687 end += 12
01688 (_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01689 start = end
01690 end += 4
01691 (length,) = _struct_I.unpack(str[start:end])
01692 start = end
01693 end += length
01694 if python3:
01695 self.left_info.header.frame_id = str[start:end].decode('utf-8')
01696 else:
01697 self.left_info.header.frame_id = str[start:end]
01698 _x = self
01699 start = end
01700 end += 8
01701 (_x.left_info.height, _x.left_info.width,) = _struct_2I.unpack(str[start:end])
01702 start = end
01703 end += 4
01704 (length,) = _struct_I.unpack(str[start:end])
01705 start = end
01706 end += length
01707 if python3:
01708 self.left_info.distortion_model = str[start:end].decode('utf-8')
01709 else:
01710 self.left_info.distortion_model = str[start:end]
01711 start = end
01712 end += 4
01713 (length,) = _struct_I.unpack(str[start:end])
01714 pattern = '<%sd'%length
01715 start = end
01716 end += struct.calcsize(pattern)
01717 self.left_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01718 start = end
01719 end += 72
01720 self.left_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01721 start = end
01722 end += 72
01723 self.left_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01724 start = end
01725 end += 96
01726 self.left_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01727 _x = self
01728 start = end
01729 end += 37
01730 (_x.left_info.binning_x, _x.left_info.binning_y, _x.left_info.roi.x_offset, _x.left_info.roi.y_offset, _x.left_info.roi.height, _x.left_info.roi.width, _x.left_info.roi.do_rectify, _x.right_info.header.seq, _x.right_info.header.stamp.secs, _x.right_info.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01731 self.left_info.roi.do_rectify = bool(self.left_info.roi.do_rectify)
01732 start = end
01733 end += 4
01734 (length,) = _struct_I.unpack(str[start:end])
01735 start = end
01736 end += length
01737 if python3:
01738 self.right_info.header.frame_id = str[start:end].decode('utf-8')
01739 else:
01740 self.right_info.header.frame_id = str[start:end]
01741 _x = self
01742 start = end
01743 end += 8
01744 (_x.right_info.height, _x.right_info.width,) = _struct_2I.unpack(str[start:end])
01745 start = end
01746 end += 4
01747 (length,) = _struct_I.unpack(str[start:end])
01748 start = end
01749 end += length
01750 if python3:
01751 self.right_info.distortion_model = str[start:end].decode('utf-8')
01752 else:
01753 self.right_info.distortion_model = str[start:end]
01754 start = end
01755 end += 4
01756 (length,) = _struct_I.unpack(str[start:end])
01757 pattern = '<%sd'%length
01758 start = end
01759 end += struct.calcsize(pattern)
01760 self.right_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01761 start = end
01762 end += 72
01763 self.right_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01764 start = end
01765 end += 72
01766 self.right_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01767 start = end
01768 end += 96
01769 self.right_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01770 _x = self
01771 start = end
01772 end += 37
01773 (_x.right_info.binning_x, _x.right_info.binning_y, _x.right_info.roi.x_offset, _x.right_info.roi.y_offset, _x.right_info.roi.height, _x.right_info.roi.width, _x.right_info.roi.do_rectify, _x.pixel_indices.header.seq, _x.pixel_indices.header.stamp.secs, _x.pixel_indices.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01774 self.right_info.roi.do_rectify = bool(self.right_info.roi.do_rectify)
01775 start = end
01776 end += 4
01777 (length,) = _struct_I.unpack(str[start:end])
01778 start = end
01779 end += length
01780 if python3:
01781 self.pixel_indices.header.frame_id = str[start:end].decode('utf-8')
01782 else:
01783 self.pixel_indices.header.frame_id = str[start:end]
01784 start = end
01785 end += 4
01786 (length,) = _struct_I.unpack(str[start:end])
01787 pattern = '<%si'%length
01788 start = end
01789 end += struct.calcsize(pattern)
01790 self.pixel_indices.indices = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01791 _x = self
01792 start = end
01793 end += 12
01794 (_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01795 start = end
01796 end += 4
01797 (length,) = _struct_I.unpack(str[start:end])
01798 start = end
01799 end += length
01800 if python3:
01801 self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01802 else:
01803 self.point_cloud.header.frame_id = str[start:end]
01804 _x = self
01805 start = end
01806 end += 8
01807 (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01808 start = end
01809 end += 4
01810 (length,) = _struct_I.unpack(str[start:end])
01811 self.point_cloud.fields = []
01812 for i in range(0, length):
01813 val1 = sensor_msgs.msg.PointField()
01814 start = end
01815 end += 4
01816 (length,) = _struct_I.unpack(str[start:end])
01817 start = end
01818 end += length
01819 if python3:
01820 val1.name = str[start:end].decode('utf-8')
01821 else:
01822 val1.name = str[start:end]
01823 _x = val1
01824 start = end
01825 end += 9
01826 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01827 self.point_cloud.fields.append(val1)
01828 _x = self
01829 start = end
01830 end += 9
01831 (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01832 self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
01833 start = end
01834 end += 4
01835 (length,) = _struct_I.unpack(str[start:end])
01836 start = end
01837 end += length
01838 self.point_cloud.data = str[start:end]
01839 start = end
01840 end += 1
01841 (self.point_cloud.is_dense,) = _struct_B.unpack(str[start:end])
01842 self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
01843 return self
01844 except struct.error as e:
01845 raise genpy.DeserializationError(e)
01846
01847 _struct_I = genpy.struct_I
01848 _struct_IBI = struct.Struct("<IBI")
01849 _struct_6IB3I = struct.Struct("<6IB3I")
01850 _struct_B = struct.Struct("<B")
01851 _struct_12d = struct.Struct("<12d")
01852 _struct_9d = struct.Struct("<9d")
01853 _struct_BI = struct.Struct("<BI")
01854 _struct_3I = struct.Struct("<3I")
01855 _struct_B2I = struct.Struct("<B2I")
01856 _struct_2I = struct.Struct("<2I")