雙目標定跑通ORB-SLAM2

標定目的

攝像機標定分爲兩部分:

1.從世界座標系轉換到相機座標系,由於這兩個座標系都是三維的,所以這一部分就是三維空間轉到另外一個三維空間
2.從相機座標系轉換到圖像座標系,由於圖像座標系是二維的,所以這一部分就是三維空間轉到另外一個二維空間

在圖像測量過程以及機器視覺應用中,爲確定空間物體表面某點的三維幾何位置與其在圖像中對應點之間的相互關係,必須建立相機成像的幾何模型,這些幾何模型參數就是相機參數。在大多數條件下這些參數必須通過實驗與計算才能得到,這個求解參數的過程就稱之爲相機標定(或攝像機標定)。無論是在圖像測量或者機器視覺應用中,相機參數的標定都是非常關鍵的環節,其標定結果的精度及算法的穩定性直接影響相機工作產生結果的準確性。因此,做好相機標定是做好後續工作的前提,提高標定精度是科研工作的重點所在。

(雙目)攝像機標定最主要的目的:是要得求出每個攝像機的相機內參數矩陣K和畸變係數矩陣D,左右兩個攝像機的相對位置關係(即右攝像頭相對於左攝像頭的平移向量 t和旋轉矩陣R)。 由於OpenCV中StereoCalibrate標定的結果極其不穩定,甚至會得到很誇張的結果,因此推薦採用Matlab進行標定,再將標定的結果讀入OpenCV,來進行後續圖像校準和匹配。

opencv雙目標定

棋盤格

先標定單目,獲得兩個單目的內參和畸變係數,帶入到下面程序中。MATLAB單目標定工具箱TOOLBOX_calib

data文件夾(存放左右圖像)和主程序文件stereo.cpp,CMakeLists.txt在同一目錄下,左右圖像各13張,Clion直接運行。
參考:

經實測,opencv sample裏面自帶的雙目標定程序(stereo_clib.cpp),對平角相機效果較好,如果你是平角相機跳過本段,直接查看ORBSLAM2的雙目配置參數,而stereo_clib.cpp對廣角相機效果奇差。

先自行標定左右相機的單目畸變參數,填入下面代碼中的初始化參數,樓主用的kalibr標定的單目,opencv也可以標定,這個自己解決。
說明一點,單目預標定沒必要標的很精確,差不多就成,當然標的精確更好,畸變參數4,5個都可以,單目的所有預標定參數將在下面的代碼中進行迭代優化。

修改你的棋盤信息 縱橫角點數 還有每個格子的大小 單位mm。廣角雙目標定代碼如下:

//
// Created by gavyn on 20-4-27.
//

#include "opencv2/core/core.hpp"
#include "opencv2/imgproc/imgproc.hpp"
#include "opencv2/calib3d/calib3d.hpp"
#include "opencv2/highgui/highgui.hpp"
#include <vector>
#include <string>
#include <algorithm>
#include <iostream>
#include <iterator>
#include <stdio.h>
#include <stdlib.h>
#include <ctype.h>
#include <opencv2/opencv.hpp>
#include "cv.h"
#include <cv.hpp>
using namespace std;
using namespace cv;
const int imageWidth = 640;
const int imageHeight = 480;
const int boardWidth = 9;//橫向的角點數目
const int boardHeight = 6;//縱向的角點數據
const int boardCorner = boardWidth * boardHeight;//總的角點數據
const int squareSize = 10;//標定板黑白格子的大小單位mm
const int frameNumber = 13;//相機標定時需要採用的圖像幀數
const Size boardSize = Size(boardWidth, boardHeight);

Size imageSize = Size(imageWidth, imageHeight);//標定板的總內角點
Mat R, T, E, F;//R 旋轉矢量 T平移矢量 E本徵矩陣 F基礎矩陣
vector<Mat> rvecs;//旋轉向量
vector<Mat> tvecs;//平移向量
vector<vector<Point2f>> imagePointL;//左邊攝像機所有照片角點的座標集合
vector<vector<Point2f>> imagePointR;//右邊攝像機所有照片角點的座標集合
vector<vector<Point3f>> objRealPoint;//各副圖像的角點的實際物理座標集合
vector<Point2f> cornerL;//左邊攝像機某一照片角點座標集合
vector<Point2f> cornerR;//右邊攝像機某一照片角點座標集合

Mat rgbImageL, grayImageL;
Mat rgbImageR, grayImageR;
Mat Rl, Rr, Pl, Pr, Q;//校正旋轉矩陣R,投影矩陣P 重投影矩陣Q (下面有具體的含義解釋)
Mat mapLx, mapLy, mapRx, mapRy;//映射表
Rect validROIL, validROIR;//圖像校正之後,會對圖像進行裁剪,這裏的validROI就是指裁剪之後的區域

//這時候就需要你把左右相機單目標定的參數給寫上
/*事先標定好的左相機的內參矩陣
fx 0 cx
0 fy cy
0 0  1*/
Mat cameraMatrixL = (Mat_<double>(3, 3) << 296.65731645541695, 0, 343.1975436071541,
        0, 300.71016643747646, 246.01183552967473,
        0, 0, 1);
Mat distCoeffL = (Mat_<double>(4, 1) << -0.23906272129552558, 0.03436102573634348, 0.001517498429211239, -0.005280695866378259);//單目標定獲得左相機的畸變參數
/*事先標定好的右相機的內參矩陣
fx 0 cx
0 fy cy
0 0  1*/
Mat cameraMatrixR = (Mat_<double>(3, 3) << 296.92709649579353, 0, 313.1873142211607,
        0, 300.0649937238372, 217.0722185756087,
        0, 0, 1);
Mat distCoeffR = (Mat_<double>(4, 1) << -0.23753878535018613, 0.03338842944635466, 0.0026030620085220105, -0.0008840126895030034);//單目標定獲得右相機的畸變參數



void calRealPoint(vector<vector<Point3f>>& obj, int boardwidth, int boardheight, int imgNumber, int squaresize)
{
    vector<Point3f> imgpoint;
    for (int rowIndex = 0; rowIndex < boardheight; rowIndex++)
    {
        for (int colIndex = 0; colIndex < boardwidth; colIndex++)
        {
            imgpoint.push_back(Point3f(rowIndex * squaresize, colIndex * squaresize, 0));
        }
    }
    for (int imgIndex = 0; imgIndex < imgNumber; imgIndex++)
    {
        obj.push_back(imgpoint);
    }
}

//外參數
// R--右相機相對左相機的旋轉矩陣
// T--右相機相對左相機的平移矩陣
// R1,R2--左右相機校準變換(旋轉)矩陣  3×3
// P1,P2--左右相機在校準後座標系中的投影矩陣 3×4
// Q--視差-深度映射矩陣,我利用它來計算單個目標點的三維座標
//    Mat R1, R2, P1, P2, Q;//由stereoRectify()求得

void outputCameraParam(void)
{	/*保存數據*/	/*輸出數據*/
    FileStorage fs("intrinsics.yml", FileStorage::WRITE);  //文件存儲器的初始化
    if (fs.isOpened())
    {
        fs << "cameraMatrixL" << cameraMatrixL << "cameraDistcoeffL" << distCoeffL << "cameraMatrixR" << cameraMatrixR << "cameraDistcoeffR" << distCoeffR;
        fs.release();
        cout << "cameraMatrixL=:" << cameraMatrixL << endl << "cameraDistcoeffL=:" << distCoeffL << endl << "cameraMatrixR=:" << cameraMatrixR << endl << "cameraDistcoeffR=:" << distCoeffR << endl;
    }
    else
    {
        cout << "Error: can not save the intrinsics!!!!!" << endl;
    }
    fs.open("extrinsics.yml", FileStorage::WRITE);
    if (fs.isOpened())
    {
        fs << "R" << R << "T" << T << "Rl" << Rl << "Rr" << Rr << "Pl" << Pl << "Pr" << Pr << "Q" << Q;
        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 << "Error: can not save the extrinsic parameters\n";
}


int main(int argc, char* argv[])
{
    Mat img;
    int goodFrameCount = 1;
    cout << "Total Images:" << frameNumber << endl;
    while (goodFrameCount < frameNumber)
    {
        cout <<"Current image :" << goodFrameCount << endl;
        string 	filenamel,filenamer;
        char filename[100];

        /*讀取左邊的圖像*/
        sprintf(filename, "./data/left%02d.jpg", goodFrameCount + 1);
        rgbImageL = imread(filename, CV_LOAD_IMAGE_COLOR);
        cvtColor(rgbImageL, grayImageL, CV_BGR2GRAY);

        /*讀取右邊的圖像*/
        sprintf(filename, "./data/right%02d.jpg", goodFrameCount + 1);
        //sprintf(filename, "./data/right%02d.jpg", goodFrameCount + 1);
        rgbImageR = imread(filename, CV_LOAD_IMAGE_COLOR);
        cvtColor(rgbImageR, grayImageR, CV_BGR2GRAY);

        bool isFindL, isFindR;
        isFindL = findChessboardCorners(rgbImageL, boardSize, cornerL);
        isFindR = findChessboardCorners(rgbImageR, boardSize, cornerR);
        if (isFindL == true && isFindR == true)
            //如果兩幅圖像都找到了所有的角點 則說明這兩幅圖像是可行的
        {
            cornerSubPix(grayImageL, cornerL, Size(5, 5), Size(-1, -1), TermCriteria(CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 20, 0.1));
            drawChessboardCorners(rgbImageL, boardSize, cornerL, isFindL);
            imshow("chessboardL", rgbImageL);
            imagePointL.push_back(cornerL);
            cornerSubPix(grayImageR, cornerR, Size(5, 5), Size(-1, -1), TermCriteria(CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 20, 0.1));
            drawChessboardCorners(rgbImageR, boardSize, cornerR, isFindR);
            imshow("chessboardR", rgbImageR);
            imagePointR.push_back(cornerR);
            goodFrameCount++;
            cout << "The image" << goodFrameCount << " is good" << endl;
        }
        else
        {
            cout << "The image "<< goodFrameCount <<"is bad please try again" << endl;
            goodFrameCount++;
        }

        if (waitKey(10) == 'q')
        {
            break;
        }
    }
    /*	計算實際的校正點的三維座標	根據實際標定格子的大小來設置	*/
    calRealPoint(objRealPoint, boardWidth, boardHeight, frameNumber-1, squareSize);
    cout << "cal real successful" << endl;
    /*	標定攝像頭	由於左右攝像機分別都經過了單目標定	所以在此處選擇flag = CALIB_USE_INTRINSIC_GUESS	*/
    double rms = stereoCalibrate(objRealPoint, imagePointL, imagePointR,
                                 cameraMatrixL, distCoeffL,
                                 cameraMatrixR, distCoeffR,
                                 Size(imageWidth, imageHeight), R, T, E, F, CV_CALIB_USE_INTRINSIC_GUESS,
                                 TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 80, 1e-5));
    cout << "Stereo Calibration done with RMS error = " << rms << endl;
    stereoRectify(cameraMatrixL, distCoeffL, cameraMatrixR, distCoeffR, imageSize, R, T, Rl, Rr, Pl, Pr, Q,		CALIB_ZERO_DISPARITY, -1, imageSize, &validROIL, &validROIR);

    initUndistortRectifyMap(cameraMatrixL, distCoeffL, Rl, Pr, imageSize, CV_32FC1, mapLx, mapLy);
    initUndistortRectifyMap(cameraMatrixR, distCoeffR, Rr, Pr, imageSize, CV_32FC1, mapRx, mapRy);


    Mat rectifyImageL, rectifyImageR;
    cvtColor(grayImageL, rectifyImageL, CV_GRAY2BGR);
    cvtColor(grayImageR, rectifyImageR, CV_GRAY2BGR);

    imshow("Rectify Before", rectifyImageL);

    /*
    經過remap之後,左右相機的圖像已經共面並且行對準了
    */
    remap(rectifyImageL, rectifyImageL, mapLx, mapLy, INTER_LINEAR);
    remap(rectifyImageR, rectifyImageR, mapRx, mapRy, INTER_LINEAR);

    imshow("ImageL", rectifyImageL);
    imshow("ImageR", rectifyImageR);

    /*保存並輸出數據*/
    outputCameraParam();

    /*
        把校正結果顯示出來
        把左右兩幅圖像顯示到同一個畫面上
        這裏只顯示了最後一副圖像的校正結果。並沒有把所有的圖像都顯示出來
    */
    Mat canvas;
    double sf;
    int w, h;
    sf = 600. / MAX(imageSize.width, imageSize.height);
    w = cvRound(imageSize.width * sf);
    h = cvRound(imageSize.height * sf);
    canvas.create(h, w * 2, CV_8UC3);

    /*左圖像畫到畫布上*/
    Mat canvasPart = canvas(Rect(w*0, 0, w, h));								//得到畫布的一部分
    resize(rectifyImageL, canvasPart, canvasPart.size(), 0, 0, INTER_AREA);		//把圖像縮放到跟canvasPart一樣大小
    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(rectifyImageR, canvasPart, canvasPart.size(), 0, 0, INTER_LINEAR);
    Rect vroiR(cvRound(validROIR.x * sf), cvRound(validROIR.y*sf),
               cvRound(validROIR.width * sf), cvRound(validROIR.height * sf));
    rectangle(canvasPart, vroiR, Scalar(0, 255, 0), 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);

    cout << "wait key" << endl;
    waitKey(0);
    system("pause");
    return 0;

}

立體標定函數 stereoCalibrate()

stereoCalibrate() 是用來標定一個立體攝像頭的,也就是同時標定兩個攝像頭。標定的結果除了能夠求出兩個攝像頭的內外參數矩陣,也能夠得出兩個攝像頭的位置關係R,T。
在這裏插入圖片描述
opencv標定矯正得到的外參配置文件,各參數的含義:在這裏插入圖片描述

double stereoCalibrate(InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints1,
             InputArrayOfArrays imagePoints2, InputOutputArray cameraMatrix1,InputOutputArray distCoeffs1, 
             InputOutputArray cameraMatrix2, InputOutputArray distCoeffs2, Size imageSize, OutputArray R,
             OutputArray T, OutputArray E, OutputArray F, int
             flags=CALIB_FIX_INTRINSIC , TermCriteria criteria=
             TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, 1e-6))
  • objectPoints- vector 型的數據結構,存儲標定角點在世界座標系中的位置
  • imagePoints1- vector<vector> 型的數據結構,存儲標定角點在第一個攝像機下的投影后的亞像素座標
  • imagePoints2- vector<vector> 型的數據結構,存儲標定角點在第二個攝像機下的投影后的亞像素座標
  • cameraMatrix1-輸入/輸出型的第一個攝像機的相機矩陣。如果CV_CALIB_USE_INTRINSIC_GUESS , CV_CALIB_FIX_ASPECT_RATIO ,CV_CALIB_FIX_INTRINSIC , or CV_CALIB_FIX_FOCAL_LENGTH其中的一個或多個標誌被設置,該攝像機矩陣的一些或全部參數需要被初始化
  • distCoeffs1-第一個攝像機的輸入/輸出型畸變向量。根據矯正模型的不同,輸出向量長度由標誌決定
  • cameraMatrix2-輸入/輸出型的第二個攝像機的相機矩陣。參數意義同第一個相機矩陣相似
  • distCoeffs2-第一個攝像機的輸入/輸出型畸變向量。根據矯正模型的不同,輸出向量長度由標誌決定
  • imageSize-圖像的大小
  • R-輸出型,第一和第二個攝像機之間的旋轉矩陣
  • T-輸出型,第一和第二個攝像機之間的平移矩陣
  • E-輸出型,基本矩陣
  • F-輸出型,基礎矩陣
  • flag- CV_CALIB_FIX_INTRINSIC 如果該標誌被設置,那麼就會固定輸入的cameraMatrix和distCoeffs不變,只求解R,T,E,F CV_CALIB_USE_INTRINSIC_GUESS .根據用戶提供的cameraMatrix和distCoeffs爲初始值開始迭代 CV_CALIB_FIX_PRINCIPAL_POINT 迭代過程中不會改變主點的位置 CV_CALIB_FIX_FOCAL_LENGTH 迭代過程中不會改變焦距
    不同的FLAG,可能是零或以下值的結合:
    § CV_CALIB_FIX_INTRINSIC要確認cameraMatrix? and distCoeffs?所以只有R, T, E , 和F矩陣被估計出來
    § CV_CALIB_USE_INTRINSIC_GUESS根據指定的FLAG優化一些或全部的內在參數。初始值是由用戶提供。
    § CV_CALIB_FIX_PRINCIPAL_POINT在優化過程中確定主點。
    § CV_CALIB_FIX_FOCAL_LENGTH確定和 .
    § CV_CALIB_FIX_ASPECT_RATIO優化 . 確定的比值.
    § CV_CALIB_SAME_FOCAL_LENGTH執行以及 .
    § CV_CALIB_ZERO_TANGENT_DIST設置每個相機切向畸變係數爲零並且設爲固定值。
    § CV_CALIB_FIX_K1,…,CV_CALIB_FIX_K6在優化中不改變相應的徑向畸變係數. 如果設置CV_CALIB_USE_INTRINSIC_GUESS , 使用distCoeffs矩陣提供的係數。否則將其置零.
    § CV_CALIB_RATIONAL_MODEL能夠輸出係數k4,k5,k6。提供向後兼容性,這額外FLAG應該明確指定校正函數使用理性模型和返回8個係數。如果FLAG沒有被設置,該函數計算並只返回5畸變係數。

在這裏插入圖片描述在這裏插入圖片描述

修改Euroc配置文件

// Euroc.yaml.cpp
//Created by gavyn on 20-4-28.

%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

# Camera calibration and distortion parameters (OpenCV)
/*
這個是 雙目相機的參數不是單個的做相機的相機中心跟焦距。
其對應:extrinsics.yml中的 Pr:
例如我的是
Pr: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [ 2.8559499458758660e+02, 0., 2.7029193305969238e+02,
-3.9636548646706200e+04, 0., 2.8559499458758660e+02,
2.8112063348293304e+02, 0., 0., 0., 1., 0. ]
對應的修改焦距和相機中心如下:
Camera.fx: 2.8559499458758660e+02
Camera.fy: 2.8559499458758660e+02
Camera.cx: 2.7029193305969238e+02
Camera.cy: 2.8112063348293304e+02
*/
Camera.fx: 435.2046959714599
Camera.fy: 435.2046959714599
Camera.cx: 367.4517211914062
Camera.cy: 252.2008514404297

//默認不改,因代碼中已做畸變糾正。故均爲0.
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0

Camera.width: 1280
Camera.height: 640

# Camera frames per second
Camera.fps: 20.0

# stereo baseline times fx
/*
這個參數是個大坑,其爲相機的基線×相機的焦距。orbslam的參數文件中單位是m,而opencv標定文件中的單位是mm
其數值同樣可以在Pr中找出,定位在下面矩陣中的-3.9636548646706200e+04 這個數
Pr: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [ 2.8559499458758660e+02, 0., 2.7029193305969238e+02,
-3.9636548646706200e+04, 0., 2.8559499458758660e+02,
2.8112063348293304e+02, 0., 0., 0., 1., 0. ]

-3.9636548646706200e+04 就是要填入上面的參數,毫米轉爲米,求絕對值,填入Camera.bf:  3.9636548646706200e+01
*/
Camera.bf: 47.90639384423901

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1

# Close/Far threshold. Baseline times.
/*
深度閾值,不是一個精確的數值,大概預估的,可以不改動,要改的話參考下述公式
        自己粗略估計一個相機可以良好顯示的最大距離值爲s = 10  如果fx = 100 Camera.bf = 20
那麼 ThDepth = s*fx/Camera.bf = 10 *100 /20 = 50
將你自己的參數帶入上述公式 可以得到大概的閾值。
*/
ThDepth: 35

#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 640
LEFT.width: 1280

/*
 * 左圖像畸變參數,位於intrinsics.yml中的
cameraDistcoeffL: !!opencv-matrix
rows: 5
cols: 1
dt: d
data: [ -2.8632659642339481e-01, 6.6994801733091039e-02,
-5.4763802000265397e-04, -1.4767993829858197e-03,
-6.1039950504068767e-03 ]
填入下面的 LEFT.D: 即可 
*/
# 左圖像畸變參數
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]

/*
左圖像相機內參,可在intrinsics.yml 的cameraMatrixL:找到:
cameraMatrixL: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ 2.8424872262658977e+02, 0., 3.3099977082276723e+02, 0.,
2.8535010886794362e+02, 2.5230877864759117e+02, 0., 0., 1. ]
填入LEFT.K:
*/
# 左圖像內參
LEFT.K: !!opencv-matrix
        rows: 3
cols: 3
dt: d
data: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]


/*
左相機校準變換矩陣:extrinsics.yml 中的 Rl:
Rl: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ 9.9750705548699170e-01, 3.5207065558213610e-02,
6.1156657760632900e-02, -3.5691910468923047e-02,
9.9933934145707581e-01, 6.8533308118298173e-03,
-6.0874968425042433e-02, -9.0190437917577089e-03,
9.9810465136093429e-01 ]
填入下面的LEFT.R:
*/
# 左相機校準變換矩陣
LEFT.R:  !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]


/*
投影矩陣:
extrinsics.yml 中的 Pl:
Pl: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [ 2.8559499458758660e+02, 0., 2.7029193305969238e+02, 0., 0.,
2.8559499458758660e+02, 2.8112063348293304e+02, 0., 0., 0., 1.,
0. ]
填入下面的  LEFT.P:
 */
# 左相機在校準後座標系的投影矩陣
LEFT.P:  !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [435.2046959714599, 0, 367.4517211914062, 0,  0, 435.2046959714599, 252.2008514404297, 0,  0, 0, 1, 0]

/*
RIGHT相機的設置與LEFT一致,唯一不同的就是RIGHT.P: 參數,
extrinsics.yml 中的 Pr:如下:
Pr: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [ 2.8559499458758660e+02, 0., 2.7029193305969238e+02,
-3.9636548646706200e+04, 0., 2.8559499458758660e+02,
2.8112063348293304e+02, 0., 0., 0., 1., 0. ]
對其進行修改,也就是data中的第4個值,需要轉化單位從mm轉爲m。
所以應該填入RIGHT.P: 的數值爲:
data: [ 2.8559499458758660e+02, 0., 2.7029193305969238e+02,
-3.9636548646706200e+01, 0., 2.8559499458758660e+02,
2.8112063348293304e+02, 0., 0., 0., 1., 0. ]
*/
RIGHT.height: 640
RIGHT.width: 1280
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
RIGHT.R:  !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
RIGHT.P:  !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]



#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------

# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200

# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章