TUM RGBD数据集工具及使用
1. 工具
工具下载地址:https://vision.in.tum.de/data/datasets/rgbd-dataset/tools ? add_pointclouds_to_bagfile.py 给bag中加入点云topic ? associate.py 生成depth 和 rgb的匹配信息 ? evaluate_ate.py 绝对误差评估,常用 ? evaluate_rpe.py 相对误差评估 ? generate_pointcloud.py 生成点云数据 ? generate_registered_pointcloud.py ? plot_camera_trajectories.m matlab打印轨迹 ? plot_trajectory_into_image.py ? prepare3dedges.py ? project_point_cloud_to_image.py
2. 数据集
下载地址:https://vision.in.tum.de/data/datasets/rgbd-dataset/download 数据集包含bag 及tgz 两种格式 1)bag包:图像以15hz的频率发布,imu以500hz频率发布,较多卡顿现象,发布信息:
/camera/depth/camera_info /camera/depth/image /camera/rgb/camera_info /camera/rgb/image_color /clock /cortex_marker_array /imu /rosout /rosout_agg /tf
使用方法:rosbag play <bag_name>.bag
2)tgz包:包含rgb及depth文件夹分别存放rgb图像及深度图,accelerometer.txt 存放加速度信息,相对提供的bag包数据流畅。
使用方法: 1、解析文件夹,例程如:ORB_SLAM3/Examples/RGB-D/rgbd_tum.cc 2、使用如下脚本将tgz包解析转化为bag包,此时生成的bag包比官网提供的bag流畅,频率为30hz。
generate_bags.py :
import cv2
import time, sys, os
from ros import rosbag
import roslib
import rospy
roslib.load_manifest('sensor_msgs')
from sensor_msgs.msg import Image,Imu
from geometry_msgs.msg import Vector3
from cv_bridge import CvBridge
from numpy import asarray
from PIL import ImageFile
from PIL import Image as ImagePIL
def CompSortFileNamesNr(f):
g = os.path.splitext(os.path.split(f)[1])[0]
numbertext = ''.join(c for c in g if c.isdigit())
return int(numbertext)
def ReadIMU(IMUFile):
'''return IMU data and timestamp of IMU'''
IMUfp = open(IMUFile,'r')
IMULines = IMUfp.readlines()
IMUDatas = {}
for l in IMULines:
if l[0] == "#":
continue;
items = l.rstrip('\n').split(' ')
IMUDatas[items[0]] = items[1:]
IMUfp.close()
return IMUDatas
def ReadImages(assocoations):
assofp = open(assocoations, 'r')
asso = assofp.readlines()
RGBImages = {}
depthImages = {}
for l in asso:
if l[0] == "#":
continue;
items = l.rstrip('\n').split(' ')
RGBImages[items[0]] = items[1]
depthImages[items[2]] = items[3]
assofp.close()
return RGBImages, depthImages
def CreateBag(args):
'''read assocoations.txt'''
RGBImages,depthImages = ReadImages(args[1])
IMUDatas = ReadIMU(args[2])
'''Creates a bag file with camera images'''
if not os.path.exists(args[3]):
os.system(r'touch %s' % args[3])
else:
os.system(r'rm %s' % args[3])
os.system(r'touch %s' % args[3])
bagName = rosbag.Bag(args[3], 'w')
try:
for it, iData in IMUDatas.items():
imu = Imu()
imuStamp = rospy.rostime.Time.from_sec(float(it))
linear_a = Vector3()
linear_a.x = float(iData[0])
linear_a.y = float(iData[1])
linear_a.z = float(iData[2])
imu.header.stamp = imuStamp
imu.linear_acceleration = linear_a
bagName.write("/imu",imu,imuStamp)
br = CvBridge()
for imt, img in RGBImages.items():
print("Adding %s" % img)
cv_image = cv2.imread(img)
Stamp = rospy.rostime.Time.from_sec(float(imt))
'''set image information '''
Img = br.cv2_to_imgmsg(cv_image)
Img.header.stamp = Stamp
Img.header.frame_id = "camera"
'''for mono8'''
Img.encoding = "rgb8"
bagName.write('/camera/rgb/image_color', Img, Stamp)
for dt, dimg in depthImages.items():
print("Adding %s" % dimg)
cv_image = cv2.imread(dimg, cv2.IMREAD_ANYDEPTH)
'''set image information '''
Stamp = rospy.rostime.Time.from_sec(float(dt))
'''set image information '''
dImg = br.cv2_to_imgmsg(cv_image)
dImg.header.stamp = Stamp
dImg.header.frame_id = "camera"
bagName.write('/camera/depth/image', dImg, Stamp)
finally:
bagName.close()
if __name__ == "__main__":
print(sys.argv)
if len(sys.argv) < 4:
print("Usage:\n\t python generate_bags.py /path/assocoations.txt /path/accelerometer.txt output.bag")
exit(1)
CreateBag(sys.argv)
使用方法: 首先:使用官网提供的脚本associate.py 生成assocoations.txt 文件
python rgbd_benchmark_tools/scripts/associate.py /path/rgb.txt /path/depth.txt > assocoations.txt
然后使用上述generate_bags.py 生成bag包
python rgbd_benchmark_tools/scripts/generate_bags.py /path/assocoations.txt /path/accelerometer.txt output.bag
|