簡述
在計算H 或者 F矩陣的時候需要對特征點進行坐標變換,稱之為歸一化。
原因
前輩發現計算單應矩陣時變換特征點的坐標會得到更好的效果,包括坐標的平移和尺度縮放,並且這一步驟必須放在DLT之前。DLT之后再還原到原坐標系。
書本指出歸一化與條件數確切的說是DTL矩陣A的第一個和倒數第二個奇異值的比例有關。有充分證據表明在精確數據和無限精度的算術運算條件下,歸一化並不起作用,但是有噪聲存在時解將偏離其正確結果。
個人推測:類似於機器學習中需要對數據進行歸一化,減少數據因為尺度變化過大異常值等的原因影響結果。
步驟
1.將點進行平移使其形心(x,y的均值)位於原點。
2.對點進行縮放使特征點到原點的距離為根號2,即所有點“平均”位於(1,1,1)
3.對兩幅圖進行獨立的上述變換
參考自《計算機視覺中的多視圖幾何》 3.4.4
代碼實現 from ORBslam2
/** * @brief 歸一化特征點到同一尺度(作為normalize DLT的輸入) * * [x' y' 1]' = T * [x y 1]' \n * 歸一化后x', y'的均值為0,sum(abs(x_i'-0))=1,sum(abs((y_i'-0))=1 * * @param vKeys 特征點在圖像上的坐標 * @param vNormalizedPoints 特征點歸一化后的坐標 * @param T 將特征點歸一化的矩陣 左乘 */ void Initializer::Normalize(const vector<cv::KeyPoint> &vKeys, vector<cv::Point2f> &vNormalizedPoints, cv::Mat &T) { //第一步得到所有特征點的均值,並將所有點的均值為0 float meanX = 0; float meanY = 0; for (int i = 0; i < vKeys.size(); i++) { meanX += vKeys[i].pt.x; meanY += vKeys[i].pt.y; } meanX /= vKeys.size(); meanY /= vKeys.size(); //第二步將所有點到原點的距離為根號2 float meanDevX = 0; float meanDevY = 0; for (int i = 0; i < vKeys.size(); i++) { vNormalizedPoints[i].x = vKeys[i].pt.x - meanX; vNormalizedPoints[i].y = vKeys[i].pt.y - meanY; meanDevX += fabs(vNormalizedPoints[i].x); //fabs是求一個實數的絕對值 點到原點距離的累加 meanDevY += fabs(vNormalizedPoints[i].y); } meanDevX /= vKeys.size(); //點到原點距離的平均值 meanDevY /= vKeys.size(); for (int i = 0; i < vKeys.size(); i++) { vNormalizedPoints[i].x /= meanDevX; vNormalizedPoints[i].y /= meanDevY; } //用於還原特征點到原始的坐標系,獲得矩陣 |sX 0 -meanx*sX| 用於取逆 x 快速還原 // |0 sY -meany*sY| * y // |0 0 1 | 1 float sX = 1.0 / meanDevX; float sY = 1.0 / meanDevY; T = Mat::eye(3, 3, CV_32F); T.at<float>(0, 0) = sX; T.at<float>(0, 2) = -meanX * sX; T.at<float>(1, 1) = sY; T.at<float>(1, 2) = -meanY * sY; T.at<float>(2, 2) = 1; }