_RawCloudData.py
Go to the documentation of this file.
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 #flag to mark the presence of a Header object
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 src/image_encodings.cpp
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       #message fields cannot be None, assign default values for those that are
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       # - if encoded as a list instead, serialize as bytes instead of string
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       # - if encoded as a list instead, serialize as bytes instead of string
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       # - if encoded as a list instead, serialize as bytes instead of string
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       # - if encoded as a list instead, serialize as bytes instead of string
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       # - if encoded as a list instead, serialize as bytes instead of string
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       # - if encoded as a list instead, serialize as bytes instead of string
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       # - if encoded as a list instead, serialize as bytes instead of string
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(se)
00633     except TypeError as te: self._check_types(te)
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       if python3:
00715         self.intensity.data = str[start:end].decode('utf-8')
00716       else:
00717         self.intensity.data = str[start:end]
00718       _x = self
00719       start = end
00720       end += 12
00721       (_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00722       start = end
00723       end += 4
00724       (length,) = _struct_I.unpack(str[start:end])
00725       start = end
00726       end += length
00727       if python3:
00728         self.confidence.header.frame_id = str[start:end].decode('utf-8')
00729       else:
00730         self.confidence.header.frame_id = str[start:end]
00731       _x = self
00732       start = end
00733       end += 8
00734       (_x.confidence.height, _x.confidence.width,) = _struct_2I.unpack(str[start:end])
00735       start = end
00736       end += 4
00737       (length,) = _struct_I.unpack(str[start:end])
00738       start = end
00739       end += length
00740       if python3:
00741         self.confidence.encoding = str[start:end].decode('utf-8')
00742       else:
00743         self.confidence.encoding = str[start:end]
00744       _x = self
00745       start = end
00746       end += 5
00747       (_x.confidence.is_bigendian, _x.confidence.step,) = _struct_BI.unpack(str[start:end])
00748       start = end
00749       end += 4
00750       (length,) = _struct_I.unpack(str[start:end])
00751       start = end
00752       end += length
00753       if python3:
00754         self.confidence.data = str[start:end].decode('utf-8')
00755       else:
00756         self.confidence.data = str[start:end]
00757       _x = self
00758       start = end
00759       end += 12
00760       (_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00761       start = end
00762       end += 4
00763       (length,) = _struct_I.unpack(str[start:end])
00764       start = end
00765       end += length
00766       if python3:
00767         self.depth.header.frame_id = str[start:end].decode('utf-8')
00768       else:
00769         self.depth.header.frame_id = str[start:end]
00770       _x = self
00771       start = end
00772       end += 8
00773       (_x.depth.height, _x.depth.width,) = _struct_2I.unpack(str[start:end])
00774       start = end
00775       end += 4
00776       (length,) = _struct_I.unpack(str[start:end])
00777       start = end
00778       end += length
00779       if python3:
00780         self.depth.encoding = str[start:end].decode('utf-8')
00781       else:
00782         self.depth.encoding = str[start:end]
00783       _x = self
00784       start = end
00785       end += 5
00786       (_x.depth.is_bigendian, _x.depth.step,) = _struct_BI.unpack(str[start:end])
00787       start = end
00788       end += 4
00789       (length,) = _struct_I.unpack(str[start:end])
00790       start = end
00791       end += length
00792       if python3:
00793         self.depth.data = str[start:end].decode('utf-8')
00794       else:
00795         self.depth.data = str[start:end]
00796       _x = self
00797       start = end
00798       end += 12
00799       (_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00800       start = end
00801       end += 4
00802       (length,) = _struct_I.unpack(str[start:end])
00803       start = end
00804       end += length
00805       if python3:
00806         self.depth16.header.frame_id = str[start:end].decode('utf-8')
00807       else:
00808         self.depth16.header.frame_id = str[start:end]
00809       _x = self
00810       start = end
00811       end += 8
00812       (_x.depth16.height, _x.depth16.width,) = _struct_2I.unpack(str[start:end])
00813       start = end
00814       end += 4
00815       (length,) = _struct_I.unpack(str[start:end])
00816       start = end
00817       end += length
00818       if python3:
00819         self.depth16.encoding = str[start:end].decode('utf-8')
00820       else:
00821         self.depth16.encoding = str[start:end]
00822       _x = self
00823       start = end
00824       end += 5
00825       (_x.depth16.is_bigendian, _x.depth16.step,) = _struct_BI.unpack(str[start:end])
00826       start = end
00827       end += 4
00828       (length,) = _struct_I.unpack(str[start:end])
00829       start = end
00830       end += length
00831       if python3:
00832         self.depth16.data = str[start:end].decode('utf-8')
00833       else:
00834         self.depth16.data = str[start:end]
00835       _x = self
00836       start = end
00837       end += 12
00838       (_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00839       start = end
00840       end += 4
00841       (length,) = _struct_I.unpack(str[start:end])
00842       start = end
00843       end += length
00844       if python3:
00845         self.range_info.header.frame_id = str[start:end].decode('utf-8')
00846       else:
00847         self.range_info.header.frame_id = str[start:end]
00848       _x = self
00849       start = end
00850       end += 8
00851       (_x.range_info.height, _x.range_info.width,) = _struct_2I.unpack(str[start:end])
00852       start = end
00853       end += 4
00854       (length,) = _struct_I.unpack(str[start:end])
00855       start = end
00856       end += length
00857       if python3:
00858         self.range_info.distortion_model = str[start:end].decode('utf-8')
00859       else:
00860         self.range_info.distortion_model = str[start:end]
00861       start = end
00862       end += 4
00863       (length,) = _struct_I.unpack(str[start:end])
00864       pattern = '<%sd'%length
00865       start = end
00866       end += struct.calcsize(pattern)
00867       self.range_info.D = struct.unpack(pattern, str[start:end])
00868       start = end
00869       end += 72
00870       self.range_info.K = _struct_9d.unpack(str[start:end])
00871       start = end
00872       end += 72
00873       self.range_info.R = _struct_9d.unpack(str[start:end])
00874       start = end
00875       end += 96
00876       self.range_info.P = _struct_12d.unpack(str[start:end])
00877       _x = self
00878       start = end
00879       end += 37
00880       (_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])
00881       self.range_info.roi.do_rectify = bool(self.range_info.roi.do_rectify)
00882       start = end
00883       end += 4
00884       (length,) = _struct_I.unpack(str[start:end])
00885       start = end
00886       end += length
00887       if python3:
00888         self.left_image.header.frame_id = str[start:end].decode('utf-8')
00889       else:
00890         self.left_image.header.frame_id = str[start:end]
00891       _x = self
00892       start = end
00893       end += 8
00894       (_x.left_image.height, _x.left_image.width,) = _struct_2I.unpack(str[start:end])
00895       start = end
00896       end += 4
00897       (length,) = _struct_I.unpack(str[start:end])
00898       start = end
00899       end += length
00900       if python3:
00901         self.left_image.encoding = str[start:end].decode('utf-8')
00902       else:
00903         self.left_image.encoding = str[start:end]
00904       _x = self
00905       start = end
00906       end += 5
00907       (_x.left_image.is_bigendian, _x.left_image.step,) = _struct_BI.unpack(str[start:end])
00908       start = end
00909       end += 4
00910       (length,) = _struct_I.unpack(str[start:end])
00911       start = end
00912       end += length
00913       if python3:
00914         self.left_image.data = str[start:end].decode('utf-8')
00915       else:
00916         self.left_image.data = str[start:end]
00917       _x = self
00918       start = end
00919       end += 12
00920       (_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00921       start = end
00922       end += 4
00923       (length,) = _struct_I.unpack(str[start:end])
00924       start = end
00925       end += length
00926       if python3:
00927         self.right_image.header.frame_id = str[start:end].decode('utf-8')
00928       else:
00929         self.right_image.header.frame_id = str[start:end]
00930       _x = self
00931       start = end
00932       end += 8
00933       (_x.right_image.height, _x.right_image.width,) = _struct_2I.unpack(str[start:end])
00934       start = end
00935       end += 4
00936       (length,) = _struct_I.unpack(str[start:end])
00937       start = end
00938       end += length
00939       if python3:
00940         self.right_image.encoding = str[start:end].decode('utf-8')
00941       else:
00942         self.right_image.encoding = str[start:end]
00943       _x = self
00944       start = end
00945       end += 5
00946       (_x.right_image.is_bigendian, _x.right_image.step,) = _struct_BI.unpack(str[start:end])
00947       start = end
00948       end += 4
00949       (length,) = _struct_I.unpack(str[start:end])
00950       start = end
00951       end += length
00952       if python3:
00953         self.right_image.data = str[start:end].decode('utf-8')
00954       else:
00955         self.right_image.data = str[start:end]
00956       _x = self
00957       start = end
00958       end += 12
00959       (_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00960       start = end
00961       end += 4
00962       (length,) = _struct_I.unpack(str[start:end])
00963       start = end
00964       end += length
00965       if python3:
00966         self.left_info.header.frame_id = str[start:end].decode('utf-8')
00967       else:
00968         self.left_info.header.frame_id = str[start:end]
00969       _x = self
00970       start = end
00971       end += 8
00972       (_x.left_info.height, _x.left_info.width,) = _struct_2I.unpack(str[start:end])
00973       start = end
00974       end += 4
00975       (length,) = _struct_I.unpack(str[start:end])
00976       start = end
00977       end += length
00978       if python3:
00979         self.left_info.distortion_model = str[start:end].decode('utf-8')
00980       else:
00981         self.left_info.distortion_model = str[start:end]
00982       start = end
00983       end += 4
00984       (length,) = _struct_I.unpack(str[start:end])
00985       pattern = '<%sd'%length
00986       start = end
00987       end += struct.calcsize(pattern)
00988       self.left_info.D = struct.unpack(pattern, str[start:end])
00989       start = end
00990       end += 72
00991       self.left_info.K = _struct_9d.unpack(str[start:end])
00992       start = end
00993       end += 72
00994       self.left_info.R = _struct_9d.unpack(str[start:end])
00995       start = end
00996       end += 96
00997       self.left_info.P = _struct_12d.unpack(str[start:end])
00998       _x = self
00999       start = end
01000       end += 37
01001       (_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])
01002       self.left_info.roi.do_rectify = bool(self.left_info.roi.do_rectify)
01003       start = end
01004       end += 4
01005       (length,) = _struct_I.unpack(str[start:end])
01006       start = end
01007       end += length
01008       if python3:
01009         self.right_info.header.frame_id = str[start:end].decode('utf-8')
01010       else:
01011         self.right_info.header.frame_id = str[start:end]
01012       _x = self
01013       start = end
01014       end += 8
01015       (_x.right_info.height, _x.right_info.width,) = _struct_2I.unpack(str[start:end])
01016       start = end
01017       end += 4
01018       (length,) = _struct_I.unpack(str[start:end])
01019       start = end
01020       end += length
01021       if python3:
01022         self.right_info.distortion_model = str[start:end].decode('utf-8')
01023       else:
01024         self.right_info.distortion_model = str[start:end]
01025       start = end
01026       end += 4
01027       (length,) = _struct_I.unpack(str[start:end])
01028       pattern = '<%sd'%length
01029       start = end
01030       end += struct.calcsize(pattern)
01031       self.right_info.D = struct.unpack(pattern, str[start:end])
01032       start = end
01033       end += 72
01034       self.right_info.K = _struct_9d.unpack(str[start:end])
01035       start = end
01036       end += 72
01037       self.right_info.R = _struct_9d.unpack(str[start:end])
01038       start = end
01039       end += 96
01040       self.right_info.P = _struct_12d.unpack(str[start:end])
01041       _x = self
01042       start = end
01043       end += 37
01044       (_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])
01045       self.right_info.roi.do_rectify = bool(self.right_info.roi.do_rectify)
01046       start = end
01047       end += 4
01048       (length,) = _struct_I.unpack(str[start:end])
01049       start = end
01050       end += length
01051       if python3:
01052         self.pixel_indices.header.frame_id = str[start:end].decode('utf-8')
01053       else:
01054         self.pixel_indices.header.frame_id = str[start:end]
01055       start = end
01056       end += 4
01057       (length,) = _struct_I.unpack(str[start:end])
01058       pattern = '<%si'%length
01059       start = end
01060       end += struct.calcsize(pattern)
01061       self.pixel_indices.indices = struct.unpack(pattern, str[start:end])
01062       _x = self
01063       start = end
01064       end += 12
01065       (_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01066       start = end
01067       end += 4
01068       (length,) = _struct_I.unpack(str[start:end])
01069       start = end
01070       end += length
01071       if python3:
01072         self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01073       else:
01074         self.point_cloud.header.frame_id = str[start:end]
01075       _x = self
01076       start = end
01077       end += 8
01078       (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01079       start = end
01080       end += 4
01081       (length,) = _struct_I.unpack(str[start:end])
01082       self.point_cloud.fields = []
01083       for i in range(0, length):
01084         val1 = sensor_msgs.msg.PointField()
01085         start = end
01086         end += 4
01087         (length,) = _struct_I.unpack(str[start:end])
01088         start = end
01089         end += length
01090         if python3:
01091           val1.name = str[start:end].decode('utf-8')
01092         else:
01093           val1.name = str[start:end]
01094         _x = val1
01095         start = end
01096         end += 9
01097         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01098         self.point_cloud.fields.append(val1)
01099       _x = self
01100       start = end
01101       end += 9
01102       (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01103       self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
01104       start = end
01105       end += 4
01106       (length,) = _struct_I.unpack(str[start:end])
01107       start = end
01108       end += length
01109       if python3:
01110         self.point_cloud.data = str[start:end].decode('utf-8')
01111       else:
01112         self.point_cloud.data = str[start:end]
01113       start = end
01114       end += 1
01115       (self.point_cloud.is_dense,) = _struct_B.unpack(str[start:end])
01116       self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
01117       return self
01118     except struct.error as e:
01119       raise genpy.DeserializationError(e) #most likely buffer underfill
01120 
01121 
01122   def serialize_numpy(self, buff, numpy):
01123     """
01124     serialize message with numpy array types into buffer
01125     :param buff: buffer, ``StringIO``
01126     :param numpy: numpy python module
01127     """
01128     try:
01129       _x = self
01130       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
01131       _x = self.header.frame_id
01132       length = len(_x)
01133       if python3 or type(_x) == unicode:
01134         _x = _x.encode('utf-8')
01135         length = len(_x)
01136       buff.write(struct.pack('<I%ss'%length, length, _x))
01137       _x = self
01138       buff.write(_struct_3I.pack(_x.intensity.header.seq, _x.intensity.header.stamp.secs, _x.intensity.header.stamp.nsecs))
01139       _x = self.intensity.header.frame_id
01140       length = len(_x)
01141       if python3 or type(_x) == unicode:
01142         _x = _x.encode('utf-8')
01143         length = len(_x)
01144       buff.write(struct.pack('<I%ss'%length, length, _x))
01145       _x = self
01146       buff.write(_struct_2I.pack(_x.intensity.height, _x.intensity.width))
01147       _x = self.intensity.encoding
01148       length = len(_x)
01149       if python3 or type(_x) == unicode:
01150         _x = _x.encode('utf-8')
01151         length = len(_x)
01152       buff.write(struct.pack('<I%ss'%length, length, _x))
01153       _x = self
01154       buff.write(_struct_BI.pack(_x.intensity.is_bigendian, _x.intensity.step))
01155       _x = self.intensity.data
01156       length = len(_x)
01157       # - if encoded as a list instead, serialize as bytes instead of string
01158       if type(_x) in [list, tuple]:
01159         buff.write(struct.pack('<I%sB'%length, length, *_x))
01160       else:
01161         buff.write(struct.pack('<I%ss'%length, length, _x))
01162       _x = self
01163       buff.write(_struct_3I.pack(_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs))
01164       _x = self.confidence.header.frame_id
01165       length = len(_x)
01166       if python3 or type(_x) == unicode:
01167         _x = _x.encode('utf-8')
01168         length = len(_x)
01169       buff.write(struct.pack('<I%ss'%length, length, _x))
01170       _x = self
01171       buff.write(_struct_2I.pack(_x.confidence.height, _x.confidence.width))
01172       _x = self.confidence.encoding
01173       length = len(_x)
01174       if python3 or type(_x) == unicode:
01175         _x = _x.encode('utf-8')
01176         length = len(_x)
01177       buff.write(struct.pack('<I%ss'%length, length, _x))
01178       _x = self
01179       buff.write(_struct_BI.pack(_x.confidence.is_bigendian, _x.confidence.step))
01180       _x = self.confidence.data
01181       length = len(_x)
01182       # - if encoded as a list instead, serialize as bytes instead of string
01183       if type(_x) in [list, tuple]:
01184         buff.write(struct.pack('<I%sB'%length, length, *_x))
01185       else:
01186         buff.write(struct.pack('<I%ss'%length, length, _x))
01187       _x = self
01188       buff.write(_struct_3I.pack(_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs))
01189       _x = self.depth.header.frame_id
01190       length = len(_x)
01191       if python3 or type(_x) == unicode:
01192         _x = _x.encode('utf-8')
01193         length = len(_x)
01194       buff.write(struct.pack('<I%ss'%length, length, _x))
01195       _x = self
01196       buff.write(_struct_2I.pack(_x.depth.height, _x.depth.width))
01197       _x = self.depth.encoding
01198       length = len(_x)
01199       if python3 or type(_x) == unicode:
01200         _x = _x.encode('utf-8')
01201         length = len(_x)
01202       buff.write(struct.pack('<I%ss'%length, length, _x))
01203       _x = self
01204       buff.write(_struct_BI.pack(_x.depth.is_bigendian, _x.depth.step))
01205       _x = self.depth.data
01206       length = len(_x)
01207       # - if encoded as a list instead, serialize as bytes instead of string
01208       if type(_x) in [list, tuple]:
01209         buff.write(struct.pack('<I%sB'%length, length, *_x))
01210       else:
01211         buff.write(struct.pack('<I%ss'%length, length, _x))
01212       _x = self
01213       buff.write(_struct_3I.pack(_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs))
01214       _x = self.depth16.header.frame_id
01215       length = len(_x)
01216       if python3 or type(_x) == unicode:
01217         _x = _x.encode('utf-8')
01218         length = len(_x)
01219       buff.write(struct.pack('<I%ss'%length, length, _x))
01220       _x = self
01221       buff.write(_struct_2I.pack(_x.depth16.height, _x.depth16.width))
01222       _x = self.depth16.encoding
01223       length = len(_x)
01224       if python3 or type(_x) == unicode:
01225         _x = _x.encode('utf-8')
01226         length = len(_x)
01227       buff.write(struct.pack('<I%ss'%length, length, _x))
01228       _x = self
01229       buff.write(_struct_BI.pack(_x.depth16.is_bigendian, _x.depth16.step))
01230       _x = self.depth16.data
01231       length = len(_x)
01232       # - if encoded as a list instead, serialize as bytes instead of string
01233       if type(_x) in [list, tuple]:
01234         buff.write(struct.pack('<I%sB'%length, length, *_x))
01235       else:
01236         buff.write(struct.pack('<I%ss'%length, length, _x))
01237       _x = self
01238       buff.write(_struct_3I.pack(_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs))
01239       _x = self.range_info.header.frame_id
01240       length = len(_x)
01241       if python3 or type(_x) == unicode:
01242         _x = _x.encode('utf-8')
01243         length = len(_x)
01244       buff.write(struct.pack('<I%ss'%length, length, _x))
01245       _x = self
01246       buff.write(_struct_2I.pack(_x.range_info.height, _x.range_info.width))
01247       _x = self.range_info.distortion_model
01248       length = len(_x)
01249       if python3 or type(_x) == unicode:
01250         _x = _x.encode('utf-8')
01251         length = len(_x)
01252       buff.write(struct.pack('<I%ss'%length, length, _x))
01253       length = len(self.range_info.D)
01254       buff.write(_struct_I.pack(length))
01255       pattern = '<%sd'%length
01256       buff.write(self.range_info.D.tostring())
01257       buff.write(self.range_info.K.tostring())
01258       buff.write(self.range_info.R.tostring())
01259       buff.write(self.range_info.P.tostring())
01260       _x = self
01261       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))
01262       _x = self.left_image.header.frame_id
01263       length = len(_x)
01264       if python3 or type(_x) == unicode:
01265         _x = _x.encode('utf-8')
01266         length = len(_x)
01267       buff.write(struct.pack('<I%ss'%length, length, _x))
01268       _x = self
01269       buff.write(_struct_2I.pack(_x.left_image.height, _x.left_image.width))
01270       _x = self.left_image.encoding
01271       length = len(_x)
01272       if python3 or type(_x) == unicode:
01273         _x = _x.encode('utf-8')
01274         length = len(_x)
01275       buff.write(struct.pack('<I%ss'%length, length, _x))
01276       _x = self
01277       buff.write(_struct_BI.pack(_x.left_image.is_bigendian, _x.left_image.step))
01278       _x = self.left_image.data
01279       length = len(_x)
01280       # - if encoded as a list instead, serialize as bytes instead of string
01281       if type(_x) in [list, tuple]:
01282         buff.write(struct.pack('<I%sB'%length, length, *_x))
01283       else:
01284         buff.write(struct.pack('<I%ss'%length, length, _x))
01285       _x = self
01286       buff.write(_struct_3I.pack(_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.header.stamp.nsecs))
01287       _x = self.right_image.header.frame_id
01288       length = len(_x)
01289       if python3 or type(_x) == unicode:
01290         _x = _x.encode('utf-8')
01291         length = len(_x)
01292       buff.write(struct.pack('<I%ss'%length, length, _x))
01293       _x = self
01294       buff.write(_struct_2I.pack(_x.right_image.height, _x.right_image.width))
01295       _x = self.right_image.encoding
01296       length = len(_x)
01297       if python3 or type(_x) == unicode:
01298         _x = _x.encode('utf-8')
01299         length = len(_x)
01300       buff.write(struct.pack('<I%ss'%length, length, _x))
01301       _x = self
01302       buff.write(_struct_BI.pack(_x.right_image.is_bigendian, _x.right_image.step))
01303       _x = self.right_image.data
01304       length = len(_x)
01305       # - if encoded as a list instead, serialize as bytes instead of string
01306       if type(_x) in [list, tuple]:
01307         buff.write(struct.pack('<I%sB'%length, length, *_x))
01308       else:
01309         buff.write(struct.pack('<I%ss'%length, length, _x))
01310       _x = self
01311       buff.write(_struct_3I.pack(_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs))
01312       _x = self.left_info.header.frame_id
01313       length = len(_x)
01314       if python3 or type(_x) == unicode:
01315         _x = _x.encode('utf-8')
01316         length = len(_x)
01317       buff.write(struct.pack('<I%ss'%length, length, _x))
01318       _x = self
01319       buff.write(_struct_2I.pack(_x.left_info.height, _x.left_info.width))
01320       _x = self.left_info.distortion_model
01321       length = len(_x)
01322       if python3 or type(_x) == unicode:
01323         _x = _x.encode('utf-8')
01324         length = len(_x)
01325       buff.write(struct.pack('<I%ss'%length, length, _x))
01326       length = len(self.left_info.D)
01327       buff.write(_struct_I.pack(length))
01328       pattern = '<%sd'%length
01329       buff.write(self.left_info.D.tostring())
01330       buff.write(self.left_info.K.tostring())
01331       buff.write(self.left_info.R.tostring())
01332       buff.write(self.left_info.P.tostring())
01333       _x = self
01334       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))
01335       _x = self.right_info.header.frame_id
01336       length = len(_x)
01337       if python3 or type(_x) == unicode:
01338         _x = _x.encode('utf-8')
01339         length = len(_x)
01340       buff.write(struct.pack('<I%ss'%length, length, _x))
01341       _x = self
01342       buff.write(_struct_2I.pack(_x.right_info.height, _x.right_info.width))
01343       _x = self.right_info.distortion_model
01344       length = len(_x)
01345       if python3 or type(_x) == unicode:
01346         _x = _x.encode('utf-8')
01347         length = len(_x)
01348       buff.write(struct.pack('<I%ss'%length, length, _x))
01349       length = len(self.right_info.D)
01350       buff.write(_struct_I.pack(length))
01351       pattern = '<%sd'%length
01352       buff.write(self.right_info.D.tostring())
01353       buff.write(self.right_info.K.tostring())
01354       buff.write(self.right_info.R.tostring())
01355       buff.write(self.right_info.P.tostring())
01356       _x = self
01357       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))
01358       _x = self.pixel_indices.header.frame_id
01359       length = len(_x)
01360       if python3 or type(_x) == unicode:
01361         _x = _x.encode('utf-8')
01362         length = len(_x)
01363       buff.write(struct.pack('<I%ss'%length, length, _x))
01364       length = len(self.pixel_indices.indices)
01365       buff.write(_struct_I.pack(length))
01366       pattern = '<%si'%length
01367       buff.write(self.pixel_indices.indices.tostring())
01368       _x = self
01369       buff.write(_struct_3I.pack(_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
01370       _x = self.point_cloud.header.frame_id
01371       length = len(_x)
01372       if python3 or type(_x) == unicode:
01373         _x = _x.encode('utf-8')
01374         length = len(_x)
01375       buff.write(struct.pack('<I%ss'%length, length, _x))
01376       _x = self
01377       buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
01378       length = len(self.point_cloud.fields)
01379       buff.write(_struct_I.pack(length))
01380       for val1 in self.point_cloud.fields:
01381         _x = val1.name
01382         length = len(_x)
01383         if python3 or type(_x) == unicode:
01384           _x = _x.encode('utf-8')
01385           length = len(_x)
01386         buff.write(struct.pack('<I%ss'%length, length, _x))
01387         _x = val1
01388         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
01389       _x = self
01390       buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
01391       _x = self.point_cloud.data
01392       length = len(_x)
01393       # - if encoded as a list instead, serialize as bytes instead of string
01394       if type(_x) in [list, tuple]:
01395         buff.write(struct.pack('<I%sB'%length, length, *_x))
01396       else:
01397         buff.write(struct.pack('<I%ss'%length, length, _x))
01398       buff.write(_struct_B.pack(self.point_cloud.is_dense))
01399     except struct.error as se: self._check_types(se)
01400     except TypeError as te: self._check_types(te)
01401 
01402   def deserialize_numpy(self, str, numpy):
01403     """
01404     unpack serialized message in str into this message instance using numpy for array types
01405     :param str: byte array of serialized message, ``str``
01406     :param numpy: numpy python module
01407     """
01408     try:
01409       if self.header is None:
01410         self.header = std_msgs.msg.Header()
01411       if self.intensity is None:
01412         self.intensity = sensor_msgs.msg.Image()
01413       if self.confidence is None:
01414         self.confidence = sensor_msgs.msg.Image()
01415       if self.depth is None:
01416         self.depth = sensor_msgs.msg.Image()
01417       if self.depth16 is None:
01418         self.depth16 = sensor_msgs.msg.Image()
01419       if self.range_info is None:
01420         self.range_info = sensor_msgs.msg.CameraInfo()
01421       if self.left_image is None:
01422         self.left_image = sensor_msgs.msg.Image()
01423       if self.right_image is None:
01424         self.right_image = sensor_msgs.msg.Image()
01425       if self.left_info is None:
01426         self.left_info = sensor_msgs.msg.CameraInfo()
01427       if self.right_info is None:
01428         self.right_info = sensor_msgs.msg.CameraInfo()
01429       if self.pixel_indices is None:
01430         self.pixel_indices = cr_capture.msg.PixelIndices()
01431       if self.point_cloud is None:
01432         self.point_cloud = sensor_msgs.msg.PointCloud2()
01433       end = 0
01434       _x = self
01435       start = end
01436       end += 12
01437       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01438       start = end
01439       end += 4
01440       (length,) = _struct_I.unpack(str[start:end])
01441       start = end
01442       end += length
01443       if python3:
01444         self.header.frame_id = str[start:end].decode('utf-8')
01445       else:
01446         self.header.frame_id = str[start:end]
01447       _x = self
01448       start = end
01449       end += 12
01450       (_x.intensity.header.seq, _x.intensity.header.stamp.secs, _x.intensity.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01451       start = end
01452       end += 4
01453       (length,) = _struct_I.unpack(str[start:end])
01454       start = end
01455       end += length
01456       if python3:
01457         self.intensity.header.frame_id = str[start:end].decode('utf-8')
01458       else:
01459         self.intensity.header.frame_id = str[start:end]
01460       _x = self
01461       start = end
01462       end += 8
01463       (_x.intensity.height, _x.intensity.width,) = _struct_2I.unpack(str[start:end])
01464       start = end
01465       end += 4
01466       (length,) = _struct_I.unpack(str[start:end])
01467       start = end
01468       end += length
01469       if python3:
01470         self.intensity.encoding = str[start:end].decode('utf-8')
01471       else:
01472         self.intensity.encoding = str[start:end]
01473       _x = self
01474       start = end
01475       end += 5
01476       (_x.intensity.is_bigendian, _x.intensity.step,) = _struct_BI.unpack(str[start:end])
01477       start = end
01478       end += 4
01479       (length,) = _struct_I.unpack(str[start:end])
01480       start = end
01481       end += length
01482       if python3:
01483         self.intensity.data = str[start:end].decode('utf-8')
01484       else:
01485         self.intensity.data = str[start:end]
01486       _x = self
01487       start = end
01488       end += 12
01489       (_x.confidence.header.seq, _x.confidence.header.stamp.secs, _x.confidence.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01490       start = end
01491       end += 4
01492       (length,) = _struct_I.unpack(str[start:end])
01493       start = end
01494       end += length
01495       if python3:
01496         self.confidence.header.frame_id = str[start:end].decode('utf-8')
01497       else:
01498         self.confidence.header.frame_id = str[start:end]
01499       _x = self
01500       start = end
01501       end += 8
01502       (_x.confidence.height, _x.confidence.width,) = _struct_2I.unpack(str[start:end])
01503       start = end
01504       end += 4
01505       (length,) = _struct_I.unpack(str[start:end])
01506       start = end
01507       end += length
01508       if python3:
01509         self.confidence.encoding = str[start:end].decode('utf-8')
01510       else:
01511         self.confidence.encoding = str[start:end]
01512       _x = self
01513       start = end
01514       end += 5
01515       (_x.confidence.is_bigendian, _x.confidence.step,) = _struct_BI.unpack(str[start:end])
01516       start = end
01517       end += 4
01518       (length,) = _struct_I.unpack(str[start:end])
01519       start = end
01520       end += length
01521       if python3:
01522         self.confidence.data = str[start:end].decode('utf-8')
01523       else:
01524         self.confidence.data = str[start:end]
01525       _x = self
01526       start = end
01527       end += 12
01528       (_x.depth.header.seq, _x.depth.header.stamp.secs, _x.depth.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01529       start = end
01530       end += 4
01531       (length,) = _struct_I.unpack(str[start:end])
01532       start = end
01533       end += length
01534       if python3:
01535         self.depth.header.frame_id = str[start:end].decode('utf-8')
01536       else:
01537         self.depth.header.frame_id = str[start:end]
01538       _x = self
01539       start = end
01540       end += 8
01541       (_x.depth.height, _x.depth.width,) = _struct_2I.unpack(str[start:end])
01542       start = end
01543       end += 4
01544       (length,) = _struct_I.unpack(str[start:end])
01545       start = end
01546       end += length
01547       if python3:
01548         self.depth.encoding = str[start:end].decode('utf-8')
01549       else:
01550         self.depth.encoding = str[start:end]
01551       _x = self
01552       start = end
01553       end += 5
01554       (_x.depth.is_bigendian, _x.depth.step,) = _struct_BI.unpack(str[start:end])
01555       start = end
01556       end += 4
01557       (length,) = _struct_I.unpack(str[start:end])
01558       start = end
01559       end += length
01560       if python3:
01561         self.depth.data = str[start:end].decode('utf-8')
01562       else:
01563         self.depth.data = str[start:end]
01564       _x = self
01565       start = end
01566       end += 12
01567       (_x.depth16.header.seq, _x.depth16.header.stamp.secs, _x.depth16.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01568       start = end
01569       end += 4
01570       (length,) = _struct_I.unpack(str[start:end])
01571       start = end
01572       end += length
01573       if python3:
01574         self.depth16.header.frame_id = str[start:end].decode('utf-8')
01575       else:
01576         self.depth16.header.frame_id = str[start:end]
01577       _x = self
01578       start = end
01579       end += 8
01580       (_x.depth16.height, _x.depth16.width,) = _struct_2I.unpack(str[start:end])
01581       start = end
01582       end += 4
01583       (length,) = _struct_I.unpack(str[start:end])
01584       start = end
01585       end += length
01586       if python3:
01587         self.depth16.encoding = str[start:end].decode('utf-8')
01588       else:
01589         self.depth16.encoding = str[start:end]
01590       _x = self
01591       start = end
01592       end += 5
01593       (_x.depth16.is_bigendian, _x.depth16.step,) = _struct_BI.unpack(str[start:end])
01594       start = end
01595       end += 4
01596       (length,) = _struct_I.unpack(str[start:end])
01597       start = end
01598       end += length
01599       if python3:
01600         self.depth16.data = str[start:end].decode('utf-8')
01601       else:
01602         self.depth16.data = str[start:end]
01603       _x = self
01604       start = end
01605       end += 12
01606       (_x.range_info.header.seq, _x.range_info.header.stamp.secs, _x.range_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01607       start = end
01608       end += 4
01609       (length,) = _struct_I.unpack(str[start:end])
01610       start = end
01611       end += length
01612       if python3:
01613         self.range_info.header.frame_id = str[start:end].decode('utf-8')
01614       else:
01615         self.range_info.header.frame_id = str[start:end]
01616       _x = self
01617       start = end
01618       end += 8
01619       (_x.range_info.height, _x.range_info.width,) = _struct_2I.unpack(str[start:end])
01620       start = end
01621       end += 4
01622       (length,) = _struct_I.unpack(str[start:end])
01623       start = end
01624       end += length
01625       if python3:
01626         self.range_info.distortion_model = str[start:end].decode('utf-8')
01627       else:
01628         self.range_info.distortion_model = str[start:end]
01629       start = end
01630       end += 4
01631       (length,) = _struct_I.unpack(str[start:end])
01632       pattern = '<%sd'%length
01633       start = end
01634       end += struct.calcsize(pattern)
01635       self.range_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01636       start = end
01637       end += 72
01638       self.range_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01639       start = end
01640       end += 72
01641       self.range_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01642       start = end
01643       end += 96
01644       self.range_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01645       _x = self
01646       start = end
01647       end += 37
01648       (_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])
01649       self.range_info.roi.do_rectify = bool(self.range_info.roi.do_rectify)
01650       start = end
01651       end += 4
01652       (length,) = _struct_I.unpack(str[start:end])
01653       start = end
01654       end += length
01655       if python3:
01656         self.left_image.header.frame_id = str[start:end].decode('utf-8')
01657       else:
01658         self.left_image.header.frame_id = str[start:end]
01659       _x = self
01660       start = end
01661       end += 8
01662       (_x.left_image.height, _x.left_image.width,) = _struct_2I.unpack(str[start:end])
01663       start = end
01664       end += 4
01665       (length,) = _struct_I.unpack(str[start:end])
01666       start = end
01667       end += length
01668       if python3:
01669         self.left_image.encoding = str[start:end].decode('utf-8')
01670       else:
01671         self.left_image.encoding = str[start:end]
01672       _x = self
01673       start = end
01674       end += 5
01675       (_x.left_image.is_bigendian, _x.left_image.step,) = _struct_BI.unpack(str[start:end])
01676       start = end
01677       end += 4
01678       (length,) = _struct_I.unpack(str[start:end])
01679       start = end
01680       end += length
01681       if python3:
01682         self.left_image.data = str[start:end].decode('utf-8')
01683       else:
01684         self.left_image.data = str[start:end]
01685       _x = self
01686       start = end
01687       end += 12
01688       (_x.right_image.header.seq, _x.right_image.header.stamp.secs, _x.right_image.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.right_image.header.frame_id = str[start:end].decode('utf-8')
01696       else:
01697         self.right_image.header.frame_id = str[start:end]
01698       _x = self
01699       start = end
01700       end += 8
01701       (_x.right_image.height, _x.right_image.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.right_image.encoding = str[start:end].decode('utf-8')
01709       else:
01710         self.right_image.encoding = str[start:end]
01711       _x = self
01712       start = end
01713       end += 5
01714       (_x.right_image.is_bigendian, _x.right_image.step,) = _struct_BI.unpack(str[start:end])
01715       start = end
01716       end += 4
01717       (length,) = _struct_I.unpack(str[start:end])
01718       start = end
01719       end += length
01720       if python3:
01721         self.right_image.data = str[start:end].decode('utf-8')
01722       else:
01723         self.right_image.data = str[start:end]
01724       _x = self
01725       start = end
01726       end += 12
01727       (_x.left_info.header.seq, _x.left_info.header.stamp.secs, _x.left_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01728       start = end
01729       end += 4
01730       (length,) = _struct_I.unpack(str[start:end])
01731       start = end
01732       end += length
01733       if python3:
01734         self.left_info.header.frame_id = str[start:end].decode('utf-8')
01735       else:
01736         self.left_info.header.frame_id = str[start:end]
01737       _x = self
01738       start = end
01739       end += 8
01740       (_x.left_info.height, _x.left_info.width,) = _struct_2I.unpack(str[start:end])
01741       start = end
01742       end += 4
01743       (length,) = _struct_I.unpack(str[start:end])
01744       start = end
01745       end += length
01746       if python3:
01747         self.left_info.distortion_model = str[start:end].decode('utf-8')
01748       else:
01749         self.left_info.distortion_model = str[start:end]
01750       start = end
01751       end += 4
01752       (length,) = _struct_I.unpack(str[start:end])
01753       pattern = '<%sd'%length
01754       start = end
01755       end += struct.calcsize(pattern)
01756       self.left_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01757       start = end
01758       end += 72
01759       self.left_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01760       start = end
01761       end += 72
01762       self.left_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01763       start = end
01764       end += 96
01765       self.left_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01766       _x = self
01767       start = end
01768       end += 37
01769       (_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])
01770       self.left_info.roi.do_rectify = bool(self.left_info.roi.do_rectify)
01771       start = end
01772       end += 4
01773       (length,) = _struct_I.unpack(str[start:end])
01774       start = end
01775       end += length
01776       if python3:
01777         self.right_info.header.frame_id = str[start:end].decode('utf-8')
01778       else:
01779         self.right_info.header.frame_id = str[start:end]
01780       _x = self
01781       start = end
01782       end += 8
01783       (_x.right_info.height, _x.right_info.width,) = _struct_2I.unpack(str[start:end])
01784       start = end
01785       end += 4
01786       (length,) = _struct_I.unpack(str[start:end])
01787       start = end
01788       end += length
01789       if python3:
01790         self.right_info.distortion_model = str[start:end].decode('utf-8')
01791       else:
01792         self.right_info.distortion_model = str[start:end]
01793       start = end
01794       end += 4
01795       (length,) = _struct_I.unpack(str[start:end])
01796       pattern = '<%sd'%length
01797       start = end
01798       end += struct.calcsize(pattern)
01799       self.right_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01800       start = end
01801       end += 72
01802       self.right_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01803       start = end
01804       end += 72
01805       self.right_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01806       start = end
01807       end += 96
01808       self.right_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01809       _x = self
01810       start = end
01811       end += 37
01812       (_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])
01813       self.right_info.roi.do_rectify = bool(self.right_info.roi.do_rectify)
01814       start = end
01815       end += 4
01816       (length,) = _struct_I.unpack(str[start:end])
01817       start = end
01818       end += length
01819       if python3:
01820         self.pixel_indices.header.frame_id = str[start:end].decode('utf-8')
01821       else:
01822         self.pixel_indices.header.frame_id = str[start:end]
01823       start = end
01824       end += 4
01825       (length,) = _struct_I.unpack(str[start:end])
01826       pattern = '<%si'%length
01827       start = end
01828       end += struct.calcsize(pattern)
01829       self.pixel_indices.indices = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01830       _x = self
01831       start = end
01832       end += 12
01833       (_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01834       start = end
01835       end += 4
01836       (length,) = _struct_I.unpack(str[start:end])
01837       start = end
01838       end += length
01839       if python3:
01840         self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01841       else:
01842         self.point_cloud.header.frame_id = str[start:end]
01843       _x = self
01844       start = end
01845       end += 8
01846       (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01847       start = end
01848       end += 4
01849       (length,) = _struct_I.unpack(str[start:end])
01850       self.point_cloud.fields = []
01851       for i in range(0, length):
01852         val1 = sensor_msgs.msg.PointField()
01853         start = end
01854         end += 4
01855         (length,) = _struct_I.unpack(str[start:end])
01856         start = end
01857         end += length
01858         if python3:
01859           val1.name = str[start:end].decode('utf-8')
01860         else:
01861           val1.name = str[start:end]
01862         _x = val1
01863         start = end
01864         end += 9
01865         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01866         self.point_cloud.fields.append(val1)
01867       _x = self
01868       start = end
01869       end += 9
01870       (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01871       self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
01872       start = end
01873       end += 4
01874       (length,) = _struct_I.unpack(str[start:end])
01875       start = end
01876       end += length
01877       if python3:
01878         self.point_cloud.data = str[start:end].decode('utf-8')
01879       else:
01880         self.point_cloud.data = str[start:end]
01881       start = end
01882       end += 1
01883       (self.point_cloud.is_dense,) = _struct_B.unpack(str[start:end])
01884       self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
01885       return self
01886     except struct.error as e:
01887       raise genpy.DeserializationError(e) #most likely buffer underfill
01888 
01889 _struct_I = genpy.struct_I
01890 _struct_IBI = struct.Struct("<IBI")
01891 _struct_6IB3I = struct.Struct("<6IB3I")
01892 _struct_B = struct.Struct("<B")
01893 _struct_12d = struct.Struct("<12d")
01894 _struct_9d = struct.Struct("<9d")
01895 _struct_BI = struct.Struct("<BI")
01896 _struct_3I = struct.Struct("<3I")
01897 _struct_B2I = struct.Struct("<B2I")
01898 _struct_2I = struct.Struct("<2I")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


cr_capture
Author(s): youhei kakiuchi, JSK
autogenerated on Sun Mar 24 2013 02:36:20