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