1 kalibr标定包
1.1 下载安装
mkdir -p kalibr_ws/src
cd kalibr_ws/src
git clone https://github.com/ethz-asl/kalibr.git
cd ..
catkin build -DCMAKE_BUILD_TYPE=Release -j4
1.2 标定流程
1.2.1 录制rosbag包
开启相机端视频流mvs开启,标定过程中尽量让各个姿态保持时间长一点,且四个角,中心位置等都出现绕xyz轴旋转的图
tips : 注意mvs是否相机驱动正确设置时间戳,通过MVS的UI可查看,不正确设置所有帧的时间戳都是出厂的时间戳,录包后数据没法区分(否则会报错TargetViewTable]: Tried to add second view to a given cameraId & timestamp. Maybe try to reduce the approximate syncing tolerance )
roslaunch mvs_ros_driver mvs_camera_trigger.launch
rosbag record /left_camera/image -o "cam_calib"
由于此处我未检查MVS的相机驱动,所以将采集的rosbag转换为数据集后再再次转为可用的rosbag
转换文件为:
tips:注意数据集命名,一组图像命名为cam0,如果是多相机就是cam1等分别创建文件夹命名,imu也是,然后统一放到一个文件夹里,我这是放到了data_set文件夹
#include <ros/ros.h>
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <boost/filesystem.hpp>
int main(int argc, char** argv)
{
if (argc < 5) {
std::cerr << "用法: " << argv[0] << " <bag路径> <图像话题> <输出文件夹> <抽帧间隔>" << std::endl;
return -1;
}
std::string bag_path = argv[1];
std::string image_topic = argv[2];
std::string output_dir = argv[3];
int frame_interval = std::stoi(argv[4]);
// 创建输出文件夹
boost::filesystem::create_directories(output_dir);
rosbag::Bag bag;
try {
bag.open(bag_path, rosbag::bagmode::Read);
} catch (rosbag::BagException &e) {
std::cerr << "无法打开bag文件: " << e.what() << std::endl;
return -1;
}
rosbag::View view(bag, rosbag::TopicQuery(image_topic));
int frame_count = 0;
int saved_count = 0;
for (const rosbag::MessageInstance& m : view) {
sensor_msgs::Image::ConstPtr img_msg = m.instantiate<sensor_msgs::Image>();
if (!img_msg) continue;
if (frame_count % frame_interval == 0) {
try {
cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(img_msg, "bgr8");
auto now = std::chrono::system_clock::now();
auto ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count();
std::stringstream ss;
ss << output_dir << "/" << ns << ".jpg";
cv::imwrite(ss.str(), cv_ptr->image);
saved_count++;
std::cout << "保存图片: " << ss.str() << std::endl;
}
catch (cv_bridge::Exception& e) {
std::cerr << "cv_bridge 转换失败: " << e.what() << std::endl;
}
}
frame_count++;
}
std::cout << "总共保存了 " << saved_count << " 张图片" << std::endl;
bag.close();
return 0;
}
然后调用kalibr本身的kalibr_bagcreator包创建新的可用rosbag
rosrun kalibr kalibr_bagcreater --folder /home/bagfile/data_set --output-bag /home//bagfile/new_bag_20250815.bag
1.2.2 标定步骤
利用kalibr_calibrate进行标定,先创建一个apriltag.yaml文件,说明标定板的情况
target_type: 'aprilgrid' #gridtype
tagCols: 6 #number of apriltags
tagRows: 6 #number of apriltags
tagSize: 0.055 #size of apriltag, edge to edge [m]
tagSpacing: 0.3 #ratio of space between tags to tagSize
rosrun kalibr kalibr_calibrate_cameras --bag /home/bagfile/new-bag-20250815.bag --topics /left_camera/image --models pinhole-radtan --target /home/bagfile/apriltag_6x6.yaml --show-extraction --approx-sync 0.01
.bag是采集的数据包名称,topics处是待标记单目的topic(注意新数据集后的该话题会改变,要rosbag info看一下),pinhole-radtan表示采用的畸变类型,april_6x6_max.yaml是适用于你自己标定板参数的配置文件,–show-extraction显示抽帧提取corner过程,approx-sync是时间差
1.2.3 标定质量分析
我这里error的pix比较多,应该再多些位姿
程序会输出三个文件:
report-cam-%BAGNAME%.pdf:PDF版本的结果报告,包含绘制的图片和标定的参数。
results-cam-%BAGNAME%.txt:以文本文件储存的标定结果。
camchain-%BAGNAME%.yaml:以YAML格式储存的标定结果。它可以直接用来作为相机-IMU校正的输入。