摄像机标定从标定板类型可以分为:一维标定物,二维标定物和三维标定物(哈哈哈)
1 一维标定物
一维标定物标定算法是利用摄像机投影过程中的交比不变性的原理,常用来标定摄像机阵列(多个摄像机)。具体原理可参考:基于一维标定物的多摄像机标定。一维标定物见下图所示,一个直杆上有3个点,三个点之间的距离需要实现精确测量。在标定过程中,只需要在各个摄像机的视场空间不断挥动标定杆,就可以精确标定摄像机的内外参数。一维标定物在多摄像机标定中使用起来非常灵活方便,非常建议在该种场景下使用。
(在这里特别感谢一下吴福朝,张广军等人在早期对传统的计算机视觉(也可以叫几何视觉吧)的贡献,我是从计算机视觉中的数学方法(吴福朝),机器视觉(张广军),计算机视觉中的多视图几何(韦穗翻译)这三本书入门机器视觉的。)
2 三维标定物
三维标定物主要利用已知的三维标志点座标和图像点标定摄像机内外参数,原理类似与二维标定物的标定方法。三维标定物制作起来成本比较高,在张正友标定法之前应用的比较广泛,现在基本上已经不在使用了。
3 二维标定物
二维标定物是现在主流的摄像机标定方法,主要优点是,标定板成本较低,标定操作简单方便,标定精度高(好处多多)。二维标定物是从张正友标定法出来之后流行起来的。大部分的标定算法都是two stage:1是解方程,就是通过几何约束求解未知参数;2,迭代优化,基于1中求解的参数,建立目标函数,通过迭代优化的方式增加参数的精度。只有经过这两部得到的标定参数才是最优。张正友标定法也是按照这两步进行,下面也会讲解相机和激光间的标定也是这样进行的。当然,在一些高精度三维测量中(三维结构光扫描仪等),还会加入其它的优化手段。
3.1 标定方法
二维标定物的摄像机标定方法基本上都是用张正友标定法,详细原理现在网上已经有太多了这里不展开叙述,简单来说可以分成以下步骤:
- 提取标定图像上的标志点,联合已知的标定板三维点座标,通过DLT方法,求解单应矩阵H。
- 单应矩阵中,利用旋转矩阵的正交性,增加约束方程,求解相机的内部参数A(相机的焦距和中心点座标)
- 通过已知的内部参数和H矩阵,求解外部参数(R,t)。需要注意的是这里的外部参数是指相机座标系和标定板座标系之间的旋转平移变换
- 建立相机畸变模型(radtan)
- 建立目标函数,优化标定参数(A,R,t,畸变参数),目标函数是反投影残差参数。这一步也就是paper中所说的最大似然估计。
- 如果是双目标定的情况,在两个相机分别进行上述标定后,求解两个相机之间的外部参数(R,t)。
- 建立目标函数,优化内外参。
需要注意的是:
- 针对双目摄像机标定,虽然opencv里面直接有双目标定函数,但是通常意义下,最好先使用单目标定分别标定左右相机,然后使用双目标定函数标定外参。
- 畸变参数问题,针对小视角相机,畸变比较小,可以先忽略畸变参数求解相机内参,然后通过优化方式求解畸变参数。但是对于鱼眼相机,畸变比较大,是不是不能这么做。需要先估计畸变参数,或者是畸变参数和相机内参一起估计。例如opencv中的equidistant模型标定。这一块需要再继续研究一下。
3.2 标定板类型
事先说明,在高精度相机标定中,标定板的选择至关重要,标定板的精度也非常的高,在高精度三维重建和测量领域,使用的相机和镜头都是工业级别的。但是针对VSLAM行业,使用的相机都是相机模组,标定精度要求不是那么高,使用opencv,kalibr等标定代码已经可以完全满足标定需求。
目前二维标定板可以分为两种类型:角点标定板和圆形标定板。如下图所示,其中角点标定板有我们常用的棋盘格(chessboard)标定板(下图左上),kalibr标定所使用二维标识码(Apriltag)标定板(下图右上);圆形标定板可以自己设计(如下图左下,欢迎拍砖),还可以使用halcon中自带的标定板(下图右下)。值得一提的是,halcon工具在相机标定领域已经遥遥领先。现在很多做三维测量的公司都在使用这个机器视觉库。
在特征点提取精度方面圆形标定的提取精度高于棋盘格类型的平面标定板。Which pattern? Biasing aspects of planar calibration patterns and detection methods 一文也详细介绍了圆形标定板的优势。这也是为什么在高精度三维测量,三维重建领域,常常使用圆形标定板的原因。这里值得注意的是,由于相机几何投影的原因,标定板投影到图像上,圆形会变成椭圆。因此我们在图像上是需要提取椭圆的圆心的。因此提取椭圆圆心大致分为一下过程:
- 提取圆形轮廓,将每个椭圆划分开。可以利用opencv轮廓提取函数完成
- 利用边缘检测算子提取椭圆的边缘
- 亚像素边缘提取(二次曲线拟合法,灰度矩法等)
- 椭圆拟合(hough变换,最小二乘法),得到椭圆圆心
指的注意的是,亚像素边缘提取对圆心提取的精度至关重要。但由于图像噪声的关系,边缘提取方法,椭圆拟合方法需要斟酌使用。
在上图的圆形标定中,我们在中间设置了不对称(既不是轴对称,也不是中心对称)的五个大圆,有两个目的:一是无论我们怎么摆设标定板,都不会改变圆的排序序号,即在相机标定时,在标定板上建立世界座标系是唯一的,这在一定程度会提升相机标定的精度。二是在标定时,由于相机视角原因,即使没有将标定板拍摄完全,也可以根据中间五个大圆,将图像上的圆正确排序。
在使用圆形标定板的时候,还需要特别注意一个问题,就是所谓的偏心差(也叫透视偏差),英文名:perspective bias,即标定板上的圆心投影到图像上,投影点并不是图像上的椭圆圆心(是不是有很多问号???)。如下图所示,有一圆半径为r,圆心C,投影到图像平面IP上,圆心的真正投影点应该为C’,然而由于透视偏差的存在,我们通过图像椭圆拟合得到的圆心为B’,投影偏差就是B’C’。需要注意,透视偏差是视觉几何客观存在的差异,并不是图像提取等噪声产生的误差,因此这个偏差叫做bias,而不是error。是不是有点类似与IMU bias。如何解决该bias,2000年左右就已经有人把该个圆形透视偏差模型用几何公式的方式完全建模出来, 我们直接可以使用[1]。关于这个偏差这里列举一些文献,有兴趣的同学可以详细研究一下 [1] [2][3][4][5]。
3.3 提升标定精度
这里再次强调,如果是在SLAM等环境下标定相机,我们常用的opencv,matlab标定方法就已经可以满足标定精度的需求。因为SLAM的定位精度是厘米级别(有做的更好精度的,欢迎拍砖)的。但是对于高精度的三维重建,重建精度达到0.02mm,甚至于微米级别的,那么提升标定精度就是必须的。在高精度三维重建领域,例如三维扫描仪,主要是主动打结构光的方式,通过解码(通常是解相位),利用三角测量原理重建三维模型的。因此相机的标定参数和图像的匹配精度是影响三维重建的主要因素。这里主要是对如何提升相机标定参数,谈一些自己的想法。
除了上面所提的使用圆形标定板,并且需要进行圆心透视偏差的补偿外,还有一些其它方法:
- 提高标定板的精度,我们所使用的标定板精度是否真正精确,这需要第三方高精度测量设备测试。这里有两个方面需要注意,一是标定板上圆与圆之间的距离是否准确;二是我们所使用的标定的平面性如何,一般我们使用的标定板有铝制的,陶瓷的,玻璃的。随着加工工艺的提升,标定板的精度越来越好,但是标定板的几何参数我们需要进一步精确。一般来讲,标定板的精度比我们的三维重建精度要高一个数量级。因此,在三维测量领域,高精度标定板的成本是很高的。
- 算法优化。在进行单目和双目标定后,我们需要再加一部迭代优化方法,目标函数仍然是反投影残差,优化变量依旧是相机的内外参数,但是这里我们使用的标定板3D点座标是更精确的座标(因为张氏标定法的原因,标定板是平面的,但是由于制作误差,其实并不是平的),这里我们在优化的时候可以使用真实的3D点,并且加入透视偏差模型,得到更加精确的参数。这方面有需求的话,后面专门写个博客。
- 在标定的过程中,摆放标定板的位置也至关重要。一般来说,对于小视角相机,摆放7-10步就可以精确标定出相机的内参,分别是:标准正方,向下倾斜,向上倾斜,向左倾斜,向右倾斜, 远离摄像头,靠近摄像头.,如果视野大,在远离摄像头的位置上也摆设几步标定板。这也是有人做过大量实验验证过的。当然针对鱼眼相机等大视角相机,需要摆放更多的位置。其实在我们使用kalibr标定工具标定时,很多图像是冗余的,不知道kalibr里面有没有挑选图像的步骤。
3.4 相机标定评价标准
一般,评价摄像机标定精度是使用反投影残差的。在高精度相机标定中,反投影残差可以达到0.02pixel左右的精度。在VSLAM领域,相机标定反投影残差精度在0.5pixel就可以了,甚至对于fisheye相机,1-2pixel也可以接受。当然对fisheye相机,用到了其它的相机模型(Omni等),这个在后面专门出个博客,介绍相机模型介绍。
但是使用反投影残差作为相机标定评判标准并不是很严格。我们上面介绍的,在相机标定过程中,需要经过很多次的迭代优化,迭代优化的目标函数都是使反投影残差最小。在优化的过程中也许会陷入局部最小,或者由于这次一些其他原因(光线原因,摆放标定板原因等),噪声比较大,标定参数也许不是最优,但是反投影残差也可能比较小。因此我们需要寻求更好的评判标准。
针对双目相机。双目相机最大优势是可以三角化重建标志点。因此在标定结束后,可以将标定板放置在摄像头前,对标定板的标志点进行三角化,得到三维座标。然后求解标定板上圆心之间的距离,和真实数据对比距离差。代码如下:
//------------------------evaluate stereo calibration result---------------------------
vector<float> v3D_error;
vector<double> disparity_aver;
std::cout << "******** stereo calibration error ********" << std::endl;
for (int index=calib_imgs_num; index<calib_imgs_num+evalu_imgs_num; ++index)
{
char left_img[100], right_img[100];
sprintf(left_img, "%s%s%d.%s", img_dir.c_str(), leftimg_filename.c_str(), index, images_format.c_str());
sprintf(right_img, "%s%s%d.%s", img_dir.c_str(), rightimg_filename.c_str(), index, images_format.c_str());
cv::Mat img1 = imread(left_img, CV_LOAD_IMAGE_COLOR);
cv::Mat img2 = imread(right_img, CV_LOAD_IMAGE_COLOR);
if (img1.empty() || img2.empty() )
{
std::cout << index << ": NAN" << std::endl;
continue;
}
cv::Mat recImg1, recImg2, gray1, gray2;
remap(img1, recImg1, rmap[0][0], rmap[0][1], CV_INTER_LINEAR);
remap(img2, recImg2, rmap[1][0], rmap[1][1], CV_INTER_LINEAR);
cv::cvtColor(recImg1, gray1, CV_BGR2GRAY);
cv::cvtColor(recImg2, gray2, CV_BGR2GRAY);
bool found1 = false, found2 = false;
Size board_size = Size(board_width, board_height);
vector<Point2f> corners1, corners2;
vector<cv::Point3f> v3DPoints;
found1 = cv::findChessboardCorners(recImg1, board_size, corners1, CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FILTER_QUADS);
found2 = cv::findChessboardCorners(recImg2, board_size, corners2, CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FILTER_QUADS);
if (found1 && found2)
{
cv::cornerSubPix(gray1, corners1, cv::Size(5, 5), cv::Size(-1, -1), cv::TermCriteria(CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 30, 0.1));
cv::drawChessboardCorners(gray1, board_size, corners1, found1);
cv::cornerSubPix(gray2, corners2, cv::Size(5, 5), cv::Size(-1, -1), cv::TermCriteria(CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 30, 0.1));
cv::drawChessboardCorners(gray2, board_size, corners2, found2);
}
else
{
std::cout << index << ": NAN" << std::endl;
continue;
}
//stereo disparity error
double disparity_error = 0.0;
for (int i = 0; i < board_width * board_height; ++i)
{
double disparity_tmp = abs(corners1[i].y - corners2[i].y);
disparity_error += disparity_tmp;
}
disparity_error = disparity_error / (board_width * board_height);
disparity_aver.push_back(disparity_error);
//3D reconstruction error
double f = P1.at<double>(0, 0);
double tx = T.at<double>(0, 0);
double ty = T.at<double>(1, 0);
double tz = T.at<double>(2, 0);
for (int i = 0; i < board_width * board_height; ++i)
{
double y_1 = corners1[i].x - P1.at<double>(0, 2);
double x_1 = corners1[i].y - P1.at<double>(1, 2);
double y_2 = corners2[i].x - P2.at<double>(0, 2);
double x_2 = corners2[i].y - P2.at<double>(1, 2);
double w_z = (f * tx - x_2 * tz) / (x_2 - x_1);
double w_x = w_z * x_1 / f;
double w_y = w_z * y_1 / f;
v3DPoints.push_back(cv::Point3f(w_x, w_y, w_z));
}
float dis_error = 0.0;
int err_num = 0;
//水平相邻角点距离误差
for (int i = 0; i < board_height; ++i)
for (int j = 0; j < board_width - 1; ++j)
{
float err_t = abs(sqrt((v3DPoints[i * board_width + j].x - v3DPoints[i * board_width + j + 1].x) * (v3DPoints[i * board_width + j].x - v3DPoints[i * board_width + j + 1].x) + (v3DPoints[i * board_width + j].y - v3DPoints[i * board_width + j + 1].y) * (v3DPoints[i * board_width + j].y - v3DPoints[i * board_width + j + 1].y) + (v3DPoints[i * board_width + j].z - v3DPoints[i * board_width + j + 1].z) * (v3DPoints[i * board_width + j].z - v3DPoints[i * board_width + j + 1].z)) - square_size);
dis_error += err_t;
err_num++;
std::cout << "error " << i * board_width + j << ": " << err_t << std::endl;
}
//竖直相邻角点距离误差
for (int i = 0; i < board_width; ++i)
{
for (int j = 0; j < board_height - 1; ++j)
{
float err_t = abs(sqrt((v3DPoints[j * board_width + i].x - v3DPoints[(j + 1) * board_width + i].x) * (v3DPoints[j * board_width + i].x - v3DPoints[(j + 1) * board_width + i].x) + (v3DPoints[j * board_width + i].y - v3DPoints[(j + 1) * board_width + i].y) * (v3DPoints[j * board_width + i].y - v3DPoints[(j + 1) * board_width + i].y) + (v3DPoints[j * board_width + i].z - v3DPoints[(j + 1) * board_width + i].z) * (v3DPoints[j * board_width + i].z - v3DPoints[(j + 1) * board_width + i].z)) - square_size);
dis_error += err_t;
err_num++;
//cout << err_t << endl;
}
}
v3D_error.push_back(dis_error / err_num);
std::cout << "image." << index << "--stereo disparity error: " << disparity_error << " pixel" << "---"
<< "3D reconstruction erro: " << dis_error / err_num << " mm" <<std::endl;
针对单目相机,使用反投影残差应该也许是评价相机标定很好的方法了。
以上主要是针对高精度标定怎么去做,相机标定原理核心是张正友标定法,但是需要做一些改进和优化。这也是笔者以前的工作,现在主要做VSLAM方面的事情,对这方面没有太大的要求,但相机标定精度当然是越高越好。并且相机标定是一个最好的几何视觉入门课程。
这里有个自己写的针对单目相机,单目鱼眼相机,双目相机,双目鱼眼相机的opencv标定代码,鱼眼相机使用的是equidistant畸变模型。代码是基于别人上修改的,只加入了双目重建误差评价方法。至于高精度相机标定方面的代码,由于方方面面的原因,没法公开。现在一些基于双目视觉的高精度重建设备已经可以达到微米级别,大多出自国外,这里我辈还需努力啊。
opencv标定代码地址:https://github.com/GaoJunqiang/camera_calibration
后面再出个博客专门介绍相机和线激光的标定(线结构光高精度三维重建领域,也是以前在研究生时的一个课题),相机和单线激光雷达标定(多传感器融合定位)。感觉这两个之间有很多共同之处。
参考
- [1] Ahn S J, Warnecke H J, Kotowski R. Systematic geometric image measurement errors of circular object targets: Mathematical formulation and correction[J]. The Photogrammetric Record, 1999, 16(93): 485-502.
- [2] 吴建霖, 蒋理兴, 王安成,等. 圆形标志投影偏心差补偿算法[J]. 中国图象图形学报, 2018, 023(010):1549-1557.
- [3] 黄道明. 近景摄影测量中圆形目标的投影偏心差及模拟分析[J]. 工程建设, 2011(02):14-17.
- [4] 廖祥春, 冯文灏. 圆形标志及其椭圆构像间中心偏差的确定[J]. 武汉大学学报:信息科学版, 1999, 024(003):235-239.
- [5] Heikkila J, Silven O. A four-step camera calibration procedure with implicit image correction[C]//Proceedings of IEEE computer society conference on computer vision and pattern recognition. IEEE, 1997: 1106-1112.