00001 """autogenerated by genpy from hector_worldmodel_msgs/ImagePercept.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 hector_worldmodel_msgs.msg
00008 import sensor_msgs.msg
00009 import std_msgs.msg
00010
00011 class ImagePercept(genpy.Message):
00012 _md5sum = "cfe1ba9ccbb3e43950b420f7336a3c6c"
00013 _type = "hector_worldmodel_msgs/ImagePercept"
00014 _has_header = True
00015 _full_text = """# hector_worldmodel_msgs/ImagePercept
00016 # This message represents an observation of an object in a single image.
00017
00018 # The header should equal the header of the corresponding image.
00019 Header header
00020
00021 # The camera info which is needed to project from image coordinates to world coordinates
00022 sensor_msgs/CameraInfo camera_info
00023
00024 # Center coordinates of the percept in image coordinates
00025 # x: axis points to the right in the image
00026 # y: axis points downward in the image
00027 float32 x
00028 float32 y
00029
00030 # Normalized size of the percept in image coordinates (or 0.0)
00031 float32 width
00032 float32 height
00033
00034 # Distance estimate (slope distance) (or 0.0)
00035 float32 distance
00036
00037 # Additional information about the percept
00038 PerceptInfo info
00039
00040 ================================================================================
00041 MSG: std_msgs/Header
00042 # Standard metadata for higher-level stamped data types.
00043 # This is generally used to communicate timestamped data
00044 # in a particular coordinate frame.
00045 #
00046 # sequence ID: consecutively increasing ID
00047 uint32 seq
00048 #Two-integer timestamp that is expressed as:
00049 # * stamp.secs: seconds (stamp_secs) since epoch
00050 # * stamp.nsecs: nanoseconds since stamp_secs
00051 # time-handling sugar is provided by the client library
00052 time stamp
00053 #Frame this data is associated with
00054 # 0: no frame
00055 # 1: global frame
00056 string frame_id
00057
00058 ================================================================================
00059 MSG: sensor_msgs/CameraInfo
00060 # This message defines meta information for a camera. It should be in a
00061 # camera namespace on topic "camera_info" and accompanied by up to five
00062 # image topics named:
00063 #
00064 # image_raw - raw data from the camera driver, possibly Bayer encoded
00065 # image - monochrome, distorted
00066 # image_color - color, distorted
00067 # image_rect - monochrome, rectified
00068 # image_rect_color - color, rectified
00069 #
00070 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00071 # for producing the four processed image topics from image_raw and
00072 # camera_info. The meaning of the camera parameters are described in
00073 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00074 #
00075 # The image_geometry package provides a user-friendly interface to
00076 # common operations using this meta information. If you want to, e.g.,
00077 # project a 3d point into image coordinates, we strongly recommend
00078 # using image_geometry.
00079 #
00080 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00081 # zeroed out. In particular, clients may assume that K[0] == 0.0
00082 # indicates an uncalibrated camera.
00083
00084 #######################################################################
00085 # Image acquisition info #
00086 #######################################################################
00087
00088 # Time of image acquisition, camera coordinate frame ID
00089 Header header # Header timestamp should be acquisition time of image
00090 # Header frame_id should be optical frame of camera
00091 # origin of frame should be optical center of camera
00092 # +x should point to the right in the image
00093 # +y should point down in the image
00094 # +z should point into the plane of the image
00095
00096
00097 #######################################################################
00098 # Calibration Parameters #
00099 #######################################################################
00100 # These are fixed during camera calibration. Their values will be the #
00101 # same in all messages until the camera is recalibrated. Note that #
00102 # self-calibrating systems may "recalibrate" frequently. #
00103 # #
00104 # The internal parameters can be used to warp a raw (distorted) image #
00105 # to: #
00106 # 1. An undistorted image (requires D and K) #
00107 # 2. A rectified image (requires D, K, R) #
00108 # The projection matrix P projects 3D points into the rectified image.#
00109 #######################################################################
00110
00111 # The image dimensions with which the camera was calibrated. Normally
00112 # this will be the full camera resolution in pixels.
00113 uint32 height
00114 uint32 width
00115
00116 # The distortion model used. Supported models are listed in
00117 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00118 # simple model of radial and tangential distortion - is sufficent.
00119 string distortion_model
00120
00121 # The distortion parameters, size depending on the distortion model.
00122 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00123 float64[] D
00124
00125 # Intrinsic camera matrix for the raw (distorted) images.
00126 # [fx 0 cx]
00127 # K = [ 0 fy cy]
00128 # [ 0 0 1]
00129 # Projects 3D points in the camera coordinate frame to 2D pixel
00130 # coordinates using the focal lengths (fx, fy) and principal point
00131 # (cx, cy).
00132 float64[9] K # 3x3 row-major matrix
00133
00134 # Rectification matrix (stereo cameras only)
00135 # A rotation matrix aligning the camera coordinate system to the ideal
00136 # stereo image plane so that epipolar lines in both stereo images are
00137 # parallel.
00138 float64[9] R # 3x3 row-major matrix
00139
00140 # Projection/camera matrix
00141 # [fx' 0 cx' Tx]
00142 # P = [ 0 fy' cy' Ty]
00143 # [ 0 0 1 0]
00144 # By convention, this matrix specifies the intrinsic (camera) matrix
00145 # of the processed (rectified) image. That is, the left 3x3 portion
00146 # is the normal camera intrinsic matrix for the rectified image.
00147 # It projects 3D points in the camera coordinate frame to 2D pixel
00148 # coordinates using the focal lengths (fx', fy') and principal point
00149 # (cx', cy') - these may differ from the values in K.
00150 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00151 # also have R = the identity and P[1:3,1:3] = K.
00152 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00153 # position of the optical center of the second camera in the first
00154 # camera's frame. We assume Tz = 0 so both cameras are in the same
00155 # stereo image plane. The first camera always has Tx = Ty = 0. For
00156 # the right (second) camera of a horizontal stereo pair, Ty = 0 and
00157 # Tx = -fx' * B, where B is the baseline between the cameras.
00158 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00159 # the rectified image is given by:
00160 # [u v w]' = P * [X Y Z 1]'
00161 # x = u / w
00162 # y = v / w
00163 # This holds for both images of a stereo pair.
00164 float64[12] P # 3x4 row-major matrix
00165
00166
00167 #######################################################################
00168 # Operational Parameters #
00169 #######################################################################
00170 # These define the image region actually captured by the camera #
00171 # driver. Although they affect the geometry of the output image, they #
00172 # may be changed freely without recalibrating the camera. #
00173 #######################################################################
00174
00175 # Binning refers here to any camera setting which combines rectangular
00176 # neighborhoods of pixels into larger "super-pixels." It reduces the
00177 # resolution of the output image to
00178 # (width / binning_x) x (height / binning_y).
00179 # The default values binning_x = binning_y = 0 is considered the same
00180 # as binning_x = binning_y = 1 (no subsampling).
00181 uint32 binning_x
00182 uint32 binning_y
00183
00184 # Region of interest (subwindow of full camera resolution), given in
00185 # full resolution (unbinned) image coordinates. A particular ROI
00186 # always denotes the same window of pixels on the camera sensor,
00187 # regardless of binning settings.
00188 # The default setting of roi (all values 0) is considered the same as
00189 # full resolution (roi.width = width, roi.height = height).
00190 RegionOfInterest roi
00191
00192 ================================================================================
00193 MSG: sensor_msgs/RegionOfInterest
00194 # This message is used to specify a region of interest within an image.
00195 #
00196 # When used to specify the ROI setting of the camera when the image was
00197 # taken, the height and width fields should either match the height and
00198 # width fields for the associated image; or height = width = 0
00199 # indicates that the full resolution image was captured.
00200
00201 uint32 x_offset # Leftmost pixel of the ROI
00202 # (0 if the ROI includes the left edge of the image)
00203 uint32 y_offset # Topmost pixel of the ROI
00204 # (0 if the ROI includes the top edge of the image)
00205 uint32 height # Height of ROI
00206 uint32 width # Width of ROI
00207
00208 # True if a distinct rectified ROI should be calculated from the "raw"
00209 # ROI in this message. Typically this should be False if the full image
00210 # is captured (ROI not used), and True if a subwindow is captured (ROI
00211 # used).
00212 bool do_rectify
00213
00214 ================================================================================
00215 MSG: hector_worldmodel_msgs/PerceptInfo
00216 # hector_worldmodel_msgs/PerceptInfo
00217 # This message contains information about the estimated class and object identity
00218
00219 # A string identifying the object's class (all objects of a class look the same)
00220 string class_id
00221
00222 # The class association support of the observation
00223 # The support is the log odd likelihood ratio given by log(p(y/observation y belongs to object of class class_id) / p(y/observation y is a false positive))
00224 float32 class_support
00225
00226 # A string identifying a specific object
00227 string object_id
00228
00229 # The object association support of the observation
00230 # The support is the log odd likelihood ratio given by log(p(observation belongs to object object_id) / p(observation is false positive or belongs to another object))
00231 float32 object_support
00232
00233 # A string that contains the name or a description of the specific object
00234 string name
00235
00236 """
00237 __slots__ = ['header','camera_info','x','y','width','height','distance','info']
00238 _slot_types = ['std_msgs/Header','sensor_msgs/CameraInfo','float32','float32','float32','float32','float32','hector_worldmodel_msgs/PerceptInfo']
00239
00240 def __init__(self, *args, **kwds):
00241 """
00242 Constructor. Any message fields that are implicitly/explicitly
00243 set to None will be assigned a default value. The recommend
00244 use is keyword arguments as this is more robust to future message
00245 changes. You cannot mix in-order arguments and keyword arguments.
00246
00247 The available fields are:
00248 header,camera_info,x,y,width,height,distance,info
00249
00250 :param args: complete set of field values, in .msg order
00251 :param kwds: use keyword arguments corresponding to message field names
00252 to set specific fields.
00253 """
00254 if args or kwds:
00255 super(ImagePercept, self).__init__(*args, **kwds)
00256
00257 if self.header is None:
00258 self.header = std_msgs.msg.Header()
00259 if self.camera_info is None:
00260 self.camera_info = sensor_msgs.msg.CameraInfo()
00261 if self.x is None:
00262 self.x = 0.
00263 if self.y is None:
00264 self.y = 0.
00265 if self.width is None:
00266 self.width = 0.
00267 if self.height is None:
00268 self.height = 0.
00269 if self.distance is None:
00270 self.distance = 0.
00271 if self.info is None:
00272 self.info = hector_worldmodel_msgs.msg.PerceptInfo()
00273 else:
00274 self.header = std_msgs.msg.Header()
00275 self.camera_info = sensor_msgs.msg.CameraInfo()
00276 self.x = 0.
00277 self.y = 0.
00278 self.width = 0.
00279 self.height = 0.
00280 self.distance = 0.
00281 self.info = hector_worldmodel_msgs.msg.PerceptInfo()
00282
00283 def _get_types(self):
00284 """
00285 internal API method
00286 """
00287 return self._slot_types
00288
00289 def serialize(self, buff):
00290 """
00291 serialize message into buffer
00292 :param buff: buffer, ``StringIO``
00293 """
00294 try:
00295 _x = self
00296 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00297 _x = self.header.frame_id
00298 length = len(_x)
00299 if python3 or type(_x) == unicode:
00300 _x = _x.encode('utf-8')
00301 length = len(_x)
00302 buff.write(struct.pack('<I%ss'%length, length, _x))
00303 _x = self
00304 buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs))
00305 _x = self.camera_info.header.frame_id
00306 length = len(_x)
00307 if python3 or type(_x) == unicode:
00308 _x = _x.encode('utf-8')
00309 length = len(_x)
00310 buff.write(struct.pack('<I%ss'%length, length, _x))
00311 _x = self
00312 buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width))
00313 _x = self.camera_info.distortion_model
00314 length = len(_x)
00315 if python3 or type(_x) == unicode:
00316 _x = _x.encode('utf-8')
00317 length = len(_x)
00318 buff.write(struct.pack('<I%ss'%length, length, _x))
00319 length = len(self.camera_info.D)
00320 buff.write(_struct_I.pack(length))
00321 pattern = '<%sd'%length
00322 buff.write(struct.pack(pattern, *self.camera_info.D))
00323 buff.write(_struct_9d.pack(*self.camera_info.K))
00324 buff.write(_struct_9d.pack(*self.camera_info.R))
00325 buff.write(_struct_12d.pack(*self.camera_info.P))
00326 _x = self
00327 buff.write(_struct_6IB5f.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.x, _x.y, _x.width, _x.height, _x.distance))
00328 _x = self.info.class_id
00329 length = len(_x)
00330 if python3 or type(_x) == unicode:
00331 _x = _x.encode('utf-8')
00332 length = len(_x)
00333 buff.write(struct.pack('<I%ss'%length, length, _x))
00334 buff.write(_struct_f.pack(self.info.class_support))
00335 _x = self.info.object_id
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 buff.write(_struct_f.pack(self.info.object_support))
00342 _x = self.info.name
00343 length = len(_x)
00344 if python3 or type(_x) == unicode:
00345 _x = _x.encode('utf-8')
00346 length = len(_x)
00347 buff.write(struct.pack('<I%ss'%length, length, _x))
00348 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00349 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00350
00351 def deserialize(self, str):
00352 """
00353 unpack serialized message in str into this message instance
00354 :param str: byte array of serialized message, ``str``
00355 """
00356 try:
00357 if self.header is None:
00358 self.header = std_msgs.msg.Header()
00359 if self.camera_info is None:
00360 self.camera_info = sensor_msgs.msg.CameraInfo()
00361 if self.info is None:
00362 self.info = hector_worldmodel_msgs.msg.PerceptInfo()
00363 end = 0
00364 _x = self
00365 start = end
00366 end += 12
00367 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00368 start = end
00369 end += 4
00370 (length,) = _struct_I.unpack(str[start:end])
00371 start = end
00372 end += length
00373 if python3:
00374 self.header.frame_id = str[start:end].decode('utf-8')
00375 else:
00376 self.header.frame_id = str[start:end]
00377 _x = self
00378 start = end
00379 end += 12
00380 (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00381 start = end
00382 end += 4
00383 (length,) = _struct_I.unpack(str[start:end])
00384 start = end
00385 end += length
00386 if python3:
00387 self.camera_info.header.frame_id = str[start:end].decode('utf-8')
00388 else:
00389 self.camera_info.header.frame_id = str[start:end]
00390 _x = self
00391 start = end
00392 end += 8
00393 (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end])
00394 start = end
00395 end += 4
00396 (length,) = _struct_I.unpack(str[start:end])
00397 start = end
00398 end += length
00399 if python3:
00400 self.camera_info.distortion_model = str[start:end].decode('utf-8')
00401 else:
00402 self.camera_info.distortion_model = str[start:end]
00403 start = end
00404 end += 4
00405 (length,) = _struct_I.unpack(str[start:end])
00406 pattern = '<%sd'%length
00407 start = end
00408 end += struct.calcsize(pattern)
00409 self.camera_info.D = struct.unpack(pattern, str[start:end])
00410 start = end
00411 end += 72
00412 self.camera_info.K = _struct_9d.unpack(str[start:end])
00413 start = end
00414 end += 72
00415 self.camera_info.R = _struct_9d.unpack(str[start:end])
00416 start = end
00417 end += 96
00418 self.camera_info.P = _struct_12d.unpack(str[start:end])
00419 _x = self
00420 start = end
00421 end += 45
00422 (_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.x, _x.y, _x.width, _x.height, _x.distance,) = _struct_6IB5f.unpack(str[start:end])
00423 self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify)
00424 start = end
00425 end += 4
00426 (length,) = _struct_I.unpack(str[start:end])
00427 start = end
00428 end += length
00429 if python3:
00430 self.info.class_id = str[start:end].decode('utf-8')
00431 else:
00432 self.info.class_id = str[start:end]
00433 start = end
00434 end += 4
00435 (self.info.class_support,) = _struct_f.unpack(str[start:end])
00436 start = end
00437 end += 4
00438 (length,) = _struct_I.unpack(str[start:end])
00439 start = end
00440 end += length
00441 if python3:
00442 self.info.object_id = str[start:end].decode('utf-8')
00443 else:
00444 self.info.object_id = str[start:end]
00445 start = end
00446 end += 4
00447 (self.info.object_support,) = _struct_f.unpack(str[start:end])
00448 start = end
00449 end += 4
00450 (length,) = _struct_I.unpack(str[start:end])
00451 start = end
00452 end += length
00453 if python3:
00454 self.info.name = str[start:end].decode('utf-8')
00455 else:
00456 self.info.name = str[start:end]
00457 return self
00458 except struct.error as e:
00459 raise genpy.DeserializationError(e)
00460
00461
00462 def serialize_numpy(self, buff, numpy):
00463 """
00464 serialize message with numpy array types into buffer
00465 :param buff: buffer, ``StringIO``
00466 :param numpy: numpy python module
00467 """
00468 try:
00469 _x = self
00470 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00471 _x = self.header.frame_id
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 = self
00478 buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs))
00479 _x = self.camera_info.header.frame_id
00480 length = len(_x)
00481 if python3 or type(_x) == unicode:
00482 _x = _x.encode('utf-8')
00483 length = len(_x)
00484 buff.write(struct.pack('<I%ss'%length, length, _x))
00485 _x = self
00486 buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width))
00487 _x = self.camera_info.distortion_model
00488 length = len(_x)
00489 if python3 or type(_x) == unicode:
00490 _x = _x.encode('utf-8')
00491 length = len(_x)
00492 buff.write(struct.pack('<I%ss'%length, length, _x))
00493 length = len(self.camera_info.D)
00494 buff.write(_struct_I.pack(length))
00495 pattern = '<%sd'%length
00496 buff.write(self.camera_info.D.tostring())
00497 buff.write(self.camera_info.K.tostring())
00498 buff.write(self.camera_info.R.tostring())
00499 buff.write(self.camera_info.P.tostring())
00500 _x = self
00501 buff.write(_struct_6IB5f.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.x, _x.y, _x.width, _x.height, _x.distance))
00502 _x = self.info.class_id
00503 length = len(_x)
00504 if python3 or type(_x) == unicode:
00505 _x = _x.encode('utf-8')
00506 length = len(_x)
00507 buff.write(struct.pack('<I%ss'%length, length, _x))
00508 buff.write(_struct_f.pack(self.info.class_support))
00509 _x = self.info.object_id
00510 length = len(_x)
00511 if python3 or type(_x) == unicode:
00512 _x = _x.encode('utf-8')
00513 length = len(_x)
00514 buff.write(struct.pack('<I%ss'%length, length, _x))
00515 buff.write(_struct_f.pack(self.info.object_support))
00516 _x = self.info.name
00517 length = len(_x)
00518 if python3 or type(_x) == unicode:
00519 _x = _x.encode('utf-8')
00520 length = len(_x)
00521 buff.write(struct.pack('<I%ss'%length, length, _x))
00522 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00523 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00524
00525 def deserialize_numpy(self, str, numpy):
00526 """
00527 unpack serialized message in str into this message instance using numpy for array types
00528 :param str: byte array of serialized message, ``str``
00529 :param numpy: numpy python module
00530 """
00531 try:
00532 if self.header is None:
00533 self.header = std_msgs.msg.Header()
00534 if self.camera_info is None:
00535 self.camera_info = sensor_msgs.msg.CameraInfo()
00536 if self.info is None:
00537 self.info = hector_worldmodel_msgs.msg.PerceptInfo()
00538 end = 0
00539 _x = self
00540 start = end
00541 end += 12
00542 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00543 start = end
00544 end += 4
00545 (length,) = _struct_I.unpack(str[start:end])
00546 start = end
00547 end += length
00548 if python3:
00549 self.header.frame_id = str[start:end].decode('utf-8')
00550 else:
00551 self.header.frame_id = str[start:end]
00552 _x = self
00553 start = end
00554 end += 12
00555 (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00556 start = end
00557 end += 4
00558 (length,) = _struct_I.unpack(str[start:end])
00559 start = end
00560 end += length
00561 if python3:
00562 self.camera_info.header.frame_id = str[start:end].decode('utf-8')
00563 else:
00564 self.camera_info.header.frame_id = str[start:end]
00565 _x = self
00566 start = end
00567 end += 8
00568 (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end])
00569 start = end
00570 end += 4
00571 (length,) = _struct_I.unpack(str[start:end])
00572 start = end
00573 end += length
00574 if python3:
00575 self.camera_info.distortion_model = str[start:end].decode('utf-8')
00576 else:
00577 self.camera_info.distortion_model = str[start:end]
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 pattern = '<%sd'%length
00582 start = end
00583 end += struct.calcsize(pattern)
00584 self.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00585 start = end
00586 end += 72
00587 self.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00588 start = end
00589 end += 72
00590 self.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00591 start = end
00592 end += 96
00593 self.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
00594 _x = self
00595 start = end
00596 end += 45
00597 (_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.x, _x.y, _x.width, _x.height, _x.distance,) = _struct_6IB5f.unpack(str[start:end])
00598 self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify)
00599 start = end
00600 end += 4
00601 (length,) = _struct_I.unpack(str[start:end])
00602 start = end
00603 end += length
00604 if python3:
00605 self.info.class_id = str[start:end].decode('utf-8')
00606 else:
00607 self.info.class_id = str[start:end]
00608 start = end
00609 end += 4
00610 (self.info.class_support,) = _struct_f.unpack(str[start:end])
00611 start = end
00612 end += 4
00613 (length,) = _struct_I.unpack(str[start:end])
00614 start = end
00615 end += length
00616 if python3:
00617 self.info.object_id = str[start:end].decode('utf-8')
00618 else:
00619 self.info.object_id = str[start:end]
00620 start = end
00621 end += 4
00622 (self.info.object_support,) = _struct_f.unpack(str[start:end])
00623 start = end
00624 end += 4
00625 (length,) = _struct_I.unpack(str[start:end])
00626 start = end
00627 end += length
00628 if python3:
00629 self.info.name = str[start:end].decode('utf-8')
00630 else:
00631 self.info.name = str[start:end]
00632 return self
00633 except struct.error as e:
00634 raise genpy.DeserializationError(e)
00635
00636 _struct_I = genpy.struct_I
00637 _struct_12d = struct.Struct("<12d")
00638 _struct_f = struct.Struct("<f")
00639 _struct_9d = struct.Struct("<9d")
00640 _struct_3I = struct.Struct("<3I")
00641 _struct_6IB5f = struct.Struct("<6IB5f")
00642 _struct_2I = struct.Struct("<2I")