双目测距--3 双目标定

news/2024/7/21 7:31:26 标签: matlab, 数码相机, 图像处理

目录

-1 流程说明:

0 几个重要 函数

1、calibrateCamera()函数

2、stereoCalibrate()

3、findChessboardCorners() 棋盘格角点检测

4、stereoRectify()

5、initUndistortRectifyMap()

6、remap() 

1、用于标定的图像

 2、标定前

3、OpenCV进行双目标定

单目标定 calibration.h

双目标定 doule--camera--calibration.h

主函数 mian.cpp


 

 

-1 流程说明:

  1. 单目标定:分别得到左相机、右相机的cameraMatrix(内部参数值)、disCoeffs(畸变矩阵)
  2. 双目标定:固定左右相机的内部参数值、畸变矩阵,求R (右相机坐标系相对于左相机坐标系的旋转矩阵),T(右相机坐标系相对于左相机坐标系的平移动向量), E(本征矩阵), F(基础矩阵)

0 几个重要 函数

1、calibrateCamera()函数

本代码在单目标定使用此函数

输入:世界坐标系的点、对应图像坐标系的点、图像尺寸

输出:相机的两个内参数(内参数矩阵、畸变矩阵)、两个外参数(旋转向量、位移向量)

double calibrateCamera(InputArrayOfArrays objectPoints, //世界坐标系的点
InputArrayOfArrays imagePoints, // 对应图像坐标系点
Size imageSize,  // 图像尺寸
InputOutputArray cameraMatrix, // 内参数矩阵 
InputOutputArray distCoeffs,  // 畸变矩阵
OutputArrayOfArrays rvecs,  // 旋转向量
OutputArrayOfArrays tvecs,  // 位移向量
int flags=0)

2、stereoCalibrate()

此函数用于 本代码双目标定

double stereoCalibrate( InputArrayOfArrays objectPoints, //【输入量】标定板特征点在世界坐标系下的坐标

    InputArrayOfArrays imagePoints1, //【输入量】标定板特征点在左相机像素坐标系下的坐标
InputArrayOfArrays imagePoints2, //【输入量】标定板特征点在右相机像素坐标系下的坐标
 InputOutputArray cameraMatrix1,  // 【输入量/输出量】左相机的内参矩阵
InputOutputArray distCoeffs1, // 【输入量/输出量】左相机的畸变量
 InputOutputArray cameraMatrix2, //【输入量/输出量】 右相机的内参矩阵
 InputOutputArray distCoeffs2,   // 【输入量/输出量】右相机的畸变量
 Size imageSize,    // 【输入量】标定板图像尺寸
InputOutputArray R, // 【输出量】右相机坐标系相对于左相机坐标系的旋转矩阵
InputOutputArray T, // 【输出量】右相机坐标系相对左相机坐标系的平移向量
OutputArray E,  // 【输出量】本征矩阵
OutputArray F, //【输出量】基本矩阵 
OutputArray perViewErrors, //【输出量】不同对(不同视角)的图像所对应的均方根重投影误差
int flags = CALIB_FIX_INTRINSIC, //【输入量】 函数的算法参数
 TermCriteria criteria = TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, //【输入量】 迭代优化终止条件
30, 
1e-6) );

不同的 flags(这里用的是第一个):

CALIB_FIX_INTRINSIC 只有R, T, E, and F 矩阵被估计。
CALIB_USE_INTRINSIC_GUESS 根据指定的标志优化部分或全部内在参数。初始值由用户提供。

3、findChessboardCorners() 棋盘格角点检测

bool findChessboardCorners( InputArray image, 
                                Size patternSize, 
                                OutputArray corners,
                                int flags = CALIB_CB_ADAPTIVE_THRESH + 
                                CALIB_CB_NORMALIZE_IMAGE );

第一个参数是输入的棋盘格图像(可以是8位单通道或三通道图像);
第二个参数是棋盘格内部的角点的行列数(注意:不是棋盘格的行列数,如棋盘格的行列数分别为4、8,而内部角点的行列数分别是3、7,因此这里应该指定为cv::Size(3, 7));
第三个参数是检测到的棋盘格角点,类型为std::vectorcv::Point2f。
第四个参数flag,用于指定在检测棋盘格角点的过程中所应用的一种或多种过滤方法,可以使用下面的一种或多种,如果都是用则使用OR:
cv::CALIB_CB_ADAPTIVE_THRESH:使用自适应阈值将图像转化成二值图像
cv::CALIB_CB_NORMALIZE_IMAGE:归一化图像灰度系数(用直方图均衡化或者自适应阈值)
cv::CALIB_CB_FILTER_QUADS:在轮廓提取阶段,使用附加条件排除错误的假设
cv::CALIB_CV_FAST_CHECK:快速检测

4、stereoRectify()

函数说明:
为每个摄像头计算立体校正的映射矩阵。所以其运行结果并不是直接将图片进行立体矫正,而是得出进行立体矫正所需要的映射矩阵
函数原型:

void stereoRectify( InputArray cameraMatrix1, InputArray distCoeffs1,
                                 InputArray cameraMatrix2, InputArray distCoeffs2,
                                 Size imageSize, InputArray R, InputArray T,
                                 OutputArray R1, OutputArray R2,
                                 OutputArray P1, OutputArray P2,
                                 OutputArray Q, int flags = CALIB_ZERO_DISPARITY,
                                 double alpha = -1, Size newImageSize = Size(),
                                 CV_OUT Rect* validPixROI1 = 0, CV_OUT Rect* validPixROI2 = 0 );

cameraMatrix1-第一个摄像机的摄像机矩阵
distCoeffs1-第一个摄像机的畸变向量
cameraMatrix2-第二个摄像机的摄像机矩阵
distCoeffs1-第二个摄像机的畸变向量
imageSize-图像大小
R- stereoCalibrate() 求得的R矩阵
T- stereoCalibrate() 求得的T矩阵
R1-输出矩阵,第一个摄像机的校正变换矩阵(旋转变换)
R2-输出矩阵,第二个摄像机的校正变换矩阵(旋转矩阵)
P1-输出矩阵,第一个摄像机在新坐标系下的投影矩阵
P2-输出矩阵,第二个摄像机在想坐标系下的投影矩阵

Q-4*4的深度差异映射矩阵
flags-可选的标志有两种零或者 CV_CALIB_ZERO_DISPARITY ,如果设置 CV_CALIB_ZERO_DISPARITY 的话,该函数会让两幅校正后的图像的主点有相同的像素坐标。否则该函数会水平或垂直的移动图像,以使得其有用的范围最大
alpha-拉伸参数。如果设置为负或忽略,将不进行拉伸。如果设置为0,那么校正后图像只有有效的部分会被显示(没有黑色的部分),如果设置为1,那么就会显示整个图像。设置为0~1之间的某个值,其效果也居于两者之间。
newImageSize-校正后的图像分辨率,默认为原分辨率大小。
validPixROI1-可选的输出参数,Rect型数据。其内部的所有像素都有效
validPixROI2-可选的输出参数,Rect型数据。其内部的所有像素都有效

5、initUndistortRectifyMap()

函数作用:

计算畸变矫正和立体校正的映射变换

函数原型:

void initUndistortRectifyMap(InputArray cameraMatrix, InputArray distCoeffs,
                             InputArray R, InputArray newCameraMatrix,
                             Size size, int m1type, OutputArray map1, OutputArray map2);

参数:

cameraMatrix-摄像机参数矩阵
distCoeffs-畸变参数矩阵
R- stereoCalibrate() 求得的R矩阵
newCameraMatrix-矫正后的摄像机矩阵(可省略)
Size-没有矫正图像的分辨率
m1type-第一个输出映射的数据类型,可以为 CV_32FC1  或  CV_16SC2
map1-输出的第一个映射变换
map2-输出的第二个映射变换

6、remap() 

函数作用

几何变换函数 。

在本代码中,利用此函数最终 得到畸变矫正,立体矫正后的图像,即左右相机共面且行对准了

所以说,下一个博客 中我可以直接 用initUndistortRectifyMap()得到的映射值直接进行几何变换!

整理工作应该早进行的,我之前的代码存在冗余。

函数原型:

void remap( InputArray src, OutputArray dst,
                         InputArray map1, InputArray map2,
                         int interpolation, int borderMode = BORDER_CONSTANT,
                         const Scalar& borderValue = Scalar());

参数:

src-原图像
dst-几何变换后的图像
map1-第一个映射,无论是点(x,y)或者单纯x的值都需要是CV_16SC2 ,CV_32FC1 , 或 CV_32FC2类型
map2-第二个映射,y需要是CV_16UC1 , CV_32FC1类型。或者当map1是点(x,y)时,map2为空。
interpolation-插值方法,但是不支持最近邻插值
剩下两个我也没看懂,但是一般示例程序中不会设置
 

1、用于标定的图像

在这之前你已经获得了双目相机拍摄的棋盘图像用于对左右相机内外参数进行标定,注意图像的名字要对应,如 left01.png right01.png

 

 2、标定前

不过在看下面的代码之前,你得先用Matlab对你拍摄的左右图像进行标定,如果你熟练这个软件,你可以把标定结果直接导出来用(下面的代码你不用看了)。

如果你和我一样,之前从没用过Matlab,不知道怎么导出标定结果,还是选择用OpenCV完成标定。那你听我娓娓道来:

  1. 用Matlab对左右成对图像进行标定,这个比较简单,在网上能搜到不少大佬的教程
  2. 在Matlab标定后,会对每对图像都有一个评分,去除哪些评分低的,使得总体的标定评分合理。
  3. 在你的图像文件夹删除刚刚评分低的图像对,然后用OpenCV进行标定

3、OpenCV进行双目标定

先进行左右相机各自标定,获得左右相机内参数。接着进行双目标定,获得左右相机外参数。

单目标定 calibration.h

#ifndef CALIBRATION_H
#define CALIBRATION_H

#include <iostream>
#include <fstream>

#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <opencv2/imgproc/imgproc.hpp>


using namespace std;
using namespace cv;

class calibration{
private:
    // 输入路径
    string fileInPath;

    // 输入图片
    vector<Mat> images;

    // 输出路径
    string fileOutPath;


    // 图像数量
    int image_count;

    // 图像尺寸
    Size image_size;

    //标定板每行、列的角点数
    Size board_corner_size;

    // 缓存每幅图像上检测到的角点
    vector<Point2f> image_points_buf;

    // 保存检测到的所有角点
    vector<vector<Point2f>> image_points_seq;


    // 角点个数
    int corner_count;

    // 实际测量得到的标定板上每个棋盘格的大小
    Size square_size;

    // 保存标定板上角点的三维坐标
    vector<vector<Point3f>> obejct_points;

    // 摄像机内参数矩阵
    Mat camraMatrix;

    // 摄像机的5个畸变系数;k1,k2,p1,p2,k3
    Mat disCoeffs;

    //每幅图像的旋转向量
    vector<Mat> tvecsMat;

    //每幅图像的平移向量
    vector<Mat> rvecMat;


public:
    calibration()
    {
        image_count = 0;
        corner_count = -1;

        camraMatrix = Mat(3,3,CV_32FC1,Scalar::all(0));
        disCoeffs = Mat(1,5,CV_32FC1, Scalar::all(0));

    }


    // 设置输入
    void setInputPath(string filePath)
    {
        vector<String> fn;
        glob(filePath, fn, false);


        int num = fn.size();
        for (int i=0; i<num; i++)
        {
            images.push_back(imread(fn[i]));

        }
    }

    // 设置角点尺寸
    void setCornerSize(int x, int y)
    {
        board_corner_size.width = x;
        board_corner_size.height = y;
    }

    // 设置棋盘格子大小
    void setSqureSize(int x, int y)
    {
        square_size = Size(x,y);
    }

    // 设置相机参数输出路径
    void setOutputPath(string filepath)
    {
        fileOutPath = filepath;
    }


    // 提取角点信息,并进一步提取亚像素角点信息
    void findCorners(bool draw=false)
    {
        cout<< "开始提取角点......."<<endl;

        for (int i=0; i<images.size(); i++)
        {

            // 读取图片
            Mat imageInput = images[i];

            image_count++;

            // 获取图片尺寸
            if(image_count==1)
            {
                image_size.width = imageInput.cols;
                image_size.height = imageInput.rows;
            }

            // 转灰度图像
            Mat gray_image;
            cvtColor(imageInput,gray_image,COLOR_BGR2GRAY);

            // 提取角点
            if (0 == findChessboardCorners(gray_image,
                                           board_corner_size,
                                           image_points_buf))
            {
                cout << "***" << " cannot find chessboardcorners";
            }
            else
            {
                cornerSubPix(gray_image,image_points_buf,
                             Size(5,5),Size(-1,-1),
                             TermCriteria(TermCriteria::EPS +
                                          TermCriteria::MAX_ITER, 30, 0.1));
                // 绘制内角点
                if(draw)
                {
                    drawChessboardCorners(gray_image, board_corner_size,
                                               image_points_buf, false);

                    imshow("img",gray_image);
                    waitKey(500);

                }
                // 保存角点
                image_points_seq.push_back(image_points_buf);
            }
        }


       //查看每张图片所检测到的内角点数量
       int num = image_points_seq.size();
       for (int i=0; i<num; i++)
       {
           cout<< "第 " << i
               << "张图片的内角点数量:"
               <<image_points_seq[i].size()
              << endl;
       }
       cout << "**********角点提取完成************"
            <<endl<<endl<<endl;
    }



    // 相机标定
    void standard()
    {
        // 三维坐标
        int i,j,t;
        for(t=0; t<image_count; t++)
        {
            vector<Point3f> tempPointSet;
            for (i=0; i<board_corner_size.height;i++)
            {
                for(j=0;j<board_corner_size.width;j++)
                {
                    Point3f realPoint;

                    realPoint.x=j*square_size.width;
                    realPoint.y=i*square_size.height;
                    realPoint.z=0;
                    tempPointSet.push_back(realPoint);
                }
            }
            obejct_points.push_back(tempPointSet);
        }

        // 三维坐标与图像的二维点进行标定
        /* 三维点、角点--->相机内参数、相机外参数*/
        cout<<"**********开始标定****************"<<endl;
        calibrateCamera(obejct_points,
                        image_points_seq,
                        image_size,
                        camraMatrix,
                        disCoeffs,
                        rvecMat,
                        tvecsMat);
        cout<<"**********标定完成****************"<<endl<<endl<<endl;

        // 对标定结果进行评价
        cout<<"**********开始评价标定****************"<<endl;
        double total_err = 0.0; // 所有图像的平均误差的总和
        double err = 0.0;      // 每幅图像的平均误差
        vector<Point2f> image_points_new; // 保存重新计算得到的投影点

        /*三维坐标、相机内参数---->二维图像坐标*/
        for (i=0; i<image_count; i++)
        {
           vector<Point3f> temp_obejct = obejct_points[i];
           projectPoints(temp_obejct,
                         rvecMat[i],
                         tvecsMat[i],
                         camraMatrix,
                         disCoeffs,
                         image_points_new);

           /*计算刚刚的投影得到的坐标与角点坐标的误差值*/
           vector<Point2f> temp_corners = image_points_seq[i];
           Mat temp_corners_mat = Mat(1, temp_corners.size(),
                                   CV_32FC2);
           Mat image_points_new_mat = Mat(1, image_points_new.size(),
                                          CV_32FC2);

           for (int j=0; j<temp_corners.size(); j++)
           {
               image_points_new_mat.at<Vec2f>(0,j) =
                       Vec2f(image_points_new[j].x, image_points_new[j].y);
               temp_corners_mat.at<Vec2f>(0,j) =
                       Vec2f(temp_corners[j].x, temp_corners[j].y);
           }

           err = norm(image_points_new_mat,temp_corners_mat, NORM_L2);
           total_err += err /= (board_corner_size.width * board_corner_size.height);
           cout << "第" << i+1 << "副图像的平均误差:"
                << err << "像素" << endl;

        }

        cout << "总体误差:" << total_err / image_count
             << "像素" << endl;
        cout << "********评价完成*******" <<endl<<endl<<endl;

        // 保存相机参数
        cv::FileStorage fs2(fileOutPath, cv::FileStorage::WRITE);
        fs2 << "cameraMatrix" << camraMatrix;
        fs2 << "disCoeffs"<<disCoeffs;
        fs2.release();
        cout<< "camraMatrix:" <<endl
            << camraMatrix<<endl;
        cout<<"discoeffs:"<<endl
           <<disCoeffs<<endl<<endl;
        cout << "*******已保存相机参数*****"<<endl<<endl;

    }

    // 利用标记结果矫正
    void correction(Mat& image, Mat &out)
    {
        Mat mapx = Mat(image.size(),CV_32FC1);
        Mat mapy = Mat(image.size(), CV_32FC1);
        Mat R = Mat::eye(3,3,CV_32F);

        initUndistortRectifyMap(camraMatrix,
                                disCoeffs,
                                R,
                                camraMatrix,
                                image.size(),
                                CV_32FC1,
                                mapx, mapy);
        remap(image, out, mapx, mapy, INTER_LINEAR);
        imshow("correction",out);
        imshow("img", image);
        waitKey();
    }
};

双目标定 doule--camera--calibration.h

#include <iostream>
//#include <fstream>
#include <stdio.h>

#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/opencv.hpp>

using namespace cv;
using namespace std;

// 双目标定
// 参考:https://blog.csdn.net/u010801994/article/details/84563208

class doubleCalibration{
private:

    // 左右摄像机图片路径
    string img_path_L,img_path_R;

    // 保存输出路径
    string outPath;

    // 左右相机内参
    /*摄像机内参反映的是摄像机坐标系到图喜爱嗯坐标系之间的投影关系
    /*包括fx,fy,cx,y,以及畸变系数[k1,k2,p1,p2,k3]
   /*事先标定好的左相机的内参矩阵
    fx 0 cx
    0 fy cy
    0  0  1
    */
    Mat cameraMatrix_L;
    Mat cameraMatrix_R;
    Mat discoeff_L; /*畸变系数[k1,k2,p1,p2,k3]*/
    Mat discoeff_R;

    // 标定版内角点尺寸
    Size board_Corner_size;

    // 标定版棋盘格子尺寸
    Size square_size;

    // 图片尺寸
    Size img_size;

    // 标定板的实际物理坐标
    vector<vector<Point3f>> obejct_points;

    // 被读取的图片数量
    int img_cout;



    // 左边、右边摄像机所有照片角点的坐标集合
    vector<vector<Point2f>> corners_L;
    vector<vector<Point2f>> corners_R;


    // 图像
    Mat imgL;
    Mat imgR;
    Mat grayL;
    Mat grayR;

    Mat rectifyImageL2, rectifyImageR2;
    Mat rectifyImageL, rectifyImageR;

    /*s摄像机外参反映的是摄像机坐标系和世界坐标系之间的旋转R和平移T关系*/
    /* 外参一旦标定好,下两个相机的结构就要保持固定,否杂外参就会发生变化,需要重新进行外参标定*/
    Mat R, T, E,F;/*R旋转矢量 T平移矢量 E本征矩阵  F基础矩阵*/

//    Mat intrinsic; 这些没有用
//    Mat distortion_coeff;
//    vector<Mat> rvecs; //R
//    vector<Mat> tvecs; //T

    // 对极线校正(立体校正)用
    Mat Rl, Rr, Pl, Pr,Q;/*矫正旋转矩阵R,投影矩阵P,重投影矩阵Q*/
    Mat mapLx, mapLy, mapRx, mapRy; // 映射表
    Rect validROIL, validROIR;/*图像矫正之后,会对图像进行剪裁,其中,validROI建材之后的区域*/

private:

    void outputCameraParam(void)
    {
        /*保存数据*/
        /*输出数据*/
        Mat rectifyImageL2, rectifyImageR2;
        string outPath1 =outPath + "intrisics.yml";


        FileStorage fs(outPath1, FileStorage::WRITE);
        if(fs.isOpened())
        {
            fs << "cameraMatrixL" << cameraMatrix_L
               << "cameradistCoeffsL" << discoeff_L
               << "cameraMatrixR" << cameraMatrix_R
               << "cameradistCoeffsR" << discoeff_R;
            fs.release();
            cout << "cameraMatrixL = " << cameraMatrix_L <<endl
                 << "cameradistCoeffsL = " << discoeff_L <<endl
                 << "cameraMatrixR = " << cameraMatrix_R <<endl
                 << "cameradistCoeffsR = " << discoeff_R<<endl;

        }
        else
        {
            cout << "Erro:can not save the intrinsics!!!!"<<endl;
        }

        string outPath2 =outPath + "extrinsics.yml";
        fs.open(outPath2, FileStorage::WRITE);
        if (fs.isOpened())
        {
            fs << "R" << R << "T" << T << "Rl" << Rl << "Rr" <<Rr
               << "Pl" << Pl << "Pr" << Pr << "Q" << Q

               << "mapLx"<< mapLx /*这些应该就够了*/
               << "mapLy"<< mapLy
               << "mapRx" << mapRx
               << "mapRy"<< mapRy ;

            cout << "R" << R  << endl
                 << "T" << T << endl
                 << "Rl" << Rl << endl
                 << "Rr" <<Rr << endl
                 << "Pl" << Pl << endl
                 << "Pr" << Pr << endl
                 << "Q" << Q << endl;

            fs.release();
        }
        else
        {
            cout << "Erro:can not save the extrinsics parameters!!!!"<<endl;
        }
    }

public:
    doubleCalibration():img_cout(0){}
    // 设置左右摄像机图片路径
    void setImgInPath(string L, string R)
    {
        img_path_L = L;
        img_path_R = R;
    }

    // 设置输出路径
    void setOutPath(string path)
    {
        outPath = path;
    }

    // 设置左右相机参数文件路径
    void setCameraParameterInput(string L, string R)
    {
        cv::FileStorage file_L(L, FileStorage::READ);
        cv::FileStorage file_R(R,FileStorage::READ);

        file_L["cameraMatrix"] >> cameraMatrix_L;
        file_L["disCoeffs"] >> discoeff_L;
        file_R["cameraMatrix"] >> cameraMatrix_R;
        file_R["disCoeffs"] >> discoeff_R;

        cout << "cameraMatrix_L :" <<endl<< cameraMatrix_L <<endl
             << "discoeff_L :"  <<endl<<  discoeff_L <<endl
             << "cameraMatrix_R :" <<endl<< cameraMatrix_R <<endl
             << "discoeff_R :" <<endl<< discoeff_R <<endl <<endl;
    }

    // 设置标定板内角点尺寸
    void setCornerSize(int x, int y)
    {
        board_Corner_size.width = x;
        board_Corner_size.height = y;
    }

    // 设置标定版棋盘格子尺寸
    void setSquareSize(int x ,int y)
    {
        square_size.width = x;
        square_size.height = y;
    }

    // 设置标定板的实际物理坐标
    void set3DCoordinates()
    {
       vector<Point3f> tempPoints; // 与角点走向相匹配
       for (int rowIndex = 0; rowIndex < board_Corner_size.height; rowIndex++)
       {
           for (int colIndex = 0; colIndex < board_Corner_size.width; colIndex++)
           {

               Point3f realPoint;

               realPoint.x=colIndex * square_size.width;
               realPoint.y=rowIndex * square_size.height;
               realPoint.z=0;
               tempPoints.push_back(realPoint);

           }
       }

       for (int imgIndex = 0; imgIndex<img_cout; imgIndex++)
       {
           obejct_points.push_back(tempPoints);
       }
    }



    // 提取角点
    void getCorners()
    {

        vector<Point2f> temp_points_L;
        vector<Point2f> temp_points_R;

        string fileNameL;
        string fileNameR;

        cout<< "**********正在提取角点......" <<endl;

        vector<string> fnL, fnR;
        vector<Mat> imagesL, imagesR;
        glob(img_path_L, fnL);
        glob(img_path_R, fnR);

        if (fnL.size() == fnR.size())
        {
            for (int i=0; i<fnL.size(); i++)
            {
                imagesL.push_back(imread(fnL[i]));
                imagesR.push_back(imread(fnR[i]));

            }
        }



        for (int i =0; i<imagesL.size(); i++)
        {
            img_cout++;
            imgL = imagesL[i];
            imgR = imagesR[i];

            cvtColor(imgL,grayL,COLOR_BGR2GRAY);
            cvtColor(imgR,grayR,COLOR_BGR2GRAY);


            if (findChessboardCorners(grayL, board_Corner_size,temp_points_L)
                    && findChessboardCorners(grayR, board_Corner_size, temp_points_R))
            {

                cornerSubPix(grayL, temp_points_L,
                             Size(5,5), Size(-1,-1),
                             TermCriteria(TermCriteria::EPS|TermCriteria::MAX_ITER, 20, 0.01));
                drawChessboardCorners(imgL,board_Corner_size,
                                      temp_points_L,true);

                cornerSubPix(grayR, temp_points_R,
                             Size(5,5), Size(-1,-1),
                             TermCriteria(TermCriteria::EPS|TermCriteria::MAX_ITER, 20, 0.01));
                drawChessboardCorners(imgR,board_Corner_size,
                                      temp_points_R,true);

                imshow("chessborad",imgL);
                imshow("chessborad",imgL);
                corners_L.push_back(temp_points_L);
                corners_R.push_back(temp_points_R);

                cout << "******"<<fnL[i]<< "成功提取到内角点"<<endl;
                cout << "******"<<fnR[i]<< "成功提取到内角点"<<endl<<endl;
                if ((char)waitKey(50)=='q')
                {
                    break;
                }
            }

            if (img_cout ==1)
            {
                img_size.width = imgL.cols;
                img_size.height = imgL.rows;
            }

        }

        cout << "总共有 " << img_cout << " x2 张图片提取到内角点"<<endl<<endl<<endl;
    }



    // 标定摄像头
    void calibration()
    {

        cout << "img_cout:" <<img_cout<<endl;
        set3DCoordinates();

        // 双目标定
        Mat perViewErrors;
        double rms = stereoCalibrate(obejct_points, corners_L,corners_R,
                                     cameraMatrix_L,discoeff_L,
                                     cameraMatrix_R, discoeff_R,
                                     img_size,
                                     R,  /*右相机坐标系相对于左相机坐标系的旋转矩阵*/
                                     T, /* 右相机坐标系相对于左相机坐标系的平移向量*/
                                     E, /* 本征矩阵*/
                                     F, /* 基本矩阵*/
                                     perViewErrors,
                                     CALIB_FIX_INTRINSIC,
                                     TermCriteria(TermCriteria::COUNT+TermCriteria::EPS,
                                                  100, 1e-6));
        // CALIB_USE_INTRINSIC_GUESS 根据指定的标志优化部分或全部内在参数。初始值由用户提供。
        //CALIB_FIX_INTRINSIC:是否固定内参;只有R, T, E, and F 矩阵被估计。
        cout << "Stereo Calibration done with RMS error = " << rms << endl;
        waitKey();

        // 要通过两幅图像估计物体的深度信息,就必须在两幅图像中准确地匹配到同一物体
        // 这样才能根据该物点在两幅图像中的位置关系,计算物体深度
        // 为了降低匹配的计算量,两个摄像头的成像平面应处于统一平面
        // 立体校正为每个摄像头计算立体校正所需要的映射矩阵,达到上述目的
        stereoRectify(cameraMatrix_L,discoeff_L,cameraMatrix_R,discoeff_R,
                      img_size, R, T, Rl,Rr, Pl, Pr, Q, CALIB_ZERO_DISPARITY, -1,
                      img_size, &validROIL, &validROIR);

        // 对极线校正(立体校正),(得到校正映射)
        initUndistortRectifyMap(cameraMatrix_L,discoeff_L,
                                Rl,Pl,img_size,CV_32FC1,
                                mapLx,mapLy);
        initUndistortRectifyMap(cameraMatrix_R, discoeff_R,
                                Rr,Pr,img_size, CV_32FC1,
                                mapRx,mapRy);


        cvtColor(grayL, rectifyImageL, COLOR_GRAY2BGR);
        cvtColor(grayR, rectifyImageR, COLOR_GRAY2BGR);

        imshow("Recitify Before", rectifyImageL);
        imshow("Recitify Before", rectifyImageR);

        // 进行映射
        // 经过remap之后,左右相机的图像已经共面并且行对准了
        remap(rectifyImageL, rectifyImageL2, mapLx, mapLy, INTER_LINEAR);
        remap(rectifyImageR,rectifyImageR2,mapLx,mapLy,INTER_LINEAR);

        imshow("recitify Before", rectifyImageL2);
        imshow("recitify Before", rectifyImageR2);

        outputCameraParam();
    }

    // 显示校正结果
    void showRect()
    {
        Mat canvas;
        double sf;
        int w,h;
        sf = 600. / max(img_size.width, img_size.height); /*宽1200,高600*/
        w = cvRound(img_size.width * sf);
        h = cvRound(img_size.height * sf);
        canvas.create(h, w*2, CV_8UC3);

        // 左图像画到画布上
        Mat canvasPart = canvas(Rect(0,0,w,h)); // 浅复制
        resize(rectifyImageL2,canvasPart, canvasPart.size(), 0, 0, INTER_AREA);
        Rect vroiL(cvRound(validROIL.x * sf), cvRound(validROIL.y * sf),
                   cvRound(validROIL.width * sf), cvRound(validROIL.height *sf));
        rectangle(canvasPart, vroiL, Scalar(0,0,255), 3, 8);
        cout << "Painted ImageL" << endl;

        // 右图像画到画布上
        canvasPart = canvas(Rect(w,0,w,h));
        resize(rectifyImageR2,canvasPart, canvasPart.size(), 0, 0, INTER_AREA); /*基于区域像素关系的一种重采样或者插值方式.该方法是图像抽取的首选方法,
                                                                                它可以产生更少的波纹,但是当图像放大时,它的效果与INTER_NEAREST效果相似.*/
        Rect vroiR(cvRound(validROIR.x * sf), cvRound(validROIR.y * sf),
                   cvRound(validROIR.width * sf), cvRound(validROIR.height *sf));
        rectangle(canvasPart, vroiR, Scalar(0,0,255), 3, 8);
        cout << "Painted ImageR" << endl;

        // 画上对应的线条
        for (int i=0; i< canvas.rows; i+=16)
        {
            line(canvas, Point(0,i), Point(canvas.cols, i),
                 Scalar(0, 255, 0),1,8);

        }
        imshow("rectified", canvas);
        waitKey(0);
    }


    };

主函数 mian.cpp

#include "calibration.h"
#include "double--camera--calibration.h"
//#include "get-depth-mat.h"

int main()
{
    bool LorR= 0; // 左相机标定,右相机标定
    bool double_camera = 0; // 双目标定
    bool getDepthImg = 1;

    if (LorR)
    {


        calibration standard;
        // 设置角点尺寸
        standard.setCornerSize(8, 5);

        // 设置棋盘格子大小
        standard.setSqureSize(27,27);
        // 设置输入
        standard.setInputPath("/home/jason/work/01-img/right2/*.png");
        // 设置相机参数输出
        standard.setOutputPath("/home/jason/work/my--camera/calibration/right.yml");

        // 提取角点信息,并进一步提取亚像素角点信息
        standard.findCorners(true);
        // 相机标定
        standard.standard();

    }

    if (double_camera)
    {
        doubleCalibration doubleCamera;
        doubleCamera.setImgInPath("/home/jason/work/01-img/left2/*.png",
                              "/home/jason/work/01-img/right2/*.png");
        doubleCamera.setOutPath("/home/jason/work/my--camera/calibration/");
        doubleCamera.setCameraParameterInput("/home/jason/work/my--camera/calibration/left.yml",
                                             "/home/jason/work/my--camera/calibration/right.yml");
        doubleCamera.setCornerSize(8, 5);
        doubleCamera.setSquareSize(27, 27);


        doubleCamera.getCorners();
        doubleCamera.calibration();
        doubleCamera.showRect();
    }

//    if (getDepthImg)
//    {
//        GetDepthMat depthGet;
//        depthGet.setParameterPath("/home/jason/work/my--camera/calibration/");
//        depthGet.getImg();
//    }





    return 0;


}

参考:

(单/双目)图像标定全流程(C++/Opencv实现)---代码篇_c++单目衍射图像处理_chang_rj的博客-CSDN博客
OpenCV函数用法之calibrateCamera_tiger&sheep的博客-CSDN博客

C++ OpenCV V4.x中的新版双目标定函数stereoCalibrate() 参数说明【新增perViewErrors】_ViolentElder的博客-CSDN博客

OpenCV相机标定全过程_opencv checkboard_czhzasui的博客-CSDN博客

Opencv之initUndistortRectifyMap函数和 remap()函数_敲代码的盖世英雄的博客-CSDN博客

下面这个博客很全:

StereoRectify()函数定义及用法畸变矫正与立体校正_一只会走路的鱼的博客-CSDN博客


http://www.niftyadmin.cn/n/296228.html

相关文章

BM58-字符串的排列

题目 输入一个长度为 n 字符串&#xff0c;打印出该字符串中字符的所有排列&#xff0c;你可以以任意顺序返回这个字符串数组。 例如输入字符串ABC,则输出由字符A,B,C所能排列出来的所有字符串ABC,ACB,BAC,BCA,CBA和CAB。 数据范围&#xff1a;n < 10。 要求&#xff1a;空…

Java 基础进阶篇(十二)—— Arrays 与 Collections 工具类

文章目录 一、Arrays工具类1.1 Arrays 类常用方法1.2 对于 Comparator 比较器的支持1.3 Arrays 的综合应用1.3.1 应用一&#xff1a;数组的降序排序1.3.2 应用二&#xff1a;根据学生年龄进行排序 二、Collections工具类2.1 Collections 类常用方法2.2 Collections 排序相关 AP…

【Linux】Linux安装Maven(图文解说详细版)

文章目录 前言1.去官网下载2.下载完成上传到/opt目录下3.解压缩4.配置环境变量5.刷新配置文件使得配置文件生效6.然后我们运行mvn -v查看是否成功7.出现错误&#xff0c;接下来全程高能带你刨析这个错误&#xff01;8.这里又出现一个坑&#xff0c;就是每次重新进终端的时候mvn…

Nginx 反向代理、负载均衡、页面缓存、URL重写及读写分离详解

Nginx是一款高性能的Web服务器和反向代理服务器&#xff0c;它可以用于反向代理、负载均衡、页面缓存、URL重写以及读写分离等多种应用场景。在本文中&#xff0c;我们将详细介绍Nginx反向代理、负载均衡、页面缓存、URL重写以及读写分离的原理和应用。 一、Nginx反向代理 反…

Camtasia Studio2023Mac最新电脑版屏幕录像软件

Camtasia Studio2023提供了强大的屏幕录像、视频的剪辑和编辑、视频菜单制作、视频剧场和视频播放功能等。它能在任何颜色模式下轻松地记录屏幕动作&#xff0c;包括影像、音效、鼠标移动的轨迹&#xff0c;解说声音等等&#xff0c;另外&#xff0c;它还具有及时播放和编辑压缩…

前端三剑客 - HTML

前言 前面都是一些基础的铺垫&#xff0c;现在就正式进入到web开发环节了。 我们的目标就是通过学习 JavaEE初阶&#xff0c;搭建出一个网站出来。 一个网站分成两个部分&#xff1a; 前端&#xff08;客户端&#xff09; 后端&#xff08;服务器&#xff09; 通常这里的客户端…

C++相比于C语言增加的8个特性(详解)

C相比于C语言增加的8个特性&#xff08;详解&#xff09; 文章目录 C相比于C语言增加的8个特性&#xff08;详解&#xff09;一、命名空间二、C输入和输出三、缺省参数四、函数重载五、引用六、内联函数七、auto关键字八、指针空值nullptr总结 一、命名空间 c的命名空间是为了…

Rockmq高级特性解读(二)

随着互联网的快速发展&#xff0c;消息队列成为了构建分布式系统的重要组成部分&#xff0c;而RockMQ则是在分布式消息中间件领域里的一种开源消息中间件。 RockMQ一经发布就备受广大开发者们的喜爱&#xff0c;得到了广泛的应用和推崇。它具有许多优秀的特性和功能&#xff0…