diff --git a/cob4-24/calibration/calibration_offset.urdf.xacro b/cob4-24/calibration/calibration_offset.urdf.xacro new file mode 100644 index 0000000..1bc9382 --- /dev/null +++ b/cob4-24/calibration/calibration_offset.urdf.xacro @@ -0,0 +1,132 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cob4-24/calibration/cameras/head_cam.yaml b/cob4-24/calibration/cameras/head_cam.yaml new file mode 100644 index 0000000..066eb54 --- /dev/null +++ b/cob4-24/calibration/cameras/head_cam.yaml @@ -0,0 +1,20 @@ +image_width: 1280 +image_height: 960 +camera_name: head_cam +camera_matrix: + rows: 3 + cols: 3 + data: [912.899608, 0.000000, 640.420778, 0.000000, 917.520761, 502.479759, 0.000000, 0.000000, 1.000000] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [-0.373478, 0.112529, -0.000921, -0.002183, 0.000000] +rectification_matrix: + rows: 3 + cols: 3 + data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] +projection_matrix: + rows: 3 + cols: 4 + data: [700.806335, 0.000000, 632.696581, 0.000000, 0.000000, 809.140137, 508.162883, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]