00001 """autogenerated by genpy from object_segmentation_gui/ObjectSegmentationGuiGoal.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 stereo_msgs.msg
00008 import std_msgs.msg
00009 import sensor_msgs.msg
00010
00011 class ObjectSegmentationGuiGoal(genpy.Message):
00012 _md5sum = "e1d5b6113ada0dd63b3fd30b2ac9f913"
00013 _type = "object_segmentation_gui/ObjectSegmentationGuiGoal"
00014 _has_header = False
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016 sensor_msgs/Image image
00017 sensor_msgs/CameraInfo camera_info
00018 sensor_msgs/Image wide_field
00019 sensor_msgs/CameraInfo wide_camera_info
00020
00021 sensor_msgs/PointCloud2 point_cloud
00022 stereo_msgs/DisparityImage disparity_image
00023
00024
00025 ================================================================================
00026 MSG: sensor_msgs/Image
00027 # This message contains an uncompressed image
00028 # (0, 0) is at top-left corner of image
00029 #
00030
00031 Header header # Header timestamp should be acquisition time of image
00032 # Header frame_id should be optical frame of camera
00033 # origin of frame should be optical center of cameara
00034 # +x should point to the right in the image
00035 # +y should point down in the image
00036 # +z should point into to plane of the image
00037 # If the frame_id here and the frame_id of the CameraInfo
00038 # message associated with the image conflict
00039 # the behavior is undefined
00040
00041 uint32 height # image height, that is, number of rows
00042 uint32 width # image width, that is, number of columns
00043
00044 # The legal values for encoding are in file src/image_encodings.cpp
00045 # If you want to standardize a new string format, join
00046 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00047
00048 string encoding # Encoding of pixels -- channel meaning, ordering, size
00049 # taken from the list of strings in src/image_encodings.cpp
00050
00051 uint8 is_bigendian # is this data bigendian?
00052 uint32 step # Full row length in bytes
00053 uint8[] data # actual matrix data, size is (step * rows)
00054
00055 ================================================================================
00056 MSG: std_msgs/Header
00057 # Standard metadata for higher-level stamped data types.
00058 # This is generally used to communicate timestamped data
00059 # in a particular coordinate frame.
00060 #
00061 # sequence ID: consecutively increasing ID
00062 uint32 seq
00063 #Two-integer timestamp that is expressed as:
00064 # * stamp.secs: seconds (stamp_secs) since epoch
00065 # * stamp.nsecs: nanoseconds since stamp_secs
00066 # time-handling sugar is provided by the client library
00067 time stamp
00068 #Frame this data is associated with
00069 # 0: no frame
00070 # 1: global frame
00071 string frame_id
00072
00073 ================================================================================
00074 MSG: sensor_msgs/CameraInfo
00075 # This message defines meta information for a camera. It should be in a
00076 # camera namespace on topic "camera_info" and accompanied by up to five
00077 # image topics named:
00078 #
00079 # image_raw - raw data from the camera driver, possibly Bayer encoded
00080 # image - monochrome, distorted
00081 # image_color - color, distorted
00082 # image_rect - monochrome, rectified
00083 # image_rect_color - color, rectified
00084 #
00085 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00086 # for producing the four processed image topics from image_raw and
00087 # camera_info. The meaning of the camera parameters are described in
00088 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00089 #
00090 # The image_geometry package provides a user-friendly interface to
00091 # common operations using this meta information. If you want to, e.g.,
00092 # project a 3d point into image coordinates, we strongly recommend
00093 # using image_geometry.
00094 #
00095 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00096 # zeroed out. In particular, clients may assume that K[0] == 0.0
00097 # indicates an uncalibrated camera.
00098
00099 #######################################################################
00100 # Image acquisition info #
00101 #######################################################################
00102
00103 # Time of image acquisition, camera coordinate frame ID
00104 Header header # Header timestamp should be acquisition time of image
00105 # Header frame_id should be optical frame of camera
00106 # origin of frame should be optical center of camera
00107 # +x should point to the right in the image
00108 # +y should point down in the image
00109 # +z should point into the plane of the image
00110
00111
00112 #######################################################################
00113 # Calibration Parameters #
00114 #######################################################################
00115 # These are fixed during camera calibration. Their values will be the #
00116 # same in all messages until the camera is recalibrated. Note that #
00117 # self-calibrating systems may "recalibrate" frequently. #
00118 # #
00119 # The internal parameters can be used to warp a raw (distorted) image #
00120 # to: #
00121 # 1. An undistorted image (requires D and K) #
00122 # 2. A rectified image (requires D, K, R) #
00123 # The projection matrix P projects 3D points into the rectified image.#
00124 #######################################################################
00125
00126 # The image dimensions with which the camera was calibrated. Normally
00127 # this will be the full camera resolution in pixels.
00128 uint32 height
00129 uint32 width
00130
00131 # The distortion model used. Supported models are listed in
00132 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00133 # simple model of radial and tangential distortion - is sufficent.
00134 string distortion_model
00135
00136 # The distortion parameters, size depending on the distortion model.
00137 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00138 float64[] D
00139
00140 # Intrinsic camera matrix for the raw (distorted) images.
00141 # [fx 0 cx]
00142 # K = [ 0 fy cy]
00143 # [ 0 0 1]
00144 # Projects 3D points in the camera coordinate frame to 2D pixel
00145 # coordinates using the focal lengths (fx, fy) and principal point
00146 # (cx, cy).
00147 float64[9] K # 3x3 row-major matrix
00148
00149 # Rectification matrix (stereo cameras only)
00150 # A rotation matrix aligning the camera coordinate system to the ideal
00151 # stereo image plane so that epipolar lines in both stereo images are
00152 # parallel.
00153 float64[9] R # 3x3 row-major matrix
00154
00155 # Projection/camera matrix
00156 # [fx' 0 cx' Tx]
00157 # P = [ 0 fy' cy' Ty]
00158 # [ 0 0 1 0]
00159 # By convention, this matrix specifies the intrinsic (camera) matrix
00160 # of the processed (rectified) image. That is, the left 3x3 portion
00161 # is the normal camera intrinsic matrix for the rectified image.
00162 # It projects 3D points in the camera coordinate frame to 2D pixel
00163 # coordinates using the focal lengths (fx', fy') and principal point
00164 # (cx', cy') - these may differ from the values in K.
00165 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00166 # also have R = the identity and P[1:3,1:3] = K.
00167 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00168 # position of the optical center of the second camera in the first
00169 # camera's frame. We assume Tz = 0 so both cameras are in the same
00170 # stereo image plane. The first camera always has Tx = Ty = 0. For
00171 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00172 # Tx = -fx' * B, where B is the baseline between the cameras.
00173 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00174 # the rectified image is given by:
00175 # [u v w]' = P * [X Y Z 1]'
00176 # x = u / w
00177 # y = v / w
00178 # This holds for both images of a stereo pair.
00179 float64[12] P # 3x4 row-major matrix
00180
00181
00182 #######################################################################
00183 # Operational Parameters #
00184 #######################################################################
00185 # These define the image region actually captured by the camera #
00186 # driver. Although they affect the geometry of the output image, they #
00187 # may be changed freely without recalibrating the camera. #
00188 #######################################################################
00189
00190 # Binning refers here to any camera setting which combines rectangular
00191 # neighborhoods of pixels into larger "super-pixels." It reduces the
00192 # resolution of the output image to
00193 # (width / binning_x) x (height / binning_y).
00194 # The default values binning_x = binning_y = 0 is considered the same
00195 # as binning_x = binning_y = 1 (no subsampling).
00196 uint32 binning_x
00197 uint32 binning_y
00198
00199 # Region of interest (subwindow of full camera resolution), given in
00200 # full resolution (unbinned) image coordinates. A particular ROI
00201 # always denotes the same window of pixels on the camera sensor,
00202 # regardless of binning settings.
00203 # The default setting of roi (all values 0) is considered the same as
00204 # full resolution (roi.width = width, roi.height = height).
00205 RegionOfInterest roi
00206
00207 ================================================================================
00208 MSG: sensor_msgs/RegionOfInterest
00209 # This message is used to specify a region of interest within an image.
00210 #
00211 # When used to specify the ROI setting of the camera when the image was
00212 # taken, the height and width fields should either match the height and
00213 # width fields for the associated image; or height = width = 0
00214 # indicates that the full resolution image was captured.
00215
00216 uint32 x_offset # Leftmost pixel of the ROI
00217 # (0 if the ROI includes the left edge of the image)
00218 uint32 y_offset # Topmost pixel of the ROI
00219 # (0 if the ROI includes the top edge of the image)
00220 uint32 height # Height of ROI
00221 uint32 width # Width of ROI
00222
00223 # True if a distinct rectified ROI should be calculated from the "raw"
00224 # ROI in this message. Typically this should be False if the full image
00225 # is captured (ROI not used), and True if a subwindow is captured (ROI
00226 # used).
00227 bool do_rectify
00228
00229 ================================================================================
00230 MSG: sensor_msgs/PointCloud2
00231 # This message holds a collection of N-dimensional points, which may
00232 # contain additional information such as normals, intensity, etc. The
00233 # point data is stored as a binary blob, its layout described by the
00234 # contents of the "fields" array.
00235
00236 # The point cloud data may be organized 2d (image-like) or 1d
00237 # (unordered). Point clouds organized as 2d images may be produced by
00238 # camera depth sensors such as stereo or time-of-flight.
00239
00240 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00241 # points).
00242 Header header
00243
00244 # 2D structure of the point cloud. If the cloud is unordered, height is
00245 # 1 and width is the length of the point cloud.
00246 uint32 height
00247 uint32 width
00248
00249 # Describes the channels and their layout in the binary data blob.
00250 PointField[] fields
00251
00252 bool is_bigendian # Is this data bigendian?
00253 uint32 point_step # Length of a point in bytes
00254 uint32 row_step # Length of a row in bytes
00255 uint8[] data # Actual point data, size is (row_step*height)
00256
00257 bool is_dense # True if there are no invalid points
00258
00259 ================================================================================
00260 MSG: sensor_msgs/PointField
00261 # This message holds the description of one point entry in the
00262 # PointCloud2 message format.
00263 uint8 INT8 = 1
00264 uint8 UINT8 = 2
00265 uint8 INT16 = 3
00266 uint8 UINT16 = 4
00267 uint8 INT32 = 5
00268 uint8 UINT32 = 6
00269 uint8 FLOAT32 = 7
00270 uint8 FLOAT64 = 8
00271
00272 string name # Name of field
00273 uint32 offset # Offset from start of point struct
00274 uint8 datatype # Datatype enumeration, see above
00275 uint32 count # How many elements in the field
00276
00277 ================================================================================
00278 MSG: stereo_msgs/DisparityImage
00279 # Separate header for compatibility with current TimeSynchronizer.
00280 # Likely to be removed in a later release, use image.header instead.
00281 Header header
00282
00283 # Floating point disparity image. The disparities are pre-adjusted for any
00284 # x-offset between the principal points of the two cameras (in the case
00285 # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)
00286 sensor_msgs/Image image
00287
00288 # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d.
00289 float32 f # Focal length, pixels
00290 float32 T # Baseline, world units
00291
00292 # Subwindow of (potentially) valid disparity values.
00293 sensor_msgs/RegionOfInterest valid_window
00294
00295 # The range of disparities searched.
00296 # In the disparity image, any disparity less than min_disparity is invalid.
00297 # The disparity search range defines the horopter, or 3D volume that the
00298 # stereo algorithm can "see". Points with Z outside of:
00299 # Z_min = fT / max_disparity
00300 # Z_max = fT / min_disparity
00301 # could not be found.
00302 float32 min_disparity
00303 float32 max_disparity
00304
00305 # Smallest allowed disparity increment. The smallest achievable depth range
00306 # resolution is delta_Z = (Z^2/fT)*delta_d.
00307 float32 delta_d
00308
00309 """
00310 __slots__ = ['image','camera_info','wide_field','wide_camera_info','point_cloud','disparity_image']
00311 _slot_types = ['sensor_msgs/Image','sensor_msgs/CameraInfo','sensor_msgs/Image','sensor_msgs/CameraInfo','sensor_msgs/PointCloud2','stereo_msgs/DisparityImage']
00312
00313 def __init__(self, *args, **kwds):
00314 """
00315 Constructor. Any message fields that are implicitly/explicitly
00316 set to None will be assigned a default value. The recommend
00317 use is keyword arguments as this is more robust to future message
00318 changes. You cannot mix in-order arguments and keyword arguments.
00319
00320 The available fields are:
00321 image,camera_info,wide_field,wide_camera_info,point_cloud,disparity_image
00322
00323 :param args: complete set of field values, in .msg order
00324 :param kwds: use keyword arguments corresponding to message field names
00325 to set specific fields.
00326 """
00327 if args or kwds:
00328 super(ObjectSegmentationGuiGoal, self).__init__(*args, **kwds)
00329
00330 if self.image is None:
00331 self.image = sensor_msgs.msg.Image()
00332 if self.camera_info is None:
00333 self.camera_info = sensor_msgs.msg.CameraInfo()
00334 if self.wide_field is None:
00335 self.wide_field = sensor_msgs.msg.Image()
00336 if self.wide_camera_info is None:
00337 self.wide_camera_info = sensor_msgs.msg.CameraInfo()
00338 if self.point_cloud is None:
00339 self.point_cloud = sensor_msgs.msg.PointCloud2()
00340 if self.disparity_image is None:
00341 self.disparity_image = stereo_msgs.msg.DisparityImage()
00342 else:
00343 self.image = sensor_msgs.msg.Image()
00344 self.camera_info = sensor_msgs.msg.CameraInfo()
00345 self.wide_field = sensor_msgs.msg.Image()
00346 self.wide_camera_info = sensor_msgs.msg.CameraInfo()
00347 self.point_cloud = sensor_msgs.msg.PointCloud2()
00348 self.disparity_image = stereo_msgs.msg.DisparityImage()
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.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00364 _x = self.image.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_2I.pack(_x.image.height, _x.image.width))
00372 _x = self.image.encoding
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_BI.pack(_x.image.is_bigendian, _x.image.step))
00380 _x = self.image.data
00381 length = len(_x)
00382
00383 if type(_x) in [list, tuple]:
00384 buff.write(struct.pack('<I%sB'%length, length, *_x))
00385 else:
00386 buff.write(struct.pack('<I%ss'%length, length, _x))
00387 _x = self
00388 buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs))
00389 _x = self.camera_info.header.frame_id
00390 length = len(_x)
00391 if python3 or type(_x) == unicode:
00392 _x = _x.encode('utf-8')
00393 length = len(_x)
00394 buff.write(struct.pack('<I%ss'%length, length, _x))
00395 _x = self
00396 buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width))
00397 _x = self.camera_info.distortion_model
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 length = len(self.camera_info.D)
00404 buff.write(_struct_I.pack(length))
00405 pattern = '<%sd'%length
00406 buff.write(struct.pack(pattern, *self.camera_info.D))
00407 buff.write(_struct_9d.pack(*self.camera_info.K))
00408 buff.write(_struct_9d.pack(*self.camera_info.R))
00409 buff.write(_struct_12d.pack(*self.camera_info.P))
00410 _x = self
00411 buff.write(_struct_6IB3I.pack(_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.wide_field.header.seq, _x.wide_field.header.stamp.secs, _x.wide_field.header.stamp.nsecs))
00412 _x = self.wide_field.header.frame_id
00413 length = len(_x)
00414 if python3 or type(_x) == unicode:
00415 _x = _x.encode('utf-8')
00416 length = len(_x)
00417 buff.write(struct.pack('<I%ss'%length, length, _x))
00418 _x = self
00419 buff.write(_struct_2I.pack(_x.wide_field.height, _x.wide_field.width))
00420 _x = self.wide_field.encoding
00421 length = len(_x)
00422 if python3 or type(_x) == unicode:
00423 _x = _x.encode('utf-8')
00424 length = len(_x)
00425 buff.write(struct.pack('<I%ss'%length, length, _x))
00426 _x = self
00427 buff.write(_struct_BI.pack(_x.wide_field.is_bigendian, _x.wide_field.step))
00428 _x = self.wide_field.data
00429 length = len(_x)
00430
00431 if type(_x) in [list, tuple]:
00432 buff.write(struct.pack('<I%sB'%length, length, *_x))
00433 else:
00434 buff.write(struct.pack('<I%ss'%length, length, _x))
00435 _x = self
00436 buff.write(_struct_3I.pack(_x.wide_camera_info.header.seq, _x.wide_camera_info.header.stamp.secs, _x.wide_camera_info.header.stamp.nsecs))
00437 _x = self.wide_camera_info.header.frame_id
00438 length = len(_x)
00439 if python3 or type(_x) == unicode:
00440 _x = _x.encode('utf-8')
00441 length = len(_x)
00442 buff.write(struct.pack('<I%ss'%length, length, _x))
00443 _x = self
00444 buff.write(_struct_2I.pack(_x.wide_camera_info.height, _x.wide_camera_info.width))
00445 _x = self.wide_camera_info.distortion_model
00446 length = len(_x)
00447 if python3 or type(_x) == unicode:
00448 _x = _x.encode('utf-8')
00449 length = len(_x)
00450 buff.write(struct.pack('<I%ss'%length, length, _x))
00451 length = len(self.wide_camera_info.D)
00452 buff.write(_struct_I.pack(length))
00453 pattern = '<%sd'%length
00454 buff.write(struct.pack(pattern, *self.wide_camera_info.D))
00455 buff.write(_struct_9d.pack(*self.wide_camera_info.K))
00456 buff.write(_struct_9d.pack(*self.wide_camera_info.R))
00457 buff.write(_struct_12d.pack(*self.wide_camera_info.P))
00458 _x = self
00459 buff.write(_struct_6IB3I.pack(_x.wide_camera_info.binning_x, _x.wide_camera_info.binning_y, _x.wide_camera_info.roi.x_offset, _x.wide_camera_info.roi.y_offset, _x.wide_camera_info.roi.height, _x.wide_camera_info.roi.width, _x.wide_camera_info.roi.do_rectify, _x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
00460 _x = self.point_cloud.header.frame_id
00461 length = len(_x)
00462 if python3 or type(_x) == unicode:
00463 _x = _x.encode('utf-8')
00464 length = len(_x)
00465 buff.write(struct.pack('<I%ss'%length, length, _x))
00466 _x = self
00467 buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
00468 length = len(self.point_cloud.fields)
00469 buff.write(_struct_I.pack(length))
00470 for val1 in self.point_cloud.fields:
00471 _x = val1.name
00472 length = len(_x)
00473 if python3 or type(_x) == unicode:
00474 _x = _x.encode('utf-8')
00475 length = len(_x)
00476 buff.write(struct.pack('<I%ss'%length, length, _x))
00477 _x = val1
00478 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00479 _x = self
00480 buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
00481 _x = self.point_cloud.data
00482 length = len(_x)
00483
00484 if type(_x) in [list, tuple]:
00485 buff.write(struct.pack('<I%sB'%length, length, *_x))
00486 else:
00487 buff.write(struct.pack('<I%ss'%length, length, _x))
00488 _x = self
00489 buff.write(_struct_B3I.pack(_x.point_cloud.is_dense, _x.disparity_image.header.seq, _x.disparity_image.header.stamp.secs, _x.disparity_image.header.stamp.nsecs))
00490 _x = self.disparity_image.header.frame_id
00491 length = len(_x)
00492 if python3 or type(_x) == unicode:
00493 _x = _x.encode('utf-8')
00494 length = len(_x)
00495 buff.write(struct.pack('<I%ss'%length, length, _x))
00496 _x = self
00497 buff.write(_struct_3I.pack(_x.disparity_image.image.header.seq, _x.disparity_image.image.header.stamp.secs, _x.disparity_image.image.header.stamp.nsecs))
00498 _x = self.disparity_image.image.header.frame_id
00499 length = len(_x)
00500 if python3 or type(_x) == unicode:
00501 _x = _x.encode('utf-8')
00502 length = len(_x)
00503 buff.write(struct.pack('<I%ss'%length, length, _x))
00504 _x = self
00505 buff.write(_struct_2I.pack(_x.disparity_image.image.height, _x.disparity_image.image.width))
00506 _x = self.disparity_image.image.encoding
00507 length = len(_x)
00508 if python3 or type(_x) == unicode:
00509 _x = _x.encode('utf-8')
00510 length = len(_x)
00511 buff.write(struct.pack('<I%ss'%length, length, _x))
00512 _x = self
00513 buff.write(_struct_BI.pack(_x.disparity_image.image.is_bigendian, _x.disparity_image.image.step))
00514 _x = self.disparity_image.image.data
00515 length = len(_x)
00516
00517 if type(_x) in [list, tuple]:
00518 buff.write(struct.pack('<I%sB'%length, length, *_x))
00519 else:
00520 buff.write(struct.pack('<I%ss'%length, length, _x))
00521 _x = self
00522 buff.write(_struct_2f4IB3f.pack(_x.disparity_image.f, _x.disparity_image.T, _x.disparity_image.valid_window.x_offset, _x.disparity_image.valid_window.y_offset, _x.disparity_image.valid_window.height, _x.disparity_image.valid_window.width, _x.disparity_image.valid_window.do_rectify, _x.disparity_image.min_disparity, _x.disparity_image.max_disparity, _x.disparity_image.delta_d))
00523 except struct.error as se: self._check_types(se)
00524 except TypeError as te: self._check_types(te)
00525
00526 def deserialize(self, str):
00527 """
00528 unpack serialized message in str into this message instance
00529 :param str: byte array of serialized message, ``str``
00530 """
00531 try:
00532 if self.image is None:
00533 self.image = sensor_msgs.msg.Image()
00534 if self.camera_info is None:
00535 self.camera_info = sensor_msgs.msg.CameraInfo()
00536 if self.wide_field is None:
00537 self.wide_field = sensor_msgs.msg.Image()
00538 if self.wide_camera_info is None:
00539 self.wide_camera_info = sensor_msgs.msg.CameraInfo()
00540 if self.point_cloud is None:
00541 self.point_cloud = sensor_msgs.msg.PointCloud2()
00542 if self.disparity_image is None:
00543 self.disparity_image = stereo_msgs.msg.DisparityImage()
00544 end = 0
00545 _x = self
00546 start = end
00547 end += 12
00548 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00549 start = end
00550 end += 4
00551 (length,) = _struct_I.unpack(str[start:end])
00552 start = end
00553 end += length
00554 if python3:
00555 self.image.header.frame_id = str[start:end].decode('utf-8')
00556 else:
00557 self.image.header.frame_id = str[start:end]
00558 _x = self
00559 start = end
00560 end += 8
00561 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00562 start = end
00563 end += 4
00564 (length,) = _struct_I.unpack(str[start:end])
00565 start = end
00566 end += length
00567 if python3:
00568 self.image.encoding = str[start:end].decode('utf-8')
00569 else:
00570 self.image.encoding = str[start:end]
00571 _x = self
00572 start = end
00573 end += 5
00574 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00575 start = end
00576 end += 4
00577 (length,) = _struct_I.unpack(str[start:end])
00578 start = end
00579 end += length
00580 if python3:
00581 self.image.data = str[start:end].decode('utf-8')
00582 else:
00583 self.image.data = str[start:end]
00584 _x = self
00585 start = end
00586 end += 12
00587 (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00588 start = end
00589 end += 4
00590 (length,) = _struct_I.unpack(str[start:end])
00591 start = end
00592 end += length
00593 if python3:
00594 self.camera_info.header.frame_id = str[start:end].decode('utf-8')
00595 else:
00596 self.camera_info.header.frame_id = str[start:end]
00597 _x = self
00598 start = end
00599 end += 8
00600 (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end])
00601 start = end
00602 end += 4
00603 (length,) = _struct_I.unpack(str[start:end])
00604 start = end
00605 end += length
00606 if python3:
00607 self.camera_info.distortion_model = str[start:end].decode('utf-8')
00608 else:
00609 self.camera_info.distortion_model = str[start:end]
00610 start = end
00611 end += 4
00612 (length,) = _struct_I.unpack(str[start:end])
00613 pattern = '<%sd'%length
00614 start = end
00615 end += struct.calcsize(pattern)
00616 self.camera_info.D = struct.unpack(pattern, str[start:end])
00617 start = end
00618 end += 72
00619 self.camera_info.K = _struct_9d.unpack(str[start:end])
00620 start = end
00621 end += 72
00622 self.camera_info.R = _struct_9d.unpack(str[start:end])
00623 start = end
00624 end += 96
00625 self.camera_info.P = _struct_12d.unpack(str[start:end])
00626 _x = self
00627 start = end
00628 end += 37
00629 (_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.wide_field.header.seq, _x.wide_field.header.stamp.secs, _x.wide_field.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00630 self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify)
00631 start = end
00632 end += 4
00633 (length,) = _struct_I.unpack(str[start:end])
00634 start = end
00635 end += length
00636 if python3:
00637 self.wide_field.header.frame_id = str[start:end].decode('utf-8')
00638 else:
00639 self.wide_field.header.frame_id = str[start:end]
00640 _x = self
00641 start = end
00642 end += 8
00643 (_x.wide_field.height, _x.wide_field.width,) = _struct_2I.unpack(str[start:end])
00644 start = end
00645 end += 4
00646 (length,) = _struct_I.unpack(str[start:end])
00647 start = end
00648 end += length
00649 if python3:
00650 self.wide_field.encoding = str[start:end].decode('utf-8')
00651 else:
00652 self.wide_field.encoding = str[start:end]
00653 _x = self
00654 start = end
00655 end += 5
00656 (_x.wide_field.is_bigendian, _x.wide_field.step,) = _struct_BI.unpack(str[start:end])
00657 start = end
00658 end += 4
00659 (length,) = _struct_I.unpack(str[start:end])
00660 start = end
00661 end += length
00662 if python3:
00663 self.wide_field.data = str[start:end].decode('utf-8')
00664 else:
00665 self.wide_field.data = str[start:end]
00666 _x = self
00667 start = end
00668 end += 12
00669 (_x.wide_camera_info.header.seq, _x.wide_camera_info.header.stamp.secs, _x.wide_camera_info.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.wide_camera_info.header.frame_id = str[start:end].decode('utf-8')
00677 else:
00678 self.wide_camera_info.header.frame_id = str[start:end]
00679 _x = self
00680 start = end
00681 end += 8
00682 (_x.wide_camera_info.height, _x.wide_camera_info.width,) = _struct_2I.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.wide_camera_info.distortion_model = str[start:end].decode('utf-8')
00690 else:
00691 self.wide_camera_info.distortion_model = str[start:end]
00692 start = end
00693 end += 4
00694 (length,) = _struct_I.unpack(str[start:end])
00695 pattern = '<%sd'%length
00696 start = end
00697 end += struct.calcsize(pattern)
00698 self.wide_camera_info.D = struct.unpack(pattern, str[start:end])
00699 start = end
00700 end += 72
00701 self.wide_camera_info.K = _struct_9d.unpack(str[start:end])
00702 start = end
00703 end += 72
00704 self.wide_camera_info.R = _struct_9d.unpack(str[start:end])
00705 start = end
00706 end += 96
00707 self.wide_camera_info.P = _struct_12d.unpack(str[start:end])
00708 _x = self
00709 start = end
00710 end += 37
00711 (_x.wide_camera_info.binning_x, _x.wide_camera_info.binning_y, _x.wide_camera_info.roi.x_offset, _x.wide_camera_info.roi.y_offset, _x.wide_camera_info.roi.height, _x.wide_camera_info.roi.width, _x.wide_camera_info.roi.do_rectify, _x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
00712 self.wide_camera_info.roi.do_rectify = bool(self.wide_camera_info.roi.do_rectify)
00713 start = end
00714 end += 4
00715 (length,) = _struct_I.unpack(str[start:end])
00716 start = end
00717 end += length
00718 if python3:
00719 self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
00720 else:
00721 self.point_cloud.header.frame_id = str[start:end]
00722 _x = self
00723 start = end
00724 end += 8
00725 (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
00726 start = end
00727 end += 4
00728 (length,) = _struct_I.unpack(str[start:end])
00729 self.point_cloud.fields = []
00730 for i in range(0, length):
00731 val1 = sensor_msgs.msg.PointField()
00732 start = end
00733 end += 4
00734 (length,) = _struct_I.unpack(str[start:end])
00735 start = end
00736 end += length
00737 if python3:
00738 val1.name = str[start:end].decode('utf-8')
00739 else:
00740 val1.name = str[start:end]
00741 _x = val1
00742 start = end
00743 end += 9
00744 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00745 self.point_cloud.fields.append(val1)
00746 _x = self
00747 start = end
00748 end += 9
00749 (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00750 self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
00751 start = end
00752 end += 4
00753 (length,) = _struct_I.unpack(str[start:end])
00754 start = end
00755 end += length
00756 if python3:
00757 self.point_cloud.data = str[start:end].decode('utf-8')
00758 else:
00759 self.point_cloud.data = str[start:end]
00760 _x = self
00761 start = end
00762 end += 13
00763 (_x.point_cloud.is_dense, _x.disparity_image.header.seq, _x.disparity_image.header.stamp.secs, _x.disparity_image.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00764 self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
00765 start = end
00766 end += 4
00767 (length,) = _struct_I.unpack(str[start:end])
00768 start = end
00769 end += length
00770 if python3:
00771 self.disparity_image.header.frame_id = str[start:end].decode('utf-8')
00772 else:
00773 self.disparity_image.header.frame_id = str[start:end]
00774 _x = self
00775 start = end
00776 end += 12
00777 (_x.disparity_image.image.header.seq, _x.disparity_image.image.header.stamp.secs, _x.disparity_image.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00778 start = end
00779 end += 4
00780 (length,) = _struct_I.unpack(str[start:end])
00781 start = end
00782 end += length
00783 if python3:
00784 self.disparity_image.image.header.frame_id = str[start:end].decode('utf-8')
00785 else:
00786 self.disparity_image.image.header.frame_id = str[start:end]
00787 _x = self
00788 start = end
00789 end += 8
00790 (_x.disparity_image.image.height, _x.disparity_image.image.width,) = _struct_2I.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.disparity_image.image.encoding = str[start:end].decode('utf-8')
00798 else:
00799 self.disparity_image.image.encoding = str[start:end]
00800 _x = self
00801 start = end
00802 end += 5
00803 (_x.disparity_image.image.is_bigendian, _x.disparity_image.image.step,) = _struct_BI.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.disparity_image.image.data = str[start:end].decode('utf-8')
00811 else:
00812 self.disparity_image.image.data = str[start:end]
00813 _x = self
00814 start = end
00815 end += 37
00816 (_x.disparity_image.f, _x.disparity_image.T, _x.disparity_image.valid_window.x_offset, _x.disparity_image.valid_window.y_offset, _x.disparity_image.valid_window.height, _x.disparity_image.valid_window.width, _x.disparity_image.valid_window.do_rectify, _x.disparity_image.min_disparity, _x.disparity_image.max_disparity, _x.disparity_image.delta_d,) = _struct_2f4IB3f.unpack(str[start:end])
00817 self.disparity_image.valid_window.do_rectify = bool(self.disparity_image.valid_window.do_rectify)
00818 return self
00819 except struct.error as e:
00820 raise genpy.DeserializationError(e)
00821
00822
00823 def serialize_numpy(self, buff, numpy):
00824 """
00825 serialize message with numpy array types into buffer
00826 :param buff: buffer, ``StringIO``
00827 :param numpy: numpy python module
00828 """
00829 try:
00830 _x = self
00831 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00832 _x = self.image.header.frame_id
00833 length = len(_x)
00834 if python3 or type(_x) == unicode:
00835 _x = _x.encode('utf-8')
00836 length = len(_x)
00837 buff.write(struct.pack('<I%ss'%length, length, _x))
00838 _x = self
00839 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00840 _x = self.image.encoding
00841 length = len(_x)
00842 if python3 or type(_x) == unicode:
00843 _x = _x.encode('utf-8')
00844 length = len(_x)
00845 buff.write(struct.pack('<I%ss'%length, length, _x))
00846 _x = self
00847 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00848 _x = self.image.data
00849 length = len(_x)
00850
00851 if type(_x) in [list, tuple]:
00852 buff.write(struct.pack('<I%sB'%length, length, *_x))
00853 else:
00854 buff.write(struct.pack('<I%ss'%length, length, _x))
00855 _x = self
00856 buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs))
00857 _x = self.camera_info.header.frame_id
00858 length = len(_x)
00859 if python3 or type(_x) == unicode:
00860 _x = _x.encode('utf-8')
00861 length = len(_x)
00862 buff.write(struct.pack('<I%ss'%length, length, _x))
00863 _x = self
00864 buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width))
00865 _x = self.camera_info.distortion_model
00866 length = len(_x)
00867 if python3 or type(_x) == unicode:
00868 _x = _x.encode('utf-8')
00869 length = len(_x)
00870 buff.write(struct.pack('<I%ss'%length, length, _x))
00871 length = len(self.camera_info.D)
00872 buff.write(_struct_I.pack(length))
00873 pattern = '<%sd'%length
00874 buff.write(self.camera_info.D.tostring())
00875 buff.write(self.camera_info.K.tostring())
00876 buff.write(self.camera_info.R.tostring())
00877 buff.write(self.camera_info.P.tostring())
00878 _x = self
00879 buff.write(_struct_6IB3I.pack(_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.wide_field.header.seq, _x.wide_field.header.stamp.secs, _x.wide_field.header.stamp.nsecs))
00880 _x = self.wide_field.header.frame_id
00881 length = len(_x)
00882 if python3 or type(_x) == unicode:
00883 _x = _x.encode('utf-8')
00884 length = len(_x)
00885 buff.write(struct.pack('<I%ss'%length, length, _x))
00886 _x = self
00887 buff.write(_struct_2I.pack(_x.wide_field.height, _x.wide_field.width))
00888 _x = self.wide_field.encoding
00889 length = len(_x)
00890 if python3 or type(_x) == unicode:
00891 _x = _x.encode('utf-8')
00892 length = len(_x)
00893 buff.write(struct.pack('<I%ss'%length, length, _x))
00894 _x = self
00895 buff.write(_struct_BI.pack(_x.wide_field.is_bigendian, _x.wide_field.step))
00896 _x = self.wide_field.data
00897 length = len(_x)
00898
00899 if type(_x) in [list, tuple]:
00900 buff.write(struct.pack('<I%sB'%length, length, *_x))
00901 else:
00902 buff.write(struct.pack('<I%ss'%length, length, _x))
00903 _x = self
00904 buff.write(_struct_3I.pack(_x.wide_camera_info.header.seq, _x.wide_camera_info.header.stamp.secs, _x.wide_camera_info.header.stamp.nsecs))
00905 _x = self.wide_camera_info.header.frame_id
00906 length = len(_x)
00907 if python3 or type(_x) == unicode:
00908 _x = _x.encode('utf-8')
00909 length = len(_x)
00910 buff.write(struct.pack('<I%ss'%length, length, _x))
00911 _x = self
00912 buff.write(_struct_2I.pack(_x.wide_camera_info.height, _x.wide_camera_info.width))
00913 _x = self.wide_camera_info.distortion_model
00914 length = len(_x)
00915 if python3 or type(_x) == unicode:
00916 _x = _x.encode('utf-8')
00917 length = len(_x)
00918 buff.write(struct.pack('<I%ss'%length, length, _x))
00919 length = len(self.wide_camera_info.D)
00920 buff.write(_struct_I.pack(length))
00921 pattern = '<%sd'%length
00922 buff.write(self.wide_camera_info.D.tostring())
00923 buff.write(self.wide_camera_info.K.tostring())
00924 buff.write(self.wide_camera_info.R.tostring())
00925 buff.write(self.wide_camera_info.P.tostring())
00926 _x = self
00927 buff.write(_struct_6IB3I.pack(_x.wide_camera_info.binning_x, _x.wide_camera_info.binning_y, _x.wide_camera_info.roi.x_offset, _x.wide_camera_info.roi.y_offset, _x.wide_camera_info.roi.height, _x.wide_camera_info.roi.width, _x.wide_camera_info.roi.do_rectify, _x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
00928 _x = self.point_cloud.header.frame_id
00929 length = len(_x)
00930 if python3 or type(_x) == unicode:
00931 _x = _x.encode('utf-8')
00932 length = len(_x)
00933 buff.write(struct.pack('<I%ss'%length, length, _x))
00934 _x = self
00935 buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
00936 length = len(self.point_cloud.fields)
00937 buff.write(_struct_I.pack(length))
00938 for val1 in self.point_cloud.fields:
00939 _x = val1.name
00940 length = len(_x)
00941 if python3 or type(_x) == unicode:
00942 _x = _x.encode('utf-8')
00943 length = len(_x)
00944 buff.write(struct.pack('<I%ss'%length, length, _x))
00945 _x = val1
00946 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00947 _x = self
00948 buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
00949 _x = self.point_cloud.data
00950 length = len(_x)
00951
00952 if type(_x) in [list, tuple]:
00953 buff.write(struct.pack('<I%sB'%length, length, *_x))
00954 else:
00955 buff.write(struct.pack('<I%ss'%length, length, _x))
00956 _x = self
00957 buff.write(_struct_B3I.pack(_x.point_cloud.is_dense, _x.disparity_image.header.seq, _x.disparity_image.header.stamp.secs, _x.disparity_image.header.stamp.nsecs))
00958 _x = self.disparity_image.header.frame_id
00959 length = len(_x)
00960 if python3 or type(_x) == unicode:
00961 _x = _x.encode('utf-8')
00962 length = len(_x)
00963 buff.write(struct.pack('<I%ss'%length, length, _x))
00964 _x = self
00965 buff.write(_struct_3I.pack(_x.disparity_image.image.header.seq, _x.disparity_image.image.header.stamp.secs, _x.disparity_image.image.header.stamp.nsecs))
00966 _x = self.disparity_image.image.header.frame_id
00967 length = len(_x)
00968 if python3 or type(_x) == unicode:
00969 _x = _x.encode('utf-8')
00970 length = len(_x)
00971 buff.write(struct.pack('<I%ss'%length, length, _x))
00972 _x = self
00973 buff.write(_struct_2I.pack(_x.disparity_image.image.height, _x.disparity_image.image.width))
00974 _x = self.disparity_image.image.encoding
00975 length = len(_x)
00976 if python3 or type(_x) == unicode:
00977 _x = _x.encode('utf-8')
00978 length = len(_x)
00979 buff.write(struct.pack('<I%ss'%length, length, _x))
00980 _x = self
00981 buff.write(_struct_BI.pack(_x.disparity_image.image.is_bigendian, _x.disparity_image.image.step))
00982 _x = self.disparity_image.image.data
00983 length = len(_x)
00984
00985 if type(_x) in [list, tuple]:
00986 buff.write(struct.pack('<I%sB'%length, length, *_x))
00987 else:
00988 buff.write(struct.pack('<I%ss'%length, length, _x))
00989 _x = self
00990 buff.write(_struct_2f4IB3f.pack(_x.disparity_image.f, _x.disparity_image.T, _x.disparity_image.valid_window.x_offset, _x.disparity_image.valid_window.y_offset, _x.disparity_image.valid_window.height, _x.disparity_image.valid_window.width, _x.disparity_image.valid_window.do_rectify, _x.disparity_image.min_disparity, _x.disparity_image.max_disparity, _x.disparity_image.delta_d))
00991 except struct.error as se: self._check_types(se)
00992 except TypeError as te: self._check_types(te)
00993
00994 def deserialize_numpy(self, str, numpy):
00995 """
00996 unpack serialized message in str into this message instance using numpy for array types
00997 :param str: byte array of serialized message, ``str``
00998 :param numpy: numpy python module
00999 """
01000 try:
01001 if self.image is None:
01002 self.image = sensor_msgs.msg.Image()
01003 if self.camera_info is None:
01004 self.camera_info = sensor_msgs.msg.CameraInfo()
01005 if self.wide_field is None:
01006 self.wide_field = sensor_msgs.msg.Image()
01007 if self.wide_camera_info is None:
01008 self.wide_camera_info = sensor_msgs.msg.CameraInfo()
01009 if self.point_cloud is None:
01010 self.point_cloud = sensor_msgs.msg.PointCloud2()
01011 if self.disparity_image is None:
01012 self.disparity_image = stereo_msgs.msg.DisparityImage()
01013 end = 0
01014 _x = self
01015 start = end
01016 end += 12
01017 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01018 start = end
01019 end += 4
01020 (length,) = _struct_I.unpack(str[start:end])
01021 start = end
01022 end += length
01023 if python3:
01024 self.image.header.frame_id = str[start:end].decode('utf-8')
01025 else:
01026 self.image.header.frame_id = str[start:end]
01027 _x = self
01028 start = end
01029 end += 8
01030 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
01031 start = end
01032 end += 4
01033 (length,) = _struct_I.unpack(str[start:end])
01034 start = end
01035 end += length
01036 if python3:
01037 self.image.encoding = str[start:end].decode('utf-8')
01038 else:
01039 self.image.encoding = str[start:end]
01040 _x = self
01041 start = end
01042 end += 5
01043 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
01044 start = end
01045 end += 4
01046 (length,) = _struct_I.unpack(str[start:end])
01047 start = end
01048 end += length
01049 if python3:
01050 self.image.data = str[start:end].decode('utf-8')
01051 else:
01052 self.image.data = str[start:end]
01053 _x = self
01054 start = end
01055 end += 12
01056 (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01057 start = end
01058 end += 4
01059 (length,) = _struct_I.unpack(str[start:end])
01060 start = end
01061 end += length
01062 if python3:
01063 self.camera_info.header.frame_id = str[start:end].decode('utf-8')
01064 else:
01065 self.camera_info.header.frame_id = str[start:end]
01066 _x = self
01067 start = end
01068 end += 8
01069 (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end])
01070 start = end
01071 end += 4
01072 (length,) = _struct_I.unpack(str[start:end])
01073 start = end
01074 end += length
01075 if python3:
01076 self.camera_info.distortion_model = str[start:end].decode('utf-8')
01077 else:
01078 self.camera_info.distortion_model = str[start:end]
01079 start = end
01080 end += 4
01081 (length,) = _struct_I.unpack(str[start:end])
01082 pattern = '<%sd'%length
01083 start = end
01084 end += struct.calcsize(pattern)
01085 self.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01086 start = end
01087 end += 72
01088 self.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01089 start = end
01090 end += 72
01091 self.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01092 start = end
01093 end += 96
01094 self.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01095 _x = self
01096 start = end
01097 end += 37
01098 (_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.wide_field.header.seq, _x.wide_field.header.stamp.secs, _x.wide_field.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01099 self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify)
01100 start = end
01101 end += 4
01102 (length,) = _struct_I.unpack(str[start:end])
01103 start = end
01104 end += length
01105 if python3:
01106 self.wide_field.header.frame_id = str[start:end].decode('utf-8')
01107 else:
01108 self.wide_field.header.frame_id = str[start:end]
01109 _x = self
01110 start = end
01111 end += 8
01112 (_x.wide_field.height, _x.wide_field.width,) = _struct_2I.unpack(str[start:end])
01113 start = end
01114 end += 4
01115 (length,) = _struct_I.unpack(str[start:end])
01116 start = end
01117 end += length
01118 if python3:
01119 self.wide_field.encoding = str[start:end].decode('utf-8')
01120 else:
01121 self.wide_field.encoding = str[start:end]
01122 _x = self
01123 start = end
01124 end += 5
01125 (_x.wide_field.is_bigendian, _x.wide_field.step,) = _struct_BI.unpack(str[start:end])
01126 start = end
01127 end += 4
01128 (length,) = _struct_I.unpack(str[start:end])
01129 start = end
01130 end += length
01131 if python3:
01132 self.wide_field.data = str[start:end].decode('utf-8')
01133 else:
01134 self.wide_field.data = str[start:end]
01135 _x = self
01136 start = end
01137 end += 12
01138 (_x.wide_camera_info.header.seq, _x.wide_camera_info.header.stamp.secs, _x.wide_camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01139 start = end
01140 end += 4
01141 (length,) = _struct_I.unpack(str[start:end])
01142 start = end
01143 end += length
01144 if python3:
01145 self.wide_camera_info.header.frame_id = str[start:end].decode('utf-8')
01146 else:
01147 self.wide_camera_info.header.frame_id = str[start:end]
01148 _x = self
01149 start = end
01150 end += 8
01151 (_x.wide_camera_info.height, _x.wide_camera_info.width,) = _struct_2I.unpack(str[start:end])
01152 start = end
01153 end += 4
01154 (length,) = _struct_I.unpack(str[start:end])
01155 start = end
01156 end += length
01157 if python3:
01158 self.wide_camera_info.distortion_model = str[start:end].decode('utf-8')
01159 else:
01160 self.wide_camera_info.distortion_model = str[start:end]
01161 start = end
01162 end += 4
01163 (length,) = _struct_I.unpack(str[start:end])
01164 pattern = '<%sd'%length
01165 start = end
01166 end += struct.calcsize(pattern)
01167 self.wide_camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01168 start = end
01169 end += 72
01170 self.wide_camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01171 start = end
01172 end += 72
01173 self.wide_camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
01174 start = end
01175 end += 96
01176 self.wide_camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
01177 _x = self
01178 start = end
01179 end += 37
01180 (_x.wide_camera_info.binning_x, _x.wide_camera_info.binning_y, _x.wide_camera_info.roi.x_offset, _x.wide_camera_info.roi.y_offset, _x.wide_camera_info.roi.height, _x.wide_camera_info.roi.width, _x.wide_camera_info.roi.do_rectify, _x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_6IB3I.unpack(str[start:end])
01181 self.wide_camera_info.roi.do_rectify = bool(self.wide_camera_info.roi.do_rectify)
01182 start = end
01183 end += 4
01184 (length,) = _struct_I.unpack(str[start:end])
01185 start = end
01186 end += length
01187 if python3:
01188 self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
01189 else:
01190 self.point_cloud.header.frame_id = str[start:end]
01191 _x = self
01192 start = end
01193 end += 8
01194 (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
01195 start = end
01196 end += 4
01197 (length,) = _struct_I.unpack(str[start:end])
01198 self.point_cloud.fields = []
01199 for i in range(0, length):
01200 val1 = sensor_msgs.msg.PointField()
01201 start = end
01202 end += 4
01203 (length,) = _struct_I.unpack(str[start:end])
01204 start = end
01205 end += length
01206 if python3:
01207 val1.name = str[start:end].decode('utf-8')
01208 else:
01209 val1.name = str[start:end]
01210 _x = val1
01211 start = end
01212 end += 9
01213 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
01214 self.point_cloud.fields.append(val1)
01215 _x = self
01216 start = end
01217 end += 9
01218 (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
01219 self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
01220 start = end
01221 end += 4
01222 (length,) = _struct_I.unpack(str[start:end])
01223 start = end
01224 end += length
01225 if python3:
01226 self.point_cloud.data = str[start:end].decode('utf-8')
01227 else:
01228 self.point_cloud.data = str[start:end]
01229 _x = self
01230 start = end
01231 end += 13
01232 (_x.point_cloud.is_dense, _x.disparity_image.header.seq, _x.disparity_image.header.stamp.secs, _x.disparity_image.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01233 self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
01234 start = end
01235 end += 4
01236 (length,) = _struct_I.unpack(str[start:end])
01237 start = end
01238 end += length
01239 if python3:
01240 self.disparity_image.header.frame_id = str[start:end].decode('utf-8')
01241 else:
01242 self.disparity_image.header.frame_id = str[start:end]
01243 _x = self
01244 start = end
01245 end += 12
01246 (_x.disparity_image.image.header.seq, _x.disparity_image.image.header.stamp.secs, _x.disparity_image.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01247 start = end
01248 end += 4
01249 (length,) = _struct_I.unpack(str[start:end])
01250 start = end
01251 end += length
01252 if python3:
01253 self.disparity_image.image.header.frame_id = str[start:end].decode('utf-8')
01254 else:
01255 self.disparity_image.image.header.frame_id = str[start:end]
01256 _x = self
01257 start = end
01258 end += 8
01259 (_x.disparity_image.image.height, _x.disparity_image.image.width,) = _struct_2I.unpack(str[start:end])
01260 start = end
01261 end += 4
01262 (length,) = _struct_I.unpack(str[start:end])
01263 start = end
01264 end += length
01265 if python3:
01266 self.disparity_image.image.encoding = str[start:end].decode('utf-8')
01267 else:
01268 self.disparity_image.image.encoding = str[start:end]
01269 _x = self
01270 start = end
01271 end += 5
01272 (_x.disparity_image.image.is_bigendian, _x.disparity_image.image.step,) = _struct_BI.unpack(str[start:end])
01273 start = end
01274 end += 4
01275 (length,) = _struct_I.unpack(str[start:end])
01276 start = end
01277 end += length
01278 if python3:
01279 self.disparity_image.image.data = str[start:end].decode('utf-8')
01280 else:
01281 self.disparity_image.image.data = str[start:end]
01282 _x = self
01283 start = end
01284 end += 37
01285 (_x.disparity_image.f, _x.disparity_image.T, _x.disparity_image.valid_window.x_offset, _x.disparity_image.valid_window.y_offset, _x.disparity_image.valid_window.height, _x.disparity_image.valid_window.width, _x.disparity_image.valid_window.do_rectify, _x.disparity_image.min_disparity, _x.disparity_image.max_disparity, _x.disparity_image.delta_d,) = _struct_2f4IB3f.unpack(str[start:end])
01286 self.disparity_image.valid_window.do_rectify = bool(self.disparity_image.valid_window.do_rectify)
01287 return self
01288 except struct.error as e:
01289 raise genpy.DeserializationError(e)
01290
01291 _struct_I = genpy.struct_I
01292 _struct_IBI = struct.Struct("<IBI")
01293 _struct_6IB3I = struct.Struct("<6IB3I")
01294 _struct_12d = struct.Struct("<12d")
01295 _struct_2f4IB3f = struct.Struct("<2f4IB3f")
01296 _struct_9d = struct.Struct("<9d")
01297 _struct_BI = struct.Struct("<BI")
01298 _struct_3I = struct.Struct("<3I")
01299 _struct_B3I = struct.Struct("<B3I")
01300 _struct_B2I = struct.Struct("<B2I")
01301 _struct_2I = struct.Struct("<2I")