视频讲解
1. 背景及概要
标定会决定传感器的使用表现。
标定方案力求简单且简单准确有效;
1.1. 概要
多传感器时空标定
2. 单目相机标定
2.1. 原理
2.1.1. 相机成像模型(pinhole model)
What Is Camera Calibration?- MATLAB & Simulink- MathWorks 中国
以matlab 工具箱提供的描述(不同的工具描述或选取的内参和畸变参数的个数不同):
2.1.2. 原理和方法-张正友标定法等
参考文献等:
📎摄像机标定的基本原理、实现及性能分析_小论文.pdf(数种传统方法和自标定方法)
📎OpenCV中标定函数的源码详解和改进.pdf(标定函数,去畸变函数,)
2.1.3. pnp问题-用于求解相机和标记物之间的相对位姿
PnP(Perspective-n-Point)问题:各种算法总结分析
BA:
以外参/相对位姿作为待优化变量,构造一个以重投影误差为目标函数的非线性优化问题;
可以用于视场无重叠的多相机的外参标定;
示例:使用apriltag角点检测,根据内参,三维坐标和像素坐标计算相机在棋盘格坐标系下的位姿;
//std::string file1= "/home/heyijia/ros_ws/apriltag_ws/src/log/kalibra.txt";
// 计算标定板角点的三维物理坐标和像素坐标
void CamPoseEst::FindTargetCorner(cv::Mat &img_raw,
std::vector<cv::Point3f> &p3ds,
std::vector<cv::Point2f> &p2ds)
{
// 不同 TAG 类型,使用不同姿态求解
if (CHESS == CalBoardInfo_.pt_)
{
// std::cout << "CHESSBOARD\n";
const int col = CalBoardInfo_.cols_; // 9
const int row = CalBoardInfo_.rows_; // 6
const float square_size = CalBoardInfo_.tagSize_; // 0.575 unit: m
cv::Size pattern_size(col, row);
std::vector<cv::Point2f> corners;
if (cv::findChessboardCorners(img_raw, pattern_size, corners))
{
cv::cornerSubPix(
img_raw, corners, cv::Size(11, 11), cv::Size(-1, -1),
cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
if (corners.size() == col * row)
{
int count = 0;
for (int i = 0; i < row; i++)
{
for (int j = 0; j < col; j++)
{
// Todo: change 3d-coordinate
p3ds.emplace_back(
cv::Point3f(j * square_size, i * square_size, 0.0)); // 格点的三维坐标
p2ds.emplace_back(cv::Point2f(corners[count].x, corners[count].y));
count++;
}
}
}
else
{
std::cout << "Chessboard config is not correct with image\n";
}
}
else
{
std::cout << "No chessboard detected in image\n";
}
}
else if (KALIBR_TAG_PATTERN == CalBoardInfo_.pt_)
{
const int april_rows = CalBoardInfo_.rows_; // 6
const int april_cols = CalBoardInfo_.cols_; // 6
const double tag_sz = CalBoardInfo_.tagSize_; // 0.055
const double tag_spacing = CalBoardInfo_.tagSpacing_; // 0.3
const double tag_spacing_sz = tag_sz * (1.+tag_spacing); // 0.055 + 0.0165
std::cout <<"tag size: "<< tag_sz <<" tag space: "<< tag_spacing << std::endl;
AprilTags::TagCodes tagCodes(AprilTags::tagCodes36h11);
AprilTags::TagDetector detector(tagCodes, CalBoardInfo_.black_border_);
TicToc tcnt;
std::vector<AprilTags::TagDetection> detections = detector.extractTags(img_raw);
double timecost = tcnt.toc();
// std::cout << timecost << std::endl;
// std::ofstream foutC_1(file1.c_str(), std::ios::app);
// foutC_1.setf(std::ios::fixed, std::ios::floatfield);
// foutC_1.precision(5);
// foutC_1<<timecost<<" "<<detections.size()<<std::endl;
// foutC_1.close();123
// if (detections.size() == april_rows * april_cols)
if (detections.size() > 0)
{
std::sort(detections.begin(), detections.end(),
AprilTags::TagDetection::sortByIdCompare);
cv::Mat tag_corners(4 * detections.size(), 2, CV_32F);
for (unsigned i = 0; i < detections.size(); i++)
{
for (unsigned j = 0; j < 4; j++)
{
tag_corners.at<float>(4 * i + j, 0) = detections[i].p[j].first;
tag_corners.at<float>(4 * i + j, 1) = detections[i].p[j].second;
}
}
int window_size = 3;
cv::cornerSubPix(
img_raw, tag_corners, cv::Size(window_size, window_size), cv::Size(-1, -1),
cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
cv::cvtColor(img_raw, img_raw, CV_GRAY2BGR);
int index = 0;
for (auto &tag : detections)
{
// debug show corners with window size
{
for (int i = 0; i < 4; ++i) {
cv::Point2f cor1(tag.p[i].first - window_size,tag.p[i].second-window_size);
cv::Point2f cor2(tag.p[i].first + window_size,tag.p[i].second+window_size);
cv::rectangle(img_raw, cor1,cor2, cv::Scalar(0, 255, 0),1);
}
}
unsigned int id = tag.id;
unsigned int tag_row = id / april_cols;
unsigned int tag_col = id % april_cols;
cv::circle(img_raw, cv::Point2f(tag.cxy.first, tag.cxy.second), 3,
cv::Scalar(0, 255, 0));
cv::putText(img_raw, std::to_string(id),
cv::Point2f(tag.cxy.first, tag.cxy.second),
CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255));
// 四个角点坐标
p3ds.emplace_back(cv::Point3f(tag_spacing_sz * tag_col,
tag_spacing_sz * tag_row, 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(index, 0),
tag_corners.at<float>(index, 1)));
++index;
p3ds.emplace_back(cv::Point3f(tag_spacing_sz * tag_col + tag_sz,
tag_spacing_sz * tag_row, 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(index, 0),
tag_corners.at<float>(index, 1)));
++index;
p3ds.emplace_back(cv::Point3f(tag_spacing_sz * tag_col + tag_sz,
tag_spacing_sz * tag_row + tag_sz, 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(index, 0),
tag_corners.at<float>(index, 1)));
++index;
p3ds.emplace_back(cv::Point3f(tag_spacing_sz * tag_col,
tag_spacing_sz * tag_row + tag_sz, 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(index, 0),
tag_corners.at<float>(index, 1)));
++index;
}
}
}
else if(APRIL_TAG_ONE == CalBoardInfo_.pt_) // TODO: 只有一个 April tag
{
const double tag_sz = CalBoardInfo_.tagSize_; // 0.165 m
AprilTags::TagCodes tagCodes(AprilTags::tagCodes36h11);
AprilTags::TagDetector detector(tagCodes, CalBoardInfo_.black_border_);
std::vector<AprilTags::TagDetection> detections = detector.extractTags(img_raw);
if(detections.size() > 0)
{
if(detections.size() > 1)
{
std::cout << "uhhhhh, too many apritags!!!\n";
return;
}
AprilTags::TagDetection tag = detections[0];
cv::Mat tag_corners(4 , 2, CV_32F);
for (unsigned j = 0; j < 4; j++)
{
tag_corners.at<float>(j, 0) = tag.p[j].first;
tag_corners.at<float>(j, 1) = tag.p[j].second;
}
// 亚像素
// int window_size = 3;
// cv::cornerSubPix(
// img_raw, tag_corners, cv::Size(window_size, window_size), cv::Size(-1, -1),
// cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
cv::cvtColor(img_raw, img_raw, CV_GRAY2BGR);
cv::circle(img_raw, cv::Point2f(tag.cxy.first, tag.cxy.second), 3,
cv::Scalar(0, 255, 0));
cv::putText(img_raw, std::to_string(tag.id),
cv::Point2f(tag.cxy.first, tag.cxy.second),
CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255));
// 四个角点坐标
p3ds.emplace_back(cv::Point3f(0., 0., 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(0, 0),
tag_corners.at<float>(0, 1)));
p3ds.emplace_back(cv::Point3f(tag_sz, 0., 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(1, 0),
tag_corners.at<float>(1, 1)));
p3ds.emplace_back(cv::Point3f(tag_sz, tag_sz, 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(2, 0),
tag_corners.at<float>(2, 1)));
p3ds.emplace_back(cv::Point3f(0., tag_sz, 0.0));
p2ds.emplace_back(cv::Point2f(tag_corners.at<float>(3, 0),
tag_corners.at<float>(3, 1)));
} else
{
std::cout << "Do not detect any apritag!!!\n";
}
}
else
{
std::cout << "Pattern type not supported yet.\n";
}
}
// 根据内参,三维坐标和像素坐标计算相机在棋盘格坐标系下的位姿
bool CamPoseEst::EstimatePose(const std::vector<cv::Point3f> &p3ds,
const std::vector<cv::Point2f> &p2ds,
const CameraPtr &cam,
Eigen::Matrix4d &Twc, cv::Mat &img_raw)
{
Twc.setIdentity();
if (p3ds.size() != p2ds.size() || p3ds.size() < 4)
{
return false;
}
cv::Mat_<float> K = (cv::Mat_<float>(3, 3) << 1, 0.0, 0, 0.0, 1, 0, 0.0, 0.0, 1.0);
cv::Mat_<float> dist = (cv::Mat_<float>(1, 5) << 0.0, 0.0, 0.0, 0.0, 0.0);
cv::Mat cv_r, cv_t;
cv::Mat inliers;
cv::solvePnP(p3ds, p2ds, K, dist, cv_r, cv_t);
// cv::solvePnPRansac(p3ds, p2ds, K, dist, cv_r, cv_t, false, 100, 2., 0.99);
cv::Mat rotation;
cv::Rodrigues(cv_r, rotation);
Eigen::Matrix3d Rcw;
cv::cv2eigen(rotation, Rcw);
Eigen::Vector3d tcw;
cv::cv2eigen(cv_t, tcw);
Twc.block<3, 3>(0, 0) = Rcw.inverse();
Twc.block<3, 1>(0, 3) = -Rcw.inverse() * tcw;
std::cout << "twc: "<<Twc(0, 3)<<" "<<Twc(1, 3)<<" "<<Twc(2, 3)<<std::endl;
cv::putText(
img_raw, "t_wc: (m) " + std::to_string(Twc(0, 3)) + " " + std::to_string(Twc(1, 3)) + " " + std::to_string(Twc(2, 3)),
cv::Point2f(50, 30), CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255, 0, 0));
// std::vector<cv::Point3f> axis;
// std::vector<cv::Point2f> imgpts;
// axis.push_back(cv::Point3f(0,0,0));
// axis.push_back(cv::Point3f(1,0,0));
// axis.push_back(cv::Point3f(0,1,0));
// axis.push_back(cv::Point3f(0,0,1));
// cv::projectPoints(axis, cv_r, cv_t, K, dist,imgpts);
std::vector<Eigen::Vector3d> axis;
std::vector<cv::Point2f> imgpts;
axis.push_back(Eigen::Vector3d(0,0,0));
axis.push_back(Eigen::Vector3d(0.2,0,0));
axis.push_back(Eigen::Vector3d(0,0.2,0));
axis.push_back(Eigen::Vector3d(0,0,0.2));
for (size_t i = 0; i < axis.size(); ++i) {
Eigen::Vector2d pt;
Eigen::Vector3d Pt = Rcw * axis[i] + tcw;
cam->spaceToPlane(Pt, pt); // 三维空间点,加上畸变投影到图像平面
imgpts.push_back(cv::Point2f(pt.x(),pt.y()));
}
cv::line(img_raw, imgpts[0], imgpts[1], cv::Scalar(255,0,0), 2);
cv::line(img_raw, imgpts[0], imgpts[2], cv::Scalar(0,255,0), 2);
cv::line(img_raw, imgpts[0], imgpts[3], cv::Scalar(0,0,255), 2);
return true;
}
bool CamPoseEst::calcCamPose(const double ×tamps, const cv::Mat &image,
const CameraPtr &cam, Eigen::Matrix4d &Twc)
{
cv::Mat img_raw = image.clone();
if (img_raw.channels() == 3)
{
cv::cvtColor(img_raw, img_raw, CV_BGR2GRAY);
}
std::vector<cv::Point3f> p3ds;
std::vector<cv::Point2f> p2ds;
// FindTargetCorner(img_raw, CHESS, p3ds, p2ds);
FindTargetCorner(img_raw, p3ds, p2ds);
std::vector<cv::Point2f> un_pts; // 对像素角点坐标去畸变
for (int i = 0, iend = (int)p2ds.size(); i < iend; ++i)
{
Eigen::Vector2d a(p2ds[i].x, p2ds[i].y);
Eigen::Vector3d b;
cam->liftProjective(a, b); // 去图像畸变, 得到归一化图像平面的坐标
un_pts.push_back(
cv::Point2f(b.x() / b.z(), b.y() / b.z() ));
}
if (EstimatePose(p3ds, un_pts, cam, Twc, img_raw))
{
cv::imshow("apriltag_detection & camPose_calculation", img_raw);
cv::waitKey(1);
return true;
}
else
{
return false;
}
}
2.1.4. 重投影误差
用于构造关于求解相对位姿的优化问题;
2.2. 标定板的设计
标定板的设计需要根据传感器的选型和标定步骤、要求来决定,可手动生成;
需要保证标定的时候,标定板尽量占据相机视野的大部分范围,同时保证成像足够清晰不模糊,角点/标记点的提取足够准确;
2.2.1. chessboard棋盘格
指定行数和列数之后能够在图像中找到有序排列的corner像素点;
特点:
具有对称性;一般的,给定标记物的尺寸参数后需要所有标记点都检测到才能保证相机在标定板中定位成功(有的算法部分遮挡也可以);
2.2.2. apriltag(自识别标记)
opencv :: aruco 与 apriltag对比:ArUco与AprilTag简介-CSDN博客
apriltag单个标签在图像中能够识别出该标签的中心位置,有序的四个角,以及标签的tag_id数字,能够携带更多信息;可以用于计算相机相对标签的位姿,并通过单应矩阵绘制ar图案;
对于由多个标签组成的阵列(所有标签的所有角点都能够独立的识别出来),即使只有部分标签落在图像视野内,也能够找到标记点三维坐标与标记点像素坐标的对应关系;
note:
kalibr标定两个相机外参时不要求两个相机的视野完全重叠也是基于上述原理,只要部分标签落在重叠的视野中即可(两个相机能够同时在一个标定物的坐标系中成功定位);
2.3. 【key】单目标定实施步骤及要求
参照matlab工具箱,实施步骤如下:
-
- 准备已知尺寸等参数的标定板(例如棋盘格),并使用相机拍摄多个不同角度和位置的图像。
- 导入图像:将图像导入MATLAB环境。可以使用imread函数加载图像,并将其存储在一个图像数组中。
- 检测角点:使用detectCheckerboardPoints函数检测标定板上的角点。该函数会自动识别标定板的角点,并返回一个角点坐标矩阵。
- 标定相机:使用calibrateCamera函数对相机进行标定。该函数使用检测到的角点坐标矩阵作为输入,并输出相机内参和畸变系数。
- 评估标定结果:使用showReprojectionErrors函数评估标定结果。该函数会显示每个标定图像的投影误差,以及整体标定的平均误差。
- 保存标定结果:使用save函数将标定结果保存到文件中,以备后续使用。
要求:
标定板平面与成像平面的夹角不要超过45度;
多个orientation;
标定板占据大部分视场;
图像不要模糊;
让格点/角点能够出现在图像的边上或者角上(有助于计算出更好的畸变参数)(手动录制样本较难保证);
后期可以剔除重投影误差较大的图片;
2.4. 单目标定结果
内参;
畸变参数;
每个样本图片中相机相对于标记物/标定板的位姿;
其他:重投影误差统计结果等;
不同的算法或者工具求得的参数个数不同;
opencv标定结果给出的是矩阵的形式,例如下面:
2.5. 标定结果评估和改进
Evaluating the Accuracy of Single Camera Calibration- MATLAB & Simulink- MathWorks 中国
使用重投影误差来评估标定结果;
每一张样本图片都可以用于计算重投影误差,可用于剔除较差的样本;
3. 【key】视场无重叠的多相机外参标定
建议先分别标定内参,内参标定结果尽量准确,方便外参的计算;
3.1. 两个标定板的位姿未知:使用手眼标定
前提:
两个标定板的位姿固定;
左右相机的内参准确已知;
左右相机是固接的,是一个组件,它们之间的相对位姿固定;
原理:
实施步骤:
改变左右相机组件的方位,保证左右相机分别能够识别到标定板,采集多个方位下的数据;
note:标定板位于图像中间时,图像的畸变是最小的;
求解工具:
3.2. 两个标定板的位姿已知:使用类似于双目标定外参的方法,优化重投影误差;
前提:
两个标定板的位姿固定且相对位姿已知;
左右相机是固接的,它们之间的相对位姿固定;
原理:
考虑:左右相机的相对姿态更加重要;
实施步骤:
3.3. 其他
参考环视相机标定:
opencalib提供了环视相机的标定方法;
4. 标定内容及步骤分解;
4.1. 传感器布局
4.2. 标定内容分解
待标定内容 | 标定方法 | 重要程度 |
双目相机的内参和外参(相对位姿); IMU的内参及相机与IMU的外参; | 单个标定板,持设备绕各个轴旋转及绕各个轴平移运动,录制数据包; | 重要 |
两侧广角/鱼眼相机的内参; | 内参分别标定; | 重要 |
左右两侧广角/鱼眼相机的外参(无重叠视野); | 使用手眼标定的方法:使用两个相对位姿未知的标定板,求解AX=XB; 或使用重投影误差构建优化问题的方法:使用两个相对位姿已知的标定板; | 重要 |
双目相机与里程计的外参及里程计的内参; | 需要计算相机计算出来的运动轨迹和里程计计算出的运动轨迹,走八字形路径; 里程计的内参可单独手动标定; | 相机与里程计外参不重要; 里程计内参重要; |
RTK与里程计外参标定 |
5. 【key】标定内容详解
5.1. 单/双目相机-imu模组的标定-使用kalibr
相机与imu同时标定,获得双目参数,imu参数以及二者直接之间的转换矩阵;
三个阶段:
1、双目标定获取双目相机内参以及双目之间的转换矩阵;
rosrun kalibr kalibr_calibrate_cameras --bag /home/heyijia/stereo_calibra.bag --topics /left /right --models pinhole-equi pinhole-equi --target /home/heyijia/april_6x6_80x80cm_A0.yaml
内容包括–bag(数据集 bag文件) --topics (相机话题)–models (相机模型)–target(参数输出文件)
2、 imu标定获取噪声密度、随机游走(使用imu_utils);
保持IMU静止不动至少两个小时(较繁琐)(计算噪声密度、随机游走,vio需要),录制IMU的bag;
IMU误差模型(零偏,尺度误差,轴偏角这些参数对于性能比较好的IMU都比较准确--according to tanhuan)
3 、imu+双目联合标定获取imu与双目之间的转换矩阵和两者时间戳的差值(需要上面两步的标定结果);
以上两次标定结果修改.yaml参数;
kalibr_calibrate_imu_camera --target april_6x6.yaml --cam camchain.yaml --imu imu_adis16448.yaml --bag /home/dji/db/stero_dji_kalibr/stereo/imu_stereo_subset.bag --bag-from-to 5 45
总结:
imu的部分内参需要单独标定,生成参数文件,供联合标定使用;
第一步和第三步可以共用一份数据包;
数据样本:
参考:
步骤操作视频(联合标定的时候需要做多个自由度的运动)
kalibr标定camera-imu内外参原理(计算角速度曲线的相位差)
5.2. 两侧相机的内参
分别单独标定,只需要一个标定板;
5.3. 两侧相机的外参(无重叠视野)
需要使用两个标定板;
有两种方法:
使用手眼标定的方法:使用两个相对位姿未知的标定板,求解AX=XB;
或使用重投影误差构建优化问题的方法:使用两个相对位姿已知的标定板;
note:
是否更加看重左右相机的orientation?;
5.4. 相机与里程计的外参及里程计的参数;
使用融合或者优化的方法;要计算相机计算出来的运动轨迹和里程计计算出的运动轨迹,走八字形路径;
里程计的内参可单独手动标定;
note:
是否使用安装参数?
某些角度(pitch)比较重要,可以直接标定单个参数;
6. 时间同步(不熟练)
由硬件决定;
使用gnss(对时间同步的要求高)相关的工具;
7. 出场之后标定
用户或者4s店标定;
自动驾驶领域有使用竖直标定板;
自动驾驶领域标定看重摄像头对直车道线及相机和lidar的外参;
环视相机标定:看重俯瞰图的成像质量;
一个环视相机标定示例
https://www.youtube.com/watch?v=sSP7rJq9cJg
https://www.youtube.com/watch?v=QsI4puDWVzw
note:标定环视相机时不要求严格的计算相机外参,看重图像拼接效果;
8. 标定装置/工作台的设计
使用桌面机械臂加持相机或者传感器组件,按照预设的轨迹运动采集数据;
可以保证:
相机相对于标定板的方位采样更加均匀;
角点能落在图像的边上和角上,让畸变参数的标定更准确;
9. 专利相关
用到三坐标测量仪等比较专业的工具;
10. 其他-开源仓库参考
10.1. 相机与2d_lidar标定
下载地址: GitHub - MegviiRobot/CamLaserCalibraTool: Extrinsic Calibration of a Camera and 2d Laser
相机与2d_lidar标定(附文章描述)
提供了如下功能:
计算各种类型标定板的所有格点的三维坐标(包括chessboard 和 apriltag);
对原始图像检测出来的标记点/角点去畸变,计算相机的位姿;
优化问题构建,利用激光点落在平面上这个约束(另外一个约束:点云线段的端点落在标定板的边上)构建误差方程,将外参作为待优化变量;
10.2. 自动驾驶产线标定与标定间方案
10.3. 使用zmq原生接口通信、调试使用经验
10.4. rosbag与自定义数据集的相互转换
10.5. 其他开源仓库(可参考常见功能或者代码的算法实现,同行专利文件)
10.6. KITTI数据集(时间戳已对齐,可直接用于验证算法功能有效性)
星星已下载,已存到nas;
opencalib;
kalibr;
imu_utils;
matlab_calibration toolbox;
opencv calib3d; auro; 去畸变,pnp, 鸟瞰图,posit;