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