1. 背景简介
在机器人视觉和 SLAM (Simultaneous Localization and Mapping) 领域,双目相机的标定和同步数据采集是构建高精度 3D 环境地图的重要步骤。本文主要分享我们在使用 Intel D435i 深度相机进行数据采集与同步图像提取过程中的一些技术细节与经验,涵盖了 ROS bag 数据采集、时间对齐以及图像转换与保存的完整流程。值得注意的是,在我前面的博客中前面提到了基于rostools的rosbag转图像的方法,并且可以用于建图,但随着建图场景的规模与复杂度增大,有一些比较致命的细节没有考虑得当,导致大场景下建图过程中回出现跟踪失败。后面分析,原来是数据集的不完全对齐造成的。因为我用到双目的图像进行三维点的映射与跟踪的重投影,下面也是就这个问题进行进一步处理。
先来回顾一下之前的rosbag提取图像的方式:
2.rosbag的详细解读
针对这个数据集:
查看rosbag的详细信息,可以看出rosbag中共录制了2441个图像,这里也是msgs给出的,意味着图像也应该有2441帧,记住这个大小。
3.基于rostools的方法
左边:
rosrun image_view extract_images _sec_per_frame:=0.0 image:=/camera/infra1/image_rect_raw _filename_format:="/media/slam/新加卷/SelfCollectionImage/Cqupt_Lab00/image0/%06d.png"
右目:
rosrun image_view extract_images _sec_per_frame:=0.0 image:=/camera/infra2/image_rect_raw _filename_format:="/media/slam/新加卷/SelfCollectionImage/Cqupt_Lab00/image1/%06d.png"
得到的图像预览,这里可以可以发现,左右图像来自不同的时间戳,虽然这是我后面排查的结果,有点生硬了~~~
但后面确实印证了想法,图片只有2029张,这个是对应不上前面rosbag的2441帧图片的,说明有丢失帧的现象,在提取过程中。后面种种迹象都说明该情况,特别是提取后出现左右图像数量不一致的情况。
总结一下以上方法的问题是在于:在传统方法中,我们可以使用 rosrun image_view extract_images
提取左右相机的图像,但这种方法存在以下问题:
时间错配:无法精确对齐左右相机的时间戳。
文件名不一致:左右图片的命名方式不同,难以匹配。
丢帧:在高帧率数据采集时容易丢失部分帧。
4.自定义图像对齐与提取脚本
为了解决这些问题,我们编写了一个 Python 脚本,实现了时间戳对齐、图像转换和批量保存。
#!/usr/bin/env python3
import rosbag
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import os
bag_path = "/media/slam/DataSet/Rosbag_collectByCqupt/cqupt01_2025-05-09-09-57-15.bag"
output_dir = "/media/slam/DataSet/SelfCollectionImage/Cqupt_Lab02"
infra1_topic = "/camera/infra1/image_rect_raw"
infra2_topic = "/camera/infra2/image_rect_raw"
time_threshold = 0.0167 # 时间戳对齐阈值(秒)
bridge = CvBridge()
infra1_msgs = {}
infra2_msgs = {}
print(f"Processing {bag_path}...")
with rosbag.Bag(bag_path, "r") as bag:
for topic, msg, t in bag.read_messages(topics=[infra1_topic, infra2_topic]):
timestamp = msg.header.stamp.to_sec()
if topic == infra1_topic:
infra1_msgs[timestamp] = msg
elif topic == infra2_topic:
infra2_msgs[timestamp] = msg
matched_pairs = 0
total_pairs = len(infra1_msgs)
for idx, timestamp in enumerate(infra1_msgs, start=1):
closest_right_timestamp = min(
infra2_msgs.keys(),
key=lambda x: abs(x - timestamp)
)
time_diff = abs(closest_right_timestamp - timestamp)
if time_diff < time_threshold:
left_image = bridge.imgmsg_to_cv2(infra1_msgs[timestamp], "mono8")
left_filename = f"{output_dir}/image_0/{timestamp:.6f}.png"
cv2.imwrite(left_filename, left_image)
right_image = bridge.imgmsg_to_cv2(infra2_msgs[closest_right_timestamp], "mono8")
right_filename = f"{output_dir}/image_1/{timestamp:.6f}.png"
cv2.imwrite(right_filename, right_image)
matched_pairs += 1
# 打印进度信息
print(f"[{idx}/{total_pairs}] Saved image pair: {left_filename} - {right_filename}")
print(f"Matched {matched_pairs} image pairs")
确定好rosbag的路径,话题,保存路径。
在终端运行:
python Extacter_image_vision.py
可以看到,完整的提取了所有图像,2441个帧。也进一步说明图像只能是对齐的状态,当然在这里可以实时建图看一下效果。
注意按照orb-slam的框架,我们需要准备timestampe时间戳文件和图像顺序命名问题:
在数据集文件下打开控制台运行一下命令:
ls *.png | awk '{printf("mv \"%s\" \"%06d.png\"\n", $0, NR-1)}' | bash
得到2441张顺序命名的数据集:
运行脚本得到时间戳文件,并放在数据集文件夹下:
脚本
def generate_time_file_by_lines(num_lines, time_step_sec=0.1037359, output_path="times.txt"):
with open(output_path, "w") as f:
for i in range(num_lines):
timestamp = i * time_step_sec
f.write(f"{timestamp:.6e}\n")
print(f"Generated {num_lines} timestamps to '{output_path}'")
if __name__ == "__main__":
try:
n = int(input("请输入所需的时间戳行数: "))
generate_time_file_by_lines(n)
except ValueError:
print("请输入一个有效的整数!")
5.室内建图效果
6.总结
通过自定义脚本实现了更高精度的双目数据对齐与图像保存,为后续的 3D 重建与 SLAM 研究奠定了基础。未来可以尝试进一步集成时间同步算法,以提高对齐精度。