openvslam icon indicating copy to clipboard operation
openvslam copied to clipboard

yaml configuration for ZED Mini Stereo Camera

Open JinglingZhu opened this issue 4 years ago • 4 comments

I saw many similar questions but didn't find the answer. I have a ZED Mini stereo camera and it can output undistorted and rectified images. My question is that ZED provided a calibration file with two cameras' parameters (both left and right camera have a fx, fy, cx, cy...). But I noticed that there is only one group of parameters in openvslam/example/euroc/EuRoC_stereo.yaml. What should I use in yaml fie for openvslam?

And does the Camera.focal_x_baseline equal fx * baseline (Meter) like the parameter Camera.bf in ORB_SLAM2?

Appreicate!

The configuration file of ZED camera:

`[LEFT_CAM_2K] fx=1398.03 fy=1398.03 cx=1080.5 cy=625.883 k1=-0.173733 k2=0.0272837 k3=0 p1=-6.10446e-05 p2=1.67256e-05

[RIGHT_CAM_2K] fx=1402.4 fy=1402.4 cx=1157.59 cy=590.028 k1=-0.171044 k2=0.0255164 k3=0 p1=0.000338728 p2=4.94672e-05

[LEFT_CAM_FHD] fx=1398.03 fy=1398.03 cx=936.5 cy=544.883 k1=-0.173733 k2=0.0272837 k3=0 p1=-6.10446e-05 p2=1.67256e-05

[RIGHT_CAM_FHD] fx=1402.4 fy=1402.4 cx=1013.59 cy=509.028 k1=-0.171044 k2=0.0255164 k3=0 p1=0.000338728 p2=4.94672e-05

[LEFT_CAM_HD] fx=699.015 fy=699.015 cx=626.75 cy=360.9415 k1=-0.173733 k2=0.0272837 k3=0 p1=-6.10446e-05 p2=1.67256e-05

[RIGHT_CAM_HD] fx=701.2 fy=701.2 cx=665.295 cy=343.014 k1=-0.171044 k2=0.0255164 k3=0 p1=0.000338728 p2=4.94672e-05

[LEFT_CAM_VGA] fx=349.5075 fy=349.5075 cx=328.875 cy=187.97075 k1=-0.173733 k2=0.0272837 k3=0 p1=-6.10446e-05 p2=1.67256e-05

[RIGHT_CAM_VGA] fx=350.6 fy=350.6 cx=348.1475 cy=179.007 k1=-0.171044 k2=0.0255164 k3=0 p1=0.000338728 p2=4.94672e-05

[STEREO] Baseline=63.001 TY=0.000819396 TZ=-0.0538347 CV_2K=-0.00510063 CV_FHD=-0.00510063 CV_HD=-0.00510063 CV_VGA=-0.00510063 RX_2K=0.00115287 RX_FHD=0.00115287 RX_HD=0.00115287 RX_VGA=0.00115287 RZ_2K=-0.000443546 RZ_FHD=-0.000443546 RZ_HD=-0.000443546 RZ_VGA=-0.000443546

[IMU] RX=0.0115875 RY=0.000883349 RZ=-0.0234901 Gyro_Bias_X=-13 Gyro_Bias_Y=19 Gyro_Bias_Z=-2 Gyro_Var_X=0.0147498 Gyro_Var_Y=0.014177 Gyro_Var_Z=0.0134926 Accel_Bias_Z=-19 Accel_Var_X=0.000125706 Accel_Var_Y=8.90088e-06 Accel_Var_Z=1.45052e-05 `

JinglingZhu avatar Oct 15 '19 07:10 JinglingZhu

Recently, it has become possible to set the stereo camera intrinsics individually(See commit ab18c986). According to EuRoC_stereo.yaml, please write params like this:

StereoRectifier.K_left: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]
StereoRectifier.D_left: [-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
StereoRectifier.R_left: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
StereoRectifier.K_right: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
StereoRectifier.D_right: [-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
StereoRectifier.R_right: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]

However, because rotations are not provided as matrices by your camera, you should calculate them from RX and RZ.

By the way, does the undistorted and stereo-rectified two images come out? If it's true, the configuration must be filled with the K parameters after calibration. Do you have such data?

About Camera.focal_x_baseline, as you say, it equals to the product of fx and baseline length.

MikiyaShibuya avatar Oct 18 '19 08:10 MikiyaShibuya

@MikiyaShibuya

Thanks for your explanation! I wrote some code to invoke ZED SDK's api and generated a dataset like EuRoC including rectified images of left & right camera(in 2 folders: cam0 and cam1) and a csv file which stores the matching timestamp. Then I commented out the code of StereoRectifier parameters and it seems work fine. PS: I use intrinsic parameter of left camera in the yaml file.

Do you think there is some place I should improve?

Appreciate!

JinglingZhu avatar Oct 24 '19 09:10 JinglingZhu

I have the same question. For the StereoRectifier part, it can be separated to left and right camera. But how about those camera.fx, camera.fy, etc.? Both the left and right camera have those parameters, which one should I use?

Thanks in advance.

D7823 avatar Feb 02 '20 22:02 D7823

I have an E-con Tara Usb stereo camera how can I configure with this? and for stereo camera openvslam require two camera

Neel125 avatar Sep 08 '20 09:09 Neel125