How to Calibrate your ZED camera with OpenCV

Calibration #

Even though ZEDs are factory calibrated you may want to perform your own calibration and use its results in the ZED SDK.

This feature was introduced in ZED SDK version 3.4.

Using your own calibration will not erase the factory calibration, it will just replace it at runtime if requested using the API. To enable this behavior, you have to specify an opencv calibration file as InitParameters::optional_opencv_calibration_file.

Here are the steps to create your own calibration file.

Pattern #

We need a calibration pattern as a marker and as a world unit reference. You can refer to this page to create your own.

Calibration pattern good practices:

  • it should be printed or stuck to a flat surface.
  • it should be printed with accuracy, clear black and white, and no aliasing.
  • its size should be significant, A3 or more.
  • it should have enough markers (>100).
  • its marker size should be known and accurate.

Acquisition #

Once you have created your own calibration pattern you can perform your calibration acquisition. It is recommended to first do the acquisition and save the images to later compute the calibration.

Acquisition good practices:

  • the calibration pattern stays fixed, the camera moves around it.
  • put the calibration pattern in a clear area.
  • at each pose, keep the camera still for a short period to avoid motion blur.
  • the pattern should be fully visible in both the left and right images
  • multiply various poses, close up, distant, tilted…

Here is a short C++ sample to record your calibration images.

For better results perform your acquisition in FHD or 2K resolution. The ZED SDK will automatically adapt the given calibration file to the requested camera resolution at runtime.

 // Standard includes
#include <string.h>

// OpenCV include (for display)
#include <opencv2/opencv.hpp>

int main(int argc, char **argv) {   
    cv::VideoCapture zed;
    if (argc == 2)
        zed.open(atoi(argv[1]));
    else
        zed.open(0);

    //define the camera resolution
    cv::Size size_sbs(1920 * 2, 1080);

    // change camera param to fit requested resolution (ZED camera gives side by side images)
    zed.set(cv::CAP_PROP_FRAME_WIDTH, size_sbs.width);
    zed.set(cv::CAP_PROP_FRAME_HEIGHT, size_sbs.height);

    // create a file to save images names
    std::vector<std::string> v_names;

    // alloc a mat to store acquired images
    cv::Mat imag_sbs(size_sbs, CV_8UC3);
    int w_ = size_sbs.width * .5;

    // define Left and Right reference Mat
    cv::Mat imL = imag_sbs(cv::Rect(0, 0, w_, size_sbs.height));
    cv::Mat imR = imag_sbs(cv::Rect(w_, 0, w_, size_sbs.height));

    int nb_save = 0;
    const int NB_REQUIRED = 20;
    while (nb_save < NB_REQUIRED) {

        // grab and retrieve the current image
        zed >> imag_sbs;

        // Left and Right mat are directly updated because they are ref.

        cv::imshow("Left", imL); // display left image
        auto k = cv::waitKey(30);

        // if Space-bar is pressed, save the image
        if (k == 32) {
            std::string im_name("zed_image_L" + std::to_string(nb_save) + ".png");
            cv::imwrite(im_name, imL);
            v_names.push_back(im_name);

            im_name = "zed_image_R" + std::to_string(nb_save) + ".png";
            cv::imwrite(im_name, imR);
            v_names.push_back(im_name);

            nb_save++;
            std::cout << "Save im " << nb_save << "/" << NB_REQUIRED << std::endl;
        }
    }
    // close file and camera
    cv::FileStorage fs("zed_image_list.xml", cv::FileStorage::WRITE);
    fs.write("images", v_names);
    fs.release();
    zed.release();
    return EXIT_SUCCESS;
}

Left and Right images are recorded as PNG and a .xml file resumes their names to be loaded later.

Calibration #

A sample for stereo calibration is provided by opencv.

You can use the previously saved images directly with it. Do not forget to specify your calibration parameters (with/height/size).

You only have to make a few updates to generate the file which will be usable by the ZED SDK.

ZED SDK REQUIREMENTS

Intrinsic parameters:

  • Left and Right Camera Matrix: as 3x3 Matrix
  • Left and Right Distortion coefficients : as 5x1 Matrix [k1, K2, P1, P2, K3]
  • Image size, as a Size (width x height)

Extrinsic parameters:

  • Rotation, to transform Left image points to Right image points, as a 3x3 Matrix
  • Translation to transform Left image points to Right image points, as a 3x1 Matrix. T[0], the baseline between left and right sensors, should be negative and in millimeters (around -120mm for ZED/ZED2 and -63mm for ZED-M).

To export those parameters with the given code above, simply add the following changes:

    cout << "Running stereo calibration ...\n";

    Mat cameraMatrix[2], distCoeffs[2];
    cameraMatrix[0] = initCameraMatrix2D(objectPoints, imagePoints[0], imageSize, 0);
    cameraMatrix[1] = initCameraMatrix2D(objectPoints, imagePoints[1], imageSize, 0);

    distCoeffs[0] = Mat::zeros(1, 5, CV_64F);
    distCoeffs[1] = Mat::zeros(1, 5, CV_64F);
    Mat R, T, E, F;

    double rms = stereoCalibrate(objectPoints, imagePoints[0], imagePoints[1],
                                 cameraMatrix[0], distCoeffs[0],
                                 cameraMatrix[1], distCoeffs[1],
                                 imageSize, R, T, E, F,
                                 CALIB_FIX_ASPECT_RATIO +
                                 CALIB_USE_INTRINSIC_GUESS +
                                 CALIB_ZERO_TANGENT_DIST +
                                 CALIB_SAME_FOCAL_LENGTH,
                                 TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 100, 1e-5));
    cout << "done with RMS error=" << rms << endl;
    
    //-_-_-_-_-_-_-_-_-_-_-_-_-_-_-EXPORT FOR ZED SDK-_-_-_-_-_-_-_-_-_-__-_-_-_-_-_-_
    FileStorage fs("zed_calibration.yml", FileStorage::WRITE);
    if (fs.isOpened()) {
        fs << "Size" << imageSize;
        fs << "K_LEFT" << cameraMatrix[0] << "D_LEFT" << distCoeffs[0] << "K_RIGHT" << cameraMatrix[1] << "D_RIGHT" << distCoeffs[1];
        fs << "R" << R << "T" << T;
        fs.release();
    } else
        cout << "Error: can not save the extrinsic parameters\n";
    //-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_-_

The important point here is the output file format as the parameters are referred to by their names when loading them. DO NOT CHANGE “K_LEFT”, “D_RIGHT”…

You can change to calibration flags or parameters as long as you respect the requested format and naming.

To run the calibration process, run the program with the following arguments:

./zed_calibration -w=<number_of_corners_in_width_of_checkerboard> -h=<number_of_corners_in_height_of_checkerboard> -s=<square_size_in_mm> zed_image_list.xml ./

📌 Note: The square size must be specified in millimeters to produce a compatible calibration file.

The created file should look like this, it can now be read by the ZED SDK.

%YAML:1.0
---
Size: [ 1920, 1080 ]
K_LEFT: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [ 1.0561739630740988e+03, 0., 9.5479955903388236e+02, 0.,
       1.0655101534583052e+03, 5.4070306647256541e+02, 0., 0., 1. ]
D_LEFT: !!opencv-matrix
   rows: 1
   cols: 5
   dt: d
   data: [ -6.4250800697725263e-02, -7.0204351793832541e-03, 0., 0.,
       8.0362928754728780e-02 ]
K_RIGHT: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [ 1.0561739630740988e+03, 0., 9.7453658709437184e+02, 0.,
       1.0655101534583052e+03, 5.4358313913173276e+02, 0., 0., 1. ]
D_RIGHT: !!opencv-matrix
   rows: 1
   cols: 5
   dt: d
   data: [ -7.2554189408452013e-02, 3.9498684241329227e-02, 0., 0.,
       1.4743060765212916e-02 ]
R: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [ 9.9999985785830647e-01, 1.9732823768579258e-04,
       -4.9532305964778301e-04, -1.9645202059419688e-04,
       9.9999841707077197e-01, 1.7684067840452640e-03,
       4.9567123218064520e-04, -1.7683092254650132e-03,
       9.9999831369483450e-01 ]
T: !!opencv-matrix
   rows: 3
   cols: 1
   dt: d
   data: [ -1.1850257183526959e+02, 7.4052171607266154e-02,
       2.4289485282965835e+00 ]