延續前一篇的內容,在相機一座標系下的
點
和在相機二座標系下的
點
之間的關係是:
左右兩邊都同時乘上
,這裡的
是
的 skew-symmetric matrix:
再將左右兩邊同時乘上
,由於
與
垂直(
的特性),所以:
將
代入:
這個式子就是出名的對極約束 (Epipolar constraint),這個式子包含了相機的內參
,外參
,以及兩個相機的投影點
,全部放到了一個等式當中,我們可以這樣理解這個式子:
其況下,給定一個相機上的像素,這個像素在另一個相機上的投影點是有限制的(事實上是一條線上)。如果我們把
組合成一個 3x3 矩陣
,這個矩陣就是本質矩陣 (Essential Matrix):
把相機內參
也考慮進去,我們可以得到基礎矩陣 (Fundamental Matrix):
如果我們已知一個像素在相機二的投影點
,而且不知道
和
的情況下,我們可以用基礎矩陣
和 epipolar constraint
得到一個
的線性方程式,也就是說
會在一條線上,這條線就是對極線 (Epipolar Line),如下圖:

先前計算相機姿態的程式碼,裡面就有利用 opencv 的 cv2.findEssentialMat 得到 essential matrix
,這裡我們可以利用這個
和相機內參得到 fundamental matrix
,並且給定
就可以畫出在另一張圖上的對極線,程式碼如下:
def plot_epipolar_line(image1, image2, point1, point2, E, K):
# Make point1 homogenous
point1 = np.array(point1.tolist() + [1])
# Compute fundamental matrix
F = np.linalg.inv(K).T @ E @ np.linalg.inv(K)
line = F @ point1.T
line /= np.linalg.norm(line[:2])
line = line.ravel()
x = np.array([0, image1.shape[1]])
y = (-line[2] - line[0] * x) / line[1]
# Plot the result
plt.figure()
plt.subplot(121)
plt.axis("off")
plt.imshow(cv2.cvtColor(image1, cv2.COLOR_BGR2RGB))
plt.plot(point1[0], point1[1], "ro")
plt.subplot(122)
plt.axis("off")
plt.imshow(cv2.cvtColor(image2, cv2.COLOR_BGR2RGB))
plt.plot(point2[0], point2[1], "ro")
plt.plot(x, y, c="b")
plt.show()
plot_epipolar_line(rgb1, rgb2, points1[0], points2[0], E, intrinsic)
結果如圖,可以看到對應點
就在對極線上:
