ethz-asl / kalibr

The Kalibr visual-inertial calibration toolbox
Other
4.29k stars 1.4k forks source link

dont understand the result of multi_cameras calibration #502

Closed chennuo0125-HIT closed 2 years ago

chennuo0125-HIT commented 2 years ago

i calibrated extrincs between multi cameras with kalibr, and get following results:

Camera-system parameters:
    cam0 (/ob/rgb/image_raw):
     type: <class 'aslam_cv.libaslam_cv_python.DistortedPinholeCameraGeometry'>
     distortion: [ 0.05536411 -0.07911151  0.0000574   0.00006114] +- [ 0.0011901   0.00168102  0.00015149  0.00008089]
     projection: [ 435.45914384  435.74188101  325.99633446  237.22897237] +- [ 0.0873383   0.08678318  0.01774764  0.19155356]
     reprojection error: [0.000017, 0.000003] +- [1.969469, 1.554876]

    cam1 (/rs/fisheye2/image_raw):
     type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
     distortion: [ 0.0144151   0.04328469 -0.04289339  0.00743432] +- [ 0.00260723  0.00711237  0.00749886  0.0026698 ]
     projection: [ 275.46904257  275.47332053  424.2460087   396.72561891] +- [ 0.10724157  0.10752448  0.089727    0.09355803]
     reprojection error: [-0.000007, -0.000002] +- [0.771072, 0.611281]

    cam2 (/rs/fisheye1/image_raw):
     type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
     distortion: [ 0.02151672  0.02542116 -0.02405364  0.00059817] +- [ 0.00263128  0.00719539  0.00760516  0.00271117]
     projection: [ 275.20871827  275.17838792  427.40442729  396.8236588 ] +- [ 0.10717183  0.10761638  0.08845477  0.09407334]
     reprojection error: [-0.000008, -0.000002] +- [0.780705, 0.612191]

    baseline T_1_0:
     q: [ 0.01666776  0.00309728 -0.0076599   0.99982694] +- [ 0.00048461  0.00033787  0.00006493]
     t: [-0.01222477  0.02769849  0.00236502] +- [ 0.00008133  0.00008375  0.00019804]

    baseline T_2_1:
     q: [ 0.00075968 -0.00278317  0.00386212  0.99998838] +- [ 0.00035845  0.00033422  0.00005591]
     t: [ 0.06415713 -0.00017638 -0.00045003] +- [ 0.00008071  0.0000845   0.00020718]

question1: Is the reprojection error [0.000017, 0.000003] or [0.000017, 0.000003] + [1.969469, 1.554876]? question2: the result is ok ?

ishipachev commented 2 years ago

question1: the first pair of values. The second one is the RMS of the deviation I believe. question2: try to visualize it with open3d for an example. You can plot your cameras as frame with 0X, 0Y, 0Z axis. This will help you to estimate the result. But you need to transform T_2_1 and other T's accordingly.

alwynmathew commented 2 years ago

so @ishipachev, 0.000017 +- 1.969469 is the reprojection error and 0.000003 +- 1.554876 is the RMS of the deviation?

ishipachev commented 2 years ago

@alwynmathew No. [0.000017, 0.000003] -- is the mean reprojection error (not sure if I'm correct) and [+- 1.969469, +- 1.554876] are RMS

alwynmathew commented 2 years ago

@ishipachev why do we have two values as reprojection error [0.000017, 0.000003]? How can the mean reprojection error in pixels be this low?

@goldbattle is this the correct way to interpret the calibration result in kalibr?

goldbattle commented 2 years ago

The error is being printed here if you look at the code: https://github.com/ethz-asl/kalibr/blob/438f7545a303a8c8bf0699623879f149a9fec71e/aslam_offline_calibration/kalibr/python/kalibr_camera_calibration/CameraCalibrator.py#L599-L606

Thus we have the mean and its standard deviation for the x and y pixel coordinates. reprojection error: [-0.000008, -0.000002] +- [0.780705, 0.612191] Here we can see that the system is zero mean (which is good) with a standard deviation of 0.7.

The example Kalibr dataset has a STD of 0.33 and is zero mean. Its 3 sigma is 1.01 which captures the majority of reprojection errors if you inspect the PDF. reprojection error: [-0.000002, -0.000000] +- [0.336932, 0.283749] image

Normally, we want 0.1-0.3 reprojection error if you do a really good calibration. Thus you probably should recollect / focus your camera / try to improve your calibration if you are getting over 1 pixel sigma. Note that this also is dependent on the resolution of your camera (a 4K camera might be ok with 1 pixel if the FOV of the camera is the same as a 480p camera...).

Hope this helps.