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


blort_ros
Author(s): Bence Magyar
autogenerated on Thu Jan 2 2014 11:39:12