自制ORB-SLAM双目数据集,仿照EuRoC数据集格式

1.EuROC数据集介绍

参见链接EuRoC数据集介绍

2.仿制EuRoC 数据集

本人用的是双usb相机,因此,直接调用openCV python 格式创建数据集,采集照片程序和生成对应时间戳txt文件代码如下:

import os
import re
import sys
import cv2
import time

# 记录运行路径,数据集名称为dataset_路径_次数,可自行修改
run_num = 0
path_name = "B5-B4"

image_dir = "../dataset/MH_{}_{}/mav0".format(run_num, path_name)  # 图像保存文件夹路径
if not os.path.exists(image_dir):
    os.makedirs(image_dir)

left_image_dir = os.path.join(image_dir, "cam0/data")
right_image_dir = os.path.join(image_dir, "cam1/data")
if not os.path.exists(left_image_dir):
    os.makedirs(left_image_dir)
if not os.path.exists(right_image_dir):
    os.makedirs(right_image_dir)

# 创建txt文件
timeStamps_dir = "../dataset/timeStamps_{}_{}".format(path_name, run_num)  # 图像保存文件夹路径
text_file_name = "timestamps.txt"
if not os.path.exists(timeStamps_dir):
    os.makedirs(timeStamps_dir)
txt_file =os.path.join(timeStamps_dir, text_file_name)  # 时间戳保存文件路径
with open(txt_file, "w") as f:
    pass

left_cam = cv2.VideoCapture(1)  # 左侧摄像头索引
right_cam = cv2.VideoCapture(0)  # 右侧摄像头索引

# 设置图像尺寸为640x480像素
width, height = 640, 480
left_cam.set(cv2.CAP_PROP_FRAME_WIDTH, width)
left_cam.set(cv2.CAP_PROP_FRAME_HEIGHT, height)
right_cam.set(cv2.CAP_PROP_FRAME_WIDTH, width)
right_cam.set(cv2.CAP_PROP_FRAME_HEIGHT, height)

# 设置帧率为20fps
left_cam.set(cv2.CAP_PROP_FPS, 20)
right_cam.set(cv2.CAP_PROP_FPS, 20)

while True:
    ret1, left_frame = left_cam.read()
    ret2, right_frame = right_cam.read()

    if not ret1 or not ret2:
        break

    timestamp = int(time.time() * 1000)  # 当前时间戳(毫秒级)

    # 保存时间戳
    with open(txt_file, "a") as f:
        f.write(f"{timestamp}\n")

    # 保存左侧图像
    left_image_path = os.path.join(left_image_dir, f"{timestamp}.png")
    cv2.imwrite(left_image_path, left_frame)

    # 保存右侧图像
    right_image_path = os.path.join(right_image_dir, f"{timestamp}.png")
    cv2.imwrite(right_image_path, right_frame)

    cv2.imshow("Left", left_frame)
    cv2.imshow("Right", right_frame)

    # 按下键盘上的q按键退出程序
    key = cv2.waitKey(1)
    if key & 0xFF == ord("q"):
        break

left_cam.release()
right_cam.release()
cv2.destroyAllWindows()

注意,留意EuRoc数据集目录,“Euroc数据集目录/mav0/…”,因此在制作时要相同的目录结构,时间戳存储文件为电脑时间戳(程序已经设置好)。
EuROC数据集目录格式自己创建数据集目录结构述
自己创建的目录结构如上图所示。

3. 采集双目相机标定图像

标定板自选,下附采集双目标定图像程序,按下"s"键保存,按下"esc"键退出。注意采集图像时,标定板位置固定。

import os
import re
import sys
import cv2
import time

# 记录运行路径,数据集名称为dataset_路径_次数, 可自行修改
run_num = 00
path_name = "stereo"

image_dir = "../dataset/MH_{}_{}".format(run_num, path_name)  # 图像保存文件夹路径
if not os.path.exists(image_dir):
    os.makedirs(image_dir)

left_image_dir = os.path.join(image_dir, "cam0/data")
right_image_dir = os.path.join(image_dir, "cam1/data")
if not os.path.exists(left_image_dir):
    os.makedirs(left_image_dir)
if not os.path.exists(right_image_dir):
    os.makedirs(right_image_dir)

# 创建txt文件
timeStamps_dir = "../dataset/timeStamps{}_{}".format(path_name, run_num)  # 图像保存文件夹路径
text_file_name = "timestamps.txt"
if not os.path.exists(timeStamps_dir):
    os.makedirs(timeStamps_dir)
txt_file =os.path.join(timeStamps_dir, text_file_name)  # 时间戳保存文件路径
with open(txt_file, "w") as f:
    pass

left_cam = cv2.VideoCapture(1)  # 左侧摄像头索引
right_cam = cv2.VideoCapture(0)  # 右侧摄像头索引

# 设置图像尺寸为640x480像素
width, height = 640, 480
left_cam.set(cv2.CAP_PROP_FRAME_WIDTH, width)
left_cam.set(cv2.CAP_PROP_FRAME_HEIGHT, height)
right_cam.set(cv2.CAP_PROP_FRAME_WIDTH, width)
right_cam.set(cv2.CAP_PROP_FRAME_HEIGHT, height)

# 设置帧率为20fps
left_cam.set(cv2.CAP_PROP_FPS, 20)
right_cam.set(cv2.CAP_PROP_FPS, 20)

# 保存图像计数器
count = 0

while True:
    ret1, left_frame = left_cam.read()
    ret2, right_frame = right_cam.read()

    if not ret1 or not ret2:
        break

    cv2.imshow("Left", left_frame)
    cv2.imshow("Right", right_frame)

    # 按下键盘上的按键
    key = cv2.waitKey(1)
    if key & 0xFF == ord("s"):
        count += 1
        # 保存左侧图像
        left_image_path = os.path.join(left_image_dir, f"cam0_{count}.png")
        cv2.imwrite(left_image_path, left_frame)

        # 保存右侧图像
        right_image_path = os.path.join(right_image_dir, f"cam1_{count}.png")
        cv2.imwrite(right_image_path, right_frame)

    # 如果按下"Esc"键,则退出循环
    elif key == 27:
        break

left_cam.release()
right_cam.release()
cv2.destroyAllWindows()

双目相机标定参见MatLab的双目相机标定和orbslam双目参数匹配,实际上,
经过测试,发现该博客中关于yaml配置的注释有错误,需要注意,不能直接参考。

EuROC yaml 配置文件

以ORB-SLAM2/Examples/Stereo/EuRoc.yaml文件为例:

%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

# Camera calibration and distortion parameters (OpenCV) 
# 该部分正确
Camera.fx: 435.2046959714599
Camera.fy: 435.2046959714599
Camera.cx: 367.4517211914062
Camera.cy: 252.2008514404297

# 该部分只有针孔摄像机,畸变小时均可设为0
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0

# 设置图像长宽
Camera.width: 752
Camera.height: 480

# Camera frames per second 
Camera.fps: 20.0

# stereo baseline times fx
# 注意单位为m, matlab 标定后单位为mm, 计算参见上述博客
Camera.bf: 47.90639384423901

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
# 用openCV采集的图像为BGR格式,因此应该设置为0
Camera.RGB: 1

# Close/Far threshold. Baseline times.
# 该部分上述博客说的有问题
ThDepth: 35

#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 480
LEFT.width: 752
LEFT.D: !!opencv-matrix
   rows: 1
   cols: 5
   dt: d
   data:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
# 这个内参矩阵不是左相机标定出来的内参,实际上是[fx, 0, cx; 0, fy, cy; 0, 0,1]
LEFT.K: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]

# 这块因为只有双目相机,以左相机为基准坐标系,将世界坐标系建在左相机坐标系上因此应为单位阵[1, 0, 0, 0, 1, 0, 0, 0, 1]
LEFT.R:  !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
   # 这部分是用[fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1, 0],实际公式参考多视几何书籍6.1节中投影矩阵的定义k[R|t],其中
   #内参矩阵k为LEFT.K, 旋转矩阵R为单位矩阵,t为零向量
LEFT.P:  !!opencv-matrix
   rows: 3
   cols: 4
   dt: d
   data: [435.2046959714599, 0, 367.4517211914062, 0,  0, 435.2046959714599, 252.2008514404297, 0,  0, 0, 1, 0]

RIGHT.height: 480
RIGHT.width: 752
RIGHT.D: !!opencv-matrix
   rows: 1
   cols: 5
   dt: d
   data:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
   # 同左相机 [fx, 0, cx; 0, fy, cy; 0, 0,1]
RIGHT.K: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
RIGHT.R:  !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
   # 这部分矩阵为[fx, 0, cx, 0, -bf, fy, cy, 0, 0, 0, 1, 0],并不是用公式计算的K[R|t],内参矩阵为左相机K
RIGHT.P:  !!opencv-matrix
   rows: 3
   cols: 4
   dt: d
   data: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]

#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------

# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200

# ORB Extractor: Scale factor between levels in the scale pyramid 	
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid	
ORBextractor.nLevels: 8

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast			
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500

  • 0
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值