stereolabs/zed-matlab

Calibration result and getCameraInformation() does not match

changh95 opened this issue · 4 comments

I have been getting some differences in between the calibration result that is achieved by using 'ZED SDK/tools/ZED Calibration.exe'(stored in SNXXXX.conf) and the camera parameters that can be achieved from mexZED('getCameraInformation') function on MATLAB.

According to the documentation, the calibration result from the ZED SDK software and mexZED functions should be the same. But you can see differences exist in the results as shown on below image

image

The code I used is as follows:
`mexZED('create');
% Set Camera Parameters (Autocalib = off)
FreeFocusParameters.camera_disable_self_calib = 1;
FreeFocusParameters.camera_resolution = 2; %720p
FreeFocusParameters.camera_fps = 60;
FreeFocusParameters.depth_mode = 'DEPTH_MODE_NONE';
FreeFocusParameters.coordinate_system = 'COORDINATE_SYSTEM_IAMGE';

result = mexZED('open',FreeFocusParameters);
mexZED('getCameraInformation')`

You are not comparing the same thing :

  • On the file, the raw (unrectified) calibration parameters are listed. They belongs to the raw image of the camera.
  • On Matlab, the getCameraInformation outputs the rectified calibration parameters, i.e. the parameters that belongs to the rectified image from the SDK (retrieveImage(LEFT/RIGHT).
    See here: https://github.com/stereolabs/zed-matlab/blob/master/src/mex/mexZED.cpp#L594

If you want to compare them, then change the line in mexZED.cpp to output the raw parameters :
fillCameraParam(pLeft, camInfo.calibration_parameters_raw.left_cam);

You are not comparing the same thing :

  • On the file, the raw (unrectified) calibration parameters are listed. They belongs to the raw image of the camera.
  • On Matlab, the getCameraInformation outputs the rectified calibration parameters, i.e. the parameters that belongs to the rectified image from the SDK (retrieveImage(LEFT/RIGHT).
    See here: https://github.com/stereolabs/zed-matlab/blob/master/src/mex/mexZED.cpp#L594

If you want to compare them, then change the line in mexZED.cpp to output the raw parameters :
fillCameraParam(pLeft, camInfo.calibration_parameters_raw.left_cam);

Thanks for your reply @obraun-sl .

From what I've understood,

  • The file's calibration parameters are used to rectify raw images, therefore contains distortion coefficients.
  • MATLAB's calibration parameters are the result of rectified images, hence does not contain any distortion coefficients

I will have a check with my aruco algorithm while waiting for your (or other people's) confirmation. I had used the file's calibration parameters previously and the depth information seemed to strangely off. Maybe this is the cause.

Yes you are correct.
For an Aruco tracking, then use the rectified parameters since you will use rectified images from the ZED SDK.
Basically :

  • If you are using rectified image, you will always need rectified parameters ( --> camInfo.calibration_parameters.left_cam)
  • If you are using raw image (unrectified) , you will always need unrectified parameters (with distortion for ex) ( --> camInfo.calibration_parameters_raw.left_cam)

For an Aruco sample, you can check ours here :
https://github.com/stereolabs/zed-aruco

@obraun-sl
I have just checked it with aruco detection algorithm.
The parameter you suggested works perfectly with the algorithm!
Thanks a lot!

This thread will now be closed :)