00001 """autogenerated by genpy from calibration_msgs/CameraMeasurement.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import sensor_msgs.msg
00008 import geometry_msgs.msg
00009 import calibration_msgs.msg
00010 import std_msgs.msg
00011
00012 class CameraMeasurement(genpy.Message):
00013 _md5sum = "f7a0cca96cdd8e17d1424338e086252f"
00014 _type = "calibration_msgs/CameraMeasurement"
00015 _has_header = True
00016 _full_text = """Header header
00017 string camera_id
00018 geometry_msgs/Point[] image_points
00019 sensor_msgs/CameraInfo cam_info
00020
00021 # True -> The extra debugging fields are populated
00022 bool verbose
00023
00024 # Extra, partially processed data. Only needed for debugging
00025 sensor_msgs/Image image
00026 sensor_msgs/Image image_rect
00027 calibration_msgs/CalibrationPattern features
00028
00029 ================================================================================
00030 MSG: std_msgs/Header
00031 # Standard metadata for higher-level stamped data types.
00032 # This is generally used to communicate timestamped data
00033 # in a particular coordinate frame.
00034 #
00035 # sequence ID: consecutively increasing ID
00036 uint32 seq
00037 #Two-integer timestamp that is expressed as:
00038 # * stamp.secs: seconds (stamp_secs) since epoch
00039 # * stamp.nsecs: nanoseconds since stamp_secs
00040 # time-handling sugar is provided by the client library
00041 time stamp
00042 #Frame this data is associated with
00043 # 0: no frame
00044 # 1: global frame
00045 string frame_id
00046
00047 ================================================================================
00048 MSG: geometry_msgs/Point
00049 # This contains the position of a point in free space
00050 float64 x
00051 float64 y
00052 float64 z
00053
00054 ================================================================================
00055 MSG: sensor_msgs/CameraInfo
00056 # This message defines meta information for a camera. It should be in a
00057 # camera namespace on topic "camera_info" and accompanied by up to five
00058 # image topics named:
00059 #
00060 # image_raw - raw data from the camera driver, possibly Bayer encoded
00061 # image - monochrome, distorted
00062 # image_color - color, distorted
00063 # image_rect - monochrome, rectified
00064 # image_rect_color - color, rectified
00065 #
00066 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00067 # for producing the four processed image topics from image_raw and
00068 # camera_info. The meaning of the camera parameters are described in
00069 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00070 #
00071 # The image_geometry package provides a user-friendly interface to
00072 # common operations using this meta information. If you want to, e.g.,
00073 # project a 3d point into image coordinates, we strongly recommend
00074 # using image_geometry.
00075 #
00076 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00077 # zeroed out. In particular, clients may assume that K[0] == 0.0
00078 # indicates an uncalibrated camera.
00079
00080 #######################################################################
00081 # Image acquisition info #
00082 #######################################################################
00083
00084 # Time of image acquisition, camera coordinate frame ID
00085 Header header # Header timestamp should be acquisition time of image
00086 # Header frame_id should be optical frame of camera
00087 # origin of frame should be optical center of camera
00088 # +x should point to the right in the image
00089 # +y should point down in the image
00090 # +z should point into the plane of the image
00091
00092
00093 #######################################################################
00094 # Calibration Parameters #
00095 #######################################################################
00096 # These are fixed during camera calibration. Their values will be the #
00097 # same in all messages until the camera is recalibrated. Note that #
00098 # self-calibrating systems may "recalibrate" frequently. #
00099 # #
00100 # The internal parameters can be used to warp a raw (distorted) image #
00101 # to: #
00102 # 1. An undistorted image (requires D and K) #
00103 # 2. A rectified image (requires D, K, R) #
00104 # The projection matrix P projects 3D points into the rectified image.#
00105 #######################################################################
00106
00107 # The image dimensions with which the camera was calibrated. Normally
00108 # this will be the full camera resolution in pixels.
00109 uint32 height
00110 uint32 width
00111
00112 # The distortion model used. Supported models are listed in
00113 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00114 # simple model of radial and tangential distortion - is sufficent.
00115 string distortion_model
00116
00117 # The distortion parameters, size depending on the distortion model.
00118 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00119 float64[] D
00120
00121 # Intrinsic camera matrix for the raw (distorted) images.
00122 # [fx 0 cx]
00123 # K = [ 0 fy cy]
00124 # [ 0 0 1]
00125 # Projects 3D points in the camera coordinate frame to 2D pixel
00126 # coordinates using the focal lengths (fx, fy) and principal point
00127 # (cx, cy).
00128 float64[9] K # 3x3 row-major matrix
00129
00130 # Rectification matrix (stereo cameras only)
00131 # A rotation matrix aligning the camera coordinate system to the ideal
00132 # stereo image plane so that epipolar lines in both stereo images are
00133 # parallel.
00134 float64[9] R # 3x3 row-major matrix
00135
00136 # Projection/camera matrix
00137 # [fx' 0 cx' Tx]
00138 # P = [ 0 fy' cy' Ty]
00139 # [ 0 0 1 0]
00140 # By convention, this matrix specifies the intrinsic (camera) matrix
00141 # of the processed (rectified) image. That is, the left 3x3 portion
00142 # is the normal camera intrinsic matrix for the rectified image.
00143 # It projects 3D points in the camera coordinate frame to 2D pixel
00144 # coordinates using the focal lengths (fx', fy') and principal point
00145 # (cx', cy') - these may differ from the values in K.
00146 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00147 # also have R = the identity and P[1:3,1:3] = K.
00148 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00149 # position of the optical center of the second camera in the first
00150 # camera's frame. We assume Tz = 0 so both cameras are in the same
00151 # stereo image plane. The first camera always has Tx = Ty = 0. For
00152 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00153 # Tx = -fx' * B, where B is the baseline between the cameras.
00154 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00155 # the rectified image is given by:
00156 # [u v w]' = P * [X Y Z 1]'
00157 # x = u / w
00158 # y = v / w
00159 # This holds for both images of a stereo pair.
00160 float64[12] P # 3x4 row-major matrix
00161
00162
00163 #######################################################################
00164 # Operational Parameters #
00165 #######################################################################
00166 # These define the image region actually captured by the camera #
00167 # driver. Although they affect the geometry of the output image, they #
00168 # may be changed freely without recalibrating the camera. #
00169 #######################################################################
00170
00171 # Binning refers here to any camera setting which combines rectangular
00172 # neighborhoods of pixels into larger "super-pixels." It reduces the
00173 # resolution of the output image to
00174 # (width / binning_x) x (height / binning_y).
00175 # The default values binning_x = binning_y = 0 is considered the same
00176 # as binning_x = binning_y = 1 (no subsampling).
00177 uint32 binning_x
00178 uint32 binning_y
00179
00180 # Region of interest (subwindow of full camera resolution), given in
00181 # full resolution (unbinned) image coordinates. A particular ROI
00182 # always denotes the same window of pixels on the camera sensor,
00183 # regardless of binning settings.
00184 # The default setting of roi (all values 0) is considered the same as
00185 # full resolution (roi.width = width, roi.height = height).
00186 RegionOfInterest roi
00187
00188 ================================================================================
00189 MSG: sensor_msgs/RegionOfInterest
00190 # This message is used to specify a region of interest within an image.
00191 #
00192 # When used to specify the ROI setting of the camera when the image was
00193 # taken, the height and width fields should either match the height and
00194 # width fields for the associated image; or height = width = 0
00195 # indicates that the full resolution image was captured.
00196
00197 uint32 x_offset # Leftmost pixel of the ROI
00198 # (0 if the ROI includes the left edge of the image)
00199 uint32 y_offset # Topmost pixel of the ROI
00200 # (0 if the ROI includes the top edge of the image)
00201 uint32 height # Height of ROI
00202 uint32 width # Width of ROI
00203
00204 # True if a distinct rectified ROI should be calculated from the "raw"
00205 # ROI in this message. Typically this should be False if the full image
00206 # is captured (ROI not used), and True if a subwindow is captured (ROI
00207 # used).
00208 bool do_rectify
00209
00210 ================================================================================
00211 MSG: sensor_msgs/Image
00212 # This message contains an uncompressed image
00213 # (0, 0) is at top-left corner of image
00214 #
00215
00216 Header header # Header timestamp should be acquisition time of image
00217 # Header frame_id should be optical frame of camera
00218 # origin of frame should be optical center of cameara
00219 # +x should point to the right in the image
00220 # +y should point down in the image
00221 # +z should point into to plane of the image
00222 # If the frame_id here and the frame_id of the CameraInfo
00223 # message associated with the image conflict
00224 # the behavior is undefined
00225
00226 uint32 height # image height, that is, number of rows
00227 uint32 width # image width, that is, number of columns
00228
00229 # The legal values for encoding are in file src/image_encodings.cpp
00230 # If you want to standardize a new string format, join
00231 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00232
00233 string encoding # Encoding of pixels -- channel meaning, ordering, size
00234 # taken from the list of strings in src/image_encodings.cpp
00235
00236 uint8 is_bigendian # is this data bigendian?
00237 uint32 step # Full row length in bytes
00238 uint8[] data # actual matrix data, size is (step * rows)
00239
00240 ================================================================================
00241 MSG: calibration_msgs/CalibrationPattern
00242 Header header
00243 geometry_msgs/Point[] object_points
00244 geometry_msgs/Point[] image_points
00245 uint8 success
00246
00247 """
00248 __slots__ = ['header','camera_id','image_points','cam_info','verbose','image','image_rect','features']
00249 _slot_types = ['std_msgs/Header','string','geometry_msgs/Point[]','sensor_msgs/CameraInfo','bool','sensor_msgs/Image','sensor_msgs/Image','calibration_msgs/CalibrationPattern']
00250
00251 def __init__(self, *args, **kwds):
00252 """
00253 Constructor. Any message fields that are implicitly/explicitly
00254 set to None will be assigned a default value. The recommend
00255 use is keyword arguments as this is more robust to future message
00256 changes. You cannot mix in-order arguments and keyword arguments.
00257
00258 The available fields are:
00259 header,camera_id,image_points,cam_info,verbose,image,image_rect,features
00260
00261 :param args: complete set of field values, in .msg order
00262 :param kwds: use keyword arguments corresponding to message field names
00263 to set specific fields.
00264 """
00265 if args or kwds:
00266 super(CameraMeasurement, self).__init__(*args, **kwds)
00267
00268 if self.header is None:
00269 self.header = std_msgs.msg.Header()
00270 if self.camera_id is None:
00271 self.camera_id = ''
00272 if self.image_points is None:
00273 self.image_points = []
00274 if self.cam_info is None:
00275 self.cam_info = sensor_msgs.msg.CameraInfo()
00276 if self.verbose is None:
00277 self.verbose = False
00278 if self.image is None:
00279 self.image = sensor_msgs.msg.Image()
00280 if self.image_rect is None:
00281 self.image_rect = sensor_msgs.msg.Image()
00282 if self.features is None:
00283 self.features = calibration_msgs.msg.CalibrationPattern()
00284 else:
00285 self.header = std_msgs.msg.Header()
00286 self.camera_id = ''
00287 self.image_points = []
00288 self.cam_info = sensor_msgs.msg.CameraInfo()
00289 self.verbose = False
00290 self.image = sensor_msgs.msg.Image()
00291 self.image_rect = sensor_msgs.msg.Image()
00292 self.features = calibration_msgs.msg.CalibrationPattern()
00293
00294 def _get_types(self):
00295 """
00296 internal API method
00297 """
00298 return self._slot_types
00299
00300 def serialize(self, buff):
00301 """
00302 serialize message into buffer
00303 :param buff: buffer, ``StringIO``
00304 """
00305 try:
00306 _x = self
00307 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00308 _x = self.header.frame_id
00309 length = len(_x)
00310 if python3 or type(_x) == unicode:
00311 _x = _x.encode('utf-8')
00312 length = len(_x)
00313 buff.write(struct.pack('<I%ss'%length, length, _x))
00314 _x = self.camera_id
00315 length = len(_x)
00316 if python3 or type(_x) == unicode:
00317 _x = _x.encode('utf-8')
00318 length = len(_x)
00319 buff.write(struct.pack('<I%ss'%length, length, _x))
00320 length = len(self.image_points)
00321 buff.write(_struct_I.pack(length))
00322 for val1 in self.image_points:
00323 _x = val1
00324 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00325 _x = self
00326 buff.write(_struct_3I.pack(_x.cam_info.header.seq, _x.cam_info.header.stamp.secs, _x.cam_info.header.stamp.nsecs))
00327 _x = self.cam_info.header.frame_id
00328 length = len(_x)
00329 if python3 or type(_x) == unicode:
00330 _x = _x.encode('utf-8')
00331 length = len(_x)
00332 buff.write(struct.pack('<I%ss'%length, length, _x))
00333 _x = self
00334 buff.write(_struct_2I.pack(_x.cam_info.height, _x.cam_info.width))
00335 _x = self.cam_info.distortion_model
00336 length = len(_x)
00337 if python3 or type(_x) == unicode:
00338 _x = _x.encode('utf-8')
00339 length = len(_x)
00340 buff.write(struct.pack('<I%ss'%length, length, _x))
00341 length = len(self.cam_info.D)
00342 buff.write(_struct_I.pack(length))
00343 pattern = '<%sd'%length
00344 buff.write(struct.pack(pattern, *self.cam_info.D))
00345 buff.write(_struct_9d.pack(*self.cam_info.K))
00346 buff.write(_struct_9d.pack(*self.cam_info.R))
00347 buff.write(_struct_12d.pack(*self.cam_info.P))
00348 _x = self
00349 buff.write(_struct_6I2B3I.pack(_x.cam_info.binning_x, _x.cam_info.binning_y, _x.cam_info.roi.x_offset, _x.cam_info.roi.y_offset, _x.cam_info.roi.height, _x.cam_info.roi.width, _x.cam_info.roi.do_rectify, _x.verbose, _x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00350 _x = self.image.header.frame_id
00351 length = len(_x)
00352 if python3 or type(_x) == unicode:
00353 _x = _x.encode('utf-8')
00354 length = len(_x)
00355 buff.write(struct.pack('<I%ss'%length, length, _x))
00356 _x = self
00357 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00358 _x = self.image.encoding
00359 length = len(_x)
00360 if python3 or type(_x) == unicode:
00361 _x = _x.encode('utf-8')
00362 length = len(_x)
00363 buff.write(struct.pack('<I%ss'%length, length, _x))
00364 _x = self
00365 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00366 _x = self.image.data
00367 length = len(_x)
00368
00369 if type(_x) in [list, tuple]:
00370 buff.write(struct.pack('<I%sB'%length, length, *_x))
00371 else:
00372 buff.write(struct.pack('<I%ss'%length, length, _x))
00373 _x = self
00374 buff.write(_struct_3I.pack(_x.image_rect.header.seq, _x.image_rect.header.stamp.secs, _x.image_rect.header.stamp.nsecs))
00375 _x = self.image_rect.header.frame_id
00376 length = len(_x)
00377 if python3 or type(_x) == unicode:
00378 _x = _x.encode('utf-8')
00379 length = len(_x)
00380 buff.write(struct.pack('<I%ss'%length, length, _x))
00381 _x = self
00382 buff.write(_struct_2I.pack(_x.image_rect.height, _x.image_rect.width))
00383 _x = self.image_rect.encoding
00384 length = len(_x)
00385 if python3 or type(_x) == unicode:
00386 _x = _x.encode('utf-8')
00387 length = len(_x)
00388 buff.write(struct.pack('<I%ss'%length, length, _x))
00389 _x = self
00390 buff.write(_struct_BI.pack(_x.image_rect.is_bigendian, _x.image_rect.step))
00391 _x = self.image_rect.data
00392 length = len(_x)
00393
00394 if type(_x) in [list, tuple]:
00395 buff.write(struct.pack('<I%sB'%length, length, *_x))
00396 else:
00397 buff.write(struct.pack('<I%ss'%length, length, _x))
00398 _x = self
00399 buff.write(_struct_3I.pack(_x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs))
00400 _x = self.features.header.frame_id
00401 length = len(_x)
00402 if python3 or type(_x) == unicode:
00403 _x = _x.encode('utf-8')
00404 length = len(_x)
00405 buff.write(struct.pack('<I%ss'%length, length, _x))
00406 length = len(self.features.object_points)
00407 buff.write(_struct_I.pack(length))
00408 for val1 in self.features.object_points:
00409 _x = val1
00410 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00411 length = len(self.features.image_points)
00412 buff.write(_struct_I.pack(length))
00413 for val1 in self.features.image_points:
00414 _x = val1
00415 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00416 buff.write(_struct_B.pack(self.features.success))
00417 except struct.error as se: self._check_types(se)
00418 except TypeError as te: self._check_types(te)
00419
00420 def deserialize(self, str):
00421 """
00422 unpack serialized message in str into this message instance
00423 :param str: byte array of serialized message, ``str``
00424 """
00425 try:
00426 if self.header is None:
00427 self.header = std_msgs.msg.Header()
00428 if self.image_points is None:
00429 self.image_points = None
00430 if self.cam_info is None:
00431 self.cam_info = sensor_msgs.msg.CameraInfo()
00432 if self.image is None:
00433 self.image = sensor_msgs.msg.Image()
00434 if self.image_rect is None:
00435 self.image_rect = sensor_msgs.msg.Image()
00436 if self.features is None:
00437 self.features = calibration_msgs.msg.CalibrationPattern()
00438 end = 0
00439 _x = self
00440 start = end
00441 end += 12
00442 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00443 start = end
00444 end += 4
00445 (length,) = _struct_I.unpack(str[start:end])
00446 start = end
00447 end += length
00448 if python3:
00449 self.header.frame_id = str[start:end].decode('utf-8')
00450 else:
00451 self.header.frame_id = str[start:end]
00452 start = end
00453 end += 4
00454 (length,) = _struct_I.unpack(str[start:end])
00455 start = end
00456 end += length
00457 if python3:
00458 self.camera_id = str[start:end].decode('utf-8')
00459 else:
00460 self.camera_id = str[start:end]
00461 start = end
00462 end += 4
00463 (length,) = _struct_I.unpack(str[start:end])
00464 self.image_points = []
00465 for i in range(0, length):
00466 val1 = geometry_msgs.msg.Point()
00467 _x = val1
00468 start = end
00469 end += 24
00470 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00471 self.image_points.append(val1)
00472 _x = self
00473 start = end
00474 end += 12
00475 (_x.cam_info.header.seq, _x.cam_info.header.stamp.secs, _x.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00476 start = end
00477 end += 4
00478 (length,) = _struct_I.unpack(str[start:end])
00479 start = end
00480 end += length
00481 if python3:
00482 self.cam_info.header.frame_id = str[start:end].decode('utf-8')
00483 else:
00484 self.cam_info.header.frame_id = str[start:end]
00485 _x = self
00486 start = end
00487 end += 8
00488 (_x.cam_info.height, _x.cam_info.width,) = _struct_2I.unpack(str[start:end])
00489 start = end
00490 end += 4
00491 (length,) = _struct_I.unpack(str[start:end])
00492 start = end
00493 end += length
00494 if python3:
00495 self.cam_info.distortion_model = str[start:end].decode('utf-8')
00496 else:
00497 self.cam_info.distortion_model = str[start:end]
00498 start = end
00499 end += 4
00500 (length,) = _struct_I.unpack(str[start:end])
00501 pattern = '<%sd'%length
00502 start = end
00503 end += struct.calcsize(pattern)
00504 self.cam_info.D = struct.unpack(pattern, str[start:end])
00505 start = end
00506 end += 72
00507 self.cam_info.K = _struct_9d.unpack(str[start:end])
00508 start = end
00509 end += 72
00510 self.cam_info.R = _struct_9d.unpack(str[start:end])
00511 start = end
00512 end += 96
00513 self.cam_info.P = _struct_12d.unpack(str[start:end])
00514 _x = self
00515 start = end
00516 end += 38
00517 (_x.cam_info.binning_x, _x.cam_info.binning_y, _x.cam_info.roi.x_offset, _x.cam_info.roi.y_offset, _x.cam_info.roi.height, _x.cam_info.roi.width, _x.cam_info.roi.do_rectify, _x.verbose, _x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_6I2B3I.unpack(str[start:end])
00518 self.cam_info.roi.do_rectify = bool(self.cam_info.roi.do_rectify)
00519 self.verbose = bool(self.verbose)
00520 start = end
00521 end += 4
00522 (length,) = _struct_I.unpack(str[start:end])
00523 start = end
00524 end += length
00525 if python3:
00526 self.image.header.frame_id = str[start:end].decode('utf-8')
00527 else:
00528 self.image.header.frame_id = str[start:end]
00529 _x = self
00530 start = end
00531 end += 8
00532 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00533 start = end
00534 end += 4
00535 (length,) = _struct_I.unpack(str[start:end])
00536 start = end
00537 end += length
00538 if python3:
00539 self.image.encoding = str[start:end].decode('utf-8')
00540 else:
00541 self.image.encoding = str[start:end]
00542 _x = self
00543 start = end
00544 end += 5
00545 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00546 start = end
00547 end += 4
00548 (length,) = _struct_I.unpack(str[start:end])
00549 start = end
00550 end += length
00551 if python3:
00552 self.image.data = str[start:end].decode('utf-8')
00553 else:
00554 self.image.data = str[start:end]
00555 _x = self
00556 start = end
00557 end += 12
00558 (_x.image_rect.header.seq, _x.image_rect.header.stamp.secs, _x.image_rect.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00559 start = end
00560 end += 4
00561 (length,) = _struct_I.unpack(str[start:end])
00562 start = end
00563 end += length
00564 if python3:
00565 self.image_rect.header.frame_id = str[start:end].decode('utf-8')
00566 else:
00567 self.image_rect.header.frame_id = str[start:end]
00568 _x = self
00569 start = end
00570 end += 8
00571 (_x.image_rect.height, _x.image_rect.width,) = _struct_2I.unpack(str[start:end])
00572 start = end
00573 end += 4
00574 (length,) = _struct_I.unpack(str[start:end])
00575 start = end
00576 end += length
00577 if python3:
00578 self.image_rect.encoding = str[start:end].decode('utf-8')
00579 else:
00580 self.image_rect.encoding = str[start:end]
00581 _x = self
00582 start = end
00583 end += 5
00584 (_x.image_rect.is_bigendian, _x.image_rect.step,) = _struct_BI.unpack(str[start:end])
00585 start = end
00586 end += 4
00587 (length,) = _struct_I.unpack(str[start:end])
00588 start = end
00589 end += length
00590 if python3:
00591 self.image_rect.data = str[start:end].decode('utf-8')
00592 else:
00593 self.image_rect.data = str[start:end]
00594 _x = self
00595 start = end
00596 end += 12
00597 (_x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00598 start = end
00599 end += 4
00600 (length,) = _struct_I.unpack(str[start:end])
00601 start = end
00602 end += length
00603 if python3:
00604 self.features.header.frame_id = str[start:end].decode('utf-8')
00605 else:
00606 self.features.header.frame_id = str[start:end]
00607 start = end
00608 end += 4
00609 (length,) = _struct_I.unpack(str[start:end])
00610 self.features.object_points = []
00611 for i in range(0, length):
00612 val1 = geometry_msgs.msg.Point()
00613 _x = val1
00614 start = end
00615 end += 24
00616 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00617 self.features.object_points.append(val1)
00618 start = end
00619 end += 4
00620 (length,) = _struct_I.unpack(str[start:end])
00621 self.features.image_points = []
00622 for i in range(0, length):
00623 val1 = geometry_msgs.msg.Point()
00624 _x = val1
00625 start = end
00626 end += 24
00627 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00628 self.features.image_points.append(val1)
00629 start = end
00630 end += 1
00631 (self.features.success,) = _struct_B.unpack(str[start:end])
00632 return self
00633 except struct.error as e:
00634 raise genpy.DeserializationError(e)
00635
00636
00637 def serialize_numpy(self, buff, numpy):
00638 """
00639 serialize message with numpy array types into buffer
00640 :param buff: buffer, ``StringIO``
00641 :param numpy: numpy python module
00642 """
00643 try:
00644 _x = self
00645 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00646 _x = self.header.frame_id
00647 length = len(_x)
00648 if python3 or type(_x) == unicode:
00649 _x = _x.encode('utf-8')
00650 length = len(_x)
00651 buff.write(struct.pack('<I%ss'%length, length, _x))
00652 _x = self.camera_id
00653 length = len(_x)
00654 if python3 or type(_x) == unicode:
00655 _x = _x.encode('utf-8')
00656 length = len(_x)
00657 buff.write(struct.pack('<I%ss'%length, length, _x))
00658 length = len(self.image_points)
00659 buff.write(_struct_I.pack(length))
00660 for val1 in self.image_points:
00661 _x = val1
00662 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00663 _x = self
00664 buff.write(_struct_3I.pack(_x.cam_info.header.seq, _x.cam_info.header.stamp.secs, _x.cam_info.header.stamp.nsecs))
00665 _x = self.cam_info.header.frame_id
00666 length = len(_x)
00667 if python3 or type(_x) == unicode:
00668 _x = _x.encode('utf-8')
00669 length = len(_x)
00670 buff.write(struct.pack('<I%ss'%length, length, _x))
00671 _x = self
00672 buff.write(_struct_2I.pack(_x.cam_info.height, _x.cam_info.width))
00673 _x = self.cam_info.distortion_model
00674 length = len(_x)
00675 if python3 or type(_x) == unicode:
00676 _x = _x.encode('utf-8')
00677 length = len(_x)
00678 buff.write(struct.pack('<I%ss'%length, length, _x))
00679 length = len(self.cam_info.D)
00680 buff.write(_struct_I.pack(length))
00681 pattern = '<%sd'%length
00682 buff.write(self.cam_info.D.tostring())
00683 buff.write(self.cam_info.K.tostring())
00684 buff.write(self.cam_info.R.tostring())
00685 buff.write(self.cam_info.P.tostring())
00686 _x = self
00687 buff.write(_struct_6I2B3I.pack(_x.cam_info.binning_x, _x.cam_info.binning_y, _x.cam_info.roi.x_offset, _x.cam_info.roi.y_offset, _x.cam_info.roi.height, _x.cam_info.roi.width, _x.cam_info.roi.do_rectify, _x.verbose, _x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00688 _x = self.image.header.frame_id
00689 length = len(_x)
00690 if python3 or type(_x) == unicode:
00691 _x = _x.encode('utf-8')
00692 length = len(_x)
00693 buff.write(struct.pack('<I%ss'%length, length, _x))
00694 _x = self
00695 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00696 _x = self.image.encoding
00697 length = len(_x)
00698 if python3 or type(_x) == unicode:
00699 _x = _x.encode('utf-8')
00700 length = len(_x)
00701 buff.write(struct.pack('<I%ss'%length, length, _x))
00702 _x = self
00703 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00704 _x = self.image.data
00705 length = len(_x)
00706
00707 if type(_x) in [list, tuple]:
00708 buff.write(struct.pack('<I%sB'%length, length, *_x))
00709 else:
00710 buff.write(struct.pack('<I%ss'%length, length, _x))
00711 _x = self
00712 buff.write(_struct_3I.pack(_x.image_rect.header.seq, _x.image_rect.header.stamp.secs, _x.image_rect.header.stamp.nsecs))
00713 _x = self.image_rect.header.frame_id
00714 length = len(_x)
00715 if python3 or type(_x) == unicode:
00716 _x = _x.encode('utf-8')
00717 length = len(_x)
00718 buff.write(struct.pack('<I%ss'%length, length, _x))
00719 _x = self
00720 buff.write(_struct_2I.pack(_x.image_rect.height, _x.image_rect.width))
00721 _x = self.image_rect.encoding
00722 length = len(_x)
00723 if python3 or type(_x) == unicode:
00724 _x = _x.encode('utf-8')
00725 length = len(_x)
00726 buff.write(struct.pack('<I%ss'%length, length, _x))
00727 _x = self
00728 buff.write(_struct_BI.pack(_x.image_rect.is_bigendian, _x.image_rect.step))
00729 _x = self.image_rect.data
00730 length = len(_x)
00731
00732 if type(_x) in [list, tuple]:
00733 buff.write(struct.pack('<I%sB'%length, length, *_x))
00734 else:
00735 buff.write(struct.pack('<I%ss'%length, length, _x))
00736 _x = self
00737 buff.write(_struct_3I.pack(_x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs))
00738 _x = self.features.header.frame_id
00739 length = len(_x)
00740 if python3 or type(_x) == unicode:
00741 _x = _x.encode('utf-8')
00742 length = len(_x)
00743 buff.write(struct.pack('<I%ss'%length, length, _x))
00744 length = len(self.features.object_points)
00745 buff.write(_struct_I.pack(length))
00746 for val1 in self.features.object_points:
00747 _x = val1
00748 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00749 length = len(self.features.image_points)
00750 buff.write(_struct_I.pack(length))
00751 for val1 in self.features.image_points:
00752 _x = val1
00753 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00754 buff.write(_struct_B.pack(self.features.success))
00755 except struct.error as se: self._check_types(se)
00756 except TypeError as te: self._check_types(te)
00757
00758 def deserialize_numpy(self, str, numpy):
00759 """
00760 unpack serialized message in str into this message instance using numpy for array types
00761 :param str: byte array of serialized message, ``str``
00762 :param numpy: numpy python module
00763 """
00764 try:
00765 if self.header is None:
00766 self.header = std_msgs.msg.Header()
00767 if self.image_points is None:
00768 self.image_points = None
00769 if self.cam_info is None:
00770 self.cam_info = sensor_msgs.msg.CameraInfo()
00771 if self.image is None:
00772 self.image = sensor_msgs.msg.Image()
00773 if self.image_rect is None:
00774 self.image_rect = sensor_msgs.msg.Image()
00775 if self.features is None:
00776 self.features = calibration_msgs.msg.CalibrationPattern()
00777 end = 0
00778 _x = self
00779 start = end
00780 end += 12
00781 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00782 start = end
00783 end += 4
00784 (length,) = _struct_I.unpack(str[start:end])
00785 start = end
00786 end += length
00787 if python3:
00788 self.header.frame_id = str[start:end].decode('utf-8')
00789 else:
00790 self.header.frame_id = 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.camera_id = str[start:end].decode('utf-8')
00798 else:
00799 self.camera_id = str[start:end]
00800 start = end
00801 end += 4
00802 (length,) = _struct_I.unpack(str[start:end])
00803 self.image_points = []
00804 for i in range(0, length):
00805 val1 = geometry_msgs.msg.Point()
00806 _x = val1
00807 start = end
00808 end += 24
00809 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00810 self.image_points.append(val1)
00811 _x = self
00812 start = end
00813 end += 12
00814 (_x.cam_info.header.seq, _x.cam_info.header.stamp.secs, _x.cam_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00815 start = end
00816 end += 4
00817 (length,) = _struct_I.unpack(str[start:end])
00818 start = end
00819 end += length
00820 if python3:
00821 self.cam_info.header.frame_id = str[start:end].decode('utf-8')
00822 else:
00823 self.cam_info.header.frame_id = str[start:end]
00824 _x = self
00825 start = end
00826 end += 8
00827 (_x.cam_info.height, _x.cam_info.width,) = _struct_2I.unpack(str[start:end])
00828 start = end
00829 end += 4
00830 (length,) = _struct_I.unpack(str[start:end])
00831 start = end
00832 end += length
00833 if python3:
00834 self.cam_info.distortion_model = str[start:end].decode('utf-8')
00835 else:
00836 self.cam_info.distortion_model = str[start:end]
00837 start = end
00838 end += 4
00839 (length,) = _struct_I.unpack(str[start:end])
00840 pattern = '<%sd'%length
00841 start = end
00842 end += struct.calcsize(pattern)
00843 self.cam_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00844 start = end
00845 end += 72
00846 self.cam_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00847 start = end
00848 end += 72
00849 self.cam_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00850 start = end
00851 end += 96
00852 self.cam_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
00853 _x = self
00854 start = end
00855 end += 38
00856 (_x.cam_info.binning_x, _x.cam_info.binning_y, _x.cam_info.roi.x_offset, _x.cam_info.roi.y_offset, _x.cam_info.roi.height, _x.cam_info.roi.width, _x.cam_info.roi.do_rectify, _x.verbose, _x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_6I2B3I.unpack(str[start:end])
00857 self.cam_info.roi.do_rectify = bool(self.cam_info.roi.do_rectify)
00858 self.verbose = bool(self.verbose)
00859 start = end
00860 end += 4
00861 (length,) = _struct_I.unpack(str[start:end])
00862 start = end
00863 end += length
00864 if python3:
00865 self.image.header.frame_id = str[start:end].decode('utf-8')
00866 else:
00867 self.image.header.frame_id = str[start:end]
00868 _x = self
00869 start = end
00870 end += 8
00871 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00872 start = end
00873 end += 4
00874 (length,) = _struct_I.unpack(str[start:end])
00875 start = end
00876 end += length
00877 if python3:
00878 self.image.encoding = str[start:end].decode('utf-8')
00879 else:
00880 self.image.encoding = str[start:end]
00881 _x = self
00882 start = end
00883 end += 5
00884 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00885 start = end
00886 end += 4
00887 (length,) = _struct_I.unpack(str[start:end])
00888 start = end
00889 end += length
00890 if python3:
00891 self.image.data = str[start:end].decode('utf-8')
00892 else:
00893 self.image.data = str[start:end]
00894 _x = self
00895 start = end
00896 end += 12
00897 (_x.image_rect.header.seq, _x.image_rect.header.stamp.secs, _x.image_rect.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00898 start = end
00899 end += 4
00900 (length,) = _struct_I.unpack(str[start:end])
00901 start = end
00902 end += length
00903 if python3:
00904 self.image_rect.header.frame_id = str[start:end].decode('utf-8')
00905 else:
00906 self.image_rect.header.frame_id = str[start:end]
00907 _x = self
00908 start = end
00909 end += 8
00910 (_x.image_rect.height, _x.image_rect.width,) = _struct_2I.unpack(str[start:end])
00911 start = end
00912 end += 4
00913 (length,) = _struct_I.unpack(str[start:end])
00914 start = end
00915 end += length
00916 if python3:
00917 self.image_rect.encoding = str[start:end].decode('utf-8')
00918 else:
00919 self.image_rect.encoding = str[start:end]
00920 _x = self
00921 start = end
00922 end += 5
00923 (_x.image_rect.is_bigendian, _x.image_rect.step,) = _struct_BI.unpack(str[start:end])
00924 start = end
00925 end += 4
00926 (length,) = _struct_I.unpack(str[start:end])
00927 start = end
00928 end += length
00929 if python3:
00930 self.image_rect.data = str[start:end].decode('utf-8')
00931 else:
00932 self.image_rect.data = str[start:end]
00933 _x = self
00934 start = end
00935 end += 12
00936 (_x.features.header.seq, _x.features.header.stamp.secs, _x.features.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00937 start = end
00938 end += 4
00939 (length,) = _struct_I.unpack(str[start:end])
00940 start = end
00941 end += length
00942 if python3:
00943 self.features.header.frame_id = str[start:end].decode('utf-8')
00944 else:
00945 self.features.header.frame_id = str[start:end]
00946 start = end
00947 end += 4
00948 (length,) = _struct_I.unpack(str[start:end])
00949 self.features.object_points = []
00950 for i in range(0, length):
00951 val1 = geometry_msgs.msg.Point()
00952 _x = val1
00953 start = end
00954 end += 24
00955 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00956 self.features.object_points.append(val1)
00957 start = end
00958 end += 4
00959 (length,) = _struct_I.unpack(str[start:end])
00960 self.features.image_points = []
00961 for i in range(0, length):
00962 val1 = geometry_msgs.msg.Point()
00963 _x = val1
00964 start = end
00965 end += 24
00966 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00967 self.features.image_points.append(val1)
00968 start = end
00969 end += 1
00970 (self.features.success,) = _struct_B.unpack(str[start:end])
00971 return self
00972 except struct.error as e:
00973 raise genpy.DeserializationError(e)
00974
00975 _struct_I = genpy.struct_I
00976 _struct_B = struct.Struct("<B")
00977 _struct_12d = struct.Struct("<12d")
00978 _struct_6I2B3I = struct.Struct("<6I2B3I")
00979 _struct_9d = struct.Struct("<9d")
00980 _struct_BI = struct.Struct("<BI")
00981 _struct_3I = struct.Struct("<3I")
00982 _struct_2I = struct.Struct("<2I")
00983 _struct_3d = struct.Struct("<3d")