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